From dae8af0a78a508666de9c5fe2c1dd693535da1b8 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 28 Sep 2017 15:45:14 -0700 Subject: [PATCH 1/6] remote b3GjkPairDetector, it is obsolete and unused, causing clang compile problems see https://github.com/bulletphysics/bullet3/issues/1347 --- setup.py | 2 +- .../b3ConvexHullContact.cpp | 158 +----- .../b3GjkPairDetector.cpp | 533 ------------------ .../NarrowphaseCollision/b3GjkPairDetector.h | 84 --- 4 files changed, 11 insertions(+), 766 deletions(-) delete mode 100644 src/Bullet3OpenCL/NarrowphaseCollision/b3GjkPairDetector.cpp delete mode 100644 src/Bullet3OpenCL/NarrowphaseCollision/b3GjkPairDetector.h diff --git a/setup.py b/setup.py index 29139f534..0321e9658 100644 --- a/setup.py +++ b/setup.py @@ -441,7 +441,7 @@ print("-----") setup( name = 'pybullet', - version='1.4.9', + version='1.5.1', description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning', long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.', url='https://github.com/bulletphysics/bullet3', diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.cpp b/src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.cpp index 4bdee1a05..fb435aa7f 100644 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.cpp +++ b/src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.cpp @@ -24,8 +24,8 @@ bool clipConvexFacesAndFindContactsCPU = false;//false;//true; bool reduceConcaveContactsOnGPU = true;//false; bool reduceConvexContactsOnGPU = true;//false; bool findConvexClippingFacesGPU = true; -bool useGjk = true;///option for CPU/host testing, when findSeparatingAxisOnGpu = false -bool useGjkContacts = true;//////option for CPU/host testing when findSeparatingAxisOnGpu = false +bool useGjk = false;///option for CPU/host testing, when findSeparatingAxisOnGpu = false +bool useGjkContacts = false;//////option for CPU/host testing when findSeparatingAxisOnGpu = false static int myframecount=0;///for testing @@ -2606,146 +2606,6 @@ void computeContactSphereConvex(int pairIndex, -#include "b3GjkPairDetector.h" -#include "b3GjkEpa.h" -#include "b3VoronoiSimplexSolver.h" - -int computeContactConvexConvex( b3AlignedObjectArray& pairs, - int pairIndex, - int bodyIndexA, int bodyIndexB, - int collidableIndexA, int collidableIndexB, - const b3AlignedObjectArray& rigidBodies, - const b3AlignedObjectArray& collidables, - const b3AlignedObjectArray& convexShapes, - const b3AlignedObjectArray& convexVertices, - const b3AlignedObjectArray& uniqueEdges, - const b3AlignedObjectArray& convexIndices, - const b3AlignedObjectArray& faces, - b3AlignedObjectArray& globalContactsOut, - int& nGlobalContactsOut, - int maxContactCapacity, - b3AlignedObjectArray&hostHasSepAxis, - b3AlignedObjectArray&hostSepAxis - - - //,const b3AlignedObjectArray& oldContacts - ) -{ - int contactIndex = -1; - b3VoronoiSimplexSolver simplexSolver; - b3GjkEpaSolver2 epaSolver; - - b3GjkPairDetector gjkDetector(&simplexSolver,&epaSolver); - - b3Transform transA; - transA.setOrigin(rigidBodies[bodyIndexA].m_pos); - transA.setRotation(rigidBodies[bodyIndexA].m_quat); - - b3Transform transB; - transB.setOrigin(rigidBodies[bodyIndexB].m_pos); - transB.setRotation(rigidBodies[bodyIndexB].m_quat); - float maximumDistanceSquared = 1e30f; - - b3Vector3 resultPointOnBWorld; - b3Vector3 sepAxis2=b3MakeVector3(0,1,0); - b3Scalar distance2 = 1e30f; - - int shapeIndexA = collidables[collidableIndexA].m_shapeIndex; - int shapeIndexB = collidables[collidableIndexB].m_shapeIndex; - - //int sz = sizeof(b3Contact4); - - bool result2 = getClosestPoints(&gjkDetector, transA, transB, - convexShapes[shapeIndexA], convexShapes[shapeIndexB], - convexVertices,convexVertices, - maximumDistanceSquared, - sepAxis2, - distance2, - resultPointOnBWorld); - - - if (result2) - { - if (nGlobalContactsOut=0) - { - //printf("add existing points?\n"); - //refresh - - int numOldPoints = 0;//oldContacts[pairs[pairIndex].z].getNPoints(); - if (numOldPoints) - { - //newContact = oldContacts[pairs[pairIndex].z]; -#ifdef PERSISTENT_CONTACTS_HOST - b3ContactCache::refreshContactPoints(transA,transB,newContact); -#endif //PERSISTENT_CONTACTS_HOST - } - numPoints = b3Contact4Data_getNumPoints(&newContact); - - } - - /* - int insertIndex = m_manifoldPtr->getCacheEntry(newPt); - if (insertIndex >= 0) - { - //const btManifoldPoint& oldPoint = m_manifoldPtr->getContactPoint(insertIndex); - m_manifoldPtr->replaceContactPoint(newPt,insertIndex); - } else - { - insertIndex = m_manifoldPtr->addManifoldPoint(newPt); - } - */ - - int p=numPoints; - if (numPoints<4) - { - numPoints++; - } else - { - p=3; - } - - { - resultPointOnBWorld.w = distance2; - newContact.m_worldPosB[p] = resultPointOnBWorld; -#ifdef PERSISTENT_CONTACTS_HOST - b3Vector3 resultPointOnAWorld = resultPointOnBWorld+distance2*sepAxis2; - newContact.m_localPosA[p] = transA.inverse()*resultPointOnAWorld; - newContact.m_localPosB[p] = transB.inverse()*resultPointOnBWorld; -#endif - newContact.m_worldNormalOnB = sepAxis2; - - - hostHasSepAxis[pairIndex] = 1; - hostSepAxis[pairIndex] =sepAxis2; - //printf("sepAxis[%d]=%f,%f,%f,%f\n",pairIndex,sepAxis2.x,sepAxis2.y,sepAxis2.z,sepAxis2.w); - } - //printf("bodyIndexA %d,bodyIndexB %d,normal=%f,%f,%f numPoints %d\n",bodyIndexA,bodyIndexB,normalOnSurfaceB.x,normalOnSurfaceB.y,normalOnSurfaceB.z,numPoints); - newContact.m_worldNormalOnB.w = (b3Scalar)numPoints; - - - nGlobalContactsOut++; - } else - { - b3Error("Error: exceeding contact capacity (%d/%d)\n", nGlobalContactsOut,maxContactCapacity); - } - } - - return contactIndex; -} int computeContactConvexConvex2( int pairIndex, @@ -3025,8 +2885,8 @@ void GpuSatCollision::computeConvexConvexContactsGPUSAT( b3OpenCLArray* hostCollidables[collidableIndexB].m_shapeType == SHAPE_CONVEX_HULL) { //printf("hostPairs[i].z=%d\n",hostPairs[i].z); - //int contactIndex = computeContactConvexConvex2(i,bodyIndexA,bodyIndexB,collidableIndexA,collidableIndexB,hostBodyBuf, hostCollidables,hostConvexData,hostVertices,hostUniqueEdges,hostIndices,hostFaces,hostContacts,nContacts,maxContactCapacity,oldHostContacts); - int contactIndex = computeContactConvexConvex(hostPairs,i,bodyIndexA,bodyIndexB,collidableIndexA,collidableIndexB,hostBodyBuf,hostCollidables,hostConvexData,hostVertices,hostUniqueEdges,hostIndices,hostFaces,hostContacts,nContacts,maxContactCapacity,oldHostContacts); + int contactIndex = computeContactConvexConvex2( i,bodyIndexA,bodyIndexB,collidableIndexA,collidableIndexB,hostBodyBuf, hostCollidables,hostConvexData,hostVertices,hostUniqueEdges,hostIndices,hostFaces,hostContacts,nContacts,maxContactCapacity,oldHostContacts); + //int contactIndex = computeContactConvexConvex(hostPairs,i,bodyIndexA,bodyIndexB,collidableIndexA,collidableIndexB,hostBodyBuf,hostCollidables,hostConvexData,hostVertices,hostUniqueEdges,hostIndices,hostFaces,hostContacts,nContacts,maxContactCapacity,oldHostContacts); if (contactIndex>=0) @@ -3538,9 +3398,10 @@ void GpuSatCollision::computeConvexConvexContactsGPUSAT( b3OpenCLArray* - + //int contactIndex = computeContactConvexConvex2( i,bodyIndexA,bodyIndexB,collidableIndexA,collidableIndexB,hostBodyBuf, hostCollidables,hostConvexData,hostVertices,hostUniqueEdges,hostIndices,hostFaces,hostContacts,nContacts,maxContactCapacity,oldHostContacts); + b3AlignedObjectArray oldHostContacts; int result; - result = computeContactConvexConvex( hostPairs, + result = computeContactConvexConvex2( //hostPairs, pairIndex, bodyIndexA, bodyIndexB, collidableIndexA, collidableIndexB, @@ -3554,8 +3415,9 @@ void GpuSatCollision::computeConvexConvexContactsGPUSAT( b3OpenCLArray* hostContacts, nGlobalContactsOut, maxContactCapacity, - hostHasSepAxis, - hostSepAxis + oldHostContacts + //hostHasSepAxis, + //hostSepAxis ); }//mpr diff --git a/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkPairDetector.cpp b/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkPairDetector.cpp deleted file mode 100644 index 39f8c31ba..000000000 --- a/src/Bullet3OpenCL/NarrowphaseCollision/b3GjkPairDetector.cpp +++ /dev/null @@ -1,533 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ - -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 "b3GjkPairDetector.h" -#include "Bullet3Common/b3Transform.h" -#include "b3VoronoiSimplexSolver.h" -#include "Bullet3Collision/NarrowPhaseCollision/shared/b3ConvexPolyhedronData.h" -#include "b3VectorFloat4.h" -#include "b3GjkEpa.h" -#include "b3SupportMappings.h" - -//must be above the machine epsilon -#define REL_ERROR2 b3Scalar(1.0e-6) - -//temp globals, to improve GJK/EPA/penetration calculations -int gNumDeepPenetrationChecks2 = 0; -int gNumGjkChecks2 = 0; -int gGjkSeparatingAxis2=0; -int gEpaSeparatingAxis2=0; - - - -b3GjkPairDetector::b3GjkPairDetector(b3VoronoiSimplexSolver* simplexSolver,b3GjkEpaSolver2* penetrationDepthSolver) -:m_cachedSeparatingAxis(b3MakeVector3(b3Scalar(0.),b3Scalar(-1.),b3Scalar(0.))), -m_penetrationDepthSolver(penetrationDepthSolver), -m_simplexSolver(simplexSolver), -m_ignoreMargin(false), -m_lastUsedMethod(-1), -m_catchDegeneracies(1), -m_fixContactNormalDirection(1) -{ -} - - - - -bool calcPenDepth( b3VoronoiSimplexSolver& simplexSolver, - const b3Transform& transformA, const b3Transform& transformB, - const b3ConvexPolyhedronData& hullA, const b3ConvexPolyhedronData& hullB, - const b3AlignedObjectArray& verticesA, - const b3AlignedObjectArray& verticesB, - b3Vector3& v, b3Vector3& wWitnessOnA, b3Vector3& wWitnessOnB) -{ - - (void)v; - (void)simplexSolver; - - b3Vector3 guessVector(transformB.getOrigin()-transformA.getOrigin()); - b3GjkEpaSolver2::sResults results; - - - if(b3GjkEpaSolver2::Penetration(transformA,transformB,&hullA,&hullB,verticesA,verticesB,guessVector,results)) - { - wWitnessOnA = results.witnesses[0]; - wWitnessOnB = results.witnesses[1]; - v = results.normal; - return true; - } - else - { - if(b3GjkEpaSolver2::Distance(transformA,transformB,&hullA,&hullB,verticesA,verticesB,guessVector,results)) - { - wWitnessOnA = results.witnesses[0]; - wWitnessOnB = results.witnesses[1]; - v = results.normal; - return false; - } - } - - return false; -} -#define dot3F4 b3Dot - -inline void project(const b3ConvexPolyhedronData& hull, const float4& pos, const b3Quaternion& orn, const float4& dir, const b3AlignedObjectArray& vertices, b3Scalar& min, b3Scalar& max) -{ - min = FLT_MAX; - max = -FLT_MAX; - int numVerts = hull.m_numVertices; - - const float4 localDir = b3QuatRotate(orn.inverse(),dir); - - b3Scalar offset = dot3F4(pos,dir); - - for(int i=0;i max) max = dp; - } - if(min>max) - { - b3Scalar tmp = min; - min = max; - max = tmp; - } - min += offset; - max += offset; -} - -#if 0 -static bool TestSepAxis(const b3ConvexPolyhedronData& hullA, const b3ConvexPolyhedronData& hullB, - const float4& posA,const b3Quaternion& ornA, - const float4& posB,const b3Quaternion& ornB, - float4& sep_axis, const b3AlignedObjectArray& verticesA,const b3AlignedObjectArray& verticesB,b3Scalar& depth) -{ - b3Scalar Min0,Max0; - b3Scalar Min1,Max1; - project(hullA,posA,ornA,sep_axis,verticesA, Min0, Max0); - project(hullB,posB,ornB, sep_axis,verticesB, Min1, Max1); - - if(Max0=0.0f); - b3Scalar d1 = Max1 - Min0; - b3Assert(d1>=0.0f); - if (d0& verticesA, - const b3AlignedObjectArray& verticesB, - b3Scalar maximumDistanceSquared, - b3Vector3& resultSepNormal, - float& resultSepDistance, - b3Vector3& resultPointOnB) -{ - //resultSepDistance = maximumDistanceSquared; - - gjkDetector->m_cachedSeparatingDistance = 0.f; - - b3Scalar distance=b3Scalar(0.); - b3Vector3 normalInB= b3MakeVector3(b3Scalar(0.),b3Scalar(0.),b3Scalar(0.)); - b3Vector3 pointOnA,pointOnB; - - b3Transform localTransA = transA; - b3Transform localTransB = transB; - - b3Vector3 positionOffset = b3MakeVector3(0,0,0);// = (localTransA.getOrigin() + localTransB.getOrigin()) * b3Scalar(0.5); - localTransA.getOrigin() -= positionOffset; - localTransB.getOrigin() -= positionOffset; - - bool check2d = false;//m_minkowskiA->isConvex2d() && m_minkowskiB->isConvex2d(); - - b3Scalar marginA = 0.f;//m_marginA; - b3Scalar marginB = 0.f;//m_marginB; - - gNumGjkChecks2++; - - - //for CCD we don't use margins - if (gjkDetector->m_ignoreMargin) - { - marginA = b3Scalar(0.); - marginB = b3Scalar(0.); - } - - gjkDetector->m_curIter = 0; - int gGjkMaxIter = 1000;//this is to catch invalid input, perhaps check for #NaN? - gjkDetector->m_cachedSeparatingAxis.setValue(1,1,1);//0,0,0); - - bool isValid = false; - bool checkSimplex = false; - bool checkPenetration = true; - gjkDetector->m_degenerateSimplex = 0; - - gjkDetector->m_lastUsedMethod = -1; - - { - b3Scalar squaredDistance = B3_LARGE_FLOAT; - b3Scalar delta = -1e30f;//b3Scalar(0.); - // b3Scalar prevDelta = -1e30f;//b3Scalar(0.); - - b3Scalar margin = marginA + marginB; - // b3Scalar bestDeltaN = -1e30f; - // b3Vector3 bestSepAxis= b3MakeVector3(0,0,0); - - - - gjkDetector->m_simplexSolver->reset(); - - for ( ; ; ) - //while (true) - { - - - b3Vector3 seperatingAxisInA = (-gjkDetector->m_cachedSeparatingAxis)* localTransA.getBasis(); - b3Vector3 seperatingAxisInB = gjkDetector->m_cachedSeparatingAxis* localTransB.getBasis(); - - b3Vector3 pInA = localGetSupportVertexWithoutMargin(seperatingAxisInA,&hullA,verticesA); - b3Vector3 qInB = localGetSupportVertexWithoutMargin(seperatingAxisInB,&hullB,verticesB); - - b3Vector3 pWorld = localTransA(pInA); - b3Vector3 qWorld = localTransB(qInB); - - -#ifdef DEBUG_SPU_COLLISION_DETECTION - spu_printf("got local supporting vertices\n"); -#endif - - if (check2d) - { - pWorld[2] = 0.f; - qWorld[2] = 0.f; - } - - b3Vector3 w = pWorld - qWorld; - delta = gjkDetector->m_cachedSeparatingAxis.dot(w); - - // potential exit, they don't overlap - if ((delta > b3Scalar(0.0)) && (delta * delta > squaredDistance * maximumDistanceSquared)) - { - gjkDetector->m_degenerateSimplex = 10; - checkSimplex=true; - //checkPenetration = false; - break; - } - - //exit 0: the new point is already in the simplex, or we didn't come any closer - if (gjkDetector->m_simplexSolver->inSimplex(w)) - { - gjkDetector->m_degenerateSimplex = 1; - checkSimplex = true; - break; - } - // are we getting any closer ? - b3Scalar f0 = squaredDistance - delta; - b3Scalar f1 = squaredDistance * REL_ERROR2; - - if (f0 <= f1) - { - if (f0 <= b3Scalar(0.)) - { - gjkDetector->m_degenerateSimplex = 2; - } else - { - gjkDetector->m_degenerateSimplex = 11; - } - checkSimplex = true; - break; - } - -#ifdef DEBUG_SPU_COLLISION_DETECTION - spu_printf("addVertex 1\n"); -#endif - //add current vertex to simplex - gjkDetector->m_simplexSolver->addVertex(w, pWorld, qWorld); -#ifdef DEBUG_SPU_COLLISION_DETECTION - spu_printf("addVertex 2\n"); -#endif - b3Vector3 newCachedSeparatingAxis; - - //calculate the closest point to the origin (update vector v) - if (!gjkDetector->m_simplexSolver->closest(newCachedSeparatingAxis)) - { - gjkDetector->m_degenerateSimplex = 3; - checkSimplex = true; - break; - } - - if(newCachedSeparatingAxis.length2()m_cachedSeparatingAxis = newCachedSeparatingAxis; - gjkDetector->m_degenerateSimplex = 6; - checkSimplex = true; - break; - } - - b3Scalar previousSquaredDistance = squaredDistance; - squaredDistance = newCachedSeparatingAxis.length2(); -#if 0 -///warning: this termination condition leads to some problems in 2d test case see Bullet/Demos/Box2dDemo - if (squaredDistance>previousSquaredDistance) - { - gjkDetector->m_degenerateSimplex = 7; - squaredDistance = previousSquaredDistance; - checkSimplex = false; - break; - } -#endif // - - - //redundant gjkDetector->m_simplexSolver->compute_points(pointOnA, pointOnB); - - //are we getting any closer ? - if (previousSquaredDistance - squaredDistance <= B3_EPSILON * previousSquaredDistance) - { -// gjkDetector->m_simplexSolver->backup_closest(gjkDetector->m_cachedSeparatingAxis); - checkSimplex = true; - gjkDetector->m_degenerateSimplex = 12; - - break; - } - - gjkDetector->m_cachedSeparatingAxis = newCachedSeparatingAxis; - - //degeneracy, this is typically due to invalid/uninitialized worldtransforms for a btCollisionObject - if (gjkDetector->m_curIter++ > gGjkMaxIter) - { - #if defined(DEBUG) || defined (_DEBUG) || defined (DEBUG_SPU_COLLISION_DETECTION) - - printf("btGjkPairDetector maxIter exceeded:%i\n",gjkDetector->m_curIter); - printf("sepAxis=(%f,%f,%f), squaredDistance = %f\n", - gjkDetector->m_cachedSeparatingAxis.getX(), - gjkDetector->m_cachedSeparatingAxis.getY(), - gjkDetector->m_cachedSeparatingAxis.getZ(), - squaredDistance); - - - #endif - break; - - } - - - bool check = (!gjkDetector->m_simplexSolver->fullSimplex()); - //bool check = (!gjkDetector->m_simplexSolver->fullSimplex() && squaredDistance > B3_EPSILON * gjkDetector->m_simplexSolver->maxVertex()); - - if (!check) - { - //do we need this backup_closest here ? -// gjkDetector->m_simplexSolver->backup_closest(gjkDetector->m_cachedSeparatingAxis); - gjkDetector->m_degenerateSimplex = 13; - break; - } - } - - if (checkSimplex) - { - gjkDetector->m_simplexSolver->compute_points(pointOnA, pointOnB); - normalInB = gjkDetector->m_cachedSeparatingAxis; - b3Scalar lenSqr =gjkDetector->m_cachedSeparatingAxis.length2(); - - //valid normal - if (lenSqr < 0.0001) - { - gjkDetector->m_degenerateSimplex = 5; - } - if (lenSqr > B3_EPSILON*B3_EPSILON) - { - b3Scalar rlen = b3Scalar(1.) / b3Sqrt(lenSqr ); - normalInB *= rlen; //normalize - b3Scalar s = b3Sqrt(squaredDistance); - - b3Assert(s > b3Scalar(0.0)); - pointOnA -= gjkDetector->m_cachedSeparatingAxis * (marginA / s); - pointOnB += gjkDetector->m_cachedSeparatingAxis * (marginB / s); - distance = ((b3Scalar(1.)/rlen) - margin); - isValid = true; - - gjkDetector->m_lastUsedMethod = 1; - } else - { - gjkDetector->m_lastUsedMethod = 2; - } - } - - bool catchDegeneratePenetrationCase = - (gjkDetector->m_catchDegeneracies && gjkDetector->m_penetrationDepthSolver && gjkDetector->m_degenerateSimplex && ((distance+margin) < 0.01)); - - //if (checkPenetration && !isValid) - if (checkPenetration && (!isValid || catchDegeneratePenetrationCase )) - { - //penetration case - - //if there is no way to handle penetrations, bail out - if (gjkDetector->m_penetrationDepthSolver) - { - // Penetration depth case. - b3Vector3 tmpPointOnA,tmpPointOnB; - - gNumDeepPenetrationChecks2++; - gjkDetector->m_cachedSeparatingAxis.setZero(); - - bool isValid2 = calcPenDepth( - *gjkDetector->m_simplexSolver, - transA,transB,hullA,hullB,verticesA,verticesB, - gjkDetector->m_cachedSeparatingAxis, tmpPointOnA, tmpPointOnB - ); - - - if (isValid2) - { - b3Vector3 tmpNormalInB = tmpPointOnB-tmpPointOnA; - b3Scalar lenSqr = tmpNormalInB.length2(); - if (lenSqr <= (B3_EPSILON*B3_EPSILON)) - { - tmpNormalInB = gjkDetector->m_cachedSeparatingAxis; - lenSqr = gjkDetector->m_cachedSeparatingAxis.length2(); - } - - if (lenSqr > (B3_EPSILON*B3_EPSILON)) - { - tmpNormalInB /= b3Sqrt(lenSqr); - b3Scalar distance2 = -(tmpPointOnA-tmpPointOnB).length(); - //only replace valid penetrations when the result is deeper (check) - if (!isValid || (distance2 < distance)) - { - distance = distance2; - pointOnA = tmpPointOnA; - pointOnB = tmpPointOnB; - normalInB = tmpNormalInB; - isValid = true; - gjkDetector->m_lastUsedMethod = 3; - } else - { - gjkDetector->m_lastUsedMethod = 8; - } - } else - { - gjkDetector->m_lastUsedMethod = 9; - } - } else - - { - ///this is another degenerate case, where the initial GJK calculation reports a degenerate case - ///EPA reports no penetration, and the second GJK (using the supporting vector without margin) - ///reports a valid positive distance. Use the results of the second GJK instead of failing. - ///thanks to Jacob.Langford for the reproduction case - ///http://code.google.com/p/bullet/issues/detail?id=250 - - - if (gjkDetector->m_cachedSeparatingAxis.length2() > b3Scalar(0.)) - { - b3Scalar distance2 = (tmpPointOnA-tmpPointOnB).length()-margin; - //only replace valid distances when the distance is less - if (!isValid || (distance2 < distance)) - { - distance = distance2; - pointOnA = tmpPointOnA; - pointOnB = tmpPointOnB; - pointOnA -= gjkDetector->m_cachedSeparatingAxis * marginA ; - pointOnB += gjkDetector->m_cachedSeparatingAxis * marginB ; - normalInB = gjkDetector->m_cachedSeparatingAxis; - normalInB.normalize(); - isValid = true; - gjkDetector->m_lastUsedMethod = 6; - } else - { - gjkDetector->m_lastUsedMethod = 5; - } - } - } - - } - - } - } - - - - if (isValid && (distance < 0)) - //if (isValid && ((distance < 0) || (distance*distance < maximumDistanceSquared))) - { - - if (1)//m_fixContactNormalDirection) - { - ///@workaround for sticky convex collisions - //in some degenerate cases (usually when the use uses very small margins) - //the contact normal is pointing the wrong direction - //so fix it now (until we can deal with all degenerate cases in GJK and EPA) - //contact normals need to point from B to A in all cases, so we can simply check if the contact normal really points from B to A - //We like to use a dot product of the normal against the difference of the centroids, - //once the centroid is available in the API - //until then we use the center of the aabb to approximate the centroid - b3Vector3 posA = localTransA*hullA.m_localCenter; - b3Vector3 posB = localTransB*hullB.m_localCenter; - - - b3Vector3 diff = posA-posB; - if (diff.dot(normalInB) < 0.f) - normalInB *= -1.f; - } - gjkDetector->m_cachedSeparatingAxis = normalInB; - gjkDetector->m_cachedSeparatingDistance = distance; - - /*output.addContactPoint( - normalInB, - pointOnB+positionOffset, - distance); - */ - - static float maxPenetrationDistance = 0.f; - if (distance& verticesA, - const b3AlignedObjectArray& verticesB, - b3Scalar maximumDistanceSquared, - b3Vector3& resultSepNormal, - float& resultSepDistance, - b3Vector3& resultPointOnB); - -#endif //B3_GJK_PAIR_DETECTOR_H From dd2c7af2b2f3e06d3f2647457ac69d0e5e2ec3d4 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Fri, 29 Sep 2017 07:47:31 -0700 Subject: [PATCH 2/6] Update pybullet autogenerated C# bindings, with very basic example script that runs inside Unity 3D --- data/kuka_iiwa/model_free_base.urdf | 16 +- .../pybullet/unity3d/autogen/NativeMethods.cs | 1167 ++++++++++------- .../unity3d/examples/NewBehaviourScript.cs | 69 +- 3 files changed, 701 insertions(+), 551 deletions(-) diff --git a/data/kuka_iiwa/model_free_base.urdf b/data/kuka_iiwa/model_free_base.urdf index b87373346..3d66235c7 100644 --- a/data/kuka_iiwa/model_free_base.urdf +++ b/data/kuka_iiwa/model_free_base.urdf @@ -70,7 +70,7 @@ - + @@ -99,7 +99,7 @@ - + @@ -128,7 +128,7 @@ - + @@ -157,7 +157,7 @@ - + @@ -186,7 +186,7 @@ - + @@ -215,7 +215,7 @@ - + @@ -244,7 +244,7 @@ - + @@ -273,7 +273,7 @@ - + diff --git a/examples/pybullet/unity3d/autogen/NativeMethods.cs b/examples/pybullet/unity3d/autogen/NativeMethods.cs index 365cffa8c..29ec9f4f0 100644 --- a/examples/pybullet/unity3d/autogen/NativeMethods.cs +++ b/examples/pybullet/unity3d/autogen/NativeMethods.cs @@ -1,4 +1,11 @@ +using System.Collections; +using System.Collections.Generic; +using System.Runtime.InteropServices; +using System; + + + public partial class NativeConstants { /// PHYSICS_CLIENT_C_API_H -> @@ -14,8 +21,8 @@ public partial class NativeConstants { /// SHARED_MEMORY_KEY -> 12347 public const int SHARED_MEMORY_KEY = 12347; - /// SHARED_MEMORY_MAGIC_NUMBER -> 201708270 - public const int SHARED_MEMORY_MAGIC_NUMBER = 201708270; + /// SHARED_MEMORY_MAGIC_NUMBER -> 201709260 + public const int SHARED_MEMORY_MAGIC_NUMBER = 201709260; /// MAX_VR_BUTTONS -> 64 public const int MAX_VR_BUTTONS = 64; @@ -38,10 +45,20 @@ public partial class NativeConstants { /// VISUAL_SHAPE_MAX_PATH_LEN -> 1024 public const int VISUAL_SHAPE_MAX_PATH_LEN = 1024; + /// B3_MAX_PLUGIN_ARG_SIZE -> 128 + public const int B3_MAX_PLUGIN_ARG_SIZE = 128; + + /// B3_MAX_PLUGIN_ARG_TEXT_LEN -> 1024 + public const int B3_MAX_PLUGIN_ARG_TEXT_LEN = 1024; + /// Warning: Generation of Method Macros is not supported at this time /// B3_DECLARE_HANDLE -> "(name) typedef struct name##__ { int unused; } *name" public const string B3_DECLARE_HANDLE = "(name) typedef struct name##__ { int unused; } *name"; + /// B3_SHARED_API -> __declspec(dllexport) + /// Error generating expression: Error generating function call. Operation not implemented + public const string B3_SHARED_API = "__declspec(dllexport)"; + /// PHYSICS_CLIENT_SHARED_MEMORY_H -> /// Error generating expression: Value cannot be null. ///Parameter name: node @@ -177,6 +194,8 @@ public enum EnumSharedMemoryClientCommand { CMD_SET_ADDITIONAL_SEARCH_PATH, + CMD_CUSTOM_COMMAND, + CMD_MAX_CLIENT_COMMANDS, } @@ -355,6 +374,10 @@ public enum EnumSharedMemoryServerStatus { CMD_CHANGE_TEXTURE_COMMAND_FAILED, + CMD_CUSTOM_COMMAND_COMPLETED, + + CMD_CUSTOM_COMMAND_FAILED, + CMD_MAX_SERVER_COMMANDS, } @@ -498,6 +521,12 @@ public struct b3UserConstraint { /// int public int m_gearAuxLink; + + /// double + public double m_relativePositionTarget; + + /// double + public double m_erp; } [System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] @@ -941,6 +970,9 @@ public enum eLinkStateFlags { /// ACTUAL_STATE_COMPUTE_LINKVELOCITY -> 1 ACTUAL_STATE_COMPUTE_LINKVELOCITY = 1, + + /// ACTUAL_STATE_COMPUTE_FORWARD_KINEMATICS -> 2 + ACTUAL_STATE_COMPUTE_FORWARD_KINEMATICS = 2, } [System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] @@ -1119,80 +1151,121 @@ public enum eStateLoggingFlags { STATE_LOG_JOINT_TORQUES = (eStateLoggingFlags.STATE_LOG_JOINT_MOTOR_TORQUES + eStateLoggingFlags.STATE_LOG_JOINT_USER_TORQUES), } +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential, CharSet=System.Runtime.InteropServices.CharSet.Ansi)] +public struct b3PluginArguments { + + /// char[1024] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst=1024)] + public string m_text; + + /// int + public int m_numInts; + + /// int[128] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=128, ArraySubType=System.Runtime.InteropServices.UnmanagedType.I4)] + public int[] m_ints; + + /// int + public int m_numFloats; + + /// int[128] + [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=128, ArraySubType=System.Runtime.InteropServices.UnmanagedType.I4)] + public int[] m_floats; +} +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3PhysicsClientHandle__ { + + /// int + public int unused; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3SharedMemoryCommandHandle__ { + + /// int + public int unused; +} + +[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)] +public struct b3SharedMemoryStatusHandle__ { + + /// int + public int unused; +} public partial class NativeMethods { /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///key: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ConnectSharedMemory")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ConnectSharedMemory")] public static extern System.IntPtr b3ConnectSharedMemory(int key) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///key: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ConnectSharedMemory2")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ConnectSharedMemory2")] public static extern System.IntPtr b3ConnectSharedMemory2(int key) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ConnectPhysicsDirect")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ConnectPhysicsDirect")] public static extern System.IntPtr b3ConnectPhysicsDirect() ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///argc: int ///argv: char** - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnect")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnect")] public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnect(int argc, ref System.IntPtr argv) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///argc: int ///argv: char** - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnectSharedMemory")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnectSharedMemory")] public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnectSharedMemory(int argc, ref System.IntPtr argv) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///argc: int ///argv: char** - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnectMainThread")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnectMainThread")] public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, ref System.IntPtr argv) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///argc: int ///argv: char** - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory")] public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory(int argc, ref System.IntPtr argv) ; /// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///guiHelperPtr: void* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect")] public static extern System.IntPtr b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(System.IntPtr guiHelperPtr) ; /// Return Type: void ///clientHandle: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InProcessRenderSceneInternal")] -public static extern void b3InProcessRenderSceneInternal(System.IntPtr clientHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InProcessRenderSceneInternal")] +public static extern void b3InProcessRenderSceneInternal(IntPtr clientHandle) ; /// Return Type: void ///clientHandle: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///debugDrawMode: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InProcessDebugDrawInternal")] -public static extern void b3InProcessDebugDrawInternal(System.IntPtr clientHandle, int debugDrawMode) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InProcessDebugDrawInternal")] +public static extern void b3InProcessDebugDrawInternal(IntPtr clientHandle, int debugDrawMode) ; /// Return Type: int ///clientHandle: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///x: float ///y: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InProcessMouseMoveCallback")] -public static extern int b3InProcessMouseMoveCallback(System.IntPtr clientHandle, float x, float y) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InProcessMouseMoveCallback")] +public static extern int b3InProcessMouseMoveCallback(IntPtr clientHandle, float x, float y) ; /// Return Type: int @@ -1201,60 +1274,114 @@ public static extern int b3InProcessMouseMoveCallback(System.IntPtr clientHandl ///state: int ///x: float ///y: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InProcessMouseButtonCallback")] -public static extern int b3InProcessMouseButtonCallback(System.IntPtr clientHandle, int button, int state, float x, float y) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InProcessMouseButtonCallback")] +public static extern int b3InProcessMouseButtonCallback(IntPtr clientHandle, int button, int state, float x, float y) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3DisconnectSharedMemory")] -public static extern void b3DisconnectSharedMemory(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3DisconnectSharedMemory")] +public static extern void b3DisconnectSharedMemory(IntPtr physClient) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CanSubmitCommand")] -public static extern int b3CanSubmitCommand(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CanSubmitCommand")] +public static extern int b3CanSubmitCommand(IntPtr physClient) ; /// Return Type: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SubmitClientCommandAndWaitStatus")] -public static extern System.IntPtr b3SubmitClientCommandAndWaitStatus(System.IntPtr physClient, System.IntPtr commandHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SubmitClientCommandAndWaitStatus")] +public static extern System.IntPtr b3SubmitClientCommandAndWaitStatus(IntPtr physClient, IntPtr commandHandle) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SubmitClientCommand")] -public static extern int b3SubmitClientCommand(System.IntPtr physClient, System.IntPtr commandHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SubmitClientCommand")] +public static extern int b3SubmitClientCommand(IntPtr physClient, IntPtr commandHandle) ; /// Return Type: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ProcessServerStatus")] -public static extern System.IntPtr b3ProcessServerStatus(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ProcessServerStatus")] +public static extern System.IntPtr b3ProcessServerStatus(IntPtr physClient) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusType")] -public static extern int b3GetStatusType(System.IntPtr statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusType")] +public static extern int b3GetStatusType(IntPtr statusHandle) ; + + + /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCustomCommand")] +public static extern System.IntPtr b3CreateCustomCommand(IntPtr physClient) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///pluginPath: char* + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CustomCommandLoadPlugin")] +public static extern void b3CustomCommandLoadPlugin(IntPtr commandHandle, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string pluginPath) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusPluginUniqueId")] +public static extern int b3GetStatusPluginUniqueId(IntPtr statusHandle) ; + + + /// Return Type: int + ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusPluginCommandResult")] +public static extern int b3GetStatusPluginCommandResult(IntPtr statusHandle) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///pluginUniqueId: int + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CustomCommandUnloadPlugin")] +public static extern void b3CustomCommandUnloadPlugin(IntPtr commandHandle, int pluginUniqueId) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///pluginUniqueId: int + ///textArguments: char* + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CustomCommandExecutePluginCommand")] +public static extern void b3CustomCommandExecutePluginCommand(IntPtr commandHandle, int pluginUniqueId, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string textArguments) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///intVal: int + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CustomCommandExecuteAddIntArgument")] +public static extern void b3CustomCommandExecuteAddIntArgument(IntPtr commandHandle, int intVal) ; + + + /// Return Type: void + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///floatVal: float + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CustomCommandExecuteAddFloatArgument")] +public static extern void b3CustomCommandExecuteAddFloatArgument(IntPtr commandHandle, float floatVal) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///bodyIndicesOut: int* ///bodyIndicesCapacity: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusBodyIndices")] -public static extern int b3GetStatusBodyIndices(System.IntPtr statusHandle, ref int bodyIndicesOut, int bodyIndicesCapacity) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusBodyIndices")] +public static extern int b3GetStatusBodyIndices(IntPtr statusHandle, ref int bodyIndicesOut, int bodyIndicesCapacity) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusBodyIndex")] -public static extern int b3GetStatusBodyIndex(System.IntPtr statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusBodyIndex")] +public static extern int b3GetStatusBodyIndex(IntPtr statusHandle) ; /// Return Type: int @@ -1266,15 +1393,15 @@ public static extern int b3GetStatusBodyIndex(System.IntPtr statusHandle) ; ///actualStateQ: double** ///actualStateQdot: double** ///jointReactionForces: double** - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusActualState")] -public static extern int b3GetStatusActualState(System.IntPtr statusHandle, ref int bodyUniqueId, ref int numDegreeOfFreedomQ, ref int numDegreeOfFreedomU, ref System.IntPtr rootLocalInertialFrame, ref System.IntPtr actualStateQ, ref System.IntPtr actualStateQdot, ref System.IntPtr jointReactionForces) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusActualState")] +public static extern int b3GetStatusActualState(IntPtr statusHandle, ref int bodyUniqueId, ref int numDegreeOfFreedomQ, ref int numDegreeOfFreedomU, ref System.IntPtr rootLocalInertialFrame, ref System.IntPtr actualStateQ, ref System.IntPtr actualStateQdot, ref System.IntPtr jointReactionForces) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCollisionInfoCommandInit")] -public static extern System.IntPtr b3RequestCollisionInfoCommandInit(System.IntPtr physClient, int bodyUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCollisionInfoCommandInit")] +public static extern System.IntPtr b3RequestCollisionInfoCommandInit(IntPtr physClient, int bodyUniqueId) ; /// Return Type: int @@ -1282,49 +1409,49 @@ public static extern System.IntPtr b3RequestCollisionInfoCommandInit(System.Int ///linkIndex: int ///aabbMin: double* ///aabbMax: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusAABB")] -public static extern int b3GetStatusAABB(System.IntPtr statusHandle, int linkIndex, ref double aabbMin, ref double aabbMax) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusAABB")] +public static extern int b3GetStatusAABB(IntPtr statusHandle, int linkIndex, ref double aabbMin, ref double aabbMax) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitSyncBodyInfoCommand")] -public static extern System.IntPtr b3InitSyncBodyInfoCommand(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitSyncBodyInfoCommand")] +public static extern System.IntPtr b3InitSyncBodyInfoCommand(IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitRemoveBodyCommand")] -public static extern System.IntPtr b3InitRemoveBodyCommand(System.IntPtr physClient, int bodyUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitRemoveBodyCommand")] +public static extern System.IntPtr b3InitRemoveBodyCommand(IntPtr physClient, int bodyUniqueId) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetNumBodies")] -public static extern int b3GetNumBodies(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetNumBodies")] +public static extern int b3GetNumBodies(IntPtr physClient) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///serialIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetBodyUniqueId")] -public static extern int b3GetBodyUniqueId(System.IntPtr physClient, int serialIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetBodyUniqueId")] +public static extern int b3GetBodyUniqueId(IntPtr physClient, int serialIndex) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int ///info: b3BodyInfo* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetBodyInfo")] -public static extern int b3GetBodyInfo(System.IntPtr physClient, int bodyUniqueId, ref b3BodyInfo info) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetBodyInfo")] +public static extern int b3GetBodyInfo(IntPtr physClient, int bodyUniqueId, ref b3BodyInfo info) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - ///bodyIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetNumJoints")] -public static extern int b3GetNumJoints(System.IntPtr physClient, int bodyIndex) ; + ///bodyId: int + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetNumJoints")] +public static extern int b3GetNumJoints(IntPtr physClient, int bodyId) ; /// Return Type: int @@ -1332,29 +1459,29 @@ public static extern int b3GetNumJoints(System.IntPtr physClient, int bodyIndex ///bodyIndex: int ///jointIndex: int ///info: b3JointInfo* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetJointInfo")] -public static extern int b3GetJointInfo(System.IntPtr physClient, int bodyIndex, int jointIndex, ref b3JointInfo info) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetJointInfo")] +public static extern int b3GetJointInfo(IntPtr physClient, int bodyIndex, int jointIndex, ref b3JointInfo info) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int ///linkIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetDynamicsInfoCommandInit")] -public static extern System.IntPtr b3GetDynamicsInfoCommandInit(System.IntPtr physClient, int bodyUniqueId, int linkIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetDynamicsInfoCommandInit")] +public static extern System.IntPtr b3GetDynamicsInfoCommandInit(IntPtr physClient, int bodyUniqueId, int linkIndex) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///info: b3DynamicsInfo* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetDynamicsInfo")] -public static extern int b3GetDynamicsInfo(System.IntPtr statusHandle, ref b3DynamicsInfo info) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetDynamicsInfo")] +public static extern int b3GetDynamicsInfo(IntPtr statusHandle, ref b3DynamicsInfo info) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitChangeDynamicsInfo")] -public static extern System.IntPtr b3InitChangeDynamicsInfo(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeDynamicsInfo")] +public static extern System.IntPtr b3InitChangeDynamicsInfo(IntPtr physClient) ; /// Return Type: int @@ -1362,8 +1489,8 @@ public static extern System.IntPtr b3InitChangeDynamicsInfo(System.IntPtr physC ///bodyUniqueId: int ///linkIndex: int ///mass: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetMass")] -public static extern int b3ChangeDynamicsInfoSetMass(System.IntPtr commandHandle, int bodyUniqueId, int linkIndex, double mass) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetMass")] +public static extern int b3ChangeDynamicsInfoSetMass(IntPtr commandHandle, int bodyUniqueId, int linkIndex, double mass) ; /// Return Type: int @@ -1371,8 +1498,8 @@ public static extern int b3ChangeDynamicsInfoSetMass(System.IntPtr commandHandl ///bodyUniqueId: int ///linkIndex: int ///lateralFriction: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetLateralFriction")] -public static extern int b3ChangeDynamicsInfoSetLateralFriction(System.IntPtr commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetLateralFriction")] +public static extern int b3ChangeDynamicsInfoSetLateralFriction(IntPtr commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction) ; /// Return Type: int @@ -1380,8 +1507,8 @@ public static extern int b3ChangeDynamicsInfoSetLateralFriction(System.IntPtr c ///bodyUniqueId: int ///linkIndex: int ///friction: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetSpinningFriction")] -public static extern int b3ChangeDynamicsInfoSetSpinningFriction(System.IntPtr commandHandle, int bodyUniqueId, int linkIndex, double friction) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetSpinningFriction")] +public static extern int b3ChangeDynamicsInfoSetSpinningFriction(IntPtr commandHandle, int bodyUniqueId, int linkIndex, double friction) ; /// Return Type: int @@ -1389,8 +1516,8 @@ public static extern int b3ChangeDynamicsInfoSetSpinningFriction(System.IntPtr ///bodyUniqueId: int ///linkIndex: int ///friction: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetRollingFriction")] -public static extern int b3ChangeDynamicsInfoSetRollingFriction(System.IntPtr commandHandle, int bodyUniqueId, int linkIndex, double friction) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetRollingFriction")] +public static extern int b3ChangeDynamicsInfoSetRollingFriction(IntPtr commandHandle, int bodyUniqueId, int linkIndex, double friction) ; /// Return Type: int @@ -1398,24 +1525,24 @@ public static extern int b3ChangeDynamicsInfoSetRollingFriction(System.IntPtr c ///bodyUniqueId: int ///linkIndex: int ///restitution: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetRestitution")] -public static extern int b3ChangeDynamicsInfoSetRestitution(System.IntPtr commandHandle, int bodyUniqueId, int linkIndex, double restitution) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetRestitution")] +public static extern int b3ChangeDynamicsInfoSetRestitution(IntPtr commandHandle, int bodyUniqueId, int linkIndex, double restitution) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueId: int ///linearDamping: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetLinearDamping")] -public static extern int b3ChangeDynamicsInfoSetLinearDamping(System.IntPtr commandHandle, int bodyUniqueId, double linearDamping) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetLinearDamping")] +public static extern int b3ChangeDynamicsInfoSetLinearDamping(IntPtr commandHandle, int bodyUniqueId, double linearDamping) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueId: int ///angularDamping: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetAngularDamping")] -public static extern int b3ChangeDynamicsInfoSetAngularDamping(System.IntPtr commandHandle, int bodyUniqueId, double angularDamping) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetAngularDamping")] +public static extern int b3ChangeDynamicsInfoSetAngularDamping(IntPtr commandHandle, int bodyUniqueId, double angularDamping) ; /// Return Type: int @@ -1424,8 +1551,8 @@ public static extern int b3ChangeDynamicsInfoSetAngularDamping(System.IntPtr co ///linkIndex: int ///contactStiffness: double ///contactDamping: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetContactStiffnessAndDamping")] -public static extern int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(System.IntPtr commandHandle, int bodyUniqueId, int linkIndex, double contactStiffness, double contactDamping) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetContactStiffnessAndDamping")] +public static extern int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(IntPtr commandHandle, int bodyUniqueId, int linkIndex, double contactStiffness, double contactDamping) ; /// Return Type: int @@ -1433,8 +1560,8 @@ public static extern int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(Syst ///bodyUniqueId: int ///linkIndex: int ///frictionAnchor: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ChangeDynamicsInfoSetFrictionAnchor")] -public static extern int b3ChangeDynamicsInfoSetFrictionAnchor(System.IntPtr commandHandle, int bodyUniqueId, int linkIndex, int frictionAnchor) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ChangeDynamicsInfoSetFrictionAnchor")] +public static extern int b3ChangeDynamicsInfoSetFrictionAnchor(IntPtr commandHandle, int bodyUniqueId, int linkIndex, int frictionAnchor) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -1444,112 +1571,126 @@ public static extern int b3ChangeDynamicsInfoSetFrictionAnchor(System.IntPtr co ///childBodyIndex: int ///childJointIndex: int ///info: b3JointInfo* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitCreateUserConstraintCommand")] -public static extern System.IntPtr b3InitCreateUserConstraintCommand(System.IntPtr physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, ref b3JointInfo info) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitCreateUserConstraintCommand")] +public static extern System.IntPtr b3InitCreateUserConstraintCommand(IntPtr physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, ref b3JointInfo info) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusUserConstraintUniqueId")] -public static extern int b3GetStatusUserConstraintUniqueId(System.IntPtr statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusUserConstraintUniqueId")] +public static extern int b3GetStatusUserConstraintUniqueId(IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///userConstraintUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitChangeUserConstraintCommand")] -public static extern System.IntPtr b3InitChangeUserConstraintCommand(System.IntPtr physClient, int userConstraintUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintCommand")] +public static extern System.IntPtr b3InitChangeUserConstraintCommand(IntPtr physClient, int userConstraintUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointChildPivot: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitChangeUserConstraintSetPivotInB")] -public static extern int b3InitChangeUserConstraintSetPivotInB(System.IntPtr commandHandle, ref double jointChildPivot) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintSetPivotInB")] +public static extern int b3InitChangeUserConstraintSetPivotInB(IntPtr commandHandle, ref double jointChildPivot) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointChildFrameOrn: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitChangeUserConstraintSetFrameInB")] -public static extern int b3InitChangeUserConstraintSetFrameInB(System.IntPtr commandHandle, ref double jointChildFrameOrn) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintSetFrameInB")] +public static extern int b3InitChangeUserConstraintSetFrameInB(IntPtr commandHandle, ref double jointChildFrameOrn) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///maxAppliedForce: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitChangeUserConstraintSetMaxForce")] -public static extern int b3InitChangeUserConstraintSetMaxForce(System.IntPtr commandHandle, double maxAppliedForce) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintSetMaxForce")] +public static extern int b3InitChangeUserConstraintSetMaxForce(IntPtr commandHandle, double maxAppliedForce) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///gearRatio: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitChangeUserConstraintSetGearRatio")] -public static extern int b3InitChangeUserConstraintSetGearRatio(System.IntPtr commandHandle, double gearRatio) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintSetGearRatio")] +public static extern int b3InitChangeUserConstraintSetGearRatio(IntPtr commandHandle, double gearRatio) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///gearAuxLink: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitChangeUserConstraintSetGearAuxLink")] -public static extern int b3InitChangeUserConstraintSetGearAuxLink(System.IntPtr commandHandle, int gearAuxLink) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintSetGearAuxLink")] +public static extern int b3InitChangeUserConstraintSetGearAuxLink(IntPtr commandHandle, int gearAuxLink) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///relativePositionTarget: double + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintSetRelativePositionTarget")] +public static extern int b3InitChangeUserConstraintSetRelativePositionTarget(IntPtr commandHandle, double relativePositionTarget) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///erp: double + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitChangeUserConstraintSetERP")] +public static extern int b3InitChangeUserConstraintSetERP(IntPtr commandHandle, double erp) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///userConstraintUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitRemoveUserConstraintCommand")] -public static extern System.IntPtr b3InitRemoveUserConstraintCommand(System.IntPtr physClient, int userConstraintUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitRemoveUserConstraintCommand")] +public static extern System.IntPtr b3InitRemoveUserConstraintCommand(IntPtr physClient, int userConstraintUniqueId) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetNumUserConstraints")] -public static extern int b3GetNumUserConstraints(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetNumUserConstraints")] +public static extern int b3GetNumUserConstraints(IntPtr physClient) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///constraintUniqueId: int ///info: b3UserConstraint* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetUserConstraintInfo")] -public static extern int b3GetUserConstraintInfo(System.IntPtr physClient, int constraintUniqueId, ref b3UserConstraint info) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetUserConstraintInfo")] +public static extern int b3GetUserConstraintInfo(IntPtr physClient, int constraintUniqueId, ref b3UserConstraint info) ; /// Return Type: int ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///serialIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetUserConstraintId")] -public static extern int b3GetUserConstraintId(System.IntPtr physClient, int serialIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetUserConstraintId")] +public static extern int b3GetUserConstraintId(IntPtr physClient, int serialIndex) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///debugMode: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitRequestDebugLinesCommand")] -public static extern System.IntPtr b3InitRequestDebugLinesCommand(System.IntPtr physClient, int debugMode) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitRequestDebugLinesCommand")] +public static extern System.IntPtr b3InitRequestDebugLinesCommand(IntPtr physClient, int debugMode) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///lines: b3DebugLines* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetDebugLines")] -public static extern void b3GetDebugLines(System.IntPtr physClient, ref b3DebugLines lines) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetDebugLines")] +public static extern void b3GetDebugLines(IntPtr physClient, ref b3DebugLines lines) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitConfigureOpenGLVisualizer")] -public static extern System.IntPtr b3InitConfigureOpenGLVisualizer(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitConfigureOpenGLVisualizer")] +public static extern System.IntPtr b3InitConfigureOpenGLVisualizer(IntPtr physClient) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///flag: int ///enabled: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ConfigureOpenGLVisualizerSetVisualizationFlags")] -public static extern void b3ConfigureOpenGLVisualizerSetVisualizationFlags(System.IntPtr commandHandle, int flag, int enabled) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ConfigureOpenGLVisualizerSetVisualizationFlags")] +public static extern void b3ConfigureOpenGLVisualizerSetVisualizationFlags(IntPtr commandHandle, int flag, int enabled) ; /// Return Type: void @@ -1558,21 +1699,21 @@ public static extern void b3ConfigureOpenGLVisualizerSetVisualizationFlags(Syst ///cameraPitch: float ///cameraYaw: float ///cameraTargetPosition: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ConfigureOpenGLVisualizerSetViewMatrix")] -public static extern void b3ConfigureOpenGLVisualizerSetViewMatrix(System.IntPtr commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, ref float cameraTargetPosition) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ConfigureOpenGLVisualizerSetViewMatrix")] +public static extern void b3ConfigureOpenGLVisualizerSetViewMatrix(IntPtr commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, ref float cameraTargetPosition) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitRequestOpenGLVisualizerCameraCommand")] -public static extern System.IntPtr b3InitRequestOpenGLVisualizerCameraCommand(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitRequestOpenGLVisualizerCameraCommand")] +public static extern System.IntPtr b3InitRequestOpenGLVisualizerCameraCommand(IntPtr physClient) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///camera: b3OpenGLVisualizerCameraInfo* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusOpenGLVisualizerCamera")] -public static extern int b3GetStatusOpenGLVisualizerCamera(System.IntPtr statusHandle, ref b3OpenGLVisualizerCameraInfo camera) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusOpenGLVisualizerCamera")] +public static extern int b3GetStatusOpenGLVisualizerCamera(IntPtr statusHandle, ref b3OpenGLVisualizerCameraInfo camera) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -1582,8 +1723,8 @@ public static extern int b3GetStatusOpenGLVisualizerCamera(System.IntPtr status ///colorRGB: double* ///lineWidth: double ///lifeTime: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitUserDebugDrawAddLine3D")] -public static extern System.IntPtr b3InitUserDebugDrawAddLine3D(System.IntPtr physClient, ref double fromXYZ, ref double toXYZ, ref double colorRGB, double lineWidth, double lifeTime) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitUserDebugDrawAddLine3D")] +public static extern System.IntPtr b3InitUserDebugDrawAddLine3D(IntPtr physClient, ref double fromXYZ, ref double toXYZ, ref double colorRGB, double lineWidth, double lifeTime) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -1593,30 +1734,30 @@ public static extern System.IntPtr b3InitUserDebugDrawAddLine3D(System.IntPtr p ///colorRGB: double* ///textSize: double ///lifeTime: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitUserDebugDrawAddText3D")] -public static extern System.IntPtr b3InitUserDebugDrawAddText3D(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string txt, ref double positionXYZ, ref double colorRGB, double textSize, double lifeTime) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitUserDebugDrawAddText3D")] +public static extern System.IntPtr b3InitUserDebugDrawAddText3D(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string txt, ref double positionXYZ, ref double colorRGB, double textSize, double lifeTime) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///optionFlags: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3UserDebugTextSetOptionFlags")] -public static extern void b3UserDebugTextSetOptionFlags(System.IntPtr commandHandle, int optionFlags) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3UserDebugTextSetOptionFlags")] +public static extern void b3UserDebugTextSetOptionFlags(IntPtr commandHandle, int optionFlags) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///orientation: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3UserDebugTextSetOrientation")] -public static extern void b3UserDebugTextSetOrientation(System.IntPtr commandHandle, ref double orientation) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3UserDebugTextSetOrientation")] +public static extern void b3UserDebugTextSetOrientation(IntPtr commandHandle, ref double orientation) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///objectUniqueId: int ///linkIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3UserDebugItemSetParentObject")] -public static extern void b3UserDebugItemSetParentObject(System.IntPtr commandHandle, int objectUniqueId, int linkIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3UserDebugItemSetParentObject")] +public static extern void b3UserDebugItemSetParentObject(IntPtr commandHandle, int objectUniqueId, int linkIndex) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -1625,41 +1766,41 @@ public static extern void b3UserDebugItemSetParentObject(System.IntPtr commandH ///rangeMin: double ///rangeMax: double ///startValue: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitUserDebugAddParameter")] -public static extern System.IntPtr b3InitUserDebugAddParameter(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string txt, double rangeMin, double rangeMax, double startValue) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitUserDebugAddParameter")] +public static extern System.IntPtr b3InitUserDebugAddParameter(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string txt, double rangeMin, double rangeMax, double startValue) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///debugItemUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitUserDebugReadParameter")] -public static extern System.IntPtr b3InitUserDebugReadParameter(System.IntPtr physClient, int debugItemUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitUserDebugReadParameter")] +public static extern System.IntPtr b3InitUserDebugReadParameter(IntPtr physClient, int debugItemUniqueId) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///paramValue: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusDebugParameterValue")] -public static extern int b3GetStatusDebugParameterValue(System.IntPtr statusHandle, ref double paramValue) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusDebugParameterValue")] +public static extern int b3GetStatusDebugParameterValue(IntPtr statusHandle, ref double paramValue) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///debugItemUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitUserDebugDrawRemove")] -public static extern System.IntPtr b3InitUserDebugDrawRemove(System.IntPtr physClient, int debugItemUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitUserDebugDrawRemove")] +public static extern System.IntPtr b3InitUserDebugDrawRemove(IntPtr physClient, int debugItemUniqueId) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitUserDebugDrawRemoveAll")] -public static extern System.IntPtr b3InitUserDebugDrawRemoveAll(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitUserDebugDrawRemoveAll")] +public static extern System.IntPtr b3InitUserDebugDrawRemoveAll(IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitDebugDrawingCommand")] -public static extern System.IntPtr b3InitDebugDrawingCommand(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitDebugDrawingCommand")] +public static extern System.IntPtr b3InitDebugDrawingCommand(IntPtr physClient) ; /// Return Type: void @@ -1667,107 +1808,107 @@ public static extern System.IntPtr b3InitDebugDrawingCommand(System.IntPtr phys ///objectUniqueId: int ///linkIndex: int ///objectColorRGB: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetDebugObjectColor")] -public static extern void b3SetDebugObjectColor(System.IntPtr commandHandle, int objectUniqueId, int linkIndex, ref double objectColorRGB) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetDebugObjectColor")] +public static extern void b3SetDebugObjectColor(IntPtr commandHandle, int objectUniqueId, int linkIndex, ref double objectColorRGB) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///objectUniqueId: int ///linkIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RemoveDebugObjectColor")] -public static extern void b3RemoveDebugObjectColor(System.IntPtr commandHandle, int objectUniqueId, int linkIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RemoveDebugObjectColor")] +public static extern void b3RemoveDebugObjectColor(IntPtr commandHandle, int objectUniqueId, int linkIndex) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetDebugItemUniqueId")] -public static extern int b3GetDebugItemUniqueId(System.IntPtr statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetDebugItemUniqueId")] +public static extern int b3GetDebugItemUniqueId(IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitRequestCameraImage")] -public static extern System.IntPtr b3InitRequestCameraImage(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitRequestCameraImage")] +public static extern System.IntPtr b3InitRequestCameraImage(IntPtr physClient) ; /// Return Type: void - ///command: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///viewMatrix: float* ///projectionMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetCameraMatrices")] -public static extern void b3RequestCameraImageSetCameraMatrices(System.IntPtr command, ref float viewMatrix, ref float projectionMatrix) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetCameraMatrices")] +public static extern void b3RequestCameraImageSetCameraMatrices(IntPtr commandHandle, ref float viewMatrix, ref float projectionMatrix) ; /// Return Type: void - ///command: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///width: int ///height: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetPixelResolution")] -public static extern void b3RequestCameraImageSetPixelResolution(System.IntPtr command, int width, int height) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetPixelResolution")] +public static extern void b3RequestCameraImageSetPixelResolution(IntPtr commandHandle, int width, int height) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightDirection: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetLightDirection")] -public static extern void b3RequestCameraImageSetLightDirection(System.IntPtr commandHandle, ref float lightDirection) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetLightDirection")] +public static extern void b3RequestCameraImageSetLightDirection(IntPtr commandHandle, ref float lightDirection) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightColor: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetLightColor")] -public static extern void b3RequestCameraImageSetLightColor(System.IntPtr commandHandle, ref float lightColor) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetLightColor")] +public static extern void b3RequestCameraImageSetLightColor(IntPtr commandHandle, ref float lightColor) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightDistance: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetLightDistance")] -public static extern void b3RequestCameraImageSetLightDistance(System.IntPtr commandHandle, float lightDistance) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetLightDistance")] +public static extern void b3RequestCameraImageSetLightDistance(IntPtr commandHandle, float lightDistance) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightAmbientCoeff: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetLightAmbientCoeff")] -public static extern void b3RequestCameraImageSetLightAmbientCoeff(System.IntPtr commandHandle, float lightAmbientCoeff) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetLightAmbientCoeff")] +public static extern void b3RequestCameraImageSetLightAmbientCoeff(IntPtr commandHandle, float lightAmbientCoeff) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightDiffuseCoeff: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetLightDiffuseCoeff")] -public static extern void b3RequestCameraImageSetLightDiffuseCoeff(System.IntPtr commandHandle, float lightDiffuseCoeff) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetLightDiffuseCoeff")] +public static extern void b3RequestCameraImageSetLightDiffuseCoeff(IntPtr commandHandle, float lightDiffuseCoeff) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///lightSpecularCoeff: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetLightSpecularCoeff")] -public static extern void b3RequestCameraImageSetLightSpecularCoeff(System.IntPtr commandHandle, float lightSpecularCoeff) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetLightSpecularCoeff")] +public static extern void b3RequestCameraImageSetLightSpecularCoeff(IntPtr commandHandle, float lightSpecularCoeff) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///hasShadow: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetShadow")] -public static extern void b3RequestCameraImageSetShadow(System.IntPtr commandHandle, int hasShadow) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetShadow")] +public static extern void b3RequestCameraImageSetShadow(IntPtr commandHandle, int hasShadow) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///renderer: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSelectRenderer")] -public static extern void b3RequestCameraImageSelectRenderer(System.IntPtr commandHandle, int renderer) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSelectRenderer")] +public static extern void b3RequestCameraImageSelectRenderer(IntPtr commandHandle, int renderer) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///imageData: b3CameraImageData* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetCameraImageData")] -public static extern void b3GetCameraImageData(System.IntPtr physClient, ref b3CameraImageData imageData) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetCameraImageData")] +public static extern void b3GetCameraImageData(IntPtr physClient, ref b3CameraImageData imageData) ; /// Return Type: void @@ -1775,7 +1916,7 @@ public static extern void b3GetCameraImageData(System.IntPtr physClient, ref b3 ///cameraTargetPosition: float* ///cameraUp: float* ///viewMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ComputeViewMatrixFromPositions")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ComputeViewMatrixFromPositions")] public static extern void b3ComputeViewMatrixFromPositions(ref float cameraPosition, ref float cameraTargetPosition, ref float cameraUp, ref float viewMatrix) ; @@ -1787,7 +1928,7 @@ public static extern void b3ComputeViewMatrixFromPositions(ref float cameraPosi ///roll: float ///upAxis: int ///viewMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ComputeViewMatrixFromYawPitchRoll")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ComputeViewMatrixFromYawPitchRoll")] public static extern void b3ComputeViewMatrixFromYawPitchRoll(ref float cameraTargetPosition, float distance, float yaw, float pitch, float roll, int upAxis, ref float viewMatrix) ; @@ -1796,7 +1937,7 @@ public static extern void b3ComputeViewMatrixFromYawPitchRoll(ref float cameraT ///cameraPosition: float* ///cameraTargetPosition: float* ///cameraUp: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ComputePositionFromViewMatrix")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ComputePositionFromViewMatrix")] public static extern void b3ComputePositionFromViewMatrix(ref float viewMatrix, ref float cameraPosition, ref float cameraTargetPosition, ref float cameraUp) ; @@ -1808,7 +1949,7 @@ public static extern void b3ComputePositionFromViewMatrix(ref float viewMatrix, ///nearVal: float ///farVal: float ///projectionMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ComputeProjectionMatrix")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ComputeProjectionMatrix")] public static extern void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, float nearVal, float farVal, ref float projectionMatrix) ; @@ -1818,17 +1959,17 @@ public static extern void b3ComputeProjectionMatrix(float left, float right, fl ///nearVal: float ///farVal: float ///projectionMatrix: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ComputeProjectionMatrixFOV")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ComputeProjectionMatrixFOV")] public static extern void b3ComputeProjectionMatrixFOV(float fov, float aspect, float nearVal, float farVal, ref float projectionMatrix) ; /// Return Type: void - ///command: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///cameraPosition: float* ///cameraTargetPosition: float* ///cameraUp: float* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetViewMatrix")] -public static extern void b3RequestCameraImageSetViewMatrix(System.IntPtr command, ref float cameraPosition, ref float cameraTargetPosition, ref float cameraUp) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetViewMatrix")] +public static extern void b3RequestCameraImageSetViewMatrix(IntPtr commandHandle, ref float cameraPosition, ref float cameraTargetPosition, ref float cameraUp) ; /// Return Type: void @@ -1839,161 +1980,161 @@ public static extern void b3RequestCameraImageSetViewMatrix(System.IntPtr comma ///pitch: float ///roll: float ///upAxis: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetViewMatrix2")] -public static extern void b3RequestCameraImageSetViewMatrix2(System.IntPtr commandHandle, ref float cameraTargetPosition, float distance, float yaw, float pitch, float roll, int upAxis) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetViewMatrix2")] +public static extern void b3RequestCameraImageSetViewMatrix2(IntPtr commandHandle, ref float cameraTargetPosition, float distance, float yaw, float pitch, float roll, int upAxis) ; /// Return Type: void - ///command: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///left: float ///right: float ///bottom: float ///top: float ///nearVal: float ///farVal: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetProjectionMatrix")] -public static extern void b3RequestCameraImageSetProjectionMatrix(System.IntPtr command, float left, float right, float bottom, float top, float nearVal, float farVal) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetProjectionMatrix")] +public static extern void b3RequestCameraImageSetProjectionMatrix(IntPtr commandHandle, float left, float right, float bottom, float top, float nearVal, float farVal) ; /// Return Type: void - ///command: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///fov: float ///aspect: float ///nearVal: float ///farVal: float - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestCameraImageSetFOVProjectionMatrix")] -public static extern void b3RequestCameraImageSetFOVProjectionMatrix(System.IntPtr command, float fov, float aspect, float nearVal, float farVal) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestCameraImageSetFOVProjectionMatrix")] +public static extern void b3RequestCameraImageSetFOVProjectionMatrix(IntPtr commandHandle, float fov, float aspect, float nearVal, float farVal) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitRequestContactPointInformation")] -public static extern System.IntPtr b3InitRequestContactPointInformation(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitRequestContactPointInformation")] +public static extern System.IntPtr b3InitRequestContactPointInformation(IntPtr physClient) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueIdA: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetContactFilterBodyA")] -public static extern void b3SetContactFilterBodyA(System.IntPtr commandHandle, int bodyUniqueIdA) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetContactFilterBodyA")] +public static extern void b3SetContactFilterBodyA(IntPtr commandHandle, int bodyUniqueIdA) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueIdB: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetContactFilterBodyB")] -public static extern void b3SetContactFilterBodyB(System.IntPtr commandHandle, int bodyUniqueIdB) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetContactFilterBodyB")] +public static extern void b3SetContactFilterBodyB(IntPtr commandHandle, int bodyUniqueIdB) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexA: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetContactFilterLinkA")] -public static extern void b3SetContactFilterLinkA(System.IntPtr commandHandle, int linkIndexA) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetContactFilterLinkA")] +public static extern void b3SetContactFilterLinkA(IntPtr commandHandle, int linkIndexA) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexB: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetContactFilterLinkB")] -public static extern void b3SetContactFilterLinkB(System.IntPtr commandHandle, int linkIndexB) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetContactFilterLinkB")] +public static extern void b3SetContactFilterLinkB(IntPtr commandHandle, int linkIndexB) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - ///contactPointInfo: b3ContactInformation* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetContactPointInformation")] -public static extern void b3GetContactPointInformation(System.IntPtr physClient, ref b3ContactInformation contactPointInfo) ; + ///contactPointData: b3ContactInformation* + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetContactPointInformation")] +public static extern void b3GetContactPointInformation(IntPtr physClient, ref b3ContactInformation contactPointData) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitClosestDistanceQuery")] -public static extern System.IntPtr b3InitClosestDistanceQuery(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitClosestDistanceQuery")] +public static extern System.IntPtr b3InitClosestDistanceQuery(IntPtr physClient) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueIdA: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetClosestDistanceFilterBodyA")] -public static extern void b3SetClosestDistanceFilterBodyA(System.IntPtr commandHandle, int bodyUniqueIdA) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetClosestDistanceFilterBodyA")] +public static extern void b3SetClosestDistanceFilterBodyA(IntPtr commandHandle, int bodyUniqueIdA) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexA: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetClosestDistanceFilterLinkA")] -public static extern void b3SetClosestDistanceFilterLinkA(System.IntPtr commandHandle, int linkIndexA) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetClosestDistanceFilterLinkA")] +public static extern void b3SetClosestDistanceFilterLinkA(IntPtr commandHandle, int linkIndexA) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyUniqueIdB: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetClosestDistanceFilterBodyB")] -public static extern void b3SetClosestDistanceFilterBodyB(System.IntPtr commandHandle, int bodyUniqueIdB) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetClosestDistanceFilterBodyB")] +public static extern void b3SetClosestDistanceFilterBodyB(IntPtr commandHandle, int bodyUniqueIdB) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexB: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetClosestDistanceFilterLinkB")] -public static extern void b3SetClosestDistanceFilterLinkB(System.IntPtr commandHandle, int linkIndexB) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetClosestDistanceFilterLinkB")] +public static extern void b3SetClosestDistanceFilterLinkB(IntPtr commandHandle, int linkIndexB) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///distance: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetClosestDistanceThreshold")] -public static extern void b3SetClosestDistanceThreshold(System.IntPtr commandHandle, double distance) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetClosestDistanceThreshold")] +public static extern void b3SetClosestDistanceThreshold(IntPtr commandHandle, double distance) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///contactPointInfo: b3ContactInformation* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetClosestPointInformation")] -public static extern void b3GetClosestPointInformation(System.IntPtr physClient, ref b3ContactInformation contactPointInfo) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetClosestPointInformation")] +public static extern void b3GetClosestPointInformation(IntPtr physClient, ref b3ContactInformation contactPointInfo) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///aabbMin: double* ///aabbMax: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitAABBOverlapQuery")] -public static extern System.IntPtr b3InitAABBOverlapQuery(System.IntPtr physClient, ref double aabbMin, ref double aabbMax) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitAABBOverlapQuery")] +public static extern System.IntPtr b3InitAABBOverlapQuery(IntPtr physClient, ref double aabbMin, ref double aabbMax) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///data: b3AABBOverlapData* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetAABBOverlapResults")] -public static extern void b3GetAABBOverlapResults(System.IntPtr physClient, ref b3AABBOverlapData data) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetAABBOverlapResults")] +public static extern void b3GetAABBOverlapResults(IntPtr physClient, ref b3AABBOverlapData data) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueIdA: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitRequestVisualShapeInformation")] -public static extern System.IntPtr b3InitRequestVisualShapeInformation(System.IntPtr physClient, int bodyUniqueIdA) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitRequestVisualShapeInformation")] +public static extern System.IntPtr b3InitRequestVisualShapeInformation(IntPtr physClient, int bodyUniqueIdA) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///visualShapeInfo: b3VisualShapeInformation* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetVisualShapeInformation")] -public static extern void b3GetVisualShapeInformation(System.IntPtr physClient, ref b3VisualShapeInformation visualShapeInfo) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetVisualShapeInformation")] +public static extern void b3GetVisualShapeInformation(IntPtr physClient, ref b3VisualShapeInformation visualShapeInfo) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///filename: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitLoadTexture")] -public static extern System.IntPtr b3InitLoadTexture(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string filename) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitLoadTexture")] +public static extern System.IntPtr b3InitLoadTexture(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string filename) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusTextureUniqueId")] -public static extern int b3GetStatusTextureUniqueId(System.IntPtr statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusTextureUniqueId")] +public static extern int b3GetStatusTextureUniqueId(IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -2002,8 +2143,8 @@ public static extern int b3GetStatusTextureUniqueId(System.IntPtr statusHandle) ///width: int ///height: int ///rgbPixels: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateChangeTextureCommandInit")] -public static extern System.IntPtr b3CreateChangeTextureCommandInit(System.IntPtr physClient, int textureUniqueId, int width, int height, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string rgbPixels) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateChangeTextureCommandInit")] +public static extern System.IntPtr b3CreateChangeTextureCommandInit(IntPtr physClient, int textureUniqueId, int width, int height, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string rgbPixels) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -2012,28 +2153,28 @@ public static extern System.IntPtr b3CreateChangeTextureCommandInit(System.IntP ///jointIndex: int ///shapeIndex: int ///textureUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitUpdateVisualShape")] -public static extern System.IntPtr b3InitUpdateVisualShape(System.IntPtr physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitUpdateVisualShape")] +public static extern System.IntPtr b3InitUpdateVisualShape(IntPtr physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///rgbaColor: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3UpdateVisualShapeRGBAColor")] -public static extern void b3UpdateVisualShapeRGBAColor(System.IntPtr commandHandle, ref double rgbaColor) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3UpdateVisualShapeRGBAColor")] +public static extern void b3UpdateVisualShapeRGBAColor(IntPtr commandHandle, ref double rgbaColor) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///specularColor: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3UpdateVisualShapeSpecularColor")] -public static extern void b3UpdateVisualShapeSpecularColor(System.IntPtr commandHandle, ref double specularColor) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3UpdateVisualShapeSpecularColor")] +public static extern void b3UpdateVisualShapeSpecularColor(IntPtr commandHandle, ref double specularColor) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitPhysicsParamCommand")] -public static extern System.IntPtr b3InitPhysicsParamCommand(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitPhysicsParamCommand")] +public static extern System.IntPtr b3InitPhysicsParamCommand(IntPtr physClient) ; /// Return Type: int @@ -2041,132 +2182,132 @@ public static extern System.IntPtr b3InitPhysicsParamCommand(System.IntPtr phys ///gravx: double ///gravy: double ///gravz: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetGravity")] -public static extern int b3PhysicsParamSetGravity(System.IntPtr commandHandle, double gravx, double gravy, double gravz) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetGravity")] +public static extern int b3PhysicsParamSetGravity(IntPtr commandHandle, double gravx, double gravy, double gravz) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///timeStep: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetTimeStep")] -public static extern int b3PhysicsParamSetTimeStep(System.IntPtr commandHandle, double timeStep) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetTimeStep")] +public static extern int b3PhysicsParamSetTimeStep(IntPtr commandHandle, double timeStep) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///defaultContactERP: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetDefaultContactERP")] -public static extern int b3PhysicsParamSetDefaultContactERP(System.IntPtr commandHandle, double defaultContactERP) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetDefaultContactERP")] +public static extern int b3PhysicsParamSetDefaultContactERP(IntPtr commandHandle, double defaultContactERP) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///defaultNonContactERP: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetDefaultNonContactERP")] -public static extern int b3PhysicsParamSetDefaultNonContactERP(System.IntPtr commandHandle, double defaultNonContactERP) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetDefaultNonContactERP")] +public static extern int b3PhysicsParamSetDefaultNonContactERP(IntPtr commandHandle, double defaultNonContactERP) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///frictionERP: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetDefaultFrictionERP")] -public static extern int b3PhysicsParamSetDefaultFrictionERP(System.IntPtr commandHandle, double frictionERP) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetDefaultFrictionERP")] +public static extern int b3PhysicsParamSetDefaultFrictionERP(IntPtr commandHandle, double frictionERP) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numSubSteps: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetNumSubSteps")] -public static extern int b3PhysicsParamSetNumSubSteps(System.IntPtr commandHandle, int numSubSteps) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetNumSubSteps")] +public static extern int b3PhysicsParamSetNumSubSteps(IntPtr commandHandle, int numSubSteps) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///enableRealTimeSimulation: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetRealTimeSimulation")] -public static extern int b3PhysicsParamSetRealTimeSimulation(System.IntPtr commandHandle, int enableRealTimeSimulation) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetRealTimeSimulation")] +public static extern int b3PhysicsParamSetRealTimeSimulation(IntPtr commandHandle, int enableRealTimeSimulation) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numSolverIterations: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetNumSolverIterations")] -public static extern int b3PhysicsParamSetNumSolverIterations(System.IntPtr commandHandle, int numSolverIterations) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetNumSolverIterations")] +public static extern int b3PhysicsParamSetNumSolverIterations(IntPtr commandHandle, int numSolverIterations) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///filterMode: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetCollisionFilterMode")] -public static extern int b3PhysicsParamSetCollisionFilterMode(System.IntPtr commandHandle, int filterMode) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetCollisionFilterMode")] +public static extern int b3PhysicsParamSetCollisionFilterMode(IntPtr commandHandle, int filterMode) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///useSplitImpulse: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetUseSplitImpulse")] -public static extern int b3PhysicsParamSetUseSplitImpulse(System.IntPtr commandHandle, int useSplitImpulse) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetUseSplitImpulse")] +public static extern int b3PhysicsParamSetUseSplitImpulse(IntPtr commandHandle, int useSplitImpulse) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///splitImpulsePenetrationThreshold: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetSplitImpulsePenetrationThreshold")] -public static extern int b3PhysicsParamSetSplitImpulsePenetrationThreshold(System.IntPtr commandHandle, double splitImpulsePenetrationThreshold) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetSplitImpulsePenetrationThreshold")] +public static extern int b3PhysicsParamSetSplitImpulsePenetrationThreshold(IntPtr commandHandle, double splitImpulsePenetrationThreshold) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///contactBreakingThreshold: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetContactBreakingThreshold")] -public static extern int b3PhysicsParamSetContactBreakingThreshold(System.IntPtr commandHandle, double contactBreakingThreshold) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetContactBreakingThreshold")] +public static extern int b3PhysicsParamSetContactBreakingThreshold(IntPtr commandHandle, double contactBreakingThreshold) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///maxNumCmdPer1ms: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetMaxNumCommandsPer1ms")] -public static extern int b3PhysicsParamSetMaxNumCommandsPer1ms(System.IntPtr commandHandle, int maxNumCmdPer1ms) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetMaxNumCommandsPer1ms")] +public static extern int b3PhysicsParamSetMaxNumCommandsPer1ms(IntPtr commandHandle, int maxNumCmdPer1ms) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///enableFileCaching: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetEnableFileCaching")] -public static extern int b3PhysicsParamSetEnableFileCaching(System.IntPtr commandHandle, int enableFileCaching) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetEnableFileCaching")] +public static extern int b3PhysicsParamSetEnableFileCaching(IntPtr commandHandle, int enableFileCaching) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///restitutionVelocityThreshold: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetRestitutionVelocityThreshold")] -public static extern int b3PhysicsParamSetRestitutionVelocityThreshold(System.IntPtr commandHandle, double restitutionVelocityThreshold) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetRestitutionVelocityThreshold")] +public static extern int b3PhysicsParamSetRestitutionVelocityThreshold(IntPtr commandHandle, double restitutionVelocityThreshold) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PhysicsParamSetInternalSimFlags")] -public static extern int b3PhysicsParamSetInternalSimFlags(System.IntPtr commandHandle, int flags) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PhysicsParamSetInternalSimFlags")] +public static extern int b3PhysicsParamSetInternalSimFlags(IntPtr commandHandle, int flags) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitStepSimulationCommand")] -public static extern System.IntPtr b3InitStepSimulationCommand(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitStepSimulationCommand")] +public static extern System.IntPtr b3InitStepSimulationCommand(IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InitResetSimulationCommand")] -public static extern System.IntPtr b3InitResetSimulationCommand(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InitResetSimulationCommand")] +public static extern System.IntPtr b3InitResetSimulationCommand(IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///urdfFileName: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadUrdfCommandInit")] -public static extern System.IntPtr b3LoadUrdfCommandInit(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string urdfFileName) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadUrdfCommandInit")] +public static extern System.IntPtr b3LoadUrdfCommandInit(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string urdfFileName) ; /// Return Type: int @@ -2174,8 +2315,8 @@ public static extern System.IntPtr b3LoadUrdfCommandInit(System.IntPtr physClie ///startPosX: double ///startPosY: double ///startPosZ: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadUrdfCommandSetStartPosition")] -public static extern int b3LoadUrdfCommandSetStartPosition(System.IntPtr commandHandle, double startPosX, double startPosY, double startPosZ) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadUrdfCommandSetStartPosition")] +public static extern int b3LoadUrdfCommandSetStartPosition(IntPtr commandHandle, double startPosX, double startPosY, double startPosZ) ; /// Return Type: int @@ -2184,64 +2325,64 @@ public static extern int b3LoadUrdfCommandSetStartPosition(System.IntPtr comman ///startOrnY: double ///startOrnZ: double ///startOrnW: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadUrdfCommandSetStartOrientation")] -public static extern int b3LoadUrdfCommandSetStartOrientation(System.IntPtr commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadUrdfCommandSetStartOrientation")] +public static extern int b3LoadUrdfCommandSetStartOrientation(IntPtr commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///useMultiBody: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadUrdfCommandSetUseMultiBody")] -public static extern int b3LoadUrdfCommandSetUseMultiBody(System.IntPtr commandHandle, int useMultiBody) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadUrdfCommandSetUseMultiBody")] +public static extern int b3LoadUrdfCommandSetUseMultiBody(IntPtr commandHandle, int useMultiBody) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///useFixedBase: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadUrdfCommandSetUseFixedBase")] -public static extern int b3LoadUrdfCommandSetUseFixedBase(System.IntPtr commandHandle, int useFixedBase) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadUrdfCommandSetUseFixedBase")] +public static extern int b3LoadUrdfCommandSetUseFixedBase(IntPtr commandHandle, int useFixedBase) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadUrdfCommandSetFlags")] -public static extern int b3LoadUrdfCommandSetFlags(System.IntPtr commandHandle, int flags) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadUrdfCommandSetFlags")] +public static extern int b3LoadUrdfCommandSetFlags(IntPtr commandHandle, int flags) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///globalScaling: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadUrdfCommandSetGlobalScaling")] -public static extern int b3LoadUrdfCommandSetGlobalScaling(System.IntPtr commandHandle, double globalScaling) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadUrdfCommandSetGlobalScaling")] +public static extern int b3LoadUrdfCommandSetGlobalScaling(IntPtr commandHandle, double globalScaling) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///fileName: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadBulletCommandInit")] -public static extern System.IntPtr b3LoadBulletCommandInit(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadBulletCommandInit")] +public static extern System.IntPtr b3LoadBulletCommandInit(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///fileName: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SaveBulletCommandInit")] -public static extern System.IntPtr b3SaveBulletCommandInit(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SaveBulletCommandInit")] +public static extern System.IntPtr b3SaveBulletCommandInit(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///fileName: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadMJCFCommandInit")] -public static extern System.IntPtr b3LoadMJCFCommandInit(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadMJCFCommandInit")] +public static extern System.IntPtr b3LoadMJCFCommandInit(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadMJCFCommandSetFlags")] -public static extern void b3LoadMJCFCommandSetFlags(System.IntPtr commandHandle, int flags) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadMJCFCommandSetFlags")] +public static extern void b3LoadMJCFCommandSetFlags(IntPtr commandHandle, int flags) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -2250,8 +2391,8 @@ public static extern void b3LoadMJCFCommandSetFlags(System.IntPtr commandHandle ///jointPositionsQ: double* ///jointVelocitiesQdot: double* ///jointAccelerations: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateInverseDynamicsCommandInit")] -public static extern System.IntPtr b3CalculateInverseDynamicsCommandInit(System.IntPtr physClient, int bodyIndex, ref double jointPositionsQ, ref double jointVelocitiesQdot, ref double jointAccelerations) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateInverseDynamicsCommandInit")] +public static extern System.IntPtr b3CalculateInverseDynamicsCommandInit(IntPtr physClient, int bodyIndex, ref double jointPositionsQ, ref double jointVelocitiesQdot, ref double jointAccelerations) ; /// Return Type: int @@ -2259,8 +2400,8 @@ public static extern System.IntPtr b3CalculateInverseDynamicsCommandInit(System ///bodyUniqueId: int* ///dofCount: int* ///jointForces: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusInverseDynamicsJointForces")] -public static extern int b3GetStatusInverseDynamicsJointForces(System.IntPtr statusHandle, ref int bodyUniqueId, ref int dofCount, ref double jointForces) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusInverseDynamicsJointForces")] +public static extern int b3GetStatusInverseDynamicsJointForces(IntPtr statusHandle, ref int bodyUniqueId, ref int dofCount, ref double jointForces) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -2271,31 +2412,32 @@ public static extern int b3GetStatusInverseDynamicsJointForces(System.IntPtr st ///jointPositionsQ: double* ///jointVelocitiesQdot: double* ///jointAccelerations: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateJacobianCommandInit")] -public static extern System.IntPtr b3CalculateJacobianCommandInit(System.IntPtr physClient, int bodyIndex, int linkIndex, ref double localPosition, ref double jointPositionsQ, ref double jointVelocitiesQdot, ref double jointAccelerations) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateJacobianCommandInit")] +public static extern System.IntPtr b3CalculateJacobianCommandInit(IntPtr physClient, int bodyIndex, int linkIndex, ref double localPosition, ref double jointPositionsQ, ref double jointVelocitiesQdot, ref double jointAccelerations) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* + ///dofCount: int* ///linearJacobian: double* ///angularJacobian: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusJacobian")] -public static extern int b3GetStatusJacobian(System.IntPtr statusHandle, ref double linearJacobian, ref double angularJacobian) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusJacobian")] +public static extern int b3GetStatusJacobian(IntPtr statusHandle, ref int dofCount, ref double linearJacobian, ref double angularJacobian) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateInverseKinematicsCommandInit")] -public static extern System.IntPtr b3CalculateInverseKinematicsCommandInit(System.IntPtr physClient, int bodyIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateInverseKinematicsCommandInit")] +public static extern System.IntPtr b3CalculateInverseKinematicsCommandInit(IntPtr physClient, int bodyIndex) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///endEffectorLinkIndex: int ///targetPosition: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateInverseKinematicsAddTargetPurePosition")] -public static extern void b3CalculateInverseKinematicsAddTargetPurePosition(System.IntPtr commandHandle, int endEffectorLinkIndex, ref double targetPosition) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateInverseKinematicsAddTargetPurePosition")] +public static extern void b3CalculateInverseKinematicsAddTargetPurePosition(IntPtr commandHandle, int endEffectorLinkIndex, ref double targetPosition) ; /// Return Type: void @@ -2303,8 +2445,8 @@ public static extern void b3CalculateInverseKinematicsAddTargetPurePosition(Sys ///endEffectorLinkIndex: int ///targetPosition: double* ///targetOrientation: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateInverseKinematicsAddTargetPositionWithOrientation")] -public static extern void b3CalculateInverseKinematicsAddTargetPositionWithOrientation(System.IntPtr commandHandle, int endEffectorLinkIndex, ref double targetPosition, ref double targetOrientation) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateInverseKinematicsAddTargetPositionWithOrientation")] +public static extern void b3CalculateInverseKinematicsAddTargetPositionWithOrientation(IntPtr commandHandle, int endEffectorLinkIndex, ref double targetPosition, ref double targetOrientation) ; /// Return Type: void @@ -2316,8 +2458,8 @@ public static extern void b3CalculateInverseKinematicsAddTargetPositionWithOrie ///upperLimit: double* ///jointRange: double* ///restPose: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateInverseKinematicsPosWithNullSpaceVel")] -public static extern void b3CalculateInverseKinematicsPosWithNullSpaceVel(System.IntPtr commandHandle, int numDof, int endEffectorLinkIndex, ref double targetPosition, ref double lowerLimit, ref double upperLimit, ref double jointRange, ref double restPose) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateInverseKinematicsPosWithNullSpaceVel")] +public static extern void b3CalculateInverseKinematicsPosWithNullSpaceVel(IntPtr commandHandle, int numDof, int endEffectorLinkIndex, ref double targetPosition, ref double lowerLimit, ref double upperLimit, ref double jointRange, ref double restPose) ; /// Return Type: void @@ -2330,16 +2472,16 @@ public static extern void b3CalculateInverseKinematicsPosWithNullSpaceVel(Syste ///upperLimit: double* ///jointRange: double* ///restPose: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateInverseKinematicsPosOrnWithNullSpaceVel")] -public static extern void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(System.IntPtr commandHandle, int numDof, int endEffectorLinkIndex, ref double targetPosition, ref double targetOrientation, ref double lowerLimit, ref double upperLimit, ref double jointRange, ref double restPose) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateInverseKinematicsPosOrnWithNullSpaceVel")] +public static extern void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(IntPtr commandHandle, int numDof, int endEffectorLinkIndex, ref double targetPosition, ref double targetOrientation, ref double lowerLimit, ref double upperLimit, ref double jointRange, ref double restPose) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numDof: int ///jointDampingCoeff: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CalculateInverseKinematicsSetJointDamping")] -public static extern void b3CalculateInverseKinematicsSetJointDamping(System.IntPtr commandHandle, int numDof, ref double jointDampingCoeff) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CalculateInverseKinematicsSetJointDamping")] +public static extern void b3CalculateInverseKinematicsSetJointDamping(IntPtr commandHandle, int numDof, ref double jointDampingCoeff) ; /// Return Type: int @@ -2347,159 +2489,159 @@ public static extern void b3CalculateInverseKinematicsSetJointDamping(System.In ///bodyUniqueId: int* ///dofCount: int* ///jointPositions: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusInverseKinematicsJointPositions")] -public static extern int b3GetStatusInverseKinematicsJointPositions(System.IntPtr statusHandle, ref int bodyUniqueId, ref int dofCount, ref double jointPositions) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusInverseKinematicsJointPositions")] +public static extern int b3GetStatusInverseKinematicsJointPositions(IntPtr statusHandle, ref int bodyUniqueId, ref int dofCount, ref double jointPositions) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///sdfFileName: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadSdfCommandInit")] -public static extern System.IntPtr b3LoadSdfCommandInit(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string sdfFileName) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadSdfCommandInit")] +public static extern System.IntPtr b3LoadSdfCommandInit(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string sdfFileName) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///useMultiBody: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadSdfCommandSetUseMultiBody")] -public static extern int b3LoadSdfCommandSetUseMultiBody(System.IntPtr commandHandle, int useMultiBody) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadSdfCommandSetUseMultiBody")] +public static extern int b3LoadSdfCommandSetUseMultiBody(IntPtr commandHandle, int useMultiBody) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///globalScaling: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadSdfCommandSetUseGlobalScaling")] -public static extern int b3LoadSdfCommandSetUseGlobalScaling(System.IntPtr commandHandle, double globalScaling) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadSdfCommandSetUseGlobalScaling")] +public static extern int b3LoadSdfCommandSetUseGlobalScaling(IntPtr commandHandle, double globalScaling) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///sdfFileName: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SaveWorldCommandInit")] -public static extern System.IntPtr b3SaveWorldCommandInit(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string sdfFileName) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SaveWorldCommandInit")] +public static extern System.IntPtr b3SaveWorldCommandInit(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string sdfFileName) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///controlMode: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlCommandInit")] -public static extern System.IntPtr b3JointControlCommandInit(System.IntPtr physClient, int controlMode) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlCommandInit")] +public static extern System.IntPtr b3JointControlCommandInit(IntPtr physClient, int controlMode) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int ///controlMode: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlCommandInit2")] -public static extern System.IntPtr b3JointControlCommandInit2(System.IntPtr physClient, int bodyUniqueId, int controlMode) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlCommandInit2")] +public static extern System.IntPtr b3JointControlCommandInit2(IntPtr physClient, int bodyUniqueId, int controlMode) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///qIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlSetDesiredPosition")] -public static extern int b3JointControlSetDesiredPosition(System.IntPtr commandHandle, int qIndex, double value) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlSetDesiredPosition")] +public static extern int b3JointControlSetDesiredPosition(IntPtr commandHandle, int qIndex, double value) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlSetKp")] -public static extern int b3JointControlSetKp(System.IntPtr commandHandle, int dofIndex, double value) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlSetKp")] +public static extern int b3JointControlSetKp(IntPtr commandHandle, int dofIndex, double value) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlSetKd")] -public static extern int b3JointControlSetKd(System.IntPtr commandHandle, int dofIndex, double value) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlSetKd")] +public static extern int b3JointControlSetKd(IntPtr commandHandle, int dofIndex, double value) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlSetDesiredVelocity")] -public static extern int b3JointControlSetDesiredVelocity(System.IntPtr commandHandle, int dofIndex, double value) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlSetDesiredVelocity")] +public static extern int b3JointControlSetDesiredVelocity(IntPtr commandHandle, int dofIndex, double value) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlSetMaximumForce")] -public static extern int b3JointControlSetMaximumForce(System.IntPtr commandHandle, int dofIndex, double value) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlSetMaximumForce")] +public static extern int b3JointControlSetMaximumForce(IntPtr commandHandle, int dofIndex, double value) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///dofIndex: int ///value: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3JointControlSetDesiredForceTorque")] -public static extern int b3JointControlSetDesiredForceTorque(System.IntPtr commandHandle, int dofIndex, double value) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3JointControlSetDesiredForceTorque")] +public static extern int b3JointControlSetDesiredForceTorque(IntPtr commandHandle, int dofIndex, double value) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeCommandInit")] -public static extern System.IntPtr b3CreateCollisionShapeCommandInit(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeCommandInit")] +public static extern System.IntPtr b3CreateCollisionShapeCommandInit(IntPtr physClient) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///radius: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeAddSphere")] -public static extern int b3CreateCollisionShapeAddSphere(System.IntPtr commandHandle, double radius) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeAddSphere")] +public static extern int b3CreateCollisionShapeAddSphere(IntPtr commandHandle, double radius) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///halfExtents: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeAddBox")] -public static extern int b3CreateCollisionShapeAddBox(System.IntPtr commandHandle, ref double halfExtents) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeAddBox")] +public static extern int b3CreateCollisionShapeAddBox(IntPtr commandHandle, ref double halfExtents) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///radius: double ///height: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeAddCapsule")] -public static extern int b3CreateCollisionShapeAddCapsule(System.IntPtr commandHandle, double radius, double height) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeAddCapsule")] +public static extern int b3CreateCollisionShapeAddCapsule(IntPtr commandHandle, double radius, double height) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///radius: double ///height: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeAddCylinder")] -public static extern int b3CreateCollisionShapeAddCylinder(System.IntPtr commandHandle, double radius, double height) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeAddCylinder")] +public static extern int b3CreateCollisionShapeAddCylinder(IntPtr commandHandle, double radius, double height) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///planeNormal: double* ///planeConstant: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeAddPlane")] -public static extern int b3CreateCollisionShapeAddPlane(System.IntPtr commandHandle, ref double planeNormal, double planeConstant) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeAddPlane")] +public static extern int b3CreateCollisionShapeAddPlane(IntPtr commandHandle, ref double planeNormal, double planeConstant) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///fileName: char* ///meshScale: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeAddMesh")] -public static extern int b3CreateCollisionShapeAddMesh(System.IntPtr commandHandle, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName, ref double meshScale) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeAddMesh")] +public static extern int b3CreateCollisionShapeAddMesh(IntPtr commandHandle, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName, ref double meshScale) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///shapeIndex: int ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionSetFlag")] -public static extern void b3CreateCollisionSetFlag(System.IntPtr commandHandle, int shapeIndex, int flags) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionSetFlag")] +public static extern void b3CreateCollisionSetFlag(IntPtr commandHandle, int shapeIndex, int flags) ; /// Return Type: void @@ -2507,32 +2649,32 @@ public static extern void b3CreateCollisionSetFlag(System.IntPtr commandHandle, ///shapeIndex: int ///childPosition: double* ///childOrientation: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateCollisionShapeSetChildTransform")] -public static extern void b3CreateCollisionShapeSetChildTransform(System.IntPtr commandHandle, int shapeIndex, ref double childPosition, ref double childOrientation) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateCollisionShapeSetChildTransform")] +public static extern void b3CreateCollisionShapeSetChildTransform(IntPtr commandHandle, int shapeIndex, ref double childPosition, ref double childOrientation) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusCollisionShapeUniqueId")] -public static extern int b3GetStatusCollisionShapeUniqueId(System.IntPtr statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusCollisionShapeUniqueId")] +public static extern int b3GetStatusCollisionShapeUniqueId(IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateVisualShapeCommandInit")] -public static extern System.IntPtr b3CreateVisualShapeCommandInit(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateVisualShapeCommandInit")] +public static extern System.IntPtr b3CreateVisualShapeCommandInit(IntPtr physClient) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusVisualShapeUniqueId")] -public static extern int b3GetStatusVisualShapeUniqueId(System.IntPtr statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusVisualShapeUniqueId")] +public static extern int b3GetStatusVisualShapeUniqueId(IntPtr statusHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateMultiBodyCommandInit")] -public static extern System.IntPtr b3CreateMultiBodyCommandInit(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateMultiBodyCommandInit")] +public static extern System.IntPtr b3CreateMultiBodyCommandInit(IntPtr physClient) ; /// Return Type: int @@ -2544,8 +2686,8 @@ public static extern System.IntPtr b3CreateMultiBodyCommandInit(System.IntPtr p ///baseOrientation: double* ///baseInertialFramePosition: double* ///baseInertialFrameOrientation: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateMultiBodyBase")] -public static extern int b3CreateMultiBodyBase(System.IntPtr commandHandle, double mass, int collisionShapeUnique, int visualShapeUniqueId, ref double basePosition, ref double baseOrientation, ref double baseInertialFramePosition, ref double baseInertialFrameOrientation) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateMultiBodyBase")] +public static extern int b3CreateMultiBodyBase(IntPtr commandHandle, double mass, int collisionShapeUnique, int visualShapeUniqueId, ref double basePosition, ref double baseOrientation, ref double baseInertialFramePosition, ref double baseInertialFrameOrientation) ; /// Return Type: int @@ -2560,20 +2702,20 @@ public static extern int b3CreateMultiBodyBase(System.IntPtr commandHandle, dou ///linkParentIndex: int ///linkJointType: int ///linkJointAxis: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateMultiBodyLink")] -public static extern int b3CreateMultiBodyLink(System.IntPtr commandHandle, double linkMass, double linkCollisionShapeIndex, double linkVisualShapeIndex, ref double linkPosition, ref double linkOrientation, ref double linkInertialFramePosition, ref double linkInertialFrameOrientation, int linkParentIndex, int linkJointType, ref double linkJointAxis) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateMultiBodyLink")] +public static extern int b3CreateMultiBodyLink(IntPtr commandHandle, double linkMass, double linkCollisionShapeIndex, double linkVisualShapeIndex, ref double linkPosition, ref double linkOrientation, ref double linkInertialFramePosition, ref double linkInertialFrameOrientation, int linkParentIndex, int linkJointType, ref double linkJointAxis) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateMultiBodyUseMaximalCoordinates")] -public static extern void b3CreateMultiBodyUseMaximalCoordinates(System.IntPtr commandHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateMultiBodyUseMaximalCoordinates")] +public static extern void b3CreateMultiBodyUseMaximalCoordinates(IntPtr commandHandle) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateBoxShapeCommandInit")] -public static extern System.IntPtr b3CreateBoxShapeCommandInit(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateBoxShapeCommandInit")] +public static extern System.IntPtr b3CreateBoxShapeCommandInit(IntPtr physClient) ; /// Return Type: int @@ -2581,8 +2723,8 @@ public static extern System.IntPtr b3CreateBoxShapeCommandInit(System.IntPtr ph ///startPosX: double ///startPosY: double ///startPosZ: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateBoxCommandSetStartPosition")] -public static extern int b3CreateBoxCommandSetStartPosition(System.IntPtr commandHandle, double startPosX, double startPosY, double startPosZ) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateBoxCommandSetStartPosition")] +public static extern int b3CreateBoxCommandSetStartPosition(IntPtr commandHandle, double startPosX, double startPosY, double startPosZ) ; /// Return Type: int @@ -2591,8 +2733,8 @@ public static extern int b3CreateBoxCommandSetStartPosition(System.IntPtr comma ///startOrnY: double ///startOrnZ: double ///startOrnW: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateBoxCommandSetStartOrientation")] -public static extern int b3CreateBoxCommandSetStartOrientation(System.IntPtr commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateBoxCommandSetStartOrientation")] +public static extern int b3CreateBoxCommandSetStartOrientation(IntPtr commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; /// Return Type: int @@ -2600,22 +2742,22 @@ public static extern int b3CreateBoxCommandSetStartOrientation(System.IntPtr co ///halfExtentsX: double ///halfExtentsY: double ///halfExtentsZ: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateBoxCommandSetHalfExtents")] -public static extern int b3CreateBoxCommandSetHalfExtents(System.IntPtr commandHandle, double halfExtentsX, double halfExtentsY, double halfExtentsZ) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateBoxCommandSetHalfExtents")] +public static extern int b3CreateBoxCommandSetHalfExtents(IntPtr commandHandle, double halfExtentsX, double halfExtentsY, double halfExtentsZ) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///mass: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateBoxCommandSetMass")] -public static extern int b3CreateBoxCommandSetMass(System.IntPtr commandHandle, double mass) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateBoxCommandSetMass")] +public static extern int b3CreateBoxCommandSetMass(IntPtr commandHandle, double mass) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///collisionShapeType: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateBoxCommandSetCollisionShapeType")] -public static extern int b3CreateBoxCommandSetCollisionShapeType(System.IntPtr commandHandle, int collisionShapeType) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateBoxCommandSetCollisionShapeType")] +public static extern int b3CreateBoxCommandSetCollisionShapeType(IntPtr commandHandle, int collisionShapeType) ; /// Return Type: int @@ -2624,15 +2766,15 @@ public static extern int b3CreateBoxCommandSetCollisionShapeType(System.IntPtr ///green: double ///blue: double ///alpha: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateBoxCommandSetColorRGBA")] -public static extern int b3CreateBoxCommandSetColorRGBA(System.IntPtr commandHandle, double red, double green, double blue, double alpha) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateBoxCommandSetColorRGBA")] +public static extern int b3CreateBoxCommandSetColorRGBA(IntPtr commandHandle, double red, double green, double blue, double alpha) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyIndex: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandInit")] -public static extern System.IntPtr b3CreatePoseCommandInit(System.IntPtr physClient, int bodyIndex) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandInit")] +public static extern System.IntPtr b3CreatePoseCommandInit(IntPtr physClient, int bodyIndex) ; /// Return Type: int @@ -2640,8 +2782,8 @@ public static extern System.IntPtr b3CreatePoseCommandInit(System.IntPtr physCl ///startPosX: double ///startPosY: double ///startPosZ: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetBasePosition")] -public static extern int b3CreatePoseCommandSetBasePosition(System.IntPtr commandHandle, double startPosX, double startPosY, double startPosZ) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetBasePosition")] +public static extern int b3CreatePoseCommandSetBasePosition(IntPtr commandHandle, double startPosX, double startPosY, double startPosZ) ; /// Return Type: int @@ -2650,30 +2792,30 @@ public static extern int b3CreatePoseCommandSetBasePosition(System.IntPtr comma ///startOrnY: double ///startOrnZ: double ///startOrnW: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetBaseOrientation")] -public static extern int b3CreatePoseCommandSetBaseOrientation(System.IntPtr commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetBaseOrientation")] +public static extern int b3CreatePoseCommandSetBaseOrientation(IntPtr commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linVel: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetBaseLinearVelocity")] -public static extern int b3CreatePoseCommandSetBaseLinearVelocity(System.IntPtr commandHandle, ref double linVel) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetBaseLinearVelocity")] +public static extern int b3CreatePoseCommandSetBaseLinearVelocity(IntPtr commandHandle, ref double linVel) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///angVel: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetBaseAngularVelocity")] -public static extern int b3CreatePoseCommandSetBaseAngularVelocity(System.IntPtr commandHandle, ref double angVel) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetBaseAngularVelocity")] +public static extern int b3CreatePoseCommandSetBaseAngularVelocity(IntPtr commandHandle, ref double angVel) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numJointPositions: int ///jointPositions: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetJointPositions")] -public static extern int b3CreatePoseCommandSetJointPositions(System.IntPtr commandHandle, int numJointPositions, ref double jointPositions) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetJointPositions")] +public static extern int b3CreatePoseCommandSetJointPositions(IntPtr commandHandle, int numJointPositions, ref double jointPositions) ; /// Return Type: int @@ -2681,8 +2823,8 @@ public static extern int b3CreatePoseCommandSetJointPositions(System.IntPtr com ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointIndex: int ///jointPosition: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetJointPosition")] -public static extern int b3CreatePoseCommandSetJointPosition(System.IntPtr physClient, System.IntPtr commandHandle, int jointIndex, double jointPosition) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetJointPosition")] +public static extern int b3CreatePoseCommandSetJointPosition(IntPtr physClient, IntPtr commandHandle, int jointIndex, double jointPosition) ; /// Return Type: int @@ -2690,8 +2832,8 @@ public static extern int b3CreatePoseCommandSetJointPosition(System.IntPtr phys ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///numJointVelocities: int ///jointVelocities: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetJointVelocities")] -public static extern int b3CreatePoseCommandSetJointVelocities(System.IntPtr physClient, System.IntPtr commandHandle, int numJointVelocities, ref double jointVelocities) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetJointVelocities")] +public static extern int b3CreatePoseCommandSetJointVelocities(IntPtr physClient, IntPtr commandHandle, int numJointVelocities, ref double jointVelocities) ; /// Return Type: int @@ -2699,45 +2841,52 @@ public static extern int b3CreatePoseCommandSetJointVelocities(System.IntPtr ph ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointIndex: int ///jointVelocity: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreatePoseCommandSetJointVelocity")] -public static extern int b3CreatePoseCommandSetJointVelocity(System.IntPtr physClient, System.IntPtr commandHandle, int jointIndex, double jointVelocity) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreatePoseCommandSetJointVelocity")] +public static extern int b3CreatePoseCommandSetJointVelocity(IntPtr physClient, IntPtr commandHandle, int jointIndex, double jointVelocity) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateSensorCommandInit")] -public static extern System.IntPtr b3CreateSensorCommandInit(System.IntPtr physClient, int bodyUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateSensorCommandInit")] +public static extern System.IntPtr b3CreateSensorCommandInit(IntPtr physClient, int bodyUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///jointIndex: int ///enable: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateSensorEnable6DofJointForceTorqueSensor")] -public static extern int b3CreateSensorEnable6DofJointForceTorqueSensor(System.IntPtr commandHandle, int jointIndex, int enable) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateSensorEnable6DofJointForceTorqueSensor")] +public static extern int b3CreateSensorEnable6DofJointForceTorqueSensor(IntPtr commandHandle, int jointIndex, int enable) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndex: int ///enable: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateSensorEnableIMUForLink")] -public static extern int b3CreateSensorEnableIMUForLink(System.IntPtr commandHandle, int linkIndex, int enable) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateSensorEnableIMUForLink")] +public static extern int b3CreateSensorEnableIMUForLink(IntPtr commandHandle, int linkIndex, int enable) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///bodyUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestActualStateCommandInit")] -public static extern System.IntPtr b3RequestActualStateCommandInit(System.IntPtr physClient, int bodyUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestActualStateCommandInit")] +public static extern System.IntPtr b3RequestActualStateCommandInit(IntPtr physClient, int bodyUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///computeLinkVelocity: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestActualStateCommandComputeLinkVelocity")] -public static extern int b3RequestActualStateCommandComputeLinkVelocity(System.IntPtr commandHandle, int computeLinkVelocity) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestActualStateCommandComputeLinkVelocity")] +public static extern int b3RequestActualStateCommandComputeLinkVelocity(IntPtr commandHandle, int computeLinkVelocity) ; + + + /// Return Type: int + ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* + ///computeForwardKinematics: int + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestActualStateCommandComputeForwardKinematics")] +public static extern int b3RequestActualStateCommandComputeForwardKinematics(IntPtr commandHandle, int computeForwardKinematics) ; /// Return Type: int @@ -2745,8 +2894,8 @@ public static extern int b3RequestActualStateCommandComputeLinkVelocity(System. ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///jointIndex: int ///state: b3JointSensorState* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetJointState")] -public static extern int b3GetJointState(System.IntPtr physClient, System.IntPtr statusHandle, int jointIndex, ref b3JointSensorState state) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetJointState")] +public static extern int b3GetJointState(IntPtr physClient, IntPtr statusHandle, int jointIndex, ref b3JointSensorState state) ; /// Return Type: int @@ -2754,8 +2903,8 @@ public static extern int b3GetJointState(System.IntPtr physClient, System.IntPt ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* ///linkIndex: int ///state: b3LinkState* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetLinkState")] -public static extern int b3GetLinkState(System.IntPtr physClient, System.IntPtr statusHandle, int linkIndex, ref b3LinkState state) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetLinkState")] +public static extern int b3GetLinkState(IntPtr physClient, IntPtr statusHandle, int linkIndex, ref b3LinkState state) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -2766,8 +2915,8 @@ public static extern int b3GetLinkState(System.IntPtr physClient, System.IntPtr ///rayToWorldX: double ///rayToWorldY: double ///rayToWorldZ: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3PickBody")] -public static extern System.IntPtr b3PickBody(System.IntPtr physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3PickBody")] +public static extern System.IntPtr b3PickBody(IntPtr physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -2778,14 +2927,14 @@ public static extern System.IntPtr b3PickBody(System.IntPtr physClient, double ///rayToWorldX: double ///rayToWorldY: double ///rayToWorldZ: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3MovePickedBody")] -public static extern System.IntPtr b3MovePickedBody(System.IntPtr physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3MovePickedBody")] +public static extern System.IntPtr b3MovePickedBody(IntPtr physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RemovePickingConstraint")] -public static extern System.IntPtr b3RemovePickingConstraint(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RemovePickingConstraint")] +public static extern System.IntPtr b3RemovePickingConstraint(IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* @@ -2796,35 +2945,35 @@ public static extern System.IntPtr b3RemovePickingConstraint(System.IntPtr phys ///rayToWorldX: double ///rayToWorldY: double ///rayToWorldZ: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateRaycastCommandInit")] -public static extern System.IntPtr b3CreateRaycastCommandInit(System.IntPtr physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateRaycastCommandInit")] +public static extern System.IntPtr b3CreateRaycastCommandInit(IntPtr physClient, double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ, double rayToWorldX, double rayToWorldY, double rayToWorldZ) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3CreateRaycastBatchCommandInit")] -public static extern System.IntPtr b3CreateRaycastBatchCommandInit(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3CreateRaycastBatchCommandInit")] +public static extern System.IntPtr b3CreateRaycastBatchCommandInit(IntPtr physClient) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///rayFromWorld: double* ///rayToWorld: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RaycastBatchAddRay")] -public static extern void b3RaycastBatchAddRay(System.IntPtr commandHandle, ref double rayFromWorld, ref double rayToWorld) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RaycastBatchAddRay")] +public static extern void b3RaycastBatchAddRay(IntPtr commandHandle, ref double rayFromWorld, ref double rayToWorld) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///raycastInfo: b3RaycastInformation* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetRaycastInformation")] -public static extern void b3GetRaycastInformation(System.IntPtr physClient, ref b3RaycastInformation raycastInfo) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetRaycastInformation")] +public static extern void b3GetRaycastInformation(IntPtr physClient, ref b3RaycastInformation raycastInfo) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ApplyExternalForceCommandInit")] -public static extern System.IntPtr b3ApplyExternalForceCommandInit(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ApplyExternalForceCommandInit")] +public static extern System.IntPtr b3ApplyExternalForceCommandInit(IntPtr physClient) ; /// Return Type: void @@ -2833,9 +2982,9 @@ public static extern System.IntPtr b3ApplyExternalForceCommandInit(System.IntPt ///linkId: int ///force: double* ///position: double* - ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ApplyExternalForce")] -public static extern void b3ApplyExternalForce(System.IntPtr commandHandle, int bodyUniqueId, int linkId, ref double force, ref double position, int flags) ; + ///flag: int + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ApplyExternalForce")] +public static extern void b3ApplyExternalForce(IntPtr commandHandle, int bodyUniqueId, int linkId, ref double force, ref double position, int flag) ; /// Return Type: void @@ -2843,233 +2992,233 @@ public static extern void b3ApplyExternalForce(System.IntPtr commandHandle, int ///bodyUniqueId: int ///linkId: int ///torque: double* - ///flags: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ApplyExternalTorque")] -public static extern void b3ApplyExternalTorque(System.IntPtr commandHandle, int bodyUniqueId, int linkId, ref double torque, int flags) ; + ///flag: int + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ApplyExternalTorque")] +public static extern void b3ApplyExternalTorque(IntPtr commandHandle, int bodyUniqueId, int linkId, ref double torque, int flag) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadBunnyCommandInit")] -public static extern System.IntPtr b3LoadBunnyCommandInit(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadBunnyCommandInit")] +public static extern System.IntPtr b3LoadBunnyCommandInit(IntPtr physClient) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///scale: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadBunnySetScale")] -public static extern int b3LoadBunnySetScale(System.IntPtr commandHandle, double scale) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadBunnySetScale")] +public static extern int b3LoadBunnySetScale(IntPtr commandHandle, double scale) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///mass: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadBunnySetMass")] -public static extern int b3LoadBunnySetMass(System.IntPtr commandHandle, double mass) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadBunnySetMass")] +public static extern int b3LoadBunnySetMass(IntPtr commandHandle, double mass) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///collisionMargin: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3LoadBunnySetCollisionMargin")] -public static extern int b3LoadBunnySetCollisionMargin(System.IntPtr commandHandle, double collisionMargin) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3LoadBunnySetCollisionMargin")] +public static extern int b3LoadBunnySetCollisionMargin(IntPtr commandHandle, double collisionMargin) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestVREventsCommandInit")] -public static extern System.IntPtr b3RequestVREventsCommandInit(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestVREventsCommandInit")] +public static extern System.IntPtr b3RequestVREventsCommandInit(IntPtr physClient) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///deviceTypeFilter: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3VREventsSetDeviceTypeFilter")] -public static extern void b3VREventsSetDeviceTypeFilter(System.IntPtr commandHandle, int deviceTypeFilter) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3VREventsSetDeviceTypeFilter")] +public static extern void b3VREventsSetDeviceTypeFilter(IntPtr commandHandle, int deviceTypeFilter) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///vrEventsData: b3VREventsData* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetVREventsData")] -public static extern void b3GetVREventsData(System.IntPtr physClient, ref b3VREventsData vrEventsData) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetVREventsData")] +public static extern void b3GetVREventsData(IntPtr physClient, ref b3VREventsData vrEventsData) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetVRCameraStateCommandInit")] -public static extern System.IntPtr b3SetVRCameraStateCommandInit(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetVRCameraStateCommandInit")] +public static extern System.IntPtr b3SetVRCameraStateCommandInit(IntPtr physClient) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///rootPos: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetVRCameraRootPosition")] -public static extern int b3SetVRCameraRootPosition(System.IntPtr commandHandle, ref double rootPos) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetVRCameraRootPosition")] +public static extern int b3SetVRCameraRootPosition(IntPtr commandHandle, ref double rootPos) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///rootOrn: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetVRCameraRootOrientation")] -public static extern int b3SetVRCameraRootOrientation(System.IntPtr commandHandle, ref double rootOrn) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetVRCameraRootOrientation")] +public static extern int b3SetVRCameraRootOrientation(IntPtr commandHandle, ref double rootOrn) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///objectUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetVRCameraTrackingObject")] -public static extern int b3SetVRCameraTrackingObject(System.IntPtr commandHandle, int objectUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetVRCameraTrackingObject")] +public static extern int b3SetVRCameraTrackingObject(IntPtr commandHandle, int objectUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///flag: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetVRCameraTrackingObjectFlag")] -public static extern int b3SetVRCameraTrackingObjectFlag(System.IntPtr commandHandle, int flag) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetVRCameraTrackingObjectFlag")] +public static extern int b3SetVRCameraTrackingObjectFlag(IntPtr commandHandle, int flag) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestKeyboardEventsCommandInit")] -public static extern System.IntPtr b3RequestKeyboardEventsCommandInit(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestKeyboardEventsCommandInit")] +public static extern System.IntPtr b3RequestKeyboardEventsCommandInit(IntPtr physClient) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///keyboardEventsData: b3KeyboardEventsData* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetKeyboardEventsData")] -public static extern void b3GetKeyboardEventsData(System.IntPtr physClient, ref b3KeyboardEventsData keyboardEventsData) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetKeyboardEventsData")] +public static extern void b3GetKeyboardEventsData(IntPtr physClient, ref b3KeyboardEventsData keyboardEventsData) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3RequestMouseEventsCommandInit")] -public static extern System.IntPtr b3RequestMouseEventsCommandInit(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3RequestMouseEventsCommandInit")] +public static extern System.IntPtr b3RequestMouseEventsCommandInit(IntPtr physClient) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///mouseEventsData: b3MouseEventsData* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetMouseEventsData")] -public static extern void b3GetMouseEventsData(System.IntPtr physClient, ref b3MouseEventsData mouseEventsData) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetMouseEventsData")] +public static extern void b3GetMouseEventsData(IntPtr physClient, ref b3MouseEventsData mouseEventsData) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingCommandInit")] -public static extern System.IntPtr b3StateLoggingCommandInit(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingCommandInit")] +public static extern System.IntPtr b3StateLoggingCommandInit(IntPtr physClient) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///loggingType: int ///fileName: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingStart")] -public static extern int b3StateLoggingStart(System.IntPtr commandHandle, int loggingType, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingStart")] +public static extern int b3StateLoggingStart(IntPtr commandHandle, int loggingType, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///objectUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingAddLoggingObjectUniqueId")] -public static extern int b3StateLoggingAddLoggingObjectUniqueId(System.IntPtr commandHandle, int objectUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingAddLoggingObjectUniqueId")] +public static extern int b3StateLoggingAddLoggingObjectUniqueId(IntPtr commandHandle, int objectUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///maxLogDof: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingSetMaxLogDof")] -public static extern int b3StateLoggingSetMaxLogDof(System.IntPtr commandHandle, int maxLogDof) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingSetMaxLogDof")] +public static extern int b3StateLoggingSetMaxLogDof(IntPtr commandHandle, int maxLogDof) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexA: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingSetLinkIndexA")] -public static extern int b3StateLoggingSetLinkIndexA(System.IntPtr commandHandle, int linkIndexA) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingSetLinkIndexA")] +public static extern int b3StateLoggingSetLinkIndexA(IntPtr commandHandle, int linkIndexA) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///linkIndexB: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingSetLinkIndexB")] -public static extern int b3StateLoggingSetLinkIndexB(System.IntPtr commandHandle, int linkIndexB) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingSetLinkIndexB")] +public static extern int b3StateLoggingSetLinkIndexB(IntPtr commandHandle, int linkIndexB) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyAUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingSetBodyAUniqueId")] -public static extern int b3StateLoggingSetBodyAUniqueId(System.IntPtr commandHandle, int bodyAUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingSetBodyAUniqueId")] +public static extern int b3StateLoggingSetBodyAUniqueId(IntPtr commandHandle, int bodyAUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///bodyBUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingSetBodyBUniqueId")] -public static extern int b3StateLoggingSetBodyBUniqueId(System.IntPtr commandHandle, int bodyBUniqueId) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingSetBodyBUniqueId")] +public static extern int b3StateLoggingSetBodyBUniqueId(IntPtr commandHandle, int bodyBUniqueId) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///deviceTypeFilter: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingSetDeviceTypeFilter")] -public static extern int b3StateLoggingSetDeviceTypeFilter(System.IntPtr commandHandle, int deviceTypeFilter) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingSetDeviceTypeFilter")] +public static extern int b3StateLoggingSetDeviceTypeFilter(IntPtr commandHandle, int deviceTypeFilter) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///logFlags: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingSetLogFlags")] -public static extern int b3StateLoggingSetLogFlags(System.IntPtr commandHandle, int logFlags) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingSetLogFlags")] +public static extern int b3StateLoggingSetLogFlags(IntPtr commandHandle, int logFlags) ; /// Return Type: int ///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetStatusLoggingUniqueId")] -public static extern int b3GetStatusLoggingUniqueId(System.IntPtr statusHandle) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetStatusLoggingUniqueId")] +public static extern int b3GetStatusLoggingUniqueId(IntPtr statusHandle) ; /// Return Type: int ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* - ///loggingUniqueId: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3StateLoggingStop")] -public static extern int b3StateLoggingStop(System.IntPtr commandHandle, int loggingUniqueId) ; + ///loggingUid: int + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3StateLoggingStop")] +public static extern int b3StateLoggingStop(IntPtr commandHandle, int loggingUid) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///name: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3ProfileTimingCommandInit")] -public static extern System.IntPtr b3ProfileTimingCommandInit(System.IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string name) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3ProfileTimingCommandInit")] +public static extern System.IntPtr b3ProfileTimingCommandInit(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string name) ; /// Return Type: void ///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///duration: int - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetProfileTimingDuractionInMicroSeconds")] -public static extern void b3SetProfileTimingDuractionInMicroSeconds(System.IntPtr commandHandle, int duration) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetProfileTimingDuractionInMicroSeconds")] +public static extern void b3SetProfileTimingDuractionInMicroSeconds(IntPtr commandHandle, int duration) ; /// Return Type: void ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///timeOutInSeconds: double - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetTimeOut")] -public static extern void b3SetTimeOut(System.IntPtr physClient, double timeOutInSeconds) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetTimeOut")] +public static extern void b3SetTimeOut(IntPtr physClient, double timeOutInSeconds) ; /// Return Type: double ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3GetTimeOut")] -public static extern double b3GetTimeOut(System.IntPtr physClient) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetTimeOut")] +public static extern double b3GetTimeOut(IntPtr physClient) ; /// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__* ///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__* ///path: char* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3SetAdditionalSearchPath")] -public static extern System.IntPtr b3SetAdditionalSearchPath(System.IntPtr physClient, System.IntPtr path) ; + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3SetAdditionalSearchPath")] +public static extern System.IntPtr b3SetAdditionalSearchPath(IntPtr physClient, System.IntPtr path) ; /// Return Type: void @@ -3079,7 +3228,7 @@ public static extern System.IntPtr b3SetAdditionalSearchPath(System.IntPtr phys ///ornB: double* ///outPos: double* ///outOrn: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3MultiplyTransforms")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3MultiplyTransforms")] public static extern void b3MultiplyTransforms(ref double posA, ref double ornA, ref double posB, ref double ornB, ref double outPos, ref double outOrn) ; @@ -3088,7 +3237,7 @@ public static extern void b3MultiplyTransforms(ref double posA, ref double ornA ///orn: double* ///outPos: double* ///outOrn: double* - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010.dll", EntryPoint="b3InvertTransform")] + [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3InvertTransform")] public static extern void b3InvertTransform(ref double pos, ref double orn, ref double outPos, ref double outOrn) ; } diff --git a/examples/pybullet/unity3d/examples/NewBehaviourScript.cs b/examples/pybullet/unity3d/examples/NewBehaviourScript.cs index 026e7a709..42bcfddf0 100644 --- a/examples/pybullet/unity3d/examples/NewBehaviourScript.cs +++ b/examples/pybullet/unity3d/examples/NewBehaviourScript.cs @@ -10,25 +10,8 @@ using System; public class NewBehaviourScript : MonoBehaviour { - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3ConnectSharedMemory")] - public static extern System.IntPtr b3ConnectSharedMemory(int key); - - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3CreateInProcessPhysicsServerAndConnect")] - public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnect(int argc, ref System.IntPtr argv); - - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3InitStepSimulationCommand")] - public static extern System.IntPtr b3InitStepSimulationCommand(IntPtr physClient); - - - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3LoadUrdfCommandInit")] - public static extern System.IntPtr b3LoadUrdfCommandInit(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string urdfFileName); - - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3InitResetSimulationCommand")] - public static extern System.IntPtr b3InitResetSimulationCommand(IntPtr physClient); - - [System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3SubmitClientCommandAndWaitStatus")] - public static extern System.IntPtr b3SubmitClientCommandAndWaitStatus(IntPtr physClient, IntPtr commandHandle); - + + [DllImport("TestCppPlug.dll")] static extern int Add(int a, int b); @@ -60,27 +43,45 @@ public class NewBehaviourScript : MonoBehaviour { CallMe(IWasCalled); sharedAPI = CreateSharedAPI(30); - IntPtr pybullet = b3ConnectSharedMemory(12347); - IntPtr cmd = b3InitResetSimulationCommand(pybullet); - IntPtr status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd); - cmd = b3LoadUrdfCommandInit(pybullet, "plane.urdf"); - status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd); + pybullet = NativeMethods.b3ConnectPhysicsDirect();// SharedMemory(12347); + IntPtr cmd = NativeMethods.b3InitResetSimulationCommand(pybullet); + IntPtr status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd); + int numBodies = NativeMethods.b3GetNumBodies(pybullet); + cmd = NativeMethods.b3LoadUrdfCommandInit(pybullet, "plane.urdf"); + status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd); + EnumSharedMemoryServerStatus statusType = (EnumSharedMemoryServerStatus)NativeMethods.b3GetStatusType(status); + if (statusType == EnumSharedMemoryServerStatus.CMD_URDF_LOADING_COMPLETED) + { + numBodies = NativeMethods.b3GetNumBodies(pybullet); + text.text = numBodies.ToString(); + if (numBodies > 0) + { + + //b3BodyInfo info=new b3BodyInfo(); + //NativeMethods.b3GetBodyInfo(pybullet, 0, ref info ); + //text.text = info.m_baseName; + } + } + //IntPtr clientPtr = b3CreateInProcessPhysicsServerAndConnect(0, ref ptr); } - - // Update is called once per frame - void Update () { - IntPtr cmd = b3InitStepSimulationCommand(pybullet); - IntPtr status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd); - //System.IO.Directory.GetCurrentDirectory().ToString();// - //text.text = Add(4, 5).ToString(); - text.text = UnityEngine.Random.Range(0f, 1f).ToString();// GetMyIdPlusTen(sharedAPI).ToString(); + // Update is called once per frame + void Update () { + //if (pybullet != IntPtr.Zero) + { + IntPtr cmd = NativeMethods.b3InitStepSimulationCommand(pybullet); + IntPtr status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd); + + //text.text = System.IO.Directory.GetCurrentDirectory().ToString(); + //text.text = Add(4, 5).ToString(); + //text.text = UnityEngine.Random.Range(0f, 1f).ToString();// GetMyIdPlusTen(sharedAPI).ToString(); + } } void OnDestroy() { - - DeleteSharedAPI(sharedAPI); + NativeMethods.b3DisconnectSharedMemory(pybullet); + } } From 17115f38c281ebc0d0143dab56b8d13a2db18ce8 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Fri, 29 Sep 2017 07:50:04 -0700 Subject: [PATCH 3/6] add some timings, small fix in btSoftBody related to btMultiBody interaction --- src/BulletSoftBody/btSoftBody.cpp | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/src/BulletSoftBody/btSoftBody.cpp b/src/BulletSoftBody/btSoftBody.cpp index 52f8cd897..48efb0d8d 100644 --- a/src/BulletSoftBody/btSoftBody.cpp +++ b/src/BulletSoftBody/btSoftBody.cpp @@ -3003,6 +3003,7 @@ void btSoftBody::applyForces() // void btSoftBody::PSolve_Anchors(btSoftBody* psb,btScalar kst,btScalar ti) { + BT_PROFILE("PSolve_Anchors"); const btScalar kAHR=psb->m_cfg.kAHR*kst; const btScalar dt=psb->m_sst.sdt; for(int i=0,ni=psb->m_anchors.size();im_sst.sdt; const btScalar mrg = psb->getCollisionShape()->getMargin(); + btMultiBodyJacobianData jacobianData; for(int i=0,ni=psb->m_rcontacts.size();im_rcontacts[i]; @@ -3033,10 +3036,10 @@ void btSoftBody::PSolve_RContacts(btSoftBody* psb, btScalar kst, btScalar ti) if (cti.m_colObj->hasContactResponse()) { btVector3 va(0,0,0); - btRigidBody* rigidCol; - btMultiBodyLinkCollider* multibodyLinkCol; + btRigidBody* rigidCol=0; + btMultiBodyLinkCollider* multibodyLinkCol=0; btScalar* deltaV; - btMultiBodyJacobianData jacobianData; + if (cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY) { rigidCol = (btRigidBody*)btRigidBody::upcast(cti.m_colObj); @@ -3096,6 +3099,8 @@ void btSoftBody::PSolve_RContacts(btSoftBody* psb, btScalar kst, btScalar ti) // void btSoftBody::PSolve_SContacts(btSoftBody* psb,btScalar,btScalar ti) { + BT_PROFILE("PSolve_SContacts"); + for(int i=0,ni=psb->m_scontacts.size();im_scontacts[i]; @@ -3129,6 +3134,7 @@ void btSoftBody::PSolve_SContacts(btSoftBody* psb,btScalar,btScalar ti) // void btSoftBody::PSolve_Links(btSoftBody* psb,btScalar kst,btScalar ti) { +BT_PROFILE("PSolve_Links"); for(int i=0,ni=psb->m_links.size();im_links[i]; @@ -3151,6 +3157,7 @@ void btSoftBody::PSolve_Links(btSoftBody* psb,btScalar kst,btScalar ti) // void btSoftBody::VSolve_Links(btSoftBody* psb,btScalar kst) { + BT_PROFILE("VSolve_Links"); for(int i=0,ni=psb->m_links.size();im_links[i]; From e0dbd25cb79e2f21f9b843bc8c459d4df401b448 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Fri, 29 Sep 2017 07:50:48 -0700 Subject: [PATCH 4/6] remove some unneeded/debug BT_PROFILE markers --- .../OpenGLWindow/GLInstancingRenderer.cpp | 20 +++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index a92500af7..9d47827c2 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -622,22 +622,22 @@ void GLInstancingRenderer::writeTransforms() { { - B3_PROFILE("b3Assert(glGetError() 1"); + //B3_PROFILE("b3Assert(glGetError() 1"); b3Assert(glGetError() ==GL_NO_ERROR); } { - B3_PROFILE("glBindBuffer"); + //B3_PROFILE("glBindBuffer"); glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo); } { - B3_PROFILE("glFlush()"); + //B3_PROFILE("glFlush()"); //without the flush, the glBufferSubData can spike to really slow (seconds slow) glFlush(); } { - B3_PROFILE("b3Assert(glGetError() 2"); + //B3_PROFILE("b3Assert(glGetError() 2"); b3Assert(glGetError() ==GL_NO_ERROR); } @@ -666,22 +666,22 @@ void GLInstancingRenderer::writeTransforms() { // printf("m_data->m_totalNumInstances = %d\n", m_data->m_totalNumInstances); { - B3_PROFILE("glBufferSubData pos"); + //B3_PROFILE("glBufferSubData pos"); glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes,m_data->m_totalNumInstances*sizeof(float)*4, &m_data->m_instance_positions_ptr[0]); } { - B3_PROFILE("glBufferSubData orn"); +// B3_PROFILE("glBufferSubData orn"); glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE,m_data->m_totalNumInstances*sizeof(float)*4, &m_data->m_instance_quaternion_ptr[0]); } { - B3_PROFILE("glBufferSubData color"); +// B3_PROFILE("glBufferSubData color"); glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes+ POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE, m_data->m_totalNumInstances*sizeof(float)*4, &m_data->m_instance_colors_ptr[0]); } { - B3_PROFILE("glBufferSubData scale"); +// B3_PROFILE("glBufferSubData scale"); glBufferSubData( GL_ARRAY_BUFFER, m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE+COLOR_BUFFER_SIZE,m_data->m_totalNumInstances*sizeof(float)*3, &m_data->m_instance_scale_ptr[0]); } @@ -756,12 +756,12 @@ void GLInstancingRenderer::writeTransforms() #endif { - B3_PROFILE("glBindBuffer 2"); +// B3_PROFILE("glBindBuffer 2"); glBindBuffer(GL_ARRAY_BUFFER, 0);//m_data->m_vbo); } { - B3_PROFILE("b3Assert(glGetError() 4"); + // B3_PROFILE("b3Assert(glGetError() 4"); b3Assert(glGetError() ==GL_NO_ERROR); } From c9b76e17602ad8ff84e751c93a0a21115de3343f Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Fri, 29 Sep 2017 08:00:35 -0700 Subject: [PATCH 5/6] update pybullet_quickstartguide.pdf --- docs/pybullet_quickstartguide.pdf | Bin 1810277 -> 1867173 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/docs/pybullet_quickstartguide.pdf b/docs/pybullet_quickstartguide.pdf index 2c8fbea2af8f671fec0a87c44d5f96891a461106..9a96ab0e47d8ad1540f634e1d05a25ac41cfb89f 100644 GIT binary patch delta 567332 zcmagEbzGEh^ermgFm%JvB{4xucb5oABPkuyFw#iFpn#-EDIL-sN=O-iG)M|acikEA zd(Q8C&b^=OAFnfS>}T(_*IN4-W>(u>3NPJV*|g;qc|m-FxNIG#`8T*As31@P=xX&G z_t7IDzq*5qjirZ!zl}8zgm?!8i3kaUgdsqFWuP%oL{tz6g$Mynf&5xP5L6V%uK*Mg z5dsSU`89z;h~s1A{Xzl|Fi=tw*T%&f85ORBYLAXsMJRd3PaLrp6ohSXv5# zAflE6*4CEKY=vwjAN~K{VT#Pn)62ug(izt`>zS3c#iE^sm4$@}4s!;)%ZU;&P=_Hu zO^1@Ks|&12A&>_@2~{4Twy4KUvW}yGVcAX!2!L)D&ZwMF(SBR7qc}C=5;O#5)1sho zAc{m*@E?@&HlALdi0qN@B5KsOw6j6H6%>U(MPp1mmq#H;n>C;%hv@+Yg#{5%+ql?y z*#jYhg8yfJ78c0lD(oz5EiA4&fnOhBSP0>v@gxl#D2AYvsXpMI?8GM1wir`|W*>%h zDEF_2L}4{hzu(3A>6EmBZrSyDlAwZ`&YiG>-o&M<s30IUlb*d1o zw#+a|I7+R$x~TJj%s{E95^u0LJ(#}VYH8fArqzO``^oSgznoi6RU?aNr-pl(TFuN;=JG7@pH0{!z!EKj94n zqidoMfmJ-zxJ7s{IW-NL+?WrT;jAzN7Ohe_+H|+458&8K%Hvibl8FA3hdwfE%a4_^ z!aw@d#3pmv9R(`pJSnE0bj~72qgH`5<*@a%qt2`eKj`fWwuwus%vUS7vaQZc1cdA-NU(&ZqG{7Un989XOhhvE zA0hs67QyW_%Oik98h;orHue0G*zHqY$&Y^-1K2m4uBIzR-{Is>uU$U!0ke2DG| zAw&TN3-f^yFQFo7DB37maB)ltVuAZhAYq~Z1-?c(Dr2=Nqg^05N)D*~Yieb_wnLg)_y1p~ndF+v4JkPm}J;5vjd@H{3409a56 z5kU}omkmM|aG6Kugirx6GC8my7$G_++)_jit_7eW2MY@!B7pBBh#>EP3PIt?6mswz zDjN76H3kk8nT{X`$_FPFQ-Z5-Fkp)!`~tC_2waOn1%AQLj3Ws8_dI+NR|!r;!ayW+ z7YYPL76cU$KrCm2j|g%17y=w2WNq-zVvKkY=v`JKi2LC#xXN&6b{bMq0Yr2G#qWMARQTuLc)K!W=c5v;hY4~aiMGXp*Z1OyA+ zqXUJ%gUG<=h-l#ExEQ$iJ%u883|~O>g;Gifo`l5!#}%R>LM9+AfXoijT14MaKuYjg zMh`?WGz17-{uKifg~ADWRpD{uH2BCqh}^Xwfl98Z3L+d0yo~S(d_$B5zJrgADFjCH z6%G@YhXV;20U~!2`LA|Sk-O>=Xc+;ZyR!dXfI{xersZTLLPWn4!5vzNW*|Y9CZmD3 zi(nCe!2dB11i5Ek0xb=a8_<8@pa>QHi}hKIh6q{1eG@@YL|^WB8O=`v7vRSLAbO5i z=byHO5DOut5{FF#2SU&R2<0LrhJXgy8>sM|%9KGsY*Aza$O2!ADZ;g(G$eQ86}W4j zpa2vI27!@*9{ztb96=uh;Sh=aQ#FF*mc(ZG5D^5yk<NpQ1FfP=Uugh&Nx4lJ|`Si&MeL9h@X+?7Kf-Ug&b z@`CUlXefd+h>GrUo@JzgyR#U;E3oeH#sLZb!yE1nQiQuPGUFq3d`D%(L=(B=u{0S2 zyn`4EOB8Ybzoz&=7>MpY0^x&59RJxw9up1O9bR{~2EDgWq^%)2e93mtx%-+yBEoP} zK2^9DkeURkT(Bs@5B@1gK=e-hzu0L22spq(2-Kl>c?t{NU7*26@a~RY|1gIBQ7 z6a1q%10D#9P?it^aKXC=@I3`Az1&6Y+&n#<{or|E8gwwiCgAO0Ww<7gfdIMk{Sbis zTiK0~27o{tat8)T81xSeIrua?0|7Ff`$Q3W!`*3Q;CMpx@Fihg_}W97JGatf)k8Fa z;UClg<@m1y&g=*U+&SjI8263|pAw(}AaOvVd4B}~(7ib_;ol2V1j(R#Rj6>>DfQmo z1x5MbIt)s1(nt4#hk`{Bg94!$DCiC@fG8sl2y_n!_|7?QIB7_bGzB3{_+NS;5m7h_ zqLx5rYO=e2+*#&-g(8wiw2<%rXT%}A0I8k(5rwb7O|vh5{ls>=%XEE>vd~#gmh(@4+!2fPOYXKMl_v02M zbjR}lHEyx*DT`e7A3*;tydlbXXOIF=c%ZNnf)I>w2`X$fgnPivSd}^c=aT>TScC{5 z-3)mzBZUIom5v4;DWHpxDhuZQM&wSTAIa`j^bZ{<N+_ymMt_AjIc}J7(>X+?x&P z?jpj&|L4UDEJP`Y_6Q@#**z&P*%`~BdK zL-^Of0d#->mHLGNb}JcbR3`)>n*Y$0Oz zfanVY9F65MVrTbn!+5{F`?vo6{!R`dN*Z`4A3}R~!UQ3Dj#%!WE*t5YaPB*XjEU^n z91$b@2d*Bx6TmQL_G1*p^9HmWFd+zHzy3czqVAX)C(;Xh1W#6` zuRnO_*YThWmB#4c5EJzPEoB=OMW|EkmJxfD?u4#ppt2=qn_8v*VdtCT;tuw$&mXO- zOLDAl4lB8Dd04NHa&OP}Mu{47eGAQl_by?uvqYHR#ln>y@$As9%k6N-#~c?J?B=?m z_|iQ1_A<&m7_J4o?Vt=Vxq_#REC6r3_efpi(oPw#1#dq{Rfc?8P2y97v0K{zu#S?VxVP*Y}y9R014X z=7x^S12HB~-zgA3!yVa_fR|OV)8sPHEK0T?%y1Q7=kPsct+f6)96P=Fb@M^b4rO3q zzhkioDIj22A_`mf583b_C+q|;jrK>>v|y0iIjodH{z%&8c|k$FqLidA)O9aLmgo^& zL@c%n|GB+^>p`K7S?*wEYnkyEN1j_p^C>h!W^~8yN5WVDlZQ%Hje69kuP6;mG5q1Qj6p1J$`31QDr?+dkrx}ssI~ssLbWifdK($u`24W3 z3M+X9@q!wsY3dIO6KPPIV>v#Ti%lEv?pE7i(twoifTF z?M+Q#52B24hcN(+v>BViKt?z(A?~=zl&Lc$YmEGv(G>h5IjWGY&0yIJEgIke^6k*4=4JB<+lGZRPy&-&VtM02W%d3nY-670<#M(h+dQZD&92f|F~nXwJgpFgr0{Q-_dL&x6oled}DT%P`^ z56+Tn`}keX%ZpvdjO^2Eu#)8=-e^!a`>pKr-Uu?R_ICPkH7uP1m}LKKW7-c51;*J(b{4zw!J+YP=rosnW2JX9ZhY?U{%bP6>9Pg=KysALn7>r- zvJL7zlM$)&tO3ZKJky=g4e+fh4v z+$21vZgiB4u86UU5kDAYMN)iXtH0b%H~h#`{SW^9t4TsZ8?^~Rlme)(I z4Km1w?-6_wo+k&e7(U-)-hR_>X)57#8!9ua$qPMmPmRiiYWg_K1YJJ+^#NA;o`)$v z716i*eg1v}IIpnzC@EBL_|G$Wplyq`Ov^Cimwx0(NGw}Vk<9?M zDZY=XBwAF*)hCpLUwO{OI9xs6YsH+q3Tsw6gwKsq^>(dbk50x!nndd+o~^kZ_fu7f zcb%s3Q>M#cTaH65+Nm(lPZMiN@{i?Pceqh59@H~Dxy*yHKhc#-_-Ne;Q)jB? z^o@NqQH}NxzKwi6)2q%zQa<&v+sE^#I`d+qdRrB7`Y9FR$mHz)l*W770HhR4{Kw^M1MEw7a6Ns|17!+jRvA&I5tv>)kL ztc5=oKFUdQfE@uJnF4|6q7W0{Q90GLqM%+L8dI<`-j}?L+V0*J3K8L#7M>#tmacjx zh}NRMl~_671~Y_PE)Y_4(msitldF0~*`_>R8E-{2ev$WFTPY9%84O7WH07~Mww7Xv zwZu{TkHlsv&qy1XXirk2nNSfjOW{0KG0b!%@z7j?l`NwA9N*w%kFegrPZfm5AUBMu zhs~^~KgZVtjPv}@oVSWP@)U?9EzHD$?NE_1r#TVGAG zW75uwDq*_WI(X^Wzn-<5BD`E^vJx*9gJ>eVk-^e6W|H9 zYc08!s=VGx<6O*3@hTIom+YU_jJ!R9Yu$=KRxXbi{pU_Gn=N`nQ?rS~z$ou|411y| z7;Z$%Tpfs(MDt(0ede8kGy7_NH&Tuz9+pb8W4`o9S#?c6BwgP}|DP&_6wYclk2H z@+rr=(5%5?E9@GgMw#?SKBcAoDN-?n%WZhz%rbS}s?P~QQQm!v{(148Lb)%8XqR9c zj&QF0Xvg0*%pPO!7rHf4f>;cUo$`22hJ8M;-888L=8?Q5$y*nD^3|21&~DLUFHu6K zBW9QK{brDwR;>!A;O2uAylHWVAaMUXYrr0a+U4cxoaS!xTe7i;?0MskT1K0IwdS63 zw`*8}zuZ5QyG2uK;?`^*j((V?&@Xe)CFZ8!+D!5RPZwx8a?vxYjry{(*$O z@qu6nrS@BU4ytu@!EbmzQ=dqgt$9v(1J5_*R)hL6X(^UI;WaO&K17XYt&%0tOmZQ_ z9jzNMne=lbeH+cxzh)6um2to|lNzDp1t9(V$YHWf-)#`(dQdkh-0!h}dzH*%7^nQx z%K^eZ%;u^SrMb%Mg=bpvY7LMkQ_M507(VrF@Yh#-;ykKn#x}p>nB}mWMSlUa_ACt_ zs4?^sTK-IzA5;+y<#jOY49e3a{PwLD$KEcgEmvc@p4pjuTq3hu{kIFRI)^FkOp6ew z+sdh0=m^G4z(ws8r`Qmm+28F857;^^OZ!xdS>yYQq;;nWp}Duxn#Z4G_ceZhkmB`( zjR_?3fmkz@{zkWi@J+SOtlCJio%^duc1#vro~cYe5QC@~^I9{_NK@87O-Xj;vaSl^ z8)V-<6(^)|>rw}$80;Nxu|-zP9Vqg7(wjZTk75&Z-utol2`7g$aHsNwP97!ztry~0 zPW+`hiJ9^yWhewO3V2_bnvO=qAGbSB2$}woRBx|bjz;w{ppk8Xff+a@68yX`47ae^shXXE zTb9Y$x`)!D(o?8-32%kFo*5SP4%O74oZzTlNz8%k^?r7+_P50C17PrLUly{G2;A~< zJKoM0O;OPG@}ttO=QzVb@pbb?Rc?jJ6hs9PLx0#D+>@VcoI5XCs1WrJPjr8qu8U11 z!@p|cw;;41Wia|a4L=HJS2XdQ^BvF_r%iL#E*U;shyE=)#*)9xLH`Sb{$O{rb0%O_ zDpBa-dvb;9Uv!2wEdDsq0mnL?0o-`3EyW~QO1tu7lO^!?hUYP6UuoW)>C@6P$FiQy z#hPRmjO0Kn@287iZe4DA*EYCW@Tbb~$QMJT@3)qwQw`@V*1obqs8u3n^r_{Ew&r^j zGxz{Gtnr@AnG&S@%o;?nhF+1hnkzFlefp;}RPB~CMzO7J%R&u=!bHncBtqLx{@-%F zar<-KG+Hl{9a@zYU;iDW9K&!`<@t14q=w>5A{0R15mc$g2!E9u+LhdpRUOM_HBbD z*>7-&DTislkGY+PD}?-C<CZ(!J0lmL1IQ z3gYzmlG<&OGB(ck>mi5iAo*zO3pxeVsj5!B1oUb%Jf&NKZ!k4GCY8Fz(@6eTPqxFD z$qJs|&5eL zd9qalr%*vBgVlfu<4&^ueK5{z%EgQ!P671uq!Y|{;PN;agBiL!y#kiZx5#mi@#ANu zm5|ao->bYo+he`VZ-duQpI9kR)fQxCqc&IBIb4$TG-#=1&-H#$KFMd_ac0lZchfCv76e||lt!$z5K&eCb5OY&gW)zD<1k9r!Rir$8hs5Y-mVRGFtqH^QL! zHD_P6^Ht7gNEe?fy~FfJkGc`=c)~Pr*q*cZIQBEXMwlZ>_wZbJQ&$At+h$8ByX?=?L-_d)t+&cLGVQhAZ9i1YQbNvgUt}u_($IzqAJjhuinokkoa!EvK1i zdz?p>TgL>Z97SfW%u7>t%fWW3e`Wn zG%Zpi_=^(@JyXs*6Ugn%W4&Q|=&k1rUgmV(m&otHTvil!6{F%1Gmg%VX4O8wG<~i-< zJOOZ2>+G7N|1Ak4=Puo{r_W1hjYOM-#=g zTKqKOW&E69q)`!s|HatjWMBy|+2xI6q|*Y&RviVXLx^n#5Xv`08%_y26JVRcMrAj` zR!rA@G=3CWNUz%3nU(gd-QEMt^~5F{xn-olsBD3FVS z4omy!=h7WOsnpKyM-~trcG#PWM?<9P1Yl21+kSYdNBPqVTgWJzSd{~!=ZV5J5?vSk zCI%McD5RoTESK~&{Fj1|*NDUb5Po6w%sX#ls)e>Up?5>lE$#i8Q)SVWeYiB`D#4PF zoUpzaHdA8&701Ds^mrZSm1xJoN7C3r8nAfMacl8fFk+8L-T%IbUt>vdd%UZZya|!F z{2=DoREaIF9TR%Tr*&FWdi8Wz4YN%Pbk$o1TZmGZj0;_GwFnqJnw#-{4~%WM_9qR5 zo<<=I8yaftPG$(r)_GtvSztC=5Ty8pEq0W6YdFmes7BOfo6yjW;cSrpUB*odW>t+h zv2+62PK)IJuEQ3?I+;wtjZPk+BNE^h4ruY@**?702Wp6oc6U%E?+oR?`<9(3Zkko! zoq%^0ow`H3@w|qqx6I*}ry+GOLnwu!Ub6_Odjm{GDgV`SZ7>k=Cno(i640i|Du@YN zw{;RgRL{YBoarh_{5e;9)*<;h?BRejwa{1u%}`!*Iv_`;@#>p?sJ!#lr@x-VpKRy#XVt>Qyd|sj_vyxGa@rMA|_`~z*E3#)Q`#PEV!zaIs8kpe8!kfypbCkum_7Dd9)uKSgkqa%!c6PpnHqaf zz?F{`TQJ^_$t@1c%uaW^NvTa^u=>~{#*H^h*rqp1M`d40oU08e6yVjw1K^1z4(&89 zCF2!dSNMd_CVa7E#?vM+jDnsvHL^j6M=Pi&fx?vMwAD+W1MiL$`P3DP=%&XLYpRy+ zkA(RyzT*^fkj&$E61G_|S>P^yTGzrye0}8}W3lK%MrpSuHy(~3F5FsifJG2&D!Dt! z^_X{owOnDPh=q1THu;qIYKGF!V25F5h+c2L=KIjf{=67Kq`qTBI7t9#Bd9zd^+kt^~ zgGAqdd3CiLF5zxubkkFXmRtoFGJAJArKrwm_5`nX(UTUB_&B{Ec8pL{tju}W>87VP zis@s_(@Kj;4|%_}2zyJ);7rE&E;7H*x&lw0+L&V2_*wWWT!_jgf>=|OxXt)P8)y=g z|52h%UUawDVf;JwE5Z6E&boshISfen=F*#~HP^yI_o-E9TQ7POdNFa|)u1-R5cd6e zmM6u@6OHiJs)5YXwFSf{p!HQ~7Ne`bCgPKL&m_z}k;Tl{5yn~A2iY`Jz2K^p&10{} z=y}h0wIEG-P&V!rfg@1&!ADXj_i_!ztaIuwuj>A{Sz1FS87@*(V!UQ08p;xY=2{|U zgq}@1WL$y2Ch#KTnjK$8Q_LBlg6o))Iglue9Zb~oo0fFrnM2^!i+I7InWOQcTpIDh zY5@ft76q3iF_`;Ws5(w6eJ2&XRuniwsD_eygCWNaELq@L^l0)Yq2G#xh%mXqrASH0MMUQrjn{j>&euKxYXt zhjf#}~cS?(GG%dxX-H4&tXn?hRlXI}BI$ypVaqQEQXdK)P zYjAH{s6aKvQ+AOOeKRFZIeTM$DScg&$#0P++H37rfXa>SAvBdBJY~}rAJ8a_sqrTA zp-GgE$d(m=YjereUVe#6I_do>0kcCgL3I`vV<=$zg3fmbrw)5eeD%%8e8o6dCJTs0 zP$64b*HAN)FQ7)8V$HF{ht zL&$%SD4-}9B`Nawtv|rCc=vkiU7vw4K4k5xC`Kp5*ZCIAr7(u(qu+WwIe$@IRR577 zUH@4Cvv6l=P1`NQhIMGi$pu8+S#C9+|HCWJ$nFnW|m!Y?+`P zEyR)+#Q3X)fRK%%xUkDY6m8`5<+KIo*;hLRPy|(JE>*n2r3PS4LSCFY) zPON?s=c-Y$K0d=l*lK1~FzXv<#i!Bd&gl%H*9hKz@?ew4iP5(31JB#}*|(`|>)Q{j zq2>O58nc%(M;z-OXQtc&JgC;7`j!yQwu1hUjRSS2nt|(K=YCqWhx|HVC+5^B{J3d~ zpZE|@fIj|E8z{(}70rHx(O^Ds#($o!$P z5rd+P6kUfX>>K{g>xXi`_gxin|2zG3I*jg>)eWn%9@Qyu)vF0*Oi-Zm>qk>IzB zO;bML&fIwCN~=sJR6_ z8m(GnvLVrOP^G|#sf6@s`&eI`ar7^kbZG+zF<=&JnBE(rRDw!Ogs0|}jeiF2bez5d563Uj}uI_Ini zYY6k51hwD!h}gX&+Omfk#(1#|?xQl*S_Kn4-c#s*`<3*^E5LA*L-}S+0?_6`MN%2R zeI7xpJ*?pOB6X|XD=YNr)bg>{T2U3-#8h3CGInq9hYP(P_8eOnGhU-ylqASt{e?7zL8+a?LR#>wab&K4)N_yQz>8Z-iS$gAS)~PSK}A|qwPn*p^xE~vJLy@Mm<)zX z#pMF;trUs`|Bhm2llWen7aySW_z}04>^Yi>k_e23^Nj&;5Ww~EagCW^@?);cFqIHH zS}X9WtnmPz(G}HSE%a%>9~cjJ`GW|ReyJLM9>tJkve8x??Xt2#$1mO*D_Sx+&EpUJNOBaKTV*6&;oo013>5$MZfeaQw8NV|#gyptd+2D`QI**J8Hbi@JF5yp zu;W@Re9T|mqMZ;yFNqc=>z@sf^~w58$uy@V9(O4r0MPcrc~m*YIMwwqgg)j?`VAEm zM$VTPQe(bF6qr}<4xvp;4+-9c)i2S#23zRD`g0^$W-`qe-OuUhfumaGQ+S63PiKAV zLJk5OBE10TuMTti)sog}Eio!sVt8eOdOdmpU8H{e51f`w0CvpAv4IqJ(_$lSsRddHL!z*fZo((rWXJ&O0C~wiDGdxvxswZO<_`^oi{`Mr80{ z?W8mEFEMAFU;8aatlKmJf;jTc!&|iz(AfsJC8iW-T{CCD;JpDzRgcG{zZU@S%DyO62qfU-y|*nb!rHRYr7`n5&Ho@hW7Z z)m#zb{-~L2%)uI~U@@dVuos>x0Iw{;&*471YFH0A7N&pULw%A+^vk)kI?b|aBaIjoE7~l*%d!3sHLRIZSWDV!nx4~ z+u-J9x;aspFX4$f?&-dz_Tb68?I3I#Nz7B4OO;Y>O_J(ce%}Q^f0{rvf%M$dxJ@ZE z{%G$5s!KF93||9#_R|)e0~1;|*i4p#=L1`0r+vZs z1TYc-TWk~g#;_j?nHAx4(d9>a8@;%TGBs!fU)eWg+hv__Es4BdZ%WF$KKczAaFX}T z!Qp3Gd)CbL%>WP(=65s)UP84Zp1;&Dc+JcQ$fJMvDbKK;x|+eg`Q2aJXjt{lhbvoU zkelPpgH)WPtq}i^nHiQ`Z9%qoZJ!9bEk zC@uDK_$3y)zykiE0>Kq4)irEz3MFx1HU5(Fp^{No63O4@wyTq?oy!ZURR^|50T7y% zJRJsxhzQh2lrtq)*v4^rRo4j9@ zLgR7BI`JmL%N~US@BvrwHr=tzJZ4J50gSW=^rz*H?Fe zm`g_cgas@+v2}82&Z)aeZH)?R0a&YTAbzI-gN9G%#vC^j@wLlk=j#DC9q2!@^`c3m zg>PLG*~;Roh}kVU`0^Q3VuM#ikF+p*P+$7jvAuAJULPYomb)N+v$VORrMLld{#;Y7 zoQqm=P4NAD)s+bVW$+oy!m+kG`w$##rAO4T3c0b$pUK1}Qu7k0gL z>afTo{erFP>(eP$rfhE=y>C`*Y~#&j3A z;@9hEzoiN{YU6tSKF8XbDcdbD$X$J@vy{5U@((B*ue!Y@ZQIO%bvZ-(vEnk?r8`D_ zJhu-Q`a}rGPQSw-zPHj67pY=PN_gf^&PHo)sq#Ip*e|O^_@sT&$lGi8%p-OmUKte3 zB=PAh9|T^+ikN@JTVYX9EGq-#{S6aUcfbuPHIB8bS_W~}g)~_+7-=xD%|s`fu%bMb z*BXN#K@_Q;Jzukec^Zitchy(>G$x#`$ejt?P{Bf_`f}G^UkTiX!#L56+B)s zR0^&6<@t$L`Bo`bAFV2^s;%0Vsrxkh%=%_xJY%GGVz*&paS7N_bIFT)B5%dN(NibX zC(tPcDA|3n{_^MxBw?MNUxdvr{rewvH~*~R?CUJKY{zVI7>Ru-b62{BO0;scX0(>F zrn1JyTY*QGb+OIre8sf0KgvBbXO~iMMj<_#u@p{^bh1jI zv)m_8j@izD!*_uM=3j&lcCHl6`lQwtR3$g7jw-x(dqs=8OF7S#Moeqdel>`BB?u@L z^n_%o$&7sRvW^lFMiD)QdbmvTW^HZJZJT`W7lnB6ad*KOmQ7T;IWs&HZbLoWXha)6 zxBYA@P4+BK@?>OLpBD0Psk7^DkYA%~`s|3~!B<#M;4xx6^PygC=jF7~r`1oT&$s?W zPBbWuyv7;9XqWFYp~WsP-WYnw>z3RePh%> zG4pYlE8IzYgJ$BddDKSd=kSNE?rYjNem{O26V=wKRV&zhUsmidN@Me{jp@OlbF1#Y z^w=fJfe1$aE4QT?Jaf}C*`wyYwTSnWW=${OoB00juBALN>u(v`myN=EMM=UZ!awys zQQ?;Sx@nXA=*Ub*vN%w+N#(r25$WyBo42<$MPGQ0FtvJQ4SOTI#m;CbdbkYfai)|P1rVTOTWtj>MuDn`OH<8OJ$4? z;ZloqTpU9K!5%N^SoxE=^Eog*q92p8fQTX0o#ba(;mK|u>2yrQy{b==(gt`|I7JoB z*uJQ+R(F~0C3BK!n6XsCsYuk8qqAFO=EJ3yVEkvO?X3H~GFhx4SwPoh_zIb*#=K(Y zIiY*9{4zU($D3BQd6r!`QGe716KgU%Yeqq*{#i^`*r6M>WQf)hs!3?#BIJOyNiq0y z?H|emo+eF~q=f;-6|DnG6}C?W2|q}s9Aeg~v}L($QuSVOm!y0wdHY-$^083tV=?CQ z0vP-AA_^MC9u-d-nR3?ng73=D-|Il%ejYQVQQCp#h;88hDZnYfa8NO24P)08J|1J8 z4rl*P_Et6Rn@x%e_U-`c|B-=z_Kl+J*uo~`k=6xedEpE7 zo;vlYV!SQ|iJsim(f##v!gl!Xa?3ehAW;r?KvUxGZ*pJo?mE_)%neBnB+6GX=eyF` z&=q-bD&z0UgWp$zH)61`jsdN`hBKAmnA|njL&z0<@SBdIh2Oh}L}yV~bW)>I-Fkmu zq&Hk0o%{!*XKcY4=1aMU{AX!b+_y2X;f|$+gWa>!E36xSvmV%r)V|}D-3{LDYxDJv zWc~sD;IP|~+eO$xhcEAT817Ter(Gx_*p-%Ek8v)SUiea(MX=e&`qxO7QEm-i)S@^6 zd8~tsq|V|4Z=X`sB7>Ul36l8ba;&l9u1~s7CfgC%;!rq!xF%3V(H~+3b3d`r*53 z@o2i=EgI2?zx_#8)8XKnRI9~OKCDme4IhtryVdH)pN-S&GByOg+TwDE?%i+bE z9YJf^wY%K`yRf~brbEV{tAS!lzF_ao1Nw#igk9e+KCQpS=lAJ%&k}qBzlg)ye=Kpz8!wkgZ823^NtALbhrYV6`mts2dtcVQ)vVBbFF5?RTQZ&k{#5;(*;MZ&x&K67 zbF9C${*trgNQBG0uGBM!fAFW#*Um4qemzR({>OY@x9EO*Q3yKzVaZm6H7lNV{v5Yc zf1N4K;YXF557*)%`c1|E1Z{}^@+||8xsFXJG24e`oeG_vD6)&GJ!Vj(DEXJ2?bxgr zKTmupTwOLFH?FKrQ$5MCqumAkIyhh>T$q@T5S|q4`&5Fx8xr)PMNP$zlFlCk4C<&v zQ+gj8gBxT`Ot=Z)Auh$OfVtN3Xr-pAyPf^0NT_gMB~^8E%pVFGTbHp@@Txo2Uc{AO z7ahDLZ_a9;r7{@b8>znRe%Cr0_FBhG=|?%D_P>yfu(&xpfk+au>)}`9@h?17UHEj* zgJ?w6dgDyyw1I&M$%I)d@9-vnD4HlXgd8M0S5ddeV4obschghv!t{K&xr9HFujY4X zdAv_FyrG>wAu$;4aN(t9;MQr>=m=596?GsJEOS-9)YS{(;*yn5&34mrPuN)vw5=_I zl$Hz$_N_>VZikum&nzi8e^0vBES_3i)i^4E6hCMf;o^|>v!(BHNg<=n1AuBkH6)f5z1uFI2;P=7;g&j?2ITSi)4a2gj3W7`7{1(rV(VMj!Lktrn%p}<=3uN3rqW&Cu7HIl}jH&W-a{aJaV`o3}5{LYQ zE+9jtLv&8GWi;$(G%t3%*GmaePT~IU+_ol|4Hf~xSZ*ik{*lsC(z17g zuQ5G`c`|E7L1Iaf{&5EP}y~QC=5JX8K*S=-c{n8OEhU_Z1R$F^Y8HO$u;@9GZ2$XwlbyY`rJb`&`6L=Tz2px zsb;6Z3CfkJHn;|_q0<#gO)X5RG1Rr?urbs1POp=Bl1jXLV_fsgjFwAWVellWMpt)@ z$;L(Zjq)HJ>yWWRHu)UbI)wv1NC=ayOq&1MUP!#YA)g?oQx_p-RK=0t_8E;!kE0uPmwT9*9LS%*^?+u+GkOw90Z^}2^aI(D za#FYD($!L81jUhOA0cQF@hCeNK*kNZ_rf^}F_V{(0nu4pb!HMfkh%)`0(Iva)U2ivw~d(ikwcFgfDi>usfgWnyo z<@xDXLMLulN(tPW+{>_0%YnaP`;4FYVx=;k6n3Yu@fgGrKEdbh%bKKG_yXZ<=b5kc+>Z8j<(faV2z1#VJIk^tRUcos z2o%#~5=>X`8eso27}mUfKyYcNpX@$gH27jr)<(<5(MHWiuTT$0T^XnMnX^Zq;2lcc(rTE-{!6`;N^RVxyD?FOQ*g6V^tbq`BZLnPbFegx*$OfGf@g_m)6>oS@? zRoFW!Wk%7d<5X;feT;euILvDn#gFXH&F}l^iCVOb>qS@)w>P;<)ZTC zd}8&K_h=`E=in3BD`^v*_Fd4@5JUIb`BSrXIVx2aF78LY({S^Hi)fFDc26ChU~+0; z0~*#j^~}58tA`DGzq**FL*#6T>Sw5&)<54&@#z4Zil2lT!(7&%l&*SbMSEYWk{*if zs;Q^W$cyDYcG08RY-}3l60Ub|SrwW9i?B6_+VGM(2kxx0S65H)w8!+(`KFp`gZeyq}4gkkfrNUNQCT z%_yDS;p=!e5!gxmLtG5(oD^b~FF0a>b(Q^s&9$xtrM1t@TbOROCFCDBc)pm&k~_E{ z|4X|}Ki8C>-C&yI=)0aj*b?w*u-T@}CjQx{KgUGETWl^9s&OxTCZrzQz53JAXJ}+q z_7F5NH{Y^aE&XQSEaLL?eSWk|7PW`V*F-7oAYdD5x<@u+w&bwSue#I;aV5-3ChV+bbsZSgkyN@J*wYW z1kfToZQ38y=*pdRN%*i*gQg@iB`CZbWkqdqajqg@31 zJq~)%DxwObt`Ed5>Qa32RmH+-kv}Vh^zRo@H_n%k6)KIsmc&Tc==iU;*?W9iSb-sv z)%p*~dPJtMf3m`7HL|}YNy{wa8@k6~?N!j`p%N~);F?8hz0z!^@MU)+$j{^Q>N(zy z^63YyRp#!FlE*3XvB?Qds7D$sqPMDsGb%rTB6P#}b$C>kaopLS5DW2Sh--zaA#%$(OVf9Y&v|U$DpdPX4}f zIIemqOoElL8-9N$7Se|FCWFa1GMg+RkB|-I40)G)OFPhhbRzwUjbl^U%e*7L`|?u0 zKw2yS$w}s|3&{~kt~6w zvP_o4ir8eF)e^P_-v`*|Jer^70pxQ_X`Qr1+9B*P{&wBd^(pn2{NP{e zU+1sz?+<(q5x9qVSYQa1gR>uw?+Liy>rmqM!Usf$yo)9&q&?|@oEb(Ykg4PWe=#M~G9!y%DeP`m z%to{6>_N7U`Pkd+Gxi0$!RqiG;2Iv!6S#+`^1JykK7()O-|%mwA<}8-D}_ceNwHW_ zrT7`0nD)wE%HGOi6>&5y+PZt0+LVq!UXY4Rq;}UbMedX9R3>A z@FTdkcks>+D0E~l{YjyN3L^h*n!Lf%c`7>%pR&tD$+y7;t|5`6hCa`Fp%lE#+e?Mu zWSf8BMK+bpfde!TKvSz)fpUBg*@bqYA8AScU;*@c??EZbVqd}nm`Fc{8r0*Z@B|sf z$HFSeAhY2ccn-B9S-MY=qKF_T>3CjF!^nQ1e5d$5Gf5;&3WtTHm~B-2L_dKUaF%P} z5_f0n+;3ivgt4;hCVFb5XH)WCdrP%3}q?~}2>$N+HjD`?$jvzFY6bRJrjA!ySM zqIOrK9q7Ocu*8Ov(*xzAKU#>5_+F28f};eDM;#xCR_qyXmtSiX@4IW z6nG9c1jfRBfk&Yk+Jhy5*?7kt@D;3v9b}RJA((=Z<0q)wJ)|!5tkfmYjF!_+XkUN2 z?$-T9Zo7#MzQ^~A&;{B{hoPK*1brblup)2{rMn4Q*bOiO{nM+s${%rruIw0O`0t_n z0$tb?T<>M*9e6$vPc$$ta4+4&;a+|hF@?@@$LJZzae=LSSS4pWn=^Mu@xY3DB?u`56&m444?_p zWUNcUc{RNcpgAt3Il2RB=>X}209xYMt^N@I!~sCo!-z`&ZMq`1hVWq!ZE=6xcBfDY zt^u@91jxmEd9hCioPWo+0XpG&JNE$Sat{L6))nX8trb9bEX&7v_Q3TN;CMY>2k5m1 zp!X(#zBriy$b*5%zakuC@Z$hO9u1=S@jLjBQTLx=C|a>$_x!(&k~Md52mc57*Z*A% zPrQRWxPv>mgFCo`JGg^8xPyN?xPv?R-v%Y}2QHHMR=*ND?x*CcLRm#Oc*8*AR~cxO z{3?Mcl|s5o*%8_T)MNu`4z^U&jhyQBY85w5OT6t<;9+KpTHWTf%ZEbr3>M zYc$&V&TZ>$si`+{ne|cA0aolz*PTre&51Mi31^~98*qFi}WyN&M-5U znGx|#*5y`DpC$J)HOccIuKV5p_?a_e7DHJjyel*;BF;V1^)0Rc#>Ob z6&j@koPZ=Lv_Gm83t!6EjQ| z{4mw07U#%p5p$}~!3!~4vak2nRP5uktOEF9F5!VGGa(gbR) z(iEf7DNQ!LQE7@aSQO?+Ll_H>G+1dwq#=q%*!0mfB1RL-!ecaXEZnBIE6g^1yuuu# z(Zs~KK^+dD*4u3ENJDsJq#=U3!x;mU(rs2$k%Qhg27_L&(WoKDW{ZpjO+k zR45p254Okkk&l1t-3G5YyQg7`ff{BwHIK)rAIJM5^A4D^9YCOpZmV?c947>+IJM@g z>1rdrF8CF^hBz3!n(C32=Ik`QE|Hq2&N02dq`6HH<83cwadGj~$S_xCMwm0x8J58W zG9p~e8R2BEFeeLhhB?O$+*Aia(q(B2TGIuw3!QYom6SvdcT#JF*E#{%F8ileS{hp#M`uJ&i=i{% zAuBD9To8XlcSgKur3>uk4qC2R5KB)x-b|urtjA+$b@ZFzbbRY-D;*y>I)jc*BLgyq zw5DA$2F23?YsVOx9-SReJu!(63eB3?n>E*HAjWEqi*Q)24o9`7S-3{i%#&;)t&;6+ znKou|oNH)F*p#rXVJt1o8%Dz}#;vvyTNNGTjg5b5Z=dFfBXMooBoE!HC;F`|hB}l) zIU#H6dU@Mwt{2y!PF}rUQ;Y=DS0VRmO>WH+L-SMv?u*ipv&0~XDMwDo`|@uu2vN5} z;YvvIWVULZHN)Kt>Im7s_Sw?-185HzD@Yj&pS{aK$c zoVb7Y#gQG)KDF+s{|BOM7Iiqi&*-uTC;9C&@`l~rZMe%t3j7Bj9kc4;-h1|p9Jzk> zhNTz!PFvM+;cHd%-+SD@uW)*kW3v|zUfqQ)${UxPKWu2{g#48HOtN9%+HOV1Mx(e6 zLiJ3NZHC7i0TLt9j}+K^2U$ZXnV=BbFF1b!xiuuHsvx*X zJk;DOt94d}LW%DP6Csz^zEd#h$ovPB?sBD)RDbUyQlTZ(CVuCk1kO~E7QIrbki>s4Kja^N=ylp~u4F2rQAk<t&yo9Ez+SlEXx{+OHe2qg)B*- zOhWndHs8`Uj6A}^$1Z97&3pC_V2lL zW%vH8n@5RnvQ2{;-j*N4Q>BeJ9_~}qKUM5LNvTlZhpYTkBKPIeo|Muk-M~Te6pIV4 z=hWnwuIA)G+I6&Q*IT5!&1kUj{6a%zro=y$tlmXd`={2BM|TLi!+#%+v&(;pEPykh zfqM>U@YvpsEa>I+$Y&T~b zK&_XBwncgdifp*xKV+zW$I7f=-1T9l)Y6Qt3Wak=xVU+Z* zzrw`{+#gS1vvdsgB@TZM>{mFVOtDpgYZcU?eI;-OtOyIj7`Wmc!4*sBQteXXNrR+T zYHc(xtVcxms7^8c!iGc)iRu$GQ8`gNGVI=niBTmn57PS;GqtmfOBCys>r5wYpVIS+ z^V$o>=x95a!tHu}WU1QgbhS!X6HuGb=U5YOE){2|*MOxC@Zx{e*4R%h4;`L(nVKq? zCD=uZr$RBb5if!WGg*WswOUX~W&0Xt5?0e}LQASt^q=^_)|nO4J5Kmu+lLQ6a%ku5 z**ka6o!z~den2?6>xE&J{=lbxzyGy8>t7;I`Jedd8W~3>{5XEG*o(`^pjzaO21>mS zCcL1Dd>&m*H>iL33!JDyAyKB5h>ns|8hP#(u_7SC4n^xEFS<}t!;;b^;*h)&m7=uO zB!?`5pcG9_O_kRc^f7aV0t^2MkBn5O%dAi+Gf`4AXzl(EAM|_Ti?r$dq4u-mU%dO& zFfqRz+;1h$&ko;sTep+iDGp0V6^E54R3~GV-E>8|eujUEx>1H%mRVuTEJrL~MSm4@ zEn0U}`%)NsvmB2Mn;s&dbssq=&(RPhVrBIxTjSi2EjaJ1*qs*zIW0~G= zs-n+S_B0c76|o)A+ruTWSJA^>BcVD?Y2*huAF-e0Fr5z$Fp)N1o%uj69Y!b9d6d&? znuspm>V1E~4Mpj^kt&2#cB^x1>Wiw-2%J+0!9sG;}W1Gsu z&VKU!p2A&6o>@A)1#)sg;A?J0PNu>K-X@aXs?UGZFV^!s^FZ^=7}m#nuW3T~DC-RU zgW-$y<>AX>p4Dq42NPfa)rx=efh&niuOos%UcA|1BEHbxnbnwV;GSTgQe456;2E$# ze(l70d$-TY=n-zwmR2pEFn&e&e&_cuK5%N{m{AX}@qc^%)c{#w+pxs<@a%2jo9P2{ zMn1f7q2s`bu@$3+ZE9|RdDSuhZ(rk##lL^$XhMHN1A4gbZEY#kjni$^?bMyrNj+E( z{o|ZjP_{s)U`k1&WlGTL^!ihbqZ`hd9;i-_r{Q6G7*rU-ZS`uzKUu8P!6^-|qGMi? zB#k#NzLlnmWO?;UZ-T3pvdo#OTw|m{eR0FhtBG8D{j#&CE>by84CmsmI=YbH6{6411Ox ztn2=)e;caC+WLtoG{O!$rRPwWzxRK}| zR9>%(+hg_SVW!EZd8XASZbCV<$#Q5TU^CgMZH>cngk*w|tVJnqQ(-vpPx5~lf2%zH zEs^5TMLEo^L5VEJV5V5avrAOXQzc|B$XYEcG?`j_vtXh$hKb+>B@!aSm1xO5{a=pQ zaPPzW_pBJWqRGxx^ppCRdMhdD{lvoxb7Ziv%PcqhX4XPdKwhF(YmdQl2s3Z<*H#ga9g9a!P7 z$!~2u#2)^28UJg~inV@=zqaba9`Zdou}M75>5ID@g}WRHE=Yfe%igR^D@nF?vv%`* zt@|!rQm2zSFo(?M(^XTo({wZRvm%#6Ia$FMtLAGL>K5x)M!s!+Gt82J+g%ash!(`* zNE4))!y{zCp6t+p-3GcCd-JW$Npp+Su8^A8EqZ(DQ8iIl(Xn1rYN^rdKmou|$7nKA zV-)5}}OJdxb=^`%DwK*+JxuabV_7A}7nHgd_rxD8LFK0N7Q9Z|lyy5^x-KW~5GQ+oQ@=?_%woIPh7>1&#GUypeoPtn;1 zOeCt0FB8*7|CbmQe&erv@hEHcYU;ShhS*<$XIpGLOvI=BQ1rJ5>oILjdl zj&MNaE3CX}V|zXhv%eXui-WwHkv`jH%2~C?o^d?$(GH%O&M-c^dNpB!x1E zYubNk+e&FXms1BPe4DXhN;w!})yu(^I7jR2YfQmNOP(Z{P70NVX;T{}+8A`5358t^ zvu+5!aJ^ID3*L^4-^C5`>Q=Kdbgv}^Q&H(K9fXC94yvGDMK$S#4nZ$8zPrh82dB|0 zo+G>5Gn69g#C^{ZRtBQdq6=#9Ws45YDinVaXOaj)BBrp@b$&+a{2gRtrT=yRtCeDJ zrjczJ-zwz2x!ap0DF|1p!Oe)9QKg%6g&Pgv7J3$A+@lgit4Wk980lUOhJ(0Mf(JSB zfZ1r=gc^%@7s1=swP9}wu%SEZpWN|pD=wp}Ir;+x{UIt=On~ExB`*;xmVzr*>~?=J zmZN}Zl|v#@XvJR_<9c%nYQ&QNVa0@Gia*}2E|ZbE06R_R`-fMOT#{4iA0t*hNc<01 z7<1Yo0Tz1GP=90S?C9AsbVT&%7&=im+&~9mFhN@zIvZ$AluF6Llw>x8J~^D&K|JAh zITM^Y@tXLYgak*9(`kpH_WLwLBPV|(nua$J*6AIe4OMP}k+woi0Y_OjB^!w*ZwokvOd&#~2CuBXD?C-5SC!K@4VIY6}?j6XT zCWqDObZ6=_40(obw$9EjiCwzgJ)oaqR%;xp%%0kH$#Cz~ z3Erpk2ao%B{uYwEb#Q<2ll8+_7-N#|>P7UcpC<_~Uht3o{x|>ToxZu_Kb<%2tFDT?%1w!YKC(_@yd>#*h>l=whB8n+^hO_X3DcJIhEQ@Uxa zYMi>nw3Mweos`~G95Y=rX;o4Y89;lP#%X<~UvJGNj_ZH9foU~riE|A7R0^e1 zhiR2Urz8Llr7j!`C}R$;3&$2}yCkXX3Z|%{Q@mAv%de`KhdXz`fUdM!E!j8?Kf zz4%#vnX@%$VXFx7YJ2I9DKG2T8XeJzyve9MtEBUkWlE}i%y|BzpaqUX;GYdQH#*9M zN1ZJN!# zyhxmrMP%C4Vi(CEE+#%uVB*;!qZ#kf!q0ZsKe_D_^7Do+39%Vc^z{aSd>dah0kUsukm-XGnij)Oa{a3$%(PtD4!8QtZ|^ zwK~jVPf1BmhS)eeaw*<-z?7pJxx5;XJT)43Z3H4Tpu5NJun zhbY-;X7NcB35LOFQ8LWVo8nvpbrEOF;6ntD3ypKjpsB(1I_lYRx^&FgMXLvvy}H8x z7`bbHo9=)4T^`=-zd$Ap^>iB4w%^(n{ykE4(V@{ppUX%(QZ{y9NekA;Y#me3ZE|w$ zR;8}Z#4ddvY$2@sn7}vEOthbYN^f**R6=fee zq`_t&6N?KP!jYgIPE9Qq5822x5-Dpwa>tU0COA^*5e8Wp2H_d;{m1X}zxGv)|Dz}O zl1_ieFOsJ1j%FNxZ0DClCVjp5=`Sd4@l)-qBh_Xf7s6wmJY4jSjYSwUTn3aDiVpyb;SPXcvsbZbPsxdnuH5J#Ig0J~R z7LrJ7q!q(0iX!56whTRJ!dT3?nf$qX(A=WwrT5Hw&vn}!pp1Aj(J^r_) z>WH`=Bm8Gyf8OukIlSeb)-CeBd+zJsQ|v+twxceHUruUaus1>>*;Oi~5*QZ?)u?~% zT2Lv)p2eCht(5&(cZbHIry`e0a=_u_)aR>I zJw%3ne4do7kM^-G%9TS;9Qt1R68#iCZ&zeXEuLz+A%Cck zjLnfBkD-KNKq_k(NzD+S*&tkaedaj*>-h0{g;ZVt93Avm7g||gfH!|Xic_19vtsc0 z0U=LRJpHb0bC>)SyfULzkTy#X(k974>T(BZoIOZw(ZQ$YX?jyDhqOl8E1@jl*}59G zf)98ac%c_uhHD^M99XyphuhB27s;lf(~!c7GCWy}i>6M?sV{EWC-JCH2x^A;=y7pc z;asx<->~8G302@Vji!HN71QYq#ZvuJvqDWVzKr%dx!tH%do&uAM_cR&BaSd{Sg){> zFdjxckZ(CC4_IR=o_eE3j)7`wazh`u3Cq|z69KU@t zwqtgu(z)!Hx~QsC6E2C}#M4shBX*N4^0r_JS=lOe+ayh^QGc}*E zPc*EFw1SsQyZHAiNyAAdKhMRtHLiHo7H2Ew5EncKDs|ZwQCf+4Rfuvy<79fQ(qa|m zm%MjH;Ye=xT`F}{)Lkg8YK>Z@kr?L=NfRzfm_q?lphKh3Xh5QzP^DG{Dh;Drj7_R& zTdy%)B3mV&bWDG`B5|p^N|b5SmBfLriciVVkzMT7Y8@d%wnO$?Fdm;;BVt;iN;yKz za&iPvdxg&;p8X@W$ zgqUoUpGya=n6zdq#6q=}Y*j*dHur{Si-jL>V=^N9rk{Vm7YX$yQ>PWfR1_K^D8xzd zPibCvoPJD{^&9BJ0jR%m4JAIAepLTr-Fo`<_kJGQJ)R6RrGnU zK}lK2lqzmIzP>IFTJWGyIwNqD_far^-GdF+11OAmKNFeZod?vY3a2qDK2x_?_m+;S zb=`E`j4XedyY)>Cg={dNseiz*M6c3PNtLZ{ZRkn!S!bnJRiN)^(5$B$*gEAp)eiQ& zQemM+gCSj_xUp2F)9ceE6(&`>KE^)8i!P~3{QK2fz20Cjfl5tFEM*pIsir$XPg+z+ z4pkLt;nnEW8i!XmPfN7bbO8F!TCAZ}=*XRQ_HDJEj7q61!XNF`F4#H1>^qtYyF zOO*IXwm8RzOP76BOh-3nt`?)`nwt~+22ALU5v=UNE}0{Hut-q3{&rPg23?>QRDtv8 z%b%A$)qI~0>zc?Sq7VGB&!7>dp{MvC9&~0KnmXkt`3JMI4K1_en!3#TSr{Pyq+YI!RgkhOfrl}hy4Tg`U|D%+Fu^&+UrSH_g5Ewx;B$v zsdWfh*o2xKFQ2gA@3Uxy70X0ps}k{mQiY17!tj-;)SObaQpK4=p^%ClTH?S6u|zvX zTc(w?Dm;2+Gp)m(p))vW+)`!RJoS2`ah89>IrQmy^B{wW(1!ggZy@m43EXU@{Jq5hD4=zDAu1X`g&3 z7NH0eaWD|`rW1@-pQ!UAd*<_b$eOa+GW7IDq7U$y^dT4^2IhH7qKzcn6doQE854iQ zxrv8sBegMnXXHV{n+6scX^WwbIIp>9SkFjrbfHwJ9%$-s9u_tza+qyE^uU#%i>6!(Ia>j6??N=TP*zAn?E#0r#8$a!dKzq$tQM}2{KxOxfMmX z7Dke#r1fdiW%qvn!J}vW)jQrIaUXwOATbYq_sBc`kLW2fi9B`O|Ln!f{;dbzB7 z|L#9aT9KGaqJ7N&6$E`+UXS~)2OA9ZW{x&b45#^~{P4l1!Qou1v!e<^q%G)eSv;y} zM>N5|Xq!G{Bcg5&ZKf9AD5z=lwt~lSD3*z|qYF-*PBW$(Jye?fXu-XY7X5$dKj~je z9y+qQxJQeH{$*0N!7}>bq{IID`WF~kF>lC%2tCfUFtAGc5%(klnh=Zk(P5q~9vWrK zilEw99xoiG@c3|-B1LKznd)gL`Brf#2nIQFloNk)5hJs~oMAdC zKd;272c`)VFm;+c_*I#koH`*gSlT)yD`p`$S)L^R+mdP7o1c36jT8POdwnGDq>!Kc z>c8GGX*Y_^C;l%;%*Am-29JKKICV+(LxYczA)kIiMpeJ+fA-S@{>v-ViZ_w$3Zi+; z|B)XX``<}w7lpgC4efsj2AL>D38aVDXwe#orFHC}_%W(U@!V1s_@dGh-3sZo%7mm= zW|5CeYGn#hV~Aq?$CYuOU_G`sg{Y|amSVzf=pNhM(N{Ypc2ev#^#g_njf*r(jZf%z z8mo-o8on`_3_6{|Yz#M>jb@`xZHb}IXsbqHF`M){$);9YBcp$#?2(b+OpqnoW-}TM zD!a$9Nm1-boRV0U$PyE5A<1@$)4w5*z^#b7YO87d?xQT=;$d=jn*23@;I{yz#;>h} zUcpaXH7c($+h}TQwzL)2hfI}?yaA0^bX2w(&71{c@Wy7F@W?kM#3LH*R?$rl0x;AI zbFtiX(!WRG`tknv4Q%Gj|D0@FwCT~{{bVObntsOjbtNvDVxr@J1LW8 z$97`fls)3|;yWjHN$SgrltbbMHdz*CXrlKd(nOZzZf$>T`E;Og(bS35yJ z(J&@_wCzFdEd4Cw9Mg=%Qukt3u3e@tH?A}-N?hQ6RKL!+F2e3kH0ZUG6XWL?l~TbO zRSIkb=v9zZ=}5b!D!E~+hVV5w%>H? z=8J!uYiib(oU>SM!4Vs81smQ z=0<&CsmQUETPnOLa2_(SdthL%<<1eNa~FRI>l_bTjyZS*F-|gD9I%S+BBn+6VBIs% z!>si5dNz4jkBwTtB&`T(rIrk$5fBf+7Geg231SR$bbx?fg2D7KhBs=3P=mzDt$eO6 z_01c9r#cx$ia!0DaurA|M1E4F>cHlN=0?4DK6QLi%4UXW!v_1yS-cxHc< z1(%@`HYimo)yhic2H^&At8!2|p~$*2PhmJPG#N=0b;05WixX@wow2wX#v)?I@|iAy zE*TYYlo3en<&w}m0dEqv3h<6`*v5oQLYFf5Hs(HtVMvHmx6HFJ)u2Ca1*77G#R59y z^}FSjj~F^+AMuzXmrpeu+%o;geNBJga+WryG~J*J?m`Yg+kfs7HB26$O79>3i?OIm zRK^mBHj%1~h@2lwwFDSp^Kgx!0oGt<^3d=8fUl^`%^!zveqji#$8X-=)VqE?S4yo& zKSKOEBB$}q;i;vl$XTit`9f%-Go(%Q%|bJrv$Pq$rRXB(Qtcw2dY5pQgJFL;P{6G` z;7XDeMYP!+4#n-#H1dlvJ{a{HcUzE8Cr?Fll4p2%2Iz!fe=(pKx-mvRiy-7=_}m#8 zK1~tDoD2;>&8avXy6SYRs#6mc!IxoiI91>)ONL@$eX0YDSwUbxPWv>?=|n=N*PE$M z7V&(fBL(gmaD|Zt&)=()i9&zBe?Puyrzx{D{d0yuUmwc!5BcU!i%$LIOs{qLBVyZh z|4+{}&l#(|pZNeuOuVHJ!L9L78X9{8+BkqVPC`OW^6ei!We_X~fn}ovGc5u;gzQ$r zmhdD>!#E+J%OIdjgNLgI)Oa#^jqy)Ym;d&I!pun$_Wt<~%>{vRpFDq`>V7Kqaxw39 zr(T3E(RAk>pBJ+44`rsl_}fi`>^4whTW;2)GroB+-7{tZyiegh}EgTZ6q$t9MD7io9_d7KxT@#QockkvlnR- zxdx#@COOU&7I7`Y3VDCIeUY{rN4Yh^S~+HqYW>`00vQ|zv;o(3+>QK=(jDA>VW0K_ z_oDDN_iw^G_P4Z8xnsgH`zKlj`HdnGlY`}1Syf#QyUm7G)#lV(E->gt#wN3hOOmlw zWn7}bWf{h0vndJ^sxoi}aFMQr6-IyAk1yS)OIxLb5-aV; z`}bUG_UZj$$vPNT=c$KPR)t7mNk@Kn#&db3PnXX!CzY} zXRs1+A%cGn2jQMZ;n3KJ!99lzML9i1U>ve16D!9b!bCanWrZ{{U!E0m84qs%@UgvF zAt662M0UUI3J`z$@L)JM5ORSc!NO&;d%TS<&Eq{+0KKP?|yNzV$jMES}TPn*1koXqD z8U)xv*0xl*&EDY!!4M#;T7n`f+=1bfh#fvj-9MHY>z_oI6zR+nT)+VD@AMNjarCgp zJm)AWoXj~xFMoma=1n{Q5*+xCp?ypjJ0~@L)t z69#IqIcsO)8Ny7Fl>}L29^(Kp7;~b;36fNlomX2T;jdt9*D(j8os&xBKrJRWLWbS& zQ%E8N78HX9-e;>v7@Uj5qx+a+fNj%P-dI5VwyV5_ zy2__6`aXWdaF)lYI2FT#v=z1C0B0%Ztt!iuBdl317R+qp*dUJ{7w;ji4ky2(1vr1N zuEtqVmxl*aiFe+?x1?fsSc~sKc=%7L7$}dQL-jJl3T`5M4UnIkGI@++$@pp((45OX znu>kzdt|2Jg5hIafIAPBpn9AgzE!k|Wqw;`S*fk8EM%LQQJ>XNHmj_~)>5{{7Asp> zeWUHV(jR;7$$Zq7@v#4wC42o(l^lQaA1?Vr#(O2gR1ePe=K9Jj%4$PgsA3j3vto&` zth`-_m9JB_C@(5s*}f`w*4NrGr&bl#dMD($eV3N@lrp7(DtnXtHv4_{VY}r%`*!=6 zcGhkWu-^U5FT)<+9qvGYN7IU>2?16vji?b6%q!f_TpU)5!^GiPFRCuuUSxkM8Xuyv zHm9JrI&?6^+#kXrZ_t-tRrsv+u$9TRHdz_#_({Z{i};QJo05H5jYA)QOmyC(Y3FD7 z+Gi~NghoAI$dsPp=Rjwh^<6}|aS2fV8e^{klC73=s}QTEk~r$2V>+|6^{ zc3Wm)Q0g9c?y^2#-%Yc_kqau{?OlARZC zg&)Tj#ZhRfvrMyCnsRsKGP$|=fttYif!^G$xz+|(qo*K4uaIRmsR5_~L)s`kl*m9v`o~7OLZuZ}~ zuT@3Ouya-hWd&elkum~y*;jZ(#;P2aSIV1YPEKNH4XR;-408~Jop?XqflpvA7dPQ% z%wm7ejC#|ZGfr0Dh!=kt^-m+yDou3R-4L&RanzRw9o7jZUk;O@qJsQl7A(F|_r!6( z7>w^+wY@K#`s*`KuVrc%e}CQMKkr}nxaGjm-*0Qa?WIKO%hX%<;vYS`_@-B1KJvn= z&;#cUA7hUL*Jq+v!!tw$=LV*@rg#^+7J65@R(kJY?qPpydq{tMC{qz^erXL8W7k;v zm0sH>+r!Epaj&#TQ9R0Z%0~=q&%e~sHuQyQ%*Z|Lle*{ylfQ z|ElHJ|MH=0*4&D(_3k^2v$6CzW;SnsAZu;s^RK`4-1mU9rURBfFugC{3O^<>oGoap zwN15I>fCjKitpwq-p~CXQx5Xv=9Xs? zwws+vc#yAT3T>612Byw7o0(>t?w%F6NLpfBZTr~zspo5a(yrnR)-J0K;4GPUB4906 z_SIk%bUK2ndc=uUXV|&Yxyi{nlUm`k{9*nBewgP7?wWa)_vh5kGZ||RSt6plwi=I8 zyOvy|tVMr1bza>W&P!y$W~>|Rr0Aim-t1rV#?>o-RJD6Zf4qO)&mXyb{R7wi^yY6K zybrTC&Y#TKzn;!$ue|i@7v6p45a4V!^u`?EtPH@}`{A}+6v$u}vn`euaj_g_*IIhS zs4S>R#VS**y<_>>eJYb5uQm9`2PSKCGA9S-Yb$^J3jz_XD>D*UZ(W~piaF&|kq0|$ zUhg~)G2~fKz_C@mUu9I4%L+(5B8(^EJ6ynA-Z0fS#p1Hs9X4#s%q7co!J=C73}+L` zn2U2gHEJOrE-b4ZgEF%(md_bFI#=xjeW|aU&IJsaF0YM4eT}BqsHqh9#na4YOntlg zJUV|tfb*!&xs|=-K*e94{4Dh)cK`dE*p5#hlXhL(dh^h`%zS0ik{dQYikEmF9K^XG z3lvaf{gDuku&>!~S0XJ<3mPkJ^Mx zTZwIl|Dd1qlh&1F=GJBlHdb*2B%HyNyIp@AYemw1ZtNa*g*k7KLo9PUrfVX*$4{!I zYa>!1w{|O(^`OuHG(Ldx&?zh-qAtR~P1Hl`fqA^eP#4J#qma|^1#qiQtH@gg7*bSG z%R)}8BMXBXUbcBNE(gYnlM%Xxcpm~^K|dtjFoW#i*md81uFR{~UAQ7^(u4(543?757*06Z0mPHdRcQr{_&8U6i+| zG{(2)wU(}|*i`Xu@v*$W6nt6i^m>1+8T*-?gCzkMPbHYDqiQO@Hlc&)2qN5dMR>9$ z5O7G-@&k(G$*2j|NI{?Ph!?Bguy>_*lb7=*9XN>ca|@q!9Cm!*7EjwVMlNJW2n zMKX_cNU+dIhdfCp`})WP*eSBVH{g}C9X4c>?}6isY%cD)}?<}!N+>3 zw{MpxOi5mGz0Z!U4`m%?kf4u)!f4=+SD>gpz#AWLrS(-UNIH7HM{f?V( z<9l~ueDhtKPOtf|!|NYo%U(P9>?_Z|@H|j|3qtHMI>)y2N#r5helonZL9ULS#vZV7 zbbnT%*I(-uoQl)US}<}1EWCePmXx3vu9;XnEaHPA7U$AQIdAR6+8v$~9;VlGzh{SM z*u!}kchGd0fXF9^rl|vFKSUgwn=xaa&)m32*W}7i8v7F)jWLjzCY0UmRy!ZGTa_$q z6M)eWG59v4@)pCL!q|M}EO1h+STmek2CqE0Zrkj^{lyXHF zt9XuK!Ct!(tU`;GldOEug6L1y?cfe_A9B`%+zF0BoX#DAH;$Vtq+1xL$2^dhjXmI@ z#q{ikR$M8C=mf?-K9IpQYyG23kiA-5s6-+P&o*uEuhm#o`q#7M|l6 z&f-GYCNr#C;hYwkC-su8e8B103jN;e%~TXyP?EOFI9G0xn`Kt^yWCIY%}6sO_4}Et zlDUFD)HH`K>1gJXjxhmMQ?o@C4A(HbpgM{KRm#GmozFrB5y*e0-I@$+?1m$=q{N%` zy1`UO{>0q+iGwwh@0`Vb_S$P-U4FNH*6rMiZ|*-dr;SKAz(4z6)K}w`a3*hEVqGq> z4%^=>r>yK^c0gh@tL~yk^oiYCF)^x748l{h&;UC3b0T~VgjhK+q^U@hWu!I(%?f9$m)X0Qx9BaIdJ-Eyd$-4sEx_JEJgN+Ukz+fPr3W%Cy@mPrTR&R<5F#% z@vI(iJdG1q4u*pul^m8_%YBv)EL=0(PFUDnORr^8&t#sRO%N}2F zYZlG|DC|c}O+gSJL73XuxrlHJi~NPb{doQE(T)l>!q8DNcXP63h)(T+SwJ0rnhaKQ zddGiy>e&^ytH`Z5v#@5%NQ+Cl8JcXPq>D#hx&w;JOgcD^m7WhwczDgaJ9Dpm>8HQk zU9jT3-X9JwZM$%D16Op%+)Gz2J+OW6P%(3F=cNsIJT!DCvupkOc|ZRC&^zWh@(Eze zgI)={EUeYVJfiMbKVm<1onTM7tQ_gH;{ktx8&rIkdc^mkZ`jA_g4^!)XfU8)tH&nU z?25fmrlX3C;lDiBM+r$r72gRT)9bt6x5IbP$N5;MCc|S6EZSKEi#I)}oNP2KT^Lr3 zSp*{DM#dG7)hSAX#7nGIEpl4zS=b?ICc=nQB6J?g(-{*@6L$>4w*0LBy_FBlQ>A~w zvb8f4zu=1Q+&-;$&V(z563lhoU6XHrWr%p^P6d6q7;s`ke)Q{bi^fZSWrlU8u*AAd zSZ$37Lao}MHF)ZL)7078Y|k{`3d;&{f!dN{PBv``e?S-w!u>?~1=wDQ!VrZp z8iU4X62;dz8KAGcjV{N|6? zbNS~teULi-OPwDp+2m83b=B$Jfn_lP^WVjsLR!l<yk+3R-rImluCW(`h*j2;SXhDR&(_GI5a~*$|y>9qHgvOfdu5>5! zWVq=rxMC+e231=gYPh}Q`Xg)lKe&APZI#Z4*R6l-7szzEYkMV(OGx%yeZr6Jy>{ z{^B8k2U9UdIA<=d z#B9A&cpy#Kt{dC7jY%@GZCexDHafPQOzeqmI}>YSClgL=u6%3ne;@3%PVVZeqrUoT zR=xe)Z|}b&38xeN)F5^n)?oUu^A>*ye&|=I>`l=#{;=+_4IHsMzs5Cz4SIK`fW!THRBKln zgE`A!IeOiJE@>5trW8PbfcYD49nUDXO+tsfR{75gR5VmH;gCswovZP#vsLDX#-c_N zgA|rM-CN)t`r$(oFa1Tizm&I{SKU)V(x!MX?Tu-2C=Mfa(+?UXI<)j(*k+E-X6{rh zF<|WCn&;FU}J$NF2$C#^Y))?37iA{}rYq;`!un^YHt+mLA7 zx~?kAsdliE(~P58Gj=g)-T;ovhh3iH!s=vRAb5VW^zz7xeYpoeLGo2lb1a4XZ6aGp z1v8Mn*Lk2HR&F6g9z6q=Zln$6BsA^~St6zK+6uhK0g1bwQXn19&v-D8fwL_7r7wmF z+KQ-*kkj9Fs2kX{L4e%dbK-_Hw8Y|8mv{SB#lBr?L0TU&Gmz%wIN>yCliN)Ke~7(; zQGl_ylVq&ikmjOIqd7$t9Jaft;NZ%hU*&siZd`JQ$_}_D`#UK+QHmnf@=Qd7e?*Al zvEOC6bKAH1?!R>GAnUhvdfgN^Trzd-Wgbow%8<1<#R8+Mscut^9^WFn9fx;4uG#~e zua6g9;C=gH8#!ij>I*1Zeg7U-`oU{3lrzDYb`}q0jpJ)F^j;Q@!j@qoeWubjZp3z3 zE+k8l+3$-t-{p6VgV^2#hZe0+Op?XZrSVdrq*k3P-6{*TSP4TS-wv=jt;zJHZx1;f zazmI*z5{PaA0$9X>kV`U`&c;jg)Ju!JU1JHb>2ARomaJO`nIh-?Gj`ZHoL%FRZ2a=933u?vXwA1c>Pkc)q(nH$ewTFD1+4it1#$EN55{%P?MGHI4r&xa1+PV(-F47! zt_~2TlUx0)ECHrX8n;&*l9Z>g$iN4vIh zr>LlrVM&v!QBR4n7E^k{Hp*$ywd}i7Q2|3k_m&{Y%=jVqdjU<54n{R54m-8j_86Dq z9+BJWM3REZxx%kcIrGuSob#Q>@+a_jiFb%RwCYl0WX}nbbi$^(ZmeJvBWQp4n$wtR zqR?=(g_WJ73q!P^&S_6uLEUkZ5U3I8nIahm(&!-RpGCL`IHvW6w0#B)v6!&}27top z5T~BEBf;5NsLYRow1PCb?du}Ozf@PK`xCf46RKHUjqxv2%FFFdiXre-*>=CC4G0mx z<_UW}zb{Q;BI-4ESj_SK^)~LtuN-*|Aj4~9t>W2ei=j`=fX~L}b#QA?7|1iW*RRGK zOFszg6 zgI2K&6>=8Rxx$-jup^lvc@Un;Z&`aE@a|!V*-K8eAIB}Qq@dG_1&$|6Xa{&k(?|zZ z(IlO^ihO2uuLrUDeO^^Lb{^E7&G32&ALV3e*zfkM{r#6z2w~^mI%STXjU?Gl(MHOB z-NW)L0%y`Dd&iN^{pUdnm&Vu1%IbpnSOs@PcE=&u0<51oZKGbP$y|PnNE1K>WNq;S34F-sFp=+Xw~8Dj_z!MsT^(PNhh0IV0IY2f zpREjn-Qvg3uzf`C+JqmvlS^Bxyw2F)2%Ao#ruq2aNCzBO!{ZSOt;1{n5q~%ykVKg^ zdMti}NdAE%(2z`RK`SJ*HL%KSeasWi{I;v0&nd#bpq$5LPPBS9E4>8_eC(2UK3OO2 ze`AZ}HcVkldY0m0l0PE&aBMAh;rXs{UVn11o-*(r8?S{(> z^E0M?g5)RcM(tjp9}*(Kd-FbmmDK$)>pU9YMhxq*4xDpYa$E9`^`4^;8Y$8wyG7!* z$TcHzj{Ur@Zcr-G8)Do~AD8{-vDaDLdEhtcf9P=|`=Gh#vC28TYzwFfrm;;~n<07- zR7w##6CkBN?SGx|ZbP_|sZ~fLq`#Q*vBe}1f5TH$5;onMxE38;|H9gq88koMBkD33mYKCqF?I0Z=STLIa3cA zslb~vpr25-@lPFH#@Ysha|1GS4{@7b8$=hmC8m*RpSMupvAwoau~km){3KwGjzWhV z4NcLfzgssZ!QujYp!<|b6}gk6b;B!xwbGmKWzh8CnEjg$Wj*l@-j|zUixzUQ3V!TG zFK<~6D!*qhuOTN?7{$B~Oa3+jpf6^7jGcs_=OoRZG$?dVOis4xD|L(rFiWx(HtNp% zn98>+zB=_ks=mV9=+N!l9y)WJBQ^H2PP9uIT^J`KtXKd|29sd79J}D#?~i7<%WL+o zTUDFq9sPdkcM)$*FDbVHuQT&y7rpCYi?thrfdnX^QE)d96usO3oFUoA5t)!6AtaR2 zHX0b(+2oZ?>G7|4m4pzP)dMZSXcL&6Tz6=Lhgyemzu;SiW9A`w(&w z%TFYYQBMH{6T5XaYV=cZyo$J`J(@?CHO@jNnWg;84-Z$lW z1e_jx3uQ!QC^x8wRPx3~=Us#a^(X4=KH-Gk#mL?Vs#3TDVF$Y=o^pUIa&K>|0L9^Q z_&GDovp}w35@62l!I7vaHS5!~8cJjSxTH+%_wfJjxa9;(T+&P>hu01L?cAoJx-97OVoOR&NFn58d zsr|-v(|*0wi~}NQ_yUU2lF^=KHLM-#jDro?0SqceeZvKQ(|VOFDzwPLs6TT=BrL~h zte@@=7_((Wfuw>Kh0WQp;Z7n6^95Uccq9N1TiD@jwTA{Thy^RR9z5BFuhMynB{`#h z=wo5a@>*K7Xea>5`a{I!uhg8_Zf7FjTOn$if({ zPg;aItpl*PVdxS8;`Io9jjd2GZ5}~RzSg;3e$RCNpXzU0mj)%DAPYZN zdUu}#tZ?;kb3NM~8~auu_=ff$pP9V=;yPE2@V{~7YEOII#Pm%>yaRA|T;(WOREgx1 z_JapQJ6^j8L^pfXu*2nv=W?Sl2JIfA-lFh1>g45i{gR1ZG-&zDd=QauqSpf1%0kG^ z*I?nh}+ROZjr;Ir!`+1V)YDnImys%Kv(OG3SP#d;gXpz_8I6g=mW(VQr8X9vR zGOX{dhBGH~gbrX!F+@f*I`V}uvGPml;Vhe+4`+-%f%+<(hE6zwBULNDBXRyn^CrE= z_vI7_58`Sfz1Mx=zQ?yb_~r_(+2vHx5<$(-PQr6WFZM714W+Qt!0(g}sZ7SQ)Csg#mb9B{%A&>{ozo-}rt#U=s(=sCV z+0oPHJQXKHFxB>->tWYd4%cLJI5D6&Br7ya>rz8}8fhjMu8iT} zF>1={Ea%4p5b<#9gvr4My5>q+xajs}cD)e; zbXL(G?4f!fHe3F1ouflDB+nUj7IJNQrJEwV3_59v77rO*?It@Sc%Mjc>B>*SaPdV~ z3SjUir%W-lvbg9q#p?|)c0%1WQESQ&%>$~E@dM2;Zc3g=G@hG|lv7$fSzr!M0pt8& zyDWI3;Xs0dlmYCl8XnQ}=j1QzVsjoH7y};VPpNE(kg1?Df+3|!z z^jvt7DeH34q*5J_XUd(ZA~#2eBDdo(2jxX}m1M4zO3|ta?Ict|D4cmxNNGjqa|z5Q zj2lW3S!?#&D4~eNhUmXiI>(~x$}n%#>ly+_dC0k3fSNEIZf`{Q|KqT z$v9T<&ws>k@u$d<4y)L0@L8_6WxRAap9NwYIdmSZ@vMu91DIHn!zdJ}XSa3|iP~zz z9M0ry@wsCj4q-}C`w4l5jVf0^a7uKjV}S+P*UbLdO}3J`r1}j){9OjZo?1@Y1#ufu z&xL&5f%EYk^84dLhoX(2Z)si9zLkE}=D3xXNbeX6b{1FW827@Sc#R>gx{^983SPQp ze08~d9Kz4vq<__WhnyB)NC4D+zl@7HDdoQ5r%H}2f0Ids>4+)iw3ffID>0Ddo&spP zV~s1*ACeHstEJNA=aFYGQKKT;w4qK!p|FzK{5nQXHhgH2-IQ^&YIF~^ott+NDp0*z zvu*?n?7?-6)6&zL#WWOxI^$$Ws6~Rg{vk^U(h(*v6YQMLwc4f3?3;hhRT; zPI4YMtfhn~tM=c<~1Wa~;MZ;qh+fHXSJ5F3`QWfe&30(>A(^h2gcGl>t_gW(JGr zgkmDGzimVnhU8YWnaxJ6vt(Vx9?&+vvC5LGnC8$nYR1NROJt4%L78k0h%r+A<*SWF ztE%x{)Id*r=@FlJgg;#SQHjj!r;gzXB(cka)1Qh-W}>6yuj3_LSh1 zCcni2r_f1nnu<#moAku)Tn0bNasul+#y-VoT;ju5iRZ+oUg-hH72t4Jp`R=$LHU-+ zcQ>QM_M5oTa($-sht4RuiSFVeMC>0NZ!`K5>&I40luxW4Nf)YrX9Y>UQz?~a zBi2rzSuZDVF#@>kZn3PA2d@4W3v+#c%FQ=qZuvTi%V@Elv1-;oC7TI{Z&oR@e`#iG z7nT2Fq&5nXI}-Zuh@$WyCDuEkRfyj+6P-E|BRlN(ZIy>s;-UU@Vac)^sS2yz-<7R~ zT`t0Fld6a;N3unCPTb%vSD1%CRPWygd9N%sdClbSNtNjV*c4DK>Hg(_llvOQ1hJ^D zCGjxkqpjhH9%XrJ#Q*9~{;-NEc6yDB6eGr8Cw>1^9OXjY~SbUijY?K|V<` zFd~(7JP$u)+J|PT=_HLmF4LHW+(5|f?|_n&yVeSa>wT%MXpTFHb@FQEcV$0iNwvI% zh0Wv;5p9eGJe(+xX;*$6;kFe1G&@wXi2jcZlWF61xoi^ZSv)d z)E@4q@Wz$AKoYEBnjW2npSc2`lU_Gmjh3R`CqLf zRZ<87?)O7Q-jaZ3F>jjGX*FS@XE8f0EZVr1jfkSVScltFi}0n@vWb$61K%2!T`UzE z|8)q_iTwh30sz>A6R|c%xt)!FT$Br-$hr&N(1bhyO^J&T7coM(2?AiL(&3cQg`4AA z7{;w&v&7pCUM2>VCZ?Z{rSumR72fnmEhzf5uncLNmof6&n<( zo=3O?4`34BcT4qd%6MN1=7k<$Ja;uTJ2kw2;O5A?yOo7ZJZv!FSY`>y$L5R93Rv{! zrV)9X7(vA@D7;*Ud1$?pskSL5Z*)k9E6TU>B3f`)Vjk|3e?PRMy`BBzpEVsr#Y>eN z>Cj9r9W4@iG%XBDparEV@`b3?OI%8vFy2f6+}Kuij7SiZT8GiPa}p7YVUjv{c@mCe z??jeJWboBkaAgx>r0=#o6*ZBks=rTFB1$Y^iD^E1NbDiXk`V5$!KNlt9aFj(S6>r} z6sh3ZOq0EMiWy))uX%{?*+@r!;vR|WYJj6l1a8xOMWzkI-+Lt%>lZU+6>+w(+ z+U!K)II@bxSH(#dh4|3lnCqZ~psK}CP!UwrM!P;pYJh4= zp!KPnsA`@@chcrLNVS5knW8~=h>0oQN$8sVtN+ueTLX^ONgJNjl-SaOQ@{c^DrCde zz@ZV8wUwal>ZYE?xD87M=cC{`7%_7k8sV+5g77W$R&!O7c_05s(B>!Ep_ihL9n~>G^)muO9%3P4w34ab zg1ahtlJs)a^~NuxG@B~uovcE}B4yB?w&j>n{)NmQ_bP~NRmkzpujC`#E3szKkZh{W zL87Cq8!{V!U*;*Rlf3(ps$)gUh^3@)JdB=8MpNgN@9dT)F$KBv)cSIIGhhaxumvbuyzwASUB4MWa$!Voib;`NV$tSmygb z_08<*fg*@B04p;aiGTo{i>tGlksX|8wqD|leK0e^$fZ{lL8qv=VM+~}2;HnS!GolU z4~P^(G@A&d-$gOlM@6SsMoa&nP8o2o^JG zJ@#sRZ+2UM^FtibvyVzqBA& z>thqIsug7BNr`aQfUbg9#o5S)Xa_mNFcN%jBkHCar@3=)e_y6USIKZG#U)RdIkox3Ao#wUF$EQ0#(w~oC0 zXD;85fcJ!}f2w-wWofEM**r`9xB(ymNOZyhlLg2KH8}0vN6rDq`yk2_VG6m&&#%|i zf*@n@;7ZN-$}Bg5*de{^AX%|sC=SG4pG~OozD~4|hJ9uM4}X*gp^M7^MVEU!5?xJHHXP<_GKphezyz!7Hk&7m_{@%7+6- z1}HI$LScYN@z)!GmSY$dw4>Sv>FoNI8>06`9hXLht6b~h2>A#2)SU~6S&$O#tzfmm zpD7N!!b;`kw--oMZ4+OE6|xsnli{+UIC(($p+b(ipnQEy;tZ`TAA2xM+>>sE`GFc! z8Z+-n*9-E6nkmY*Glv|R7|7Nk5|?V403R;%RGtV6m33Vy%jz^om&hK5UM_Niqz}lU zYO=ziUI8Z(ldUG7@wY7G@*^MAb+84u8480fK8DY}#U7;puyJcerGZhel=d6$ZwFQ> zGjfvv!W?ux4hzcR;4^FDOzfj9OZA|WRl+H%1XMzV+s&~ZiqIO^>m@-ZC(Z2$;PvAt zdYl37f^(~kE}##7fcsel+kyS*)^$q8Zxh+fE_-!IqP_$Y+O;j^%ZXa~1wGa>#* zLQ{Nkw`;*DtIU=qVY5^O7Cmi*8oPd2WQzR|B({h#nBVsBY{O6HWwgSdg>*^31?GJq zd>cpRrs+kq{j?u)w7r!VCl0%20YdyGPR%X)LhVw?M+~>2e;y2(1wU>&>B-jFgSXKLFnAP%=fEy=s$384j> z7|oY65IvV9*fFsTDzreQv9kjUw1;~~x55|*eL}g$S>_buE{t0KDxA|Y04k5^PZ5^o zYlwev4tZee{hJsi$_+M#k0$511-U^M<3jy4kJUyUq*gU?$Qp9S(3)P_(r)k6ZC@Cr zuswR8`!;qo?sm%aQmlpC{fv|1uiTnN)5>e>fmbHd^u5#~q^K_FjA6Nz>i6M*TkJY{ zYa|R~kA2M)ImbM~GdhNzB%o(oDBsW~fjr2%Vh)_JEH32bW50rV!x9TIIpNKZI{CY0 zgx?xT&V`qVCUy{I?do8WUY`CurbAj%{tor3GtE)N5I5iw^&@^>%snMy@9!)(>X@(- zYtFCY&(JLd728n)r={IKCwpP-S@3?Ex-w*1%$1LVZin8A_fOOZ+Jr7O8*UO|lL)w~UK6SRI z5SL^8dM0m#M`#EKVyl_6yJM)FPVMw8%jBLdx%O$t-e@(kQ?btV*p=WXvLFYP?Lq;8 z@)f2F#0^3ESMV3hAz;3)Cv4haVJ5f^>ZF0{y-Qkg!G2zGY0BG+_0R|Y@$&apkbBg= z)*2gdLEIj{FOc-g-Sf!4)SIb4`ib!pH-jPgMv4%z;>IdQMFzgUf`3i!6S6id-Za-Z zPhG%Y@it4et7IA9#M7kjW^l}J#JCOK@1gL-W- zL*rHtm=XW0eF9A=EqIR&Bwe|H_BA+kr>PR|6!kLpX#!M|!GBIlPm z+H@J|oh^R*zauxr=P8X|1VI)u-h~%_>WYx=!mZ6J0+t2@5EF&{v>y;Ng^Y|!2k52I z?e8#x!feZ^*#?4?xlgceZ)P}5c43q%{HL4B8}M;^9q%D7?Z|6JFDxzGu9#=;!yEyR zvCrM9Pa&78&c`sV*y{XTYTqB?-JWn#o{(QLr*}N_0w9lN;T8q^qm#l%*+cR#C`oie z3pQp%fJre1SkZCTaN28QeAbk=-7BI^3Z+E{egA~+pq57l3>bW&2?@iuEAq)wTxNsg zP;U>SM+DI4t6cVQwOu|8xb)O_i=OgOf|6Xq$LmI=Ntwi6qOf{v9I6oJe?okrFA=`R zj0h;<#@TL6E$Epx4CBZ&A#QBQlA=RvlWpWi~KBIsTqM|SU-ldFad z%@AG5El_O8JTW`yUGWP!T}@cW!NgdC>NBtS=CPyzF#_=_;dAk~oaVsxl?Tvb_O~B> zfUtq&b|}V#fyB9}?~;7@j6xVpsLeB3@Fr>gv&chNa=-RGiBP4RVetV4&>$j3Z{Kc0%;GKdb|1Qp^H?u^{NXY}2WD16AR zs@+*Ixaj0Vr}q=-odo}I5s{XL$9BIj0e?+bK0a{NKPjP_0QJo#2+;f3wwdFpI%ba-pPyNt#B0=nks3Hy88Q#8J7 zkB8QF?WT)?^WRb)U~MR`C9vh@a_tR(wd4&)xg^_q?%l+G{JtTX(Vq7Nu^$UEQo*!` zd+VnKH`@lXa|#*|CVU)zrM7tm(EZ&EJuxl*6yjobU{l$Mttm`n&*y*=6!(oNH?C)9 zN7LlF?y<>eb@D6b2Qu<*_4+N3tk;=8m!2amSl&4ytXG#f69ppgIID<-dQ^&8SsXa# zZM&ExTnAs{uX@OXj63-E2*5^H1B~QEp>71@GbZ;Fd%40tK4m|rp7(nJ*})l*e7Q(& zr!LMs(vS5fEB;S-?_2F6tM^a(HP^H!Y`jG95#MmG8s68pQC0=?;rlo8py&vLl>sI4 zkrX=0xDhRl$ab$coC29HKeb3|>4VHd5wG*feN7_X+b7HuykeK(L9Sd_M{2>NTc?6k zc+??UD9|hc&v05hSY~-Z_X8nK5GvHYEq;n@Vtn6}5H=y1LQM9g^N!?Qg(Qf?5+aXT zRf~cF^$#py;;k`sVHCWAes1+Z;FGvi$A9kPu26-(jR9aV$#~OhILrPk5t#Rz2cPG% zDrHmDq3ovUCbLTwNQjdGC?@5f22F0ne9-tJb4?Xx6-&#S%en#TnT5H9Vb(va6Sqkg z!4}b)Uml)+TVf6kttG8_kNTIYTd|RB$}((}I_O2{dXX1H=8-3no9NKgNRP^St4H_2 zc`x_=joW`cp7!6QKmLB$0=b|5KnV~B1Okztu%A4iSU@w-3eA;8B%ge>z7kuv>oJXXpcLFPg{ zWup|IVtJW&wsSA*fPseF!dOJi`7m-2W8CW__8_WO+CH@RckfBo0aC$1T+zXrLGs4c z0gFW>8Mkww9wkkCQ{_J;=bNQz%}%|4fZNNGxMsSZon>2VJ-JLxlI*vk8CAtl+dGs^ zYSR#fc>sBqOs+gJKAHAF;CoL2+@+*T4q_?vLeNyuuMA(D(m~TUVu}8o+4|jyuw+C@ zye$W=r7NdFBmG7rx50`qM#QtL$H*{kL>D}B&KP@3#4A1AzE3axdPK%L@wsK5CwSnE?h4Z{CNR^u6A@mBSzg)kj?hqrU7H z^mkVVX8x4G(o1D=@}`12f2POxN7MD>YDM#0TleqRrsvY@($0IA)c!n94?~&g+s-xU zm)R@8-aY!tL}aUCm#^_zWDPY>4h>hLE7^6(qgYVomfP@s?6X_UoxWzZCV!buk+;Tu z3}D@CoqC#os=matq_fdGEloIFLIxw+{x7M8v!^V7JKSmT9g>e#-2dwb3u6BeeUZan zTJ5mD?$CQ#W$$K z8_7Q?lo?85(C-Sw`Z8Dv(!_{Bte3!yQvbS?Um#}dJc#B8?S7daT^cGn?Mchy_ z#0`fR^hW^w6{D}@#*k$; z#YyHAhzf(a&KPn1%U=RzQ0g7}Cxjk~-URpq;x^59nGfl2NwNnX&Y8fQa7}`%b1GYc z1RBMZ6EV09O$nHpS}~fsGW(Jeqm{6mnj+$&l>DL`y4iAGEPT1VA9&VhPFDfY2PmK9?%^%-%Q}x$ zpK}u4p)CvII^@;u6(jc$zaathuOPKmW%n4ru+GJ!b9ncl98-ga+Lh&VjMp%~i5`=( zRon;u*T5XJqm}q`>IYWdnU86IBkUEymD=;XbF$Z1UrB{V*>ex~%=iA9y2?7liW9OV zL|#McuE???ycGb+q2HFPFHaX%T!gql>zHwa@(%j~OD3d83H`@tFp8oCUu4#3_KTC2PviMjKN%ocBIj1izsA zN-?lEH4P+79|JvREO6_4j=XyMup24<-~0hQ;G>Ti<28UI07&^_cr3iWyv1|Eac11@Eq6G8^fLGvANDRNH@< zwAw7MlS(GiYCX@dsdIg;4;Lym1aHr?j&cojn=eAK4ZOX+l-sqoYYett_s!LTc1!H* z9_JhCx~)DlTYj~dwSre8KOMT?r#mkR`GC6*XyT85SEx_N`-%em-sg?`d4SX2LArsT zAH91QCht}hp~G-otMRCA{eJbzwZ^$8z5Cnca9jh!kw+I}t?289JGWhfu0`|jNz2tj zFK?a3#S~K@iD~Z4iF#;sxFb6b$ES($w>8Vp7^tsY4dqITMA#Ie+nOHx!(1U}FCc*O zwZp@q|I#m*#pKEj_Yf4>+^w@-p-;6&?RG;;btH@2zJfN~=J&ESS|c^`jSkzR>%A8k zvHP``^?1M*WrqIRu;wXjw&py4>Kz=VU0>63G(v7ooU$GtsLI6&-Z6*QVqwjpUR}E# zkDZ0V(e4`7l+jO(aB0F)FqWPuJAk5;Tp5k6)aKO=V-f1>UU_&n&%Sf#wo48J^HCEV z4jJW>?)ney>^`luVQ|W z$M}7TzCR=5Fh@fAOJ^$6X_y|9Fe%o1*$uzr`n6PLq~`Qqc1Yh9+B(j!Qy_UOI&90w~edM*a4zS!A%?yDvjmHh`Io%&%$HP`?`Kv@6tS?|cymK2d(IBsAjbUxd8~4$#qI zErZrisxk@m%m|vMu0jj#zKQMpGe>WrbMd5mh1;{u>95nDz9!QH zlMXU>pnpe!q{78PFaV6MBuSWW6YTHJ#jee-KWFc)e9d(CZgR~9@Y%AYK!dmhu4SJ8 zzF#>0g#%8Ge`3JC*?3dkc7S+v6K9H>D0GvhGG|`ddf|d6r!w@Ss$QU9t zU>5xp6=MW0zMlbN_%w8hQO9iQS}gWYhS|tVbboNU7>rV=X5q#Jj6UEbpOVA*Y1uqp zc*U=llS!zsm_evL49Q_chho%rMe@`a3*7=u3VNbcd@U7j2x6x+Lc5$XshzrFAfPdW zU08sNg>6`z1B5n3?*wU;tQA|EwB<=J{j$=A)G27(QL4y*05>I9hp#wgXtjtZ*_Sdi z5{{J^9c|5DBgkn+4u-~DsnekR6Xo>t0aj;B=qnDeat^0K1LN39wMs;(>Yjw7UZef@ zK=9HE%EPjH1UPTnCiRdg+q}Jqh+9*qfBaR5%0H(qIN)KqUS~5a884WnvPX#Ab!Z+$ z;{6_GYdtFKz+GD@fuUH0DyUG&!pIuy6Q#QjMm5?o6Ki*#VW31iq(}<_ZDbX`-jwvu zI7+E#C^Mu6$sgk^qvW|In*Oh({*)|rYA#4I+*&udPT6~bd!WjwiiBlJGSQCk|JAuvB+CJ)Euo`m}kV@484jRQs+e=N{~T(U*tRL7j)xD{v#$`bZ5 zod4^?jnW=)g%Xqs++bsl(KRoelx^;c`INF=7@bqf|qB@0wZv(4GRojmQ;ooVNY$>z>H^LeQ2C}*gRsN4|@V(=lvyBat1b^ejrI9AR~ zWRSb!o}So-NAa6gSj|5q5l#K3)}dyv{8dyE9TeSUsFK!BQ^){{&I;AAHh4Bu>f$Tr zi1WVG^%z&1=2teXUOXz@icOyc+bVYpa@tA-t4LErx8LCxVBqcW8!?R!(X%~V4hpYo zov$X%TT2(_QuCFnNnZch&d1_QrlerAB~IfVDMNj3)H``eq^sPIZq}@&cHtE%EDI16 z#T@AtcLMx>ky8ROV?2*ukLVY9iSN`H3>BkCxjJD7b-ihK>CG42jJcz~AumqB7;EES z2U}ne9XkfQw|Zya8Ct~OcsDCI88;_%7AshMXybee=Ea+RIC9}RCX_E^JW73xqZck< zFL*bCH~luu{3mPOxA(Uu!eL8_L+rOszKuZn>@d77U91D|&A(AP+soR`Jfe7)8`CGS z*Fx8)tm@NcK^g|SIVGPhsdF@|+iBo0 zc{giRYsgxcmRc*VTZ@(*xPHu!QDt%`;`Dx}v@3o4z0I_{8-&Il%1eSmi7`LWlOtu6 z?@xn)bPWM~yT4yTV+`9YtVM^_f-k5uC==?u8_-cNS0thCX3nQ0(rSoJFe}Nx&xf~$ zy`%p{Nt(;fnU?3!iki{M)`A4%G_9wj1Bdi_;49hFTtwNbo8H@&B3W|+d~nq$jzDW* zJut%BMlm6pUW?K6G%;Vn2)_SOMrU{Zry?1fostGD*27t!u7w{pMtv*M`q!j_*t{CC zL=uW#ReAwIq>uP6O|6f(O!I>YceOq@9lffIU8q5YN!v#0lx5(|j`!kZ&FtrB(c(2Y zf#xZ}!u~LiYvQeZX#Z9@cNoE4aIeOV-S~5q8C8)_3A2#O4p~cWr&W6AN7x zVnH&(d7`f2GJU@(lSm{RokZGN*)%mN9*bGUGN86ZW4w|H4dm#C2jA)emuahjIOqp} zZgcdfc$M>jnxf7f!LGb=5TLde7X9PKV$a}RE{n|ytXEDZ4@3z^>P#2MGWzJ!jtj1htaJaDYf>CqO0(yw${gJ<8S!UjBjZ?l0h@Dy zjeZN#D+0+fH4B;}GoBKvxtSRzbQ|FNS_o~fB6qdBS7Tjx7J=#EB5`R$2_%)qlV+1v zqUvF-wQ?%C(Z%$A#)-=fVJ(!$a-Yf--oC1Tm(SDsLa8|Luml{{;NygvJ<_D&H za9=w>B`?xTwE~-{K}|EIXseUp_yGZjQelurZ(9v)uot|A#j;Yoo>K`kk+%&z!KkckZSeHE|gu0RHSWrV6Hw5npiEDD9U z4wWm`qlqGaz91irs^Qm?y6BKh)bRdZ=&Wb~vC?oM3Fasp-gF{IF*V?qc_KidUx2k+y)#6Ozrg!;N!Cs|p3F8M9vje^uh3-oeNw z=ufCtFZOs!>k+tMWM~&lrPveu% zB`>oK_>coEtRHAPf8z}w?EKnUQmUPG@XUAb&tWDsFR(RG+fsc)j2o!EQfw2OEGEP) z@zvSGc+Rx8Bx5YZbfqMUHNf7S%# zV{uy$_}$;8k*z?q-*D`n`8DEoPzp6-GF@?F#cBojDKg#yUN4-8qZ%_xmGGu|5tY28 zG#@fk{+7ciJ68zWJAT{~#*ZO&M^q;1ey5`(`{IN<3Xf!;F~{#eC#mC;)ep39z`PJG z0$lRx2z^69^zL;ad}$H_fFJ(Ga(snt=2* z&WAl35_}$vAdE%mZJRXC;&L#Ywf4%;jlr0KA1zmeF7p*8B zxm`++x^zWLh4GTeQdtF1K`%uhJ(%cI11QVoSO&woqBqxTAMlwE?I#X|uquwa9Yh;d2Id#3my z(8HpO@IUA9tMh$Mh~{Bi7WmfkYET2R`x!40PG8kLlQtx&`plhko2Xf(kTN0jR61wV zCj+}?;Zsl%PlUgL#DNeQ4eo4xzA5A!3`lcf`vSSRD}%>*)<%>y$5>BUU0|9KI4`)} zKLfTbnY}Y9%P(C5eY(FlHELVNE8LMh%7z>9ex9e$NuG|C4u0+JbY!P;5l;d2J1JKd z|4a}3VTewCXhCYfL{q1-Bd^XR?*F3e9Ag9PqDDRKlv7V_+qP}nw$1a_wr$&Pr?xe< zZM(hm<^KATdz1a+WS?Z`?3JC9?5wq(XEDLoW9IrwPglA8pky7L2!t^{Cn?%swSVu)ay zpZ1NaWI^s#p*Jh~^5ZaDWO6o~Bq24f7Ke5b>NbwrPn?1U;pta%VPUXu+ei>Y?=SaS z4WKPLYCti~0WTU+HX={94k3o{!}Rb(t?I@2bDy-{&s-9 z0{Qm!=ma4t7=AYcCE+4}g4YzfsJbv!CwR}tOVM5IIdQ|uOXyqix@f@2%>#e7bM5}A=G|i4y|%+leoXDPp`M?8gPxx5s$Y%|{J~-l3Gf845CC67`bPiP|_=FoU z9ydixCaEM0*|fG!TV*aR8_CI)Xo{E8=`$Xl)bF5nwa~SUn4>qtBiH*aJ?-QfyiO+< zL2An9Y`5R(2=+n-yf_Qcow)Po2jNi&r1$FdqnE?yq*XOG0QV=N7UpO1>V0@v_cqo;Ry2Fjs?1LxOJQvA=JC$isOi9 ziR+wA*Jtl@jXb;aP2@P)7@Y(AiwP4y%avj(xz8_7E-o&V$T<_TBj?Nwo)vYxesi4g@`r7#pmgb|Kx7IPar+lH8b+YE^hQgLg60-8N9>O7=$NTfs z%h1%6C?&`luJE_)8G2xQtI_pl{?d&IqLxpRg}mi(+jpgVV1x(7{b@F~7Oomo$)TPj zy;elNDO5uz-0UVktA4SE<;bAvMqy)*qeIU_bi-hs@&e6$t;fOVRAt?Eu#)u$F{7ee z?YhCTwY6kIRXp4T+@b-&la`QaA~zLrgqY*5XmulC%w_;63TgL-DtyQ}KH2hz#LKU%K0r3Y}OK_~S%ErXm^=d+*Kq zJ(%cp_Yb{ffIr_+L{jceahM3^qexOaHKGhdrHr(8jLv@*%pZVOnSl-PXQC}L5$@iF+PWYt z&l6Mc_9bTsfmM)}YKfd^7MV!xvr?;8y;O&$N~O%5E=b~v?i|Z5>NKh^9Z9E8eiZ3E z6w8dg>ZqrQm7dM044cj1*0)KYHcQ)PN|({0Rg615>0XapPFbGggQ-X4YIG#_eL2qN z4nz;omITI0cZWi}0R%re=b&9Hc(W}H!N4tRqZ)(OvBLDwK~#D*WG7hr^Ib4cpWfSF%>zhjx^+H zq7R9pM3IJS*fBS@VCf&7{5@ADGKe$c#DLkwgo2FfAVj)y5%!5ctnta<;b?Par6f4? z^T^#3*Bo}PWSdP(y0GtKk*2BRMBaGn+;rIuH%H=wCPM;>L~26}jxb;kE`x5eX1|%i z=`G$}>3m0dykvK*Ztiw#1GW>IdhI#p+U(4(^$Mxp9%~GIk>60&S^03fUQXHjV1S|| z8WQ<9LvO5US|6*oy+dd7{E)3^wKD;@rM@mMgM4Kt>O@lQO6SwHMz^&qBVdzk^SlGW zHTS$p4|fil%Hf>Jg+(~EmUADDmA)Ef*@ex zKf?q*q9C3g^}HokD(vFdt^&3qOW^8M5zW3y#4>8dYN}nEgW+(VnB)av>DB!&7m*(W zrH44f8C-&7>6ic8U-k#yNTk=?QW8P3+pAHPkPSYh z%tG75$wXV{$qEyRh1OvBH#>*YFF`hy=v&!`q@-6$d2BUKJ*KWbkD+EhLqK@^?Wopd zx!sL)P$oPBoppwdKbSXq;*~{;rsj}Jrr6qJjlNAgAw}ocD{Z9Kd`jmj(?;XjAw?%~ zCs7SkjM`9q8^@TH9BH{uE{g^;v#MNid9zEpO$*jWI0=6}MLgLZ+i%Yj>ED|ptjhDT z=;>i&$%j02GPn4x+}fY#Xh5Eb%)g&L_Qd>1diy(ms$UOHm6Rz?1Rtdmt~$j2`22#T zlT+qJOFUenx6hHZ%&w;5N_nz_ZiWkBaFQ<1_hu;b`k>i2JhPSgzH!hYC^~c)==DhF zE=$?%{V_NnKM3j0Ia}pXW@0t2=<$jZ#oaW7}tPcn=@M zGpF39HU3baM5~`hI7om`5t?w=ba@ndq~4=GdmMgLp=F{A!)aK@|}cy@Z?TKTH)0r^@2ZYf+}N2r;A)$)ayfClb|6 zWmC0cJ5X=v&B_sj4rqoi9U`n(e{p$td(d)xT6^36wj0bm%)2hIZJ1MO?|b{57)~@| zAzETOSarGbcy*e>XszEZ#e(lA`#WI7Z}pC{+g&VIk9baRB%ue|H?k57kEp{~A6eQ# z*g@&0Zzn@nXd@sQfmV~PmFdG)XwT1)Jx9EWq!L~wf4_l@9AMX$8j6%stY2hXO^8D8 z;-*9QR<47kpCW+!G^$_|-iCJ?^!dcV5DtYQ9#lMwUuz6Fg@gF|YXAHy8Uk) zA}@g@%2Q;FEFwXRx^s`)Dmi)xHMjavSuhUc8yResqP%Pr1EiUcY&e+lz(DhuY&>+A zDqO&d5<=V#4j5Zhu_`lTmjw-BWx@ky z$`PkDH{eOn8DUR&W!}ozp6?4E&q`(gu5NVz`Sr7-C)ht|>nFoFicp^w>%tX0xFQSO zI>~a4E{O+hXsTZAf4zg)q)>ZbJLk#K+@;{#`M45xYe2rc#Ee07Tc;t?BTJ6Zb;EB` zUNBPJU`Hos4!UD`N#epN<%J&eRE!0WLRKX!=h|&MS8;UFg~^lZITo(9Bk2e2!bQBy z+#k`h<#AM`RH!8-Hlne8!Zy)#*zD(|4eX7@8x3uyo)Zx%$+YTCRaWIsO_L(uhSCrJ zky9c6909aC+Db$#dt@Oa#b9eDhIOS7LjA_m6NKx%NV{U-Rn)t~bR4RM^yf>bIV^bY2>%K@x2XL<>0VT>IOQ8>TV{LE)FiL1 z_)z(lKFKUTGE{sk^3$u+eG@n&ndMa~3se{x6&V?)EHZY`Rm+X|D2XbEN?9R;TV1K< zM}SFw7#9%RVCjv$QMIz=|B_(ijB#kw)+n&6SBLur$@;Uaa4tuOf67;6S=i>I%JgEq z577T7tF$*R@{F6UR7^ycteqTgNJ6J4dokIwB9y0R_5d9Z_esRHzi^s$2gd)2JI8pAu+C@i3gzSGcn28U0cFZIK^_=3)a*m9NhR-n`SMmxWS{%% zk3JoLX!64|j;Hx)OQ7}E*$-9^`s?Lh>Pk9SA zar3hHNzsjwy~Ot7AZIjOj+SNKR~`1FF2C@#Qa zo>88Do_9>|dXoWqrx`=66K?d+Z-lV*QcGVYgiE=CwU|$C`B8HxZZ)BO5Owl;5|@g_ zPgt(cm$l%lpttqu%YB9DK0?}y^s#HtjaQAOm3Cxi&(g%G_1@cUxiF2SM!bUfmHmzG zP{O4_xLtzAIC>+k)+)g?R852`8V&sU@W@-S`ruNiEE4i}TLFcjri&$9AlOIpx8w=J zcTpsE5PLf}FRH>9BlbkU|LQLjX)1ZqL8^w1mg?#&14H_hubf=QsP-WCh&W`=DlEm~ z6|#1GKHSOK4&3(}nd6Tx%ndAD`QyQfFHRrsmn@!LzE%6BHN~_@y{J+has!~SaD4fc zL-~r~`vcuk6NM9tiks2Vjg z7GD!D!dt7|NT0-;z@|!Ixv#Phfij-G!aCK8-M@l z35!>?)4=}d_H#ltDp!4$ukRx{jEARVz;h~BGz}KHS~E8Xq+n;eAFW|W#mH~@+j$a_ zs(YJU4|~!HD%y>pq8U^bFtci|t`f1+oS;n%{kjbpr4s!j zk@~@k%18bKLvEC1wKyegsbVPt6cwYxHCnB3IRdL$Eb{i1j#HO(RfS4&XT1}x)xBCRaJ^k^ z7Rm~Dd3X~C5`rsRtJtjBMWgwzZnQ{C1xjH7L`COZQOH;MKV@$ZPfVRW?DejP;~vv4 zA4(z&)W#_8c)ONlnWvELv~n-$4YfOE_CF|GLsEfepPHm9&7ZS$tC*(vY|~VcC=Q`g zE2lRT>o$W#hTT-V1v!)>=*r-w4D+VUpv`_kL2m&LA{L9_^`>kvETw}6x5x?bfyYjy9B>1W6*R{BD= zGy=4eQ9sG5#wE_6bx|fI9x|oMA$tZa!sW@&80f_(U=``&>Sglf?j_=7+=Fq;ro)fM zk=^ds%2QC-&o^iNKaRU4=+HDieB`2$k%Or6@yLUJ&5ue5<)5*fZ~nk&le_n{dS_BO zwr;*3E(5R4g|u_gx%KP;hqR$6D6vcy_51U)Kb1h=Dl8<1c)f?aUS7A%cQDtn-ZL;P zD?G&}QD%59dG z)|p1F$0)nvL)0a?ckU-+H)%PWaMLEMCO0k_VPK!Yy`R^CzmCM)NJ=U}7d${Daevmf zcyXTFodlhYp{pr#0&g;j$A+^x=FzyD& z17QErUbc-_D3o6!AsY{&;XwV=8lAOY;Mo?Rn3Z6RuFb3PDqz0aW<9jLW8Ejtz;`X! z5ua|W6xiwPEPwg;c8Xp5U<1U|7k_)R@=%;D_blJ1Au5W9c-hXz`9vS>c&%)Z3FOYIxOEd6S}fal+f1HKId1>&G6jSXQct?#{^Yh(nqn~H+Ux_Fx4<4)GC~+?n7JG5fP;y%6zOS9wKI4Olwh=U$^XyIH<+TRk zZ_8TMF3!Cb;SfjRb&?~qcV;o3I{Vwn#Al?hp_~tTI*shR4TG+WiCL2dnR*RnfATw2 ztYi_9GjmW?f2}}Bz=JKa_nnB=q`Ih|ndip-aJLn$PeX>c)!)3pM-RitRE(*#?z z{5UwbXdis$x|Fz6FsFg{HuQ)Gf>a;UyP>#G?;?64wf62B%nNjXh6E=W8Ex!R#VT3M zRE#{oUDvl$%(bM7{N&9mnvNGgbj@z3`3(K zAFm&(KdcuLwK1i695fqN8(JP|&;*VlwiD60<~#*PqMz&9(^8Vmweboec-X zQl3I2t5ZZxa{r7G`xE$~O&5l5Cz6^DE-|xusY7fu0JD;mOOso=45bH64jOhux%a0v zl*nIM7lGG>bQz&AW!KFG%%;4CNK?~O_$&0O2xA^#A36PIqJ-&>0n~WcE3#U54I#jza4fULR(W}u*hFEkSG?hwB6-Z|*pYU|(tr2z;pFW!db|trx zn$S=T3kMu`HA8pX0j46Dg%iL^y>m0gJ>Yf{If z_2XhSIU(=dgqU~BmTHo0!-V2~s$*Y^-4QN|a8C@OC}W_}@GunP^l~9gMuE?R*8X(r zEddv=kGs~KybFbeQnW-HeIpz1m8|>-uLMKJKnhz;ly_EA%LidCuU6fvahH?^K|TcF z+?p78oPCq1ix)>3OPbtTZsI}lxj*1-4HK*Z+=ypulDYup7sbAxxxOEl+>s+_PsGnH zpNy2HMHAV&+L^8o>nSrlnjH@6b#7xD-1|;hXLg$v=&%}E7{||pk5_AiFZHYw@d+#W zfSQxsyaOKoxP)0D zuP38o{VMDj<}25#o;!=iKnslgrfn~4aFi53bs?J__E@Tk0822i6ALy${;omgE&uTq zwTPLEpK{dJm2-@J-*X*|WW~Y9J9DWMo+*Ke$K*m>gtUhAgcLL9XrxJ*L zIVldUO>wXAj(lF}ayWXUg-K3=D7JNlUM9dVFn zE9XXXq5En^SfMY`y}_U3J^^+yN}m?p72T{OIs1quVahW1L!KqU)6vUtPh976ox^1( z`Zg_!j0V~*_09gr9LNoD@okHBnGCZ9lT~QAqZ+6tRgl%{d1zN+$9;99$c02asUCy_ ze~=;Ukvde>tH!OJJEVSn`M9bs-}`Vu6nwNrmtNi!(iQFc+UYE4R{}Q+S2&6ZHQlX7 z)dBpNp=i-LjORUjNOOZJezyb8eYs(uAK2z6Gn&5dye*d78UDu1dO#ovvY5(Xum8C$ zf70eo*j81XwuW@El5II_6>X&gE1fk9Ds(b*Q+HgoJ%09Om+(nJFL6htbF-MS@}lTS zvl!c%iWo9oFk4Cb91thdR+1*Oqc!b1Qt39FdZ3%R+a_%ot>{KyLmPhr?>fYwg;kAf z3uhgvqIUM!5-u~l#zj56N4iq^3md0PtIqaM&Cb#e_EKYb<6Op^>Dvytvlx74ubBa* zWFN(dM3%ggv+z&}H@?qnvF`aYmA&|M1Ii*Q_Fz2v`JX7ac|bNbvQ%q8>R!w-&@I+1 zHh;NTZC%3Mt8-CSJE?B2PI>LrOZ`3PEA6T6tKrN&kZ>9Wopxl{Tzo=Ix`omUc-XZd z)S3$k@(JF{XX{9zOJ;0pLBpPiUOcJ0v#=>;X3K19p^}&0=iMzW37_g`=@w1n+C!nr zoYhpjz0PLb2kIa-t3P1y)27dM_T=Wv|41_x3`ix#Gf)`X^sj-X7~EBu22x^!F`}#VaffmqFV}`w0EY|d*})tSlshXrJltwfnt+`Y%I@zPr=1mH`2-Kh!{+J zn0d{=N%L9>bcT2_FdT3p`zi-v6?e<%Li7k@T8>*FfDG=8zkHnXRZ4|4lXx4J0uc<& z-@KllK@VddW}7i1JtDdi2tC*v?8c7nPTvoj+1&Cwegl2Iwz&Jg+>7IywwRK}c#R`U z<5ajnLB^%~tVL(=T9sQQ<2aa^G0Ha=L8h4Pe7s;sT+G>vkOip`wb;doqk98} zR;fqm57CTkrfvA=4-mQ;TX9BBBO!|%(EgRRGDuC@txSMl)=b_E#T;_bXtcFQkGLLV|0-2oLHp`hgw?^O+t_=)Ykc~ z2`gulT}R$@VqLMXUG29n3u;Rqjy}K(g(KJJj4?lCPHtvPy<>zuQ*=x8Q>+aek*`b0 zpnC(x9Nt1xdux2sN|%nL@tT26%*wv93$N%GS91b)&W$4ZoDj;NzJxTq|&FfBcGbQMtlgeP|eYi&HbLBh?IbeZqTe! z42b@XjIP_2H*eA0Vo{ANP%5itZ6dGqqy`6V88%$((=nTqmek#^c$kM80|WmS8OZS` z#U@rw2YI6}|1l=jpaTe=;~H$XUalsk+pwH}KpyZdwWfvF)JAT6tlX!+Ly% zW@(`vXEsEYDgOxv{IZ!ln#eGMt6l_SdHk1j(q}2qR<21eF7Jm`j002%nED3!?FVu{ ze<_4G#*#=;l@wELpnuC-%Y))Bxo*A#Ul);Lg{vfBKD3h-sRG17CN^+l32+)v#L(Jy zC@&eW^B+vujRXfYaf>4{vREsU8W&t4iHXV%35kdfMiPn0Yi*A6P2|&i&c9d4^UIy< zy!ZZ9{<~pecy0UIqXC5Uve+(1pYPjF&+h*wa=^TFgqDAG$d!j~4xSLIeqa@((s>_Hqr3@CJ=v-p+y%?g3e~0r-f+Ecf@kik#Y@TP5ffSe`RI!;Kv|%}Hv3=Gs zr$Qxh{EI9!F==8S1F~$IE1O(~TMJ%gk0R&Cu%%Ie@q5K?WeamPeUqM*YuxhHGVbh6 z^|F2wmezplV?Ln=e^9iSaiB?+w&cL3W@J4`VUCH5nmVNV;tFH{nu2*U^G*f)_DXB1 zmW034bY$T!P|<|8hEPz4XG-`1QxCxhGT)k^3z`pm zcL4_$d?2tjq$7|Y>WiqX@>dN!-mfzW1^6d0d$3{y+lgLVnv$mvga4-PqSXzv0~EYm zw`Jak8@TtDBeL&Ndz+`4796OWR#-eNjIIYBwvI)g0oas{#*1=%G?!5NY1~W9&x`lF zTw4%87qjak@R@mX0H`d|@@kBX@6q=nvpG+NC?y@K2N=LAxUmTa8+6Q+zr z*sZ5IM_E~WNoF1BCKrQrF1&EMi!n8nkviS^oIc04f93Z-`+bh}XU0O^&6(Vd#+%%g z0e@c{`)(w5U$;M6ZZ0A1vi!~-P7~#G_+$@xb;6`a1oX%cmgIvv*%mi6i93WkK;8vp zEr#msB7LQ&ZX&j885X)V8Mk|^K0bdTPv(yMrma}Hs&PiV*PW?_7EA2KN;`4sD<9Vqx2R(IJm{M% ze^(jQ_t6&S9_TmsgA?3nSL~8oc+Led=_1&re#x`B%xC!P^q%7wZTr<#TJV@l+^cup zm692BKNzN`|M+DA5elEfDDO#yVD2~sX|&cdkh6{Z(qYd=P*B&^xJCr4+_a;dTuh* zD1O){+q2>wN%WL=FbsB9a2bkkMswBMH4UFw--KXi2yHohp3Pd--oT8GddtFbFY|PW z=^#JV!d90Tl1m!m)6j8q1?9l!cM6|qEY0qtWOdh3AHyJa&KO}D0TZ>W@Duj${`ZTG zHGKsEBVs%Xd#r>V8?yt~m^`0HmL$H#&niq8$z;hst&7vO4Sl_sZpOW@!_WO@mDXhy z;J@nr)b^U;|Lbr4iNa%Dc)b1ng?j#DS09i|wdfj@O*}ZMC``tI53%S2fm#4hht?t)s zxvkfX;J*%&!`F6SJ}qsPsOG%2SFhuJ9K=o|zLkFIqv9_B5PQ%3q1vXP>p!Kfm-37& zjXTCQ&I$dpSA>0Puv&MV!|nQNnXzfbGIOyyB3|U)re9pVfgQ)W()&KPlPdAN-AkO? z+3lyXU|hD!_VsyL1M&v!S_A1_v|hR$XIamX4e||rxAUhqg!b?8&w%#`ZTSs3_HGy2 zcI$KaEE>9x_34L!tRC>%vUYo&qR_*Yznbm$a2ulCF}m4Cakg2Nt)URoctT}l-tHrrZCSdyl}W4A#x zOvSkIfPyoFr>{A&p?;;K?pRgP8kg-yO*HU22Fs!aAla)Am@gzq5%Wf_uI`|_?A~|S zo4a#+rOR}?olmA^G8Mdyte!q|`KfYfUg*nPqmK2F=!B$ToU{nd+Yt_$6276lA81`S z35jW8n;7PV+`oq9XZny6E!*uF9)d_PT+|ZBj2io61YJ(gCS6m+<}H1CEapsr!6rX zqV`c!a_UrnLsrelvCy3s)kgBh5#at(UwsQBSa|;ws=nmBN!2=IxcsVLF*hhqDY9jn^(-MBHf>Vvx~OxPI}vR8*tNbQ*axhYtOVS=_eeSpKHUgNht$^k8&p_ zEnvZ3gANg0*sr$lc&;7N8g;~~^yjY`v}9n))V$k7E9ru6ilpV*@8sVpKl?*za#Lck zfL=RKMXyz-DWerhvA=Vkq?%TZ4^qM@iene?Rm0#as^ufx=FkJB#9wP+E&Z6fj<5K-_v+dI>|jh9i# z{l^4BGmQy}KA#X8hr`LWCt09+SBL74dT`tqOTw(v8Cn!NUxd7_+fdU`Y?^dgkQ(3xBZhBKy~yI{d(iV zh5hnn$`$zoyU;Ddx1prrC|vM52hH!quVb9$c<)DaP8y`vFL9h@e{#)3qo1D{TW%Jm}e*k{|@RQMjNP=r;YPZo@gUFQ+#E^GU+eZ*y zdhlG^zYgRKu1EXdr>EM}_KR7eZ*zq9q4i8bW#(-iMLK8@`EBz8P?_z%n3ES124?yY z%7VZ^aE3Y+T5wn{#r9IR9FtKA0m z)AoOcTRrL}lO&pCMwtl^LqP&6pUwl9EBRa4BdSQ^Hy`JgG+E{@?N0_;)UuVjP*_$+ zjBW5)hGpt+d6`YpX%i+8TE`DSTr-zu(bk{5ur&qtk37QZ!7NwRCK&PF%?7mbk$)&o z%o_Ad!_8RSr-E2~C`nT}iQ*o~PZ!gZVh5?JUI?rNLoi%TE%z-BoqkQ>sY7Dj z+7{mwe3;*!MP$UmQZ+1txq(k4J@f=u7^O9LJ(Pn(7U<{uVca9Ezx~-u(lg%=f0RaO z&FzdihuGEgT4{kfDA<*> z=c@Z_vW}807r7&?4XTYN^^ONum%arY&JCoR7TTb<$&M!fP3uip_dntb=BBi7qr0Ms zuH9=)4ATol4%Cv=in|U4!DF+v8iAos?T9_6hX;mXkywJXTyCgY2pe z2xpNQ#XY!`k{qEuw1o&b0-I)Y*G?AEuL(<(*ET&1?Td;TvYJ<>haQ7k$QDS!8?pPC zD=7A0+7mgzaGAKGwq+J+Bq?P?)9DMijk*Fdrd;4OVaX6q484=iV2&8RlmRU5-EuQc z4Ln`_+9d{Op+aY*GL@Jn7Ad;`Wg^-i!RFk)^gm__*5E1Azf%}*E}cG8XIGeguE=MB zr<98iAo_ih?Vbm#f@e6{72925pFSn7$Z;}|T83ib}E9GRxl6<;vfOEgDNfD+*yMz+?HPLOv zd1!=FjHKLGB?eOASaV4et9~ug3FFJJiL?Nqr>+VeV#*#)8d3)b;1nx1x?IjX^mMmQ znO;SXMQ~^pNt**GtktSj8tD;Lm4%Dk%Db(HJiD8$qV3WIUj_QbDLdK%@7JQ%YGR2- zG<450g8FFYcV&(d{AvlIx2mU`(0JYHU#nG8&fgT`uf=>1cE6K9jbX-nHk^idVru|< zsu_rM7Mj+mynj_+s|3!8Jril=K9rMw1w1uZBRn?#DrQdCwx2|NY~-pr_B6W5kuNFh z@s^cYxZ;S%cb+;;X-wMC|UB7wh??Q!_DstaC{(Srh-VjeotP|IP z8PG46-M1c>VR44L?gcKve8a447}8#Y%Dmx1+CxinF^iTEyW@7X2=iMPzlLO%Kw2y< z1JLoi4#Dn-s~U^pn~~ei=uc#UO6+kQF(|7_I~{Mg!qhsSg385vd1*rs=O4hb`e&j7 zWsB?fK`iM;Vx*<3TzJ{t!kvjs@`%!y3Vg-ERJjaSvZ9j~6=msuJe{Y;80Ga`c_vXJ zxza69_1L&}0)yS<9|3uCl=F@Q+1s`*<;>W_hC4adO0%cRxv6p!IavjgbWzUAKLlkf zM+apYOGk;gcO_9JgNINLN-ThdOc7HB&IEZkf#1e#zl|-iPV^+!Nv+e+7Q7wzk1*Z z9H5SpD+!25i`}o{L}X0S4lhZ`D(sv5qZ%a6Cj2E%T!XPd-QoYoP?tQQsi3^4T_Ck`EM9y6bAuAA+|q6^#kxItcpJA#H_pQd6`*RmO;^=ntjbDwa%I2`P{kgr%P( z*g}KBDd$Mi#8JUM@<|3voQfI@R#6={S|wR3Z>E+`9ucd2-|74kfruhdp(`alEE1_h)^OgzR+Xqd+$2FJ3bzPE=yF-6)=LJ-Pb6a2 z`3a3(6f^Z^UI((=?}Si!;CP|BWM{;=Q*d$;$j6NBJ3H%+W?;=!z%ZUHH~acHO`N1m zWsX#aoo^nfZm}~ntD8PkM)kN&=ZO_E zgyN91NR#cuz|G>fpm6iL>I1Lv zGm|nc6crS_QMBaGr*s7cTnQi5wfdf?DcXn9Sb)B2%vAzVns9O&DM~3oW`~o85|Jfa ziDWAmNt3DrK}$9#eyTx=wNw_}=gx%D!DZnJ;Tp-fOIEU{B~%Csf^^XuH-0h2v?4}7 zJiZ9}BICzaV``iPzhiVJ_n-IAZ-a`5f=QhmYYR%k#gUZu1_zd-%ZW-&lAm)-1!f64 z0kFr|+~&qWxew2;o(_Fwbd5M|GQLa56cs`{kqQ5L65_hxU5*6m^|W6l4mHPHc(e^V zSbqw^#lc*XHV7^mSnDOPlC;@^-n0+Dnz6aOg?M?*?ibn0E;KvYPy!lyTlKH>x7lae z4O$1C+8+$upZoiT)C(+LB&ZZQ$yGc#3TYH{|Db>YB|jFX7ilJEFA!w z_7g5W9^(3F(;A9M#qR=eQ(jk67N-r@G&GsVV>7AFT<{lsm7lY&v=#ggZObhu$~M6f z*U^fAI@aEzM|hd%2yM|0Lap&W>zfVfn*NiOyq*SI^q8`$cI4c5#e`y7?iVBxJme7+ zJK3%9cTyaQ%Hs7R?V_o9FUvrb6uaaW$)D0qz&Ait%s5Gebz>|Q7l#X~uK-LTs9GZU^rAsO9X8-gHWbuwG z`SGbG{(cpM-4+<~n>_!oxc`!VwotG9@f9SgEtmR#1^55PmOb@d1cV5bjWad>6A~Se zBVghnpck`ra&{s3Cp-9G0Uy#_ZCD>h@|{tiEc|rnTTP`(t!x@>`8}biDU~JSiZ4Jz z(gp$s;_&+R0P7GA0yRFLtW1|2hBSL(E0=2*6*l{iUkPgjh6F7=yeoxxh*E>1NVz+X zX#A@N$B~*CoG6P~1Na+y1(`!-Ymkq`ILyZsrUdJbBDUCFEl|08(@|hB^^0m&I$GCZ z5Da8OilC&*j1*~MoDO9VcI(IEa@&$IqBs3+;!`=d0VwE?`R)3N-tZHxl8bP#RXO zmkWQb(z3Rr69K+SeN9)>{qX87%nW~86f|T&)CnVFt{ZjB(zSQ~)9s0?xtfiL`%u1P zJJ=L7!=~$LI;lF1zKh0e!Si8=Z|~*JK%~5QHFr!Ec8fbll}8->iqdwIN4_VVjf2`A4qak((>Ns zS$#*F@{>hd&8M0<$wYVLlkaJUM;RhpT{AJ7y=L(p1puG>H(QN|8X=qB)eDVEws9uv ziY^z`U7xNH5PNORb7tH&zIV8J|J~Z(XaWiZQs5bilU=CDJPd0EnoyVm5E$+a3iket zNk7`);9(6E1zj6{7=trBsI7th&=H87g=KLp@x4@Ur(BQC!&bc1Ect`jlRKGl#}YUy zE}vyU1c3IFpx9m8_bMd?*e~Dv9gZQvstM35se5H zC(FT_2Ax86*jDlR?2LtyK#3FNeV2IKqJja#mI5ZEz40#=7x*Ywl9v|0E9HlX1Mn|< z;i6vV2K>Dp$8k2UnQy{i1xu#7cSj{k^N0R31w1I6VPo-d$+h?%e8A#k@l5bQ3jXY* z{akW#2*5lyRbQs3@m3i%KvEduK%A+pd!ZadoA^cfCk29h40%H31cc(3mA^4GX$v$u zq_k?wvR==myuqWO6dn|ae*vVJXI@>yeNt*b1C701YA-@g4_8DEW1 z$^fI`uh44jBn1kw3g~-9B2svg;{Z>Jxgdx=cp<1%dBn4Wu;6YKhEGI{NYKL+VvjmT zo*KzdF%oT>Z-l>v#t6-blat1JgV&jx!XbI0q2CsbzbG|W^Vi3wD((`;RDq@{K3)R z^M9<59*g#qj#h$IMu^8PRBkXS9VR#;QOa9&u!3&tDAJ;Z)v?XmIR6-fMVy_IP(2x@ZJkS41x( zbiDfS^U<9>7a-v+Zk29XYd$U=td8IpUH!Xtnp`Z3+otC=ALzM7m+TAtn&t#n_)E$u zaTFsqX$=*5JfSOU2hDx-8oG)HK&WV5?Bza&p+lUsLk0Ry7=h#?@RcSa>B7Rt$nv(; zYc)hbL|!B_l`28P3N0VOHjE6qN&hub+)+3Fv)=i)s3l>n$S7ql7p#vRjpWCZQo07g z8R8x;>&1sQzR>fJOV&l@`iq6G#t~u-bbz;auT)QqcX&hoM zHKppPH*Lz?xN(U-yh| z)2v~u(^sTnyV!28)6KE+{rxHCKF1Tf50VFiL*ul(U^%ov=#(bErSx=h@XKYNrk6vq z`=XFk0%k(6-=H!pVt*{1F6lT#zw%hqjrDl#?V)mom)_N=4eFXN*Z)Jhsz2w+?--Ld zm$s1m+o3c`+t)r?ru-U&Nz5jdnxW(ryzSE1Ls}b0^-OXmtwMVfovvM1ZWayGJq=s< zkuxiNg<5FEpnw^V)dz(&f+S}RmTvh3DHj_ZOqwuqmCB31zwB>a)Ae^f9irU!>HB)4 z^iPL5qg4ii8A4Fv(6ExGoEU*(*}r@34mb(}(N)UP$G_C&6*cx29*Ih7-v=MB%#5CT z;vVPm$&%=Vc{3;&cbk2@Zn1W4HJF`*XDC@J{b2ybv|WxePuu;SRH<$9!XsJsDafbG zm7M2+)BJSlpoE%U)yP@@yGC0dLDPyqeKe8!*BsODtn(M27ey!~6`lM-hFaG%uk2H0 z!s?tzIOJJwJ=_iYto%wLUX?8(iX* zW>kSMw0Yd~j3u+X?|&()|C%ezhM(nC$%rGJF;GtAUOK&|pRpQzH0MhHZ3_EfY~PiF zxdod@sl*PEcr#1W(C?jZdzgOaAAAUwS?ptZ3ZV?-D;X5c8N4^|OLzRg6kaL zN;Z**r1jJ<>i^CS>t+-neqtSl_%p?&_NC)D2-5Af9~+CN775solXwgToSn?n80b4T zb{z-z=;nQLo=L0bW=-J!!j#D<5>c2s6`kwyM-!#lQn>-{b0bmNj+L@kimldCCi4bd zy8(31x;j~dZ1|z59&@7Qxy5?cxQ-3;gOyGK$o|)7@~bjsFXp{u%alJfB`sDuTm&19 zt-VZi4ae-LH_jcRVx9#AunH7Lcr)3I(}Hrs*HSI*o2=|F~KyfKT?_l}-3@2Y33wGM}u zcp4!*7QdoL+gs=xy8NPVG97g~2tiT&jv=B_j^g1}XsTPTqG9jOBHOtF_wSC`!2*lF z?AH4WDdv)kSgVrwc_$mOf%Nyr56;C&F(p$9oyP4#l~?*T47zjLvNPQyiAI0e@?JNf zJ%D-pd~Fv+k@6X*%+P_Cisk(qDZPK5c7N!9AIG0ETZy@eijKD9t&|F61`c`Q5YNFr z>ABrs+-V{$U$1=hOVGi=0&c8zRM0>wc`MQ2tifH6!-MaL+i;M>5To4#Zo)(1D5>A7 zPWw0(lC0v$b0h9Xn9qOEloV2CALDYs$8ht3q*WM0=g8GK%B;7uQ_GJahfmgMX8E@ZbP?|`)g{q-Nz2=$c$Nd0Lv6{G^MmiqZKJSbHm2%R05i!M|2MAx(<-r@ALZTuG~?vw|6k2$Q;mYr-=(&w z!80Q8awPr`qkqQ>rsSYhrDT@{!yY%)cosnPo|o%?4$1s?NZ^0fIbn6)Ft9p2tRTP& zBCH_63UUKj9k3t*72x6k|6i#6L|;Gd!+@P%M+YPqu~B`ELL6JX#!N&AJHC~n{u`V! z_Rbrk@u=(C$?74OS{M(DLZF}Vfwjl3D~~n>ZIrO9gXZh=*r1sFmBZUb1N+-k;Tx?G z^r=e)`g-Z`c73~csirn{QhNt|vwy1dIf6o8Z^9a$4E-OEQXTxO9H1{^@J_rt4TqO6 z>FI)VZ&x1MF+hUqnfil$Bn!*8HD` ziSF1aEEK$+E*uOakKS&!pzSZUf7o7zm*U=TcAh9A9Qd~KM>kkP-wE~K11?2UpP_d9 zc0`z!rpskKdyR5W zv%Yy*sE2KUvw3VW+)EPnEb8nL;P&e0<6-yMyZFV1yM4#IaIcu=YRq5Q>pe6+D{lW2 z`jSId#3jOPJI2hRW-l)@QC4+*{ias&GNSlO#yxskba{Q>j&u~fq%oFnYwQGl<5yGTO)GuC;*ib4zM|_b}84GQv~+HKj9sA?tUJ zXU#&yUAN^WZ!S}#^Z3m%ofgoyq-A|bTqfSGB9?P`OvyZafmne4I9Z=V zq#GxQNF!wjM=h?h3Z?t>5#AM5N}s6TQU}=`xWGYV6Z_ER+oo-s ziFzSZvyq`*L3Xjg2MbWhqdRKjskt!(L>3KzjeL2+0%m%E9G(LFe%k4QM4;BZkG!n? zHJr$@K+m+i^!ib4^L1_B>4f71I9Z@UfVL>k@KhHEB>0IxgNe?JWUXArwIa8u$ahP> zW=&sr%<$b!oLI5PG^J=b`$9$89}J)lo`fh4L|+h2Hrn(|2Ktk4br!cA%G~ue!1T-4 zJ=0GiL5KU&I5m8e$({slX@p(jUB9U<@N6&?NJPr9Vslm)}DXe8=|t{bJ+Ne zST_R-{uuiP@IRmrJVd&q*3IOJJX;R$dR8sRdr2%ceo@ZAj~ydtPlerF1RQB)q@XL{ zD+AQ2+G{I;&f7R(p7AiyNpoPVcOl5$+?x{nzmlV65p=XBD%vglBl%28|_S!oO5qR@Hg%wJ%6!E8O zwiaOk4g3c)RC^M#IUvIGssW~xBT_}kqC)YJ%uhO-O2k^E?LU3PaYO++4@L~J^`sst zTZKahJ1UQ16WH6hHmK3o29qs}*U;7QpJm&(Z@Iyd#x4zN+ zd#>pX9AdF?pb2E*Me$-F0kvth2se>h-|M8d12$|noQig=Q<3!cEvNW8ZDkJKMfJK1?+{w@DV~#4&o$WYcu133sNP@f^KJ$O28QC zq}|XJ)q-zISeYgVTe{S}`jMN|<%;1rh+*{`*1@t>g@z^E7gAA|-Qn80-zts4tq*8kZ?ZC>=h4VLwD3O&&N^4yK1DR+? z!;J=#5p_)Xv0T}D0g|I0GvfYhp%_rBZ4^&^VWF{aFe-=e)|;c>W{!)rpAv<%a_g5< zf!EEA@?$7$pr$V4J8@&>wuChOP>WE^28&RLbCi|Yj3F$ED{3q$i+%d2S#CDhp5+^CqFY(%|B$*7jiVykIP{|kK!3vf{q%estQJ0alB1`h`E#sf^P_y^ z0k%winm{ZRliF~ol9{A#KV}@_W;d(xgJMA7*)NNiX9>3U+UbNCU`sM&2cHE4?Q|BJ zey5aNKX-f!S@S(b&c9G5?F+R;^!mHd=?ggEJOJW;SwsbS&3+W%=8NojmwA|i-BW_-+ZFQRkRyre_;`x_C^sr z1XsB7Cs7$)CZSn67NbTzzw$F^+A3~j3>mqPXi@goElT8jjt%myJcm;Hy08387u}QS zSpU3cP{ywoISg%u(CLDd}lxKQUxPSBgD z@!l3sSJ&$sJf+d6ZDO=pVH-j{7gNz`41$c`R`rj`Jl@c6T`YB;)1?|I-zcNUTP0U= z7J6M!CDOlRf-N7Uj}#Mn{LG}ILHt>fswBiYp(iD)=^2SNpFxmw+-ng{-6XJNa2JZz zywt~XiQ?sKgAF5G9l6;dSbiTW7G$E9X2DXYbO@Wg`;#T~qufs}m-TJ@ZvKfa+rNb* zyC-&P;Cd*J*{64q^Nbc8Gy${458eD1xa4@fFeQ}(u~HkDR8{~81hv9tdXALmw4QE# zjaF=GfbAt`Zf)T&`f>+!yLk|}jmLG*o%J~Uj@|XAuln3=s8>e2t9YN(4lO)BX81ON z%3Tu)Msv;1j{PWSnq$*ATYnK;hJHM2eCD-v(12z$wKHCgPy#A{WGH^ux9g)I1IKDt z6!$rgIg1qP`FDuj`kf3S4rTt;{xGGd%iyhrJLQ1L`hvb}6J>}J`B6FvS&2WXFbL0I zl!vRpj!8rRn?XAKJ8-zbV!OHe4CoK>Irer#X6j76UXkTTh9pDmC1gOkn1jt7Q?fP< zY7kVVqx&!jO?UAVJx%s@-v@Ms-^U0+bE>#kWps32Slyi$rDvV*gI1rH%jvr)>(%{d z>I+KETRn!}Q-w>gu-_}MktQ8np(5fMQKz1R*O0G7OAJxG>3$OQuJ2@&wkm$r!KVQL zkuR?*|CX2sajK(%Jq3~>)=l>5;QyF-CNwL}>7PLsEnCkJzYNfTyj+Vxqp%~I!{2Ps zo&6W@>ix!!Ctj}MU>7{tvi$bBWl>ds@-Q6d{2fcPvxFAFk$l2SnEe-*wQgSZp!MZY zoqf2(5nB`GZzi_UA2>mn8Pr9LN!cigZlB9gtF=W9q7|$(GaaoDu9VY7VUHrs2c5f< zH7g@B?wr8YVdT~ZwFXOQ-E({j*~PWf-~Mp5V#97q1t_1&igMEQp^D;Awizyru>Dj( zE6CA|D&8B)&u?@Vv>GZXy z6D!Ws6@$h!M&(~45LU8W_kmh7~&#W*>iB#SQ$}Ia` zb|py(a4my-(tSpBZv5-WAKkA=FRavRr^1!EcVyqZC4QyotF73V*`iU=?&omuHBipM zK<_wVRS$i0?tJqqmJcA`~twO7U zZadaGT;Y#bzezgO*Hg(Zy$MpULH(sx+uh(#)_yz@{ZnG4_$%6s+_w{FxH>iwWv@`i zcmF}x*qnX7-{VLrx6O{320 z>%;9%O4&9LA)UT)YK{){IKhT+M-e7VHeL+mUUpvy2KqsDk*&6lyew+kQ~(N#jOLAu zk-=}F3pNT6&A^kEZJqeRY}b-~P*5&%dAPPg%55hO;?R>&9%VE6H!+WoRc(Ihu_^c_ z6S!DZx36Z+BdE}D@E&DO&4U+OkwLqTYeO+8DAmZisHw;%8VQ^?CoW|5A^jT9!C{Bo z(r1Y=_Y>QJx04Z2$K}gdxw?YBfQt<9ICiw5a;3}cTP}tp0U{~bQzE3@=p~~Y5M2__ ziFf~R20uGz#QakLPgibd!^euL#2x!Yh&keA=uh>LNfSHVF_Ae&oF6A{snmD@7BZ(BVCL4r+9cG%-3jj7vJUE z`s}nu8ekU$&qO&S)-VI!fsL3Emp_Y{nB;gnLe}bQy@`rV)yCYy!~IZVaedLo@iqdg zx|(XC-4WR_9Z5SF0rw=v*YAW3wL7dj|M(yLqLB&0?mb+hDji%sIy|K6FTPZ=Q)vs4 zk96LX#;$wztwf8F9w#Q3#4aiCu5+Nxi#S=0Ybl|1R{}MzQ^R2j17l zi_8-1N=;r6g7{LmjlL=_yy=b#Ca6Sr4OiZ=D!3hdAOX)y2PYt`k6X37=tz7~d?E}Q zvysHE^Y;D`Mxdrnv?>YG$xt$1Z@R%?DP+I`d%~v}>D4y7>W1Siwy>ufb8dr!dwBJr z1vYH^E@FcWk@fM!CKK=FD>AH;t^Q&o-uVTgvBlB(d}oqGi9^M#eCc!ESISK$=j~lj zPEv4qEHily2HBc0Hm_R-{<0a$hu9OJvbW%j^(N1_eUo6Zr^%Y!@s*73kYv3PO*wY( zxtMy22DR$-x!)|zC5H$=TJuu82Tom~f|Ezi8DIc=afYJXmpOR?$o-j762WBH!-%MR zgi-N)Ty?WR<_3O(kD`Rg&k#EhpNy^3gX>%`miX>ok5;_D$$_pWs}b<1K{t)pN4T zM5DmFr=_D@vEtleNr*LJaeJyIo*I3_Zv88nGOA6#HN_zc@x_dorKRh`Pu!HIr=akLED6eYPyZcfr3(O&R2UOZYBNLh!)Hh znZKVTO-_+dnoSv_yD&HwR*|5d2f-9z8%6^l!lb{^o)Ss zvrhu zo=-2h319J)S!XrTn{Drp-zC{vQ_Ba}KXza+v6MD;=4s&Q9q>`f z)8HAebCD9G1s}DGa9=Mo=DHc1hQnU_qpsQL(5@il`KLfSbatX$fxFpO2UB9NRvhT< zetqk~OS{90*u9?o!ugZE|23lY=qv*4*(Kw|7&L<;CJtPEkU~Ld%Uy9s>MPM%fH5=A zuA!zwGf5rQ^MH$phlwSwL^t}md_{}^P~CHaQc*#Qrsi|_MZ)J(09&!!Z~sBm*3Nb0 zot+5r^>gfT7wm7wyrghlWW8ZYK20nRu?`c74J^NTE*-7R^gtIfisNgl;c%v8( zuu!%!vVrA{gq+JZHfxAb8nL)puEI@5jWDrdXLMP^@%OU( z(CsHsP>%8ssl*I@PBj_eVt6p$@u!8)C5|6OHW+D43H8BrEK8a&Ddiy|sw+9mLl_ED zV?t14Qv7g)Q>pei1XsBpA+*Fo`%%Av5^AV=YuE|8u4_Vm@cl|UARBFn6(O5OxOaz!$grOyiJ2OYv}!7~K{o;_ zjE#tOq_Rl3$S_WQB|6Z8d9UUi)uSev^gjW+&ic0UIpyF2#nA`2`t~UxkxlzAl6oBu>l(le+?4te zm`MH1n%3@g5X}_~uiKl)m1C6u_iQkfj1ocmk0JBXJ>GhVN zMo8yIUn$Fe3eq*>rjrhE>jeCFRC-geWPw7@ycb9F)AFg(gvc#@5{;`W4j-vs<1(w(Ej z^X~Obc)8G#2~k@SE6e)W^{-F&FWLn@iQ*vIbdE?bi1`g%NQLg#^`V;h=p3KGUvHP6 z=cHb6o3WXt{tz8P5rBTj4QaPq#V5h%tctgOfomw0Rwp8kkw+CLc_-utcu_>?; zf|>?cl<~jk$W=62cc57L5^r2z8^UXAv%$DSg7>3?i^A?@_(kNusb(k_{nzTB`LX`k zCKG}3ypdGNsrbB*DuF2#l~w}YK)<9-d_HXp1zZZSXM{&;qp8^lp0Og`JLL=05!(x1 z;OvrbT}Et#>5}BLGVyRQsBYKZNt?p;1_v9F7t7}QUXM#d*Ci4*;s?qn)ftUC$!L?Y z38sr}i{Iz(@BCJKhM`T+kJ^;5cS5#f9U0f0fDnFxaGFNe(wwukbne_-Xg^a` zcLxNWzh8I46}T9IWJWOU3x>~p`x5+%V4?lEm$9+0#`RVZK&9Roq`u`>HH1xz)I}xK z{9E7^d5tC#Q-pJFAd{npt3s#p$mJF;c+O6l+U(3te;NF@68g->)Uo&VPN0P{6UNWw zUT2v&nM{aKx3pa1>JlSe=R{e^M8msSXe_oAGyt2}{TJ(6YpTa(45LWJqj>=^_lPye z4{!Z2s&Mchhw(q3a|d;F)TGZFIFfZ2cK_4!kk)EjPp0U_AXQeHE_^aH$;Ynv!A3%h zhNbw^WxVB37;i<#RcKjaRlqar?9`x^I`>3$P_kv&Nu~+R>%+I(7c^X4lmRvuqCj4Q zzd&cZ{3AMA+w7eo9$IGqFd^rq3J{uGtPlSQ1c!uebDyO#G(G*<3n62ek}4;>!ThGH z{X`Qw6=WD0YHt!T`|oSgcbxF9;Xec2`f4&V*wFrB^R&}wDnDX?nI|sf9AN}fu#2y? zT#K{iYDqqP9?Nx`6!Pk^Oj9%3|Ck>g3ghnt3)&{SYBG{Ip@=Ov=6m{jG`KeoOOk!1 zql3)TLX-gZPHe>s|H0p+V9|zI*FDhpHXYLHLMDEg$?#ZYSx;NANG6)7s`_MplOEpz z3WKrOL8)q3hkPCQitoXiaoG`JgiB~)H3>Rq>zQ8iIl|3KX@pr9!hHE@bVDa7l)b_8 z682K4%5nwp5@W8P2Ozlp+w<#YK~;S$x>Uk&8-+7JPr=sguav0tK3(5V8McK+bO!@t z%NeiCsQ~ON8PRE`&8v~vL1!;03(l0#!Mo+YtzcB&^CEA%b}^XAbVHJNRM5;4Xgq?G zDjvzyt9NOACUkMbf4D7oZ!Jd~}`w60tQt-o63OUYss+Q#o}vP?&@RTk6v;;fXI!EmMGV z@S8cduDVQFlhFd#3%8?~pqI=nEEc`%(^n69oD_kd_@MJ_#3?W~G2*aVHODg%49on| zrb471r;|s01SJ{X*3wjv2El}DufyQ8``{r7<$1M?1G2U#)l+j#5dd-yITUb_ThJwg z{hhKlCnDGrt)8-$icwnzMuV@%BPn8DP~Hpm>Z+S^ zg{4lAO0j|p;n)~*4i&|a@8R~XJezv@SRe1qqAwh$*dO=!{k};{%~Y>w3CFm>2R}dA zGyR$%Ew&yMC}nGvDvvaw%V%O2(6-jXu#r0J_l}0aZXqvwJRb*%9N17HZFo4t=|?I3 z7dS!oj}r6CPm(`*HmeUGP5zTrEB3fT8;wz<12u|-Shcwyi z8pim9X22}(I`VPNGa1QcVG}WMqJK#E=VZy zKe75LZx7#@l>Ed3r0454GxnK;u4;#5a|R)poKq)h9A{34yix(O#-sJC5(RFfs<2%{ z33{RH$TQw^fdvYPVW9bdK(&~PT4@r5FZy*c9eWXt@opjYprBdlhO6Gti5(cYYn&VV z+Oar`@?=T)i<%0FeQuTcGyUL@yC6ikQR7?nK7&z zlB$b+4dd3WbXzsGEJZW0+P>#92Y_`Bzl@Yvd0-0wHi(z6ftn1M zI#)MCm|;}N#H*HH6Ghs4Pdt_TSv)-AsrSw{1eD~#fE}dS$Ex4Oq=rrj7|RZ}l__Qw zC9mhBhFVal{GxxL`{^CLPDj#q-zh&O75*dT!_~i>%t||>RhdY>9DblvYUwRl?Yl_0lTG@>`DQ-m>i4}1(7I+IQ?$g$A=%IO-%BezFnT@R#W1yF!oT}0MPm&f zVUmSQC{!5=0tCd|W_i0k3E_Ov_=q>C?6+EP{;>`<^7O8o%e z=kl}f1L6&E1eee%%Ra~!ZQsFw;#0bZyvZp=rw`W1nWhDXysBv1pfHE8!J$@w zlB^#9jQ?Z6f_P;_DA_>mB&i7m~(CbQsRG{xdDYT*-$G zxW1iO4DF|BYkX?+MmHe#2nE#{J+1iGf6?Mb02_!ic9?{Xr8nl^!hcKsk`%($VK_At zaPgbQKzDO$sgKfzW40M;x~p$A!K|dYykqNT3cF>cmT+_YO)oIgTi@tJWVH^oalM+Y zB&Pv`Ky){RG)=5zQ#Ac7g8RqoZKkDO`o`4#uoYag?yRRaA5cvyo$PT2#XSJM4+~ z|Aam9ai;#DMO96G`vYKtatQGM|Dv2$#%THM+wRmx+yXSN-w=`D-CK{^Ry)PXDF*?l z@o)>RV%ViE)5ml;@~{(IYog%2ukw`*e0XIL+Z z$ImB09j^meZ;x2Hud<>%bSwToZ)azErPXiCP`^Xy>yAq9DfHn8`g$G*t;v18dPC|H zf-hl%I`i(t!a|*XwD~1S{=I#j%-tFPj&0%VO~QI`WMlVs^TK|4G%ogb9w)Y-!j_Sh z@vJ8H@|;SstcB@C)LoqW_7t}H`1bOAmis!Wllt~BJ^psnLjk4FvG148>>&b@xJNrd zkuI|uZe+ZdnttZ#y&jy|KMX5KHnr7dr1;*l`8`nkueLi53g{lru^;w)UOAc*SVJbV zVKf{#EP8N*$Muv?Koiv>N?{}x-;Cpnr^GiWTAE`|K-5$82w@6TM?OE=^YD@~k(Q8u z6r2Zr7xqUu>o=rie0Js+jmslt%_LNUGLN!FnD?%`6=*z!=;m+Yz;iP3rtqJYmC!9V zi?5;qMrqkQEWt~yQUhEv=$|tEg>zZKKTr;z%!hG?DAYS96o&_Uk8N~~7hwi8cD}@q zWmXZf7SSjq-?t=6)9I^pw)9+_LOOAREYxFUC^c=n;4X}O;|_aWN_Y~Z-YGz!q+m-n zWD>;)(XuM5UU3XsO)j6OZZDb~RVI`xcW#z?vTA>XudQ)-5Z?Nb8tP~~paDqkpJ;In zZ8ZFrpFByg{|;zrsM{&9>q_oe%SjuONgxP_9?wM7_&o|%YV;u}F^4C;+sj>|(8iRS zBRfpd%DTh@>flaB2$3yQlZ`_`SQWu2IgddP>u6Zid*-RW)p$T;GTb&Z2QAHE97L`m z{l&neaC(Y0xM=kHA+gCarUj`V7JZ9ZM(5PH7PNzgB~IgsDil2iG&b=YnR(a-~1ZMy3d7H&%n^Jfx%N8Ytl+ z?Bi53t*XZ@Zb@|fMZ8WW!z8iqjEZ154hCEnGNgV7-m9^=!onC{LwwD@juL|i^+hRi zxmG(~X{XiYXK`*H$DoJ|#`>iz=q1+}LD-S)L4Vn6fNFbK64-s_07Y9oP1B#n-gpq! z<^>F}=dR|3RvW8=Dmlm0+1Wxe+snQ}*8Gzv4@NlHE3=OVckDy-0aDQJ39B2qn%>4q z_%{YIN2V&Ypd~P4rVMQ}?`2|M6wS{o2^bQNJnoAt5u`v8hYEw1+&@9dMg~k$LM?Jf z&Xei}Rl~b#Rm?q8I*w}CP`7BPRkNz!T|8fT$QIm9hJKEYQa-qWp>1a>!7cqNmIM+o zdClHT^Bg?Q$mgjAByU{gh*?uy+Uy=ou;-ULqmPkJW`h*q)$g_)CbGIp1lhXPGYlZ^ z-27h}wN}z5P?T`lu!8zIwO3ZJzI!_TL)CDFXfm*8zf5|iDC_qN;DyYMLLWX!EgKky zwAjoTaty~hh!u(zDifg-QWz4kbNX{0Lk@VlzDuWL+N?PClT zP`mCTN(p2*a}g;>WOhHB%3|@|@6}6CPjn5>ygk$%Oz?NFA$c!2HIoXbm~qeYs_`*P zunpl9XW$A)%W-u?47mwTa|vrxKh zMV5;wh3~*u5bjfj?vNH9IZ4cV&vcmudF(jW8T}S*HR?1(mc_5EhKhPH279lsZKMxb zL*@*@)W2_8BG6L8a_AWW;3XUCBb)k}$~*lmm9!PWgs`@gD%%R+gqKY9ZUyL)v8(j~ zLkc6N*QXn3(baZkN_#eW)DEPv@0{>9&Leu^C zQU%)q(8QT(0kaAM$ocbmjj!Nx zvuS9w1!~`Fmq!yW*Z_Pj*S_=Ik3p0@*L6X>O%MpNwO@F&zNVo8cRE846r#<;(1D9Q zVWJG%B8rgni`Cx{OzMxl2bm9?KVp7}hOZqZz!Lw$CB8PkGclWcFV1o6AM|zcPbf&3 zFU7qaN9KO3!S!xk)o9^6a_UImmsOTvf5HccvFM2%v$IM=FNG8vx3dlFO}j`Z7PkcA zGUotre=GcbAl1(cf#0N1qi_jOFWDCF3_9CM?hljR^@ok12=d%dSyWrZA2;AS*n3Fx z9(bv-1fB#&` z{V#jQSjTWAW5ipbvI(ZeRR9ya{*^lm83713uT#%grh`z>$op!j$p_jP4!~$!VF6C> zy-!B)r^GyV((L#Em1p@{D#wTWQCXrzT4Ymd@J{Lw6BuCUoifBk)$d^F@j6R0%~O0- z!6%?`a%&Yy(d1Vet}rp|#7YcBkBftAFA;71wNBORD>iyiIwmx})pcgrE$o*$LsxnB z5dws`4IZ_`V{bu;a44WP$)6T>ZW8BVzJJvN56Q-Y(${YwMgEjIEPoSV4h0KJ2US0x z(xO*;WLO2O_s_nkBIK>AbFw|q+bMlT3v!3iknJeLpzhv{we#d7?Tm6uWozmA`)?ta z`rh(umZUnV#!6&orFAv6%ezmc>whBo$R_UJWH7zCKH5SJmjM6829s1ao7~{u44;0z zZ5{U<8y~k5=08w`P9m*btm!Rt1u!*6QKi#|@{@a%<^~n~?rP3#$RJzdB^MK&sq=?E zyEA0{K4wKZzp%T^20M35cs8cOJKrM~8XnJ&tI@m&h~9jr)aQXVWhvbed)fL!?=tM? z{49L-`JhcZ%PJWhKTk(0n|CN6$y!K}gJ9MsBaL!IcJW;w&?#jD$#ReMJ+I^-YG4aQ zYp;d7{K?I~-P$=5}xw(=+r367pgSU9eo0)5iYhlz=c=x^E>4sbaR z@U3k#QM&4oNqvhjuqCGVoFV~X*+>k|me%yC7*z2ZJKMpvEw14!_*C0t1*L!8Oe;U4 zo^9$P+R3<$p6$Z-m`c`yDBQT<(kms$WF?M{~3@ZC|4?~0(``#rfm)+9g-`HP#+8lM?)7x@LXE4GGKp0dR;ynjp9igs~D3wWp! zU;vIs^{}D8qO4~e)q%U8Dau*EMoV}J511n-kg58TQ3U|5s^p0*sYeBvuFzS5U;}sQ ze~Nq}8=C+d-IFkY>H?gj`vLs4 zVir$b>0L{c!oJV6cYU_e#3eK_WKLZ-W9WMT2#eR-o*ng+{0Gtp*BvkIYb59BW>R$6 zdiY|^rw^<3Ql2`mf~|Q4h$=55!GQ5NbLkE@qA_aJ?G0lO#O1yB+HJwFgR_^mt@4CA z-1pY}EsHhX;mH>vF zRfc!ax%A+`fq1OGebszGEqbLLsvuBXi8(wF#ey|AThMboX zjC1~r*F3%ocXATq0OlFc3Z{XRKO9+TUs|Yec&=&^ziGr35(@%={_kQNa4n;jj+7^1 zp}o(RencZ%TxC!$7;v@ueLiCU6s3{2F5XPwxKji948zlM1-cKjl5F3KO*+#qz(uNe z*D(u6x_M7|rF>LcE9O9$-mBj7P~AKV3YR!*BIUB15j-E2#KbK6_sRImD%xLhL11NN z1UoQAZ)`QZt^XaO`Ckx6lAhWAsf4DUOEc`@UT+wOq53JlEF3w6qfF7>D^~lsG>XN# z#yC4uGQE=a)_yb)lDH_`>~NI=?l@5JL;_hs27OLp#WrD(BCD~B+^_U~MQyeAX~Rq$ zwI8+IsDVV%7)8NRHjn?^%8~mS6185?nwv_dxae;Re(1-@&5|pm%cg=^3H1ErFEPxh z@x-Bu$q6zn6)YS@U;$ijffO;$XMqmD~T}#jNB(+4#?dIm< zh)Cme^NNu+m(`tl7g?bqii(d5KuW>A69WtO~? z4B`KxH3c$~o->32(S6U`BSKD^x0eUkSrJS26E0)D?cHRvG37fK^rt`B&-2s=8k5nW zr%Bgb&tr3W*SH+0KhQ`%Rc(4h7mVC)-eH>_8S~obZZ($?S;3os=9KF#BQrLzjZb+|r?-3|* zHU30dD}T@dA3o6MF{CWY){YgYZp2DXw01r7$YpcJ8>p&y>!t*PX@JqtL&a)M4^#?> zZ?9Z)E$Q(fk*y$ZNX&;qDN>g`olm3Ob4g4zFn_i9-!4?ybArwP$R*PGx0be)xgyUk z?LMvz3TjU6pViY{U79UoM47Ix}}1$T@Ii=3Y-z?+5&5i}IJ1fh0XJoBDFLPar#tTY4sV z^b56ckIO`NL`;7Nrann*?I!o#6q$&Am_Lwfdt|cE*K>pK zuI0Ny_{FTMlMhQy(r6xy|62BIk~##ofJzgh2|6TqppKH!4%IC#zQOaWB|hWW-`)Qx zT=IA2?QBTK8{X4-MS~LG{ZgrC(Q?ie5@=&@P)sGz^$6^$t(U^H*3>AYMok+QuDU6M z1rxStnCMUbsp|o8KLy_OYwF+OA;E9Kd+r)R)-DRRJ_xsVMvIx7=uTvN^n+SS6L{E) zYx1#Zpn#$GAJMAK;*P#8EBhQBko{g_>4lxo@SGVuD%GXzmpzrXV~<(AJ^xUN?H?$? z#ql`b!=?X(8;;Yir-zSRl`q_{C`ve=6t-Cs#&`eVcb5H1Z67ny3Q3mAW=7D56{?!itUocv~(@uu=jc@sIs+E5d&ZvR)nmD z?)0DgKoCXqLTiTxLdMsR(+?)tLA!Yk64yL`2sDJc8dc^@TW^}k&0m9l-Z~mGsw+R@ z%ERnXh365R%YJ|5x|?@hQ^jE36JID(MtsneiWG>yPk76I#O`XcoaqZ-5|{0DHn#H? zo+3HgVi66%+Ddt$4%D8LdIux44^3@qo0*Gc6^$U1^XEjkVzWvc;%IPeJquBtmdo|_ zM1fHz+KATAlYeuj{|{YX85CC&wHboDhr!)lgS%@8gy1q*a0@OsKyVH2?(Xgk?gV!U z7TkmHyt_ZP_N&@oGj-?At=rwly3aY!69DmKCL2RWU=L$r{$+Ia6#*$j#7o%gqbpe| zvS9} zJ3TIi>{4K5k`IPw$x4bS8tkG9{Lnx(8t-8hb`OYWDE?ofy3S5G1=&gzId>2y*|_pO z(!X~nyC}q(9sB@KHcw!E^xZE=-CcXC>(D$WLNx&UlAvv+=*o6RQSb6C>obOeBCwTuB?ba>C9*&#(t@#Ty ziMqIP%_p;`8_6-FXY{=|n-XrSa9<^K)HDLi^orxW--JG89j;leJ2V`b z?B}$yb!o-76X<9nu%x;_s4mXKgL_mgfk%qFN0_P1VJfyN{yXNPH)!6ecVzQ4R18%VqQtPaiIu*u-MXlV6O zqcvG^v9$GiYuenZ(RYD*8_e_^?kd-kplwYTaj2cE%~iX+kd!hhui-LZ>1M#clmK_6 z$*!R_OqI{PP!O_3`!yg;%kzW;JZ*!a>X0`{w@7SVvW?N3dSWh7H=1Mtt!e#q*I6D= zS4arazD2PxBvNu{G<4;)mJ&nqPOfPASlPC_H*sO__{v1=W39T$?jII1qqH^B)B0|o zeIdY7bSTK7as%onc8Yd9iT5qcP+jhE>_sx?rGxLaCb!lbPKk#zM#hwj{Dh&<3iWPB_u9 z5Zm09bW^SAK^+tj{|{mcsa8^;6#wC3y1bOr!WXLP{d_jhcbpywe3$snkxFU8##@4B z9udTza8FY4>GvkLNmV;h3~K!1Xu8tsdH#Qo!zYL-KBT*go}{YrvOdzS3ne$luir!($)k~F9>9alU?&k9=ZZ_$g_G$%WisNJ z>Y>JumUl-oXHJTyXQs}zh}X2t1hi<9hi4dZv`aRlWDlS}JEOD->izDV*di3};bq;W zLN~Tm94phqzdSwo!$|$$VEqcMxWP~#-a&x=m27VSbp7`Ro|-rnka5Ss4;=r~Hfg;M zntd`z20CYfup3;gtT4tKJ_T^XR|Z0fjiqH!730O>8}Z+SRliTmsr#8#9}x$02EH?+ z+eswn{s3{a-q9r&KCDfts)T}v^3NRc2Db!=%M@hX$#5h(%9zP8e_qi+l)huvFJ|&V zK*Dd%+>FxeR#KrbN^FM}3I&LB#DW&(O4X)ldTF(t`T3}Z$%Y}I7FH|(pHSJfD*Mmc z5oVWBXakQBbeo{_(^gX3nFk^CW5JC3Hzznrr?x(5A-;>k+B?oclYxR55cx8q8(_r< ztsk&I{{UU03e}960vn@bk>3csz`x;y%h%b2C^t-O$%~UQt&HOiJcdZnMZ-m3CXtK# zSm&u~RH$NMcVqB1$S?%knE6FmxKx1!YA8%7_#*%WXzGdE{KV;nDvRM5tqP)6#;hR!Tz%h-b1( z&@%;mBx{-5Tdc2T+UueCnRG@`>)yL?#v+cj$;T%86@FKk6g%+T7o~25vz3-E8YGNa zewy4Zm}w;g3V$tfjK2ZUM{+w2Bsmq<%-5|EIKL%rp0SO8Nlll7YE}ypdRh&E7lvLT zmp+yp&s<@tkmN;Oth{O;LvsNx?BK83n9`z{(EjQ9;GrpCgyH1GIs1tigWf!q;l!~? z41Qh27Zj+KiWM=laS~2Z#HQm_fm=wg&#)oCRxI=$T6Xn1QU>hBU(sMfQvULDFY3TP z<{dgV*WnZQ)*r?@87^PGGo7xB=u+SyNJ;=8|E3Ez?`D^jM`heiLD1+h1@aDlPrx=5 zrjkq3+^?x-^bOqp7ZUXEm-&8WqPTYbH)v@5$)OSsqNbZ?+VihaXmK2i@aYSETXcXO zzsbvLc#ax|67c(DMZe3=Ask1Qet^-%K*p$#fN!^!A`GF z-Mct;fLS+1S$;D-)$%O!(9}YT*jV-(VvDyN%75^2$tUv&%Ksx}i}C*;Rq!Q4(J2%{ zrWO#Irxp;)QDOL#y>}3E0cbAtj1o+j=761enD{OfMHeYv7vnyTq?x7bR_l6uGzb9J0x%}&?F&O|^QcOLN zI7m4#yW&w#RjqBD{_fS=EH!|3W;Fxgs?0jk5Rv8N&CO5An1I73LD%gjD&hw(;NIcx z6!Wd}&rZOlhvGIL?ZMxngl8e{4Bk>%qaFINUCd^+$CUaAyK9LK-%n9Wlgn3O_}u}R zpWA$~R4Vy~G|8oC+x4i=`U-wl<&NgP{7Gu>nBqFqp6ct0IDU>^fQLc++3z_|G^$x0~SM`naaAM-$NNPsS3ENqo7H zC<===6Q^wElgfZ5KtGoiEw7CJ?|c8zB-rV(`F7{#Y{ou^m{zg(|oY;A2G0165AvlnYWzviXU}o2`Y4!a5^R66K#Xlu#LO@mB z7_uestHLRFG6SC)axX7fXnJ)DYS@;N^jYHihH3`n92iB6G^voTAcBO+rDsOxTT3$q zj88CPPrcxe`Dc&$+gQe9toFr)dvcBlI(ZGX^fC#De$*yD2noKpN&Ahf+*IROVC=!7 zWl7`#%WhF-7XC4y*cx$h@d4yA;|m6P7Wg>SqJ6%?WOC!_4Ed^*4vB(M&|&D!rTl2}iUKys%KAk|Qtn(qi%YL~NK&A>i%+_YzH7WlFo zbCd8HXQJpaRpa(uAibS+-m|8~?TjDLLED*Ilc`Hn#m_136?Hq^_8Z1Fk7jXiVTBUS zU}sfc<>{?=f%`HE`4vAue-B3NTVm6t3AnF-wg6L_ye4LqR)A_16N=CwTa0Yh+23+Z zEC`}O$&gW1TvQ-8{p2lX=w-99e!4qpBm2a%?k8o7N8 zc@-7tESs6C;eLwsHG;1KrrWwcw_qo{yO{iTr0yt2RN|bRM4$fJ$(afsTjEtYpFW$M z@Al|=nI=12tlqZe0JlKd0R!Ws1S zWfKLFt~8svpa=p~AJgGZ+&Up7$(n7AY*b{?I>)hekQ7sT^Pf{{&s_`@^LZLcCD!7J zSwfz$`Y>J_-O%DLrZcB-X4Z(LjwsG}hi<@UzB&(ko5bK>fnrIs^8q3|J{*%TJacm4 zGot$cuu&-g*G460(ja|JPJTgThT%-^e?iOv0vaXkvR^e{m%mE04|Z3wz3NotZEn2g zKi?&1i@m(2KTg{tizdGn#$>-;DTvYjiM%Ekdpp&byLt0_t&Rb{C>8@x{~o%_H*bD&vs7+qyQ_+%DKam|peeGe<`A)j{SVj26&Azv1c!#( z04Wxi{QjMICHKd!14j(x(P}YAB}FEFpqqFidw}cfF=jYgq#~zCa??wsx~CX7&!a>| z<7ac%$*K8u#9ID%qqvcWNkNxh%JYSU_KzB8aHoam~PHO zJ}XRmq6Wi<&qwb%ayG4%va8^}zq%Pj9Ta~d(X3S!FJ{ld7)pEO5~}*?@+#Zyj7~=9A@Yk`TG~$J)1BdD*>s8)_zGk<$ zvFPSVQm|M}ZVUcJclq{rqND1jIB!$)ddDjnuUWGIro*6xE{J%2uB{O9spfZZse95df& zHFJK{Ha+%;FS|f%Li1EpO-;}AVf9yll;Gd%^oRpHbgs4*h6Z|j)>*oSJ2Ry>Kg+

!X63P;ste-`DG5t!<$l>xEx^vzf2b3M`>7oEse1x&b68-ZrCXjnkZO#qZm_xOilKS(VsqCjS!gl*36*VV2 zOXEe_3 z;Mvmcq3Ezs^x>C-#*e+`)v`Rn)KY;3(=md*QTt;BRFrhShUm9RMkIlJ-3$~B=1KS@ z_K-Ym+2ZkW;p1AH&Ev8cU%Op@z2uxLocv~P)9v?TNfOg;0ORkW$;cqG_A1x5`U%;+ z)jpFiX*%xgHP3FVH7#4S<7vN54TP7ACJLTpuLCBC4YpO(3*PuLeT$uhBbC3rHT=@C z+;@@NnV7AFJ6H!RC68I4Lb$xjOm;ty%P_AdVl6Z;6OzldWC%j^-9A>E=i`AN?9_^e zS#6dXWR@1}feA+r&1gmyIPk-1)~qzvomG_c7<*@<_Gf0g(e9qQ)l*lUk+F=#%0Z;n zLBUGNv&POPkI}z;Li=nr&rPesA`4z86$pk8qi0nes2VSurVm`9GJcHksZy9G0z@7I zMV~E8-v{SBFBE;=C0U#Mc3$ItGabd9Qde!m+c;`u3@ke%6-62z6j|uUWX?-58(qjG zlVpuu=lUT3?D%FkF)n{t8z|xjiI1S&Mtqtdc4=Mg5?xFj5*hkqcnz+Awg?j%H6(wN zE{7T95_U&dB8o_2MZ{uW@+A&o=d-xrYDY7DIK6YDv@9Oi2(Mvt*xhnk!*zGLZuFh= zaM91>1?Lis4|8ot;P%D@iEou-ZnSer7d*Ztv&N<-LYLG*=(J8}tm6U;^`r({ZpPtut#!%X zvhM(Vm~h#-0V5ydD9u>R1_?bP(_$a_4dnBCw=T6e3yedtIr zvJV;XM?QH>ApLZrGNj!_BD}n+;4v9m!^7Tbl1w_hkK$A|A(FJYpLZ>rZx&AZ!`_>_ z{m=ZGl9m~@2}}3Dzy`JZ(;Ulj&9R>z6dw_@dnN|SMmF<(W^Vz@HKi$w-iO`~N&`zg z0Qa@`33_|0(=1_R6qgH(#KY$t+>{dY4cJg~?FrZ}d3p{38l5%eD2(OP={bT43+>x} z%^~`Hc0Ru1Ye+OwZRAFYw&|aP1FSK$KpT%^`V+p;z2@b(O6IwKnD4&>b+XcAw_hZs zw3{BqS-R)DG}mdj{|44{=}0Kf-6i~?2bMt4Nz1fK;rKWzbh2Xc)$%d$c0ehM++5S1yLAuQgS6ce>~uN_%zrvb zVYQ$3O)X7)A$S=L2Yt)v9nI(Efa<)s-LFhNN`_EgvP9Lcf{|IFk{r$OGVH80iIauR zwYtTBa;0YxIVT^yzkF||xCJDrPq?$P47wVxK=6_H3B-Gs99Yb^E?Q)2w~M+(mXa*p zr=p{#)f9Kp+4au*;C?(>g{A`u7Cj6Jd}aaq+^&ckeKE@c8|s+p0d2qZ#$>reNtVUm zI+x$$SVjGRLN8UO^7~6``xm=Fh}#)Vf}`=0t=A|SjNUgS5tVl1n;^EmmS9-XaX}3Q6cpnZB@*)t`^V_p z49B`>RF-aiLHY!1&v&Eq?96M*(qyJk3ACWP0)c6XEcSB#6@Hr^|I^ijGD?fCLZstg z6Vv|5={H|G>yh6Ia4y<`6k3V4GU1QoG^`N2b2XR%mw<45prQC)BgP8j;~l%ylWgQ< zw$w=#7fwZ`r;%iU)<03oUbV(z!_CiDhqg&zS%WNBQnn2T1ME$m>tnt9wKM|H?lR9# zf)1@tLsX1A-}%juFuy&t`L_9Gf(#MJpD{`-SlhKn7D-^$?GGDL|3};2X)<>Dd9wCij8EZfk zu%zRDGe{8mE5wX~LGQgekcBiNzGP#`)6Vuifm*aEP`eB5kYQ+|5=rE)RpdIMa5R3s z2DLh8K$+hGP``7DP%yUplGytz`-?TB>4{D6M_W#Qh*JvI(?#Ok5q%_|wF)Mj&DDH8=fj{M+iZCiu%@9OZ1{w$cXtA0lO zSAul@(>wWgePf=da*@tN%CemSKYo~_S39_YIO$G=RgeFjCKjy$BSTa8+=pdQptf5% zsX5Fq!2$|5V}$6x#_`V$P@iDO?w$Rw0R;@$9bZ>hxaX3R{O_Zo_Ig?mntHYn;QgyAoShznIZZ`@Q!|x}rL!YxycpizWVRu$@+%tEkfbA8y&gnQNdT`Hz8|ht-7awbm@#>!~-Va`xOWYI36Re;jd6QC8r2=o| z^o#%a>u;fE%URo?Ra9=q1P;P=9>Cj?>G%X@>7KCfJ4LN^7NPeT#iEEL?$P#ZA7Q7N z7=Bk9xN1yI)}}+->3d{w_T4(@+>|rpJke>Q!-W*w7^BJI=UaJhmy5#lWs|sU8l;np z(kP%;5iox~+^{*iDZ{*E9r3yR1fUrFiIMU(ombRuDZ;xU@Ux0@%{(Z5qIK|Z1OrM5 z7s#BzCdyGuq9SLFVu}x=HbBTXsvpkDjQZ!5o?W7F9X2?7#y9A|Ra0g661nTOCZ^14 zY|y*U`mgb3$b3U!wd=|SY!Gq$$N;!o)Jyp1(wy5ID7~2t6!PcE$n$p<6>wx-gCFbz zH5hAk{+aLN|LwVH59vK4+&a1KfUyVb_C6s*3vZJ`oH6&9HdORk`=A!BGs&pjf9dwe zM1#(Fl~e}j5@pinoi>_L+8XyjR*p)o6_iZ!M6*zrI&q+g8&apIc81V;6j@`_CNUFw zPdCDT`=7v?Hxd~A_16Xv`*D|U8Ko4=k8;@{S9`Gx_fa>W2*5|RrBtvgKy~i?UW~}g z>EV6LEh-WSI20tOj2N3+eYT}Z~%WsuuWnS+M z?6z0(1nfonz#wF&azUFZ3=&yPO`1a31ktZSwYJnhZWw5Nt55(_UxTQwE@x&Q|qa<+Gl&-!6K-J~MqGQ>0o1(skz@EZ9xBlOMe(h^VJvYn%2nF+#PTf5HYV9M z#L)Z|+!v@so?1|q;D8q|^`!FkuiHGdT4Z-4aYtnS^L_lk^x?oN>HV!$12Mb$_P)Xf zw+W&VA+@#w9wNUqvA}yaJ!yDTG-BKY>@@+-`Ts5n0Juy&7zWm?CF&ow&q+gh&2sdp zngQAtKW1UG4_4Qp3RWZ@xXkCi6f%^1NCxe3@%j{VdMPf%yTV>`a)(F?`M8TUw{CbW zS=*%_>nTo|zz%z!EPa`wF_2Xo@clzne&puSl{Zwnq%ma$b&OFU7z=GMYRiSmJeE7I zi$jD!go+HEm>t-_cv&_&k+jet=ljNsr|&si1ClQLlw@e_$=&2yy#F-2TJp3tD05xT z$4Z)2)WZK$7YkJ>cvd00CLpwAP(oc|HaVUnY17^d`26UM1KDAf<$7CWeqA105P>sS z0#C5n)t%tWgqqWhdu&C7OaJyLJAtyx)@K9iHdtDse-{r#;yCoEp!P?FaHoM|gAA;G z!o1mt&*L}Ya1Ps?Kzos?dckTiBb2$7_-hZYdcxCaG)L=kvORL8AE~O`HW=p;t<$x9 zwf1%*{W+SKbo)iScn}ihT6S7uIP`6E$Mqzhx$D8%^jql@9osgT#ZN5G$E1S1ZwYkytagAUk*_+bPs5}^8bYA_Jv4z7Rw$i zB`=AtJpTG1UOE(Loppp?Ws*6lnlU25l8;ElH%k8d=TbCoE0z*m5H!n>0JVgTSCK@d{b2@oto?K9tRAC&h16YT5^jxIXPJTZYv%T#LAXC0G3dx46klshktxp%a`FL4D(8J4{)ELRn97*`2tu}m;sC>FXbp~N?nw<6lxt9k0T=WWbB@S!uzi8HA*Q;Z?C z)!v0Bl}TdG?||CzV`FqRg2w=kAzJ8!pU_c-QrtPAcef%@*;rcp;JGpSuE9Wel{q0& z1u;V6w%oW{6F0?fa8fHo&7v9vNt{VWXX8QUp$3aTyzrRUqKN7DB5(W3!=ch8mEwVo z4GvPB9gH8Fl-*cJ6}*9p>>@pW$4Q}0s9oBy7Y!?bnp&OFJIj39w>AeFOX{D?#ezuM zREm`lU0Sq%bKJx?jS@Vc)#9i6h)~?{97Ypqek0xQN_qwSfwd&*eJB^1P}Fw zDqfK{E$_jbBwQL}xgnVl6JqG|&^vER0&uF-k)DR%UUWp*n?&xI-7<$2SkX6ow7Xb_ zQGxiMm_-s5TLV7_Yv~SSJ-I0pHvi_GhLIZwES(Zjx7&IpN)fRI)SmDqSN#f!5I-@C z)!fZT%TxVVh6YtxaYE^Mjs;S1YOfQz8Vu6xcUI_jirbtOy$@C?)U|`-SFjQ3Tc0sM zR0agn2FhFK8-`Hc%Mi)Mk$;+A{XlRQ3zYL?M~_+_$FJNCXk@`5!;@d9efvb@c$~x~ zJNowdD@-@pyjcq)dhaEgTlzdfa$eF&V7rYYm?^w+A>@#Z^+n=zBZ54quHEyZOkzbw z@eMl|ag>{8ecVG~$F=r){hw0|a@^lq=l{+cr(*3B^Yk?51Rh^5NhEW)9JAd;fxu*y zF}#X|Q+dwREv)Z|&Nr!J=9Ma<`QR$}jBS zqxVxZ-(c~c)*$Vo3;2H-=ZOBk2Xnoi{(Gr;?kypKq1>>HG zPVIiZ@a--;S&Is3G<`GZ7={AD0ApF+#V-UTJAO5ztQ*VUEsqWbFr3lt7bTn}th)bD zoeH@;1W2(lNLl4ov~fFmMF(1d+eklu7PBGPTb~Z(?WIh{%_K=PnQl&zWUfiJx%^<> z$yBG>{Jk6%qcx>N?=Ue`NY8xA|G?nGSB}G=H5vEs>Cj(t0*nH_Y%jc@2b_9>NG9YS z+7kODiAO5E?n#^<_UiT_932>x2gW+O8Bw@Ca>N&?%r^Cy0bZT)i%}&{8=Hrov?M6% z5hED=LUjBP(o+We-%onDO$Rk9s>|ud?w1sZh0W&z3Ij(p>YI8f?EHV;k9UXNf({J8wYgYxfowDicG!G_T*3(j<&rj*q>@ z*+-Y(PTzYe2@;~&G4u9F=KX^#3JUxNI8b^wSMu2S|2XI6U=puq0;!8G;)Uq8hT6*k z)EXrp^0JNtRg9YW_RR50`3i=Qe0plC3C33S&yNi#a(2DA-4^fPe~t{_B@JP->z!@o z)p}|%Bfa9#atW4(62U6Wgt;hsI^&1X{A0*fGP#Ts`2g$VMg5b+SzX;a!z_fe(iuY- z>(Xz9lXgX{`(zTDl>v+LX{WgKPeQ}$2BAM`puT)UoNW2_ zF0(TRzxuXk1mv!w(5unHs-4>fItrW{^WzKkO`A-|N;$Tiybi@i=W%y-|`ke=rn zlS(VNdodh>RUC(DvlgY_`sIlQh78RG6-hvMlhp5=^(FcNyiBLUOA4&vaX}5)rHe0O z0zoYY6{t#lyS6RP7`1Y^=h52!#KbhV^t3A$w3A~h7?UZq(jO!5)1lhJC?azCx2q%r zwjB?$%F+o*Wq|f9pxlu-OU&pwN^GuJdt)5BNe3Er%(NLN<-w=~kBVcoKELmD`eUE^ zQ3NrgM6wY|u|&3h!%ytU2!rY&b- z{SwAWf(sH~$6VFahKA`jXCI(bAR;|9Y|YpA-pSYq>x%4_kk&9s@t{p{vv$G@rS(~| z$Xl+TWyU%B>s7pF>;^uQT}Qp8zT+^wi~=hI?sF#K^_|2|k2|9BJf54;CED8Xa5{ib zy=pkmL%HoAWr%i@#6uy=Vza)w2%@I;P;tbIyP4?Om%W0U%)JCdr@|9n_oP}>3{N$< zFK*d9o~mK|UH5@zviW(VV;4=ZH1dL(q?Z|{t5R^RXq7LtnSUF1R?48vyZcR#Fvx(T zsQf4(nmKx|Jb|MeFu+W(kap2qwB6ZGh|^lLP|WN@w9k}6!KtW^n>{KII1$(fOS8p; z1D8qm`&KAIWOHxd$H-F0?0uw*F{235SLReNO4`ok69`$i&>{RZLoku*ltsZYXHzOG z;8ksIeIEcldc}7&R#3%sAs7+Zs)C7e9q0$9w54=dLSh1;G6Me%cHqxu8luQhC90d; z!L>K67;T(_lLF`XfC3o96VtrYEV(Z;v*kdXUMQgdbX28T@cW#LQ)P-23%y=Zt&`iC zEX*HJ%eep|`x9K)Aq)B%Yk-{e5)(fAPLu8JOpr-gH!_CjW@2X7b8*+aJ1OG#-cF$9 z<=qs_Ka<^x^zw=z)h@>wy>Rp0?DohA0Z67|40BPP*t!nLEBbuBXAg-kfiT~pbWkLy z!~2l6sbYWaS1fG!7eV!$ep1yOk@$`71H>|#3+lyvuic~ydf0N#kd|YHYD3lg$mA?o zw;6(I+}SF!kTAs+qu@*ow=-w5{aD~$3N4~Ge!D9c)}GIy1#SgpB1y8jjbC-v^}hM}4XPg!5sgXfAjM5LXAc8g6Ve8hEl zx{(D|va54=?A}jU8PoiRhr%C9wHG-4HB=E3sF!X!T;+Dv{YCve z53?Dq4EPbB<(hxF}9f7ooVpM zPFybaS#`XV8Q?N`C35`cvO#~jPLCx?4fOkJZ2c;;CXBJvxP0=X0VeIm+kVGa|gTSiyfvdI};V z)g+nX^V2(g6F~J9d5_|x?)eOPh6^#yttL@t7yQ!-HxUa0#SVr9Vf@P`&xw;_01Pi9a3kTSkMLC1nOkOoRDAP5;tYS&{w36)+)H| zJp`#B?y!ELm=VCOZ4ladE<`vs#U{jXrPYk5Tu&60$f|)3bCo0d3qo?}(qWCZSExnP z4R^<5D6fdIgD-GG6;Tb@GtRa>cGnJH>p#P;>TOAmbinQ3kxU~sByjw77|(W`OeX5d z81Qkk(a1+f1YehKj*T=yOq@l(1PWZw*rm6N*x1a*Zq21RT3(?#b}A9Hf_T`eXoyIC zzm*9)Xt>Vgar}55`m>T(SYa0Id!_Mr?1veZRJne*XfiNUx~?f1g&n3J-pf`%qb5^@ zDgRFm5Rnf@Ac)X+K(EM>V*4c@V;o$HHj=W7)#l4#xm|GTww7G@xzEWmB<4ibF_iWj z!*&aq!<%z7`Qv4STzv;yutQ24j=)x|`>*@GkF%AH^#@z}m%SfdFh-i}*DnS5bs@fH zM-vYCQ2TEM4HC|%%Xe^0)50=C@U9vv834>D>&bk!1(v~ z5LF4!Wi55knp0$iJDie2Z(X*Rs!I=LvM0-LN{Al!Uu75q;+qOAqLCfc*5^o`%B!j+ zbWu`aF))n2W9XBKO2glK`^7M*)9JWJh?YuC1PHTQ`vCli+!9OCqf-4^SPV~h2v=iA z<|sv!fL})P{KoCl(2*{#)K!9AU4lTOs!b0i8O#QOt59L-cxno)QpWusqT*?;6U7*# zu79s_`6WjOtDy`eCxScKMTP zfLHY+Jo~i;2iPf^=0AVd6PUsU{?)(rs?+_7arsO5hkv~AMS;mr_Z?jV3@WD$)8$F1 z&S`n|Z};3FWz_;eQa3IO>HA%j&6j}ItuKuHMWuhrVKFWIV&~dZ z3Tp8L%uP+8-ajKR*H6jEGQ9l}t$0O(9avG>Q|ZNX-iGf6<^N7_c<&5)(+|M-D0S9} z)$i4&DICq1=$hseX4^w~hN5Vm**WEYx1R;O0SDfT_z^S256@$vReY8Bwoql9L^7+% zWKnHb{Cqxmp#Bh&&N}CUS-N(wi_QEpr{5O8P{6BRO`lcD8K?jk*c|84PNOln2&_rI zSD<5|?Rx6OC*IxZP;tS}XBH(d$=QQe}^Ge~~l|sR$wpTSovUEg)iIRfG9y?4?JaEMC-V`VR@s(iDZXNkp z!x^$h)lDup&1BjaSDEbvYu!UhP{CSW6YjpRD@WPw*oRETKTO=^N^4{f2+OSMe7sFN z{vox2i)U9%hj~pg#ExTBGbM^Pr9PlR1(KPHS`xCEfDdV*4sg2J7@ot;OxfMTHNrU< z=2t(H3IBG-nk@$#ekzboTe|e}_ijdTxpx2l!aO=ffhhG4SLS2 zNWU?piViD(S3?a~{;ZV=@Zv0{2sgKgW7K|&LQxuLn_^`Pg%v_`;<PP-ay`j}N)u+NroN~MxU6f4Chp=PONJ-Z#wkHNS9>IE;F{o!Ap zb?FRi6-#q7&63M7EhwTE_jJN5L!d?`L^yc%u<3Gyzy~BtL1^O)%&5HR)9~+O-N!b% zDR34EY~t_ylfiVi$-QZ6`1n_Az#F6W-Qqp2N!M}wyHpT1(1deTf9`VMg?f(;GTv)6~0N>BZIk~}tP5aQBm-d}N3d1uwj(nVu z_rO4gq#BN))Hu&GyLh997#gl6T5TMcemvm_*;=^?r2ef@9q$w$E5#C%bF!0}9+@sp zvLm+}%LZ|pJY&xpZB~)M`(kJJDS|!iLbD5rbbdrV)Il+nJikQyyxBndq2`O?>u;UP z+(O9SBXWsYBJfK7Isd6FxrGYpQ!@E?bj;*(Y9xzfiW*eLWF%@NoBwFU(2_}MkeL2Q zwbTC}M2Gi35FKBDo9F+<&)G9rjizaJ^3AS3w1my`=zbUMpINIl#fNZ#xD@vemW$%( z4F<8CtDQT-v+fG6+|u2SmBOlCP%RGIjDre9aBs1fy(#ceJ^Q>0B>)@S?7E>}epn6c zemfcio`0{t4gW_H=5YS@)IMEz3Y={Kk794HL(NZb4^Kv2&#y6er|fT734h9c%h|dG z(w*fVxxGAqI4P|0)qEfxXo7VbEKZK1_4Qe}>+X6Ze>kq*?0$Z=eA>?&DIEd+uHK6Q zPULusy=~3sz{_X-x90P=+qh6&^2aJvQRV4!2L@pxbSra&_a_f` zGz|4Jaq#uvs&2SQ5^0m?g`!wPv^(m~=e5wDo2Vkmu*^6+i*$11i#3Ku4QFe0VM&(0 zkKuxQ(%4bB2StZ@Maydzsuj>8Pi59LE$ax4T@T2Qp8-383z7LsbOl=$ZmTc|Dm@HI z$~Pku75CWva%Oq}T*DD;4$IONWgxq)PQz0lEp|6P*(Y&UEvPx5ztxj<)%w9hKLZT+bSSoR+JzHSxW2(u!1_Y!@6Psvl~n1` z7&-rH{os#Td+6<_a{DP0Ebwg=MV+y<+@xUTy8vT%O=Dn7VBl#O%jOd7u`@%Vy|u@# zJFZ19PJsY);&mKqE_^B1u*H^rL_X8;%4d~B2qm`>A%BBuugd8!^6VTSwFI2uy{_aR5IdZ5Nm%|ao{jC~?^aUL z8--o=!BHPh$vp&n$YcF}R6QrbMo{>vN>Y9;YN&xOGxi#ZO=A$DIw!aXmc%aiT1dx2 zbRr!~DKl*eLL{!0DyugdO z2}7jV%=uFiq$`$_vz|-^lH)N;8_td9iL0+@zR;yyk|xt5aD9aDL%QGnLL+xFTDcBr zV}31oX*?7G^+`uWkS)#YYsu0`qNNdv)RfN)_D8_%{PBZtTlp0jVYo*%q{1vZIlK*3 zuo|$+SX0)D9rfS_dRHg^;6^z8$CB|3U5>i5RXjU6w5+B|&{y5`ywe}G8VF5ih$rSj z8~p?fk@qGDoE+)DOC#R-)47ML@_7KCgL9}O$!)?;h3i7Iv(3U!yU;C8L!Y{YWMtww z1>~yRoq|9&e-HiEaq74_KqgxZrIi`0E8m9+LYt^6g9h5D(KRQt-s=Z91*mv28{Q#wF|j){MxV;f&E>Ls|Dlz zOfG$pcHVt!8$+;8g4i@+Ht45z0jfMo-LwI-paOZ5_w>(CbN;E`0$hK-#-e@rDwi18WoOV_q zfBIA1hrj8TqWPL<8+y3j9DmV}31iB(PH@Z`&4^M;|KS-1q4P2>YS2^2btwjv{25i2 z_y=J#d(pRgYHT<_t#eEHR)P=`$l-^rWJNfB`k|GvevJY_ZOJc0-yn_ZUsP5xW*^oS50WjF5Qb{K|0 zn>Et~rLCU4IP`|vC$<*bZwKLfU>g9H4%VSEkRG4&XY=31-l)Jlt zf2q-jI?|VbF0qnJXxY4o3gzSB6dd=%YfYZo<`f<9p!vM)yuYCq3r7BAtDXwM2&?sS z4`U6S{LUqRE-n1{U3VeTJCm~3eHm_bEj3uWlk9I<@z9RmnpsTc;@K{{KatZ%^_AAt z{!Ue25j}y{%)8wfhw}l63#pQ=0rkWyp4V{i%sho#s!vm6Eb7(lCe?LyQcA229TG}7 z<8{G6)1ufM(cdpHx|3Q0JAsR()lYLa&RR&C?Vvl6+XYlnB ziGcTcAO-C7SviAeT!ig%wcQAx&zJ@WHL%SBo?mSnMD=T&iY&#x)lsw9tva(cui8%q~w$H7t$)?cxXzq2{{DlV}H zEJM5aa@(f*2n?Q?A==M~uTVcldS=1T}`*056JOynX~UL(bSjJ6#4XR~IPurk9y|PbHT& z30PQxmi8~FZ-ux+vmuH$*OS5$yhNI9`mgNb@5``gX)+qE`dFsbAls?8uht07fF}K( zis;Wzk$FQy_y)rSkROe{)dh+MWdv#kZPocKUnb*9Q2T~J!UN?WYb^}0pu{Yj?{dj_ z%9*z&(jx00)Ua3b*%M>jy(By{%t4(vTJce3<@rAEB`U@Jnk%Fev@S@EABVJB}*Z4@obPn41Ll}wmO z!*V7Qi~HKaV)HiGrqdPte;Zp!BYtsTO~5TH72T1wwFBL=iUfWK%Wa~Y$llGUCNu2) zN9%aIPM#q#xuZtOAC0^dLJ3@kGVgG+p8uLlLbdsK#K)&;F+WfYmXMev@Xqk`)FmO_ zk@o!+SSk1zCTgrA;2OMQVSvsPDZ$Oq!ctUOM^6b^3d$$@hiy@Zwh$9+Y<=Cv4%nH zQMc1rI`N9l?xB_(DGpsSQJ6Ox+w`l8^Vb*h^}dcBEpI}VkBXU9C`3QEj)=VUSPbqJ z;VuiVx1u~Y=pAiLVL9ABrRmDMg=5l&ofX>}K@s{@Z+5`EDo3?Yn4*prQ3pTiNTIPR zMK%@IT&RrrEq~BKmsxy|4Yn=xvr}=`Yy2T(5?$Z6FAN=Y0zp)Rm%%Q6D2#(im*It$ zAp;1-B^Eo-Ba!pIfU!7=8`@+XsQC4MG(nn(lOwn43#ju-UEt8=vscd(@9Vvd%zRFa z8Cca7J>0IpD-q1S|@6KEMZpr z0d4X0reCubD2*lwy)0elTBsg02HUnRjDiA-jq#$yE|M0@xWOAD$KGs zgM&HD&M{Dpg4kyKp0^jr`dW2u(sEshr2dMrqi{kkQTxsNflk1ZUf%78gbUlsh5#dk zaE2TFt?YfqJzcKp6dS5v-+lAsN6Yy1#aqu_knnjpFYOScfiYxhk15ZOd-N&)Hh&@= z=iu<8IB@aDX8FeKmGKH4RAVre)+CI7)a=7|8|_1Rhy%-sAQo+G9zt*MpdSij`tk!` ziJ;5dK#WuuQ2TPHr}jN9cPX^jrAn4sQCACIR08cV5-gQq=MTLt!;zk z*Z(5xE2HA*f^CCqkl?`~KyY_=hXBEXySr=S?(Pr>?jBr%YjB6)?(VO@dw;!k|IC^- z-80jDPIaBCU3K;rkhdryA24(6(G>jbWhZYUs}!B&Gb(*8UJv~9$*VLk7k!R*Tef)WwhAwp ziO!*6ydfc@D(3}lZS&<+-O*qvL+{g<=3>tgOt9XutL0B<&6TjSs z{5e+NU5#3&%+`Tnc1KLn)fk|CZGwl|_pO({{dKLPg!2!kS=WsvjK|3=GqV}~WAbi&zuuBJEBfA!(DIcLlN45QIYHdYdIU*4sAn~i9+y31b~S00xBK6r zl2?z2i3|a_IT&lB39UhT?PzQy1sxa6?yU{C0~QMHgrlhFtq1lQji5L4bzwK07>vHJ zM+zb5pm$_+t%#3P4_tzbxv1#tI%o>%M&M=e*H!AE9rZGi!txbg$QWH0C{$!4p|7>%Apg@sKy$w_zB57@+O`UN*GQNu zAE3SG+XE2|w~z+zXuBl_dB?%k8%RM`fE^V!-U14)sIx5J*}`P_H5)>e9%gJ9B4_yZ zXsHCwmuRqYpWs*zu>>fusdzcqr5K_>U>IK4Q=Mcz;;wt1PU<&eJr@ z$)U&daGy>JsipNiY@74uI*%zcrg2k&O6{AZ@l`HO@(fT#0n5 zSR}JMPdFKtiqZf+S=2@=Eni1ltyRQ`5XiN3UD8&YIXTiz8YC>KsVDPqsSt$}Q1IR> zH2pzPp%A1ued`NSogCMle(c?AS_r$OuEk1(K4%_uk;wQ6&sXb3U^}An<8Rm{!1~cJ z-6paqiHTwpOzbBbEz7?8v8L>VU5Y7E)I=U@{oR6OD#kS;Zq1FyNIa_z{)6Bz8+Opq zi0obE@(ezva%ypuWW5w7i>S~*&*{v=Z_ATV%9~h|U-`gY6A7S3FmM0&{D_DF$!Y9m= z`_U!Z8E*7}LKfjJDNe=!HvWmi0~5(O0xc>benA zcqX9>Z>fnSwEzVNFr1I-}zdhxD8UlWaMz$Dh@Vnem1%wu+$VQYpQ_gg-5XQoL4Owa`JPN zTzLMt)0mud9KYQP2`X8dDo2z`#_Xq)d-px4K0>Do-$CN3X)VEk$!;|#YBEazo&nvk zie#{H&TI~8$hz0!9A&SU;s0c(PStg3$sIf-0}3~GUewz_zeklmD{BH2b4tD(C|Sp6 zvMVH4dx%&m8l|rNoneuC1k!E9*#Sf@q#G`?0y6Vw{2Uw`gbO~KCh1sPxSQmy6<0C5 zFy9=J>oSO@Z`0GB&puu0r;K8a&A0XWxNS$3 zGSQ%-8CQE_hhBJ<4|8Al&)y**oG{Zno3!;|I2gHfXL}p%V~>hFoc+u>*MYdItwvt6a~WkH_D_(Jvhi4LF<5AFO$~FZpIOQ zfKPg_)b>vfz7K*~J|o*k)t2qLnH#+zm_KlLb-8Gj4MRsjMTFU%V$YdMi!2i`X?-4;!`4C|bvy(2bDESNFdKp~-$w zoi`KS@Pb`$Qd11M=(nNr7#I2_rV-tHc#?&?8YxBQ6m)89@OtKtAAeQlxgbc@h7l9w zWfdCoOXHDA7Qb(XV|AEYbBJgA`wP1p_5*Y>nTj$PPyuM%YP3>E0D8kGqQDC_=|)LK z~m85I@&f?zk~Y4-)9nI-u@xV?LNK_PZ79Jmd^FfT`O0 zRaGL^T%~65O{yqzjzfNHBMUVGEON;-5CLbPrEVbLT3?YYB5o6*gtHOEYz})nugvdk zX!*BdCCywCg%6k5z=Q8yjg`v2#-DJA6_o&LD{J@gSxj#3p6$SL)eO-v#)n;(f2 z%T@SV7DwaeYM>dtnxdjOx4r-<@I5Nkp|F{!c>49R&gOGPHpekK-lHd+s1BN|45U1 zic24EgoD`9y^7lWhs%h%7+TkH$KPRw0<4|jNT}31{)W~OwhZfOlLGV{`r9$XoCBt{ z)6iwWWz?h|LpoVpO+I=X9cnLOMkhhfrBdt{YIXexzYoPRBDWE8jwm-iaXAYvgaMyY zuj!Fc^@epb`~eTSAu5ym6TQb9h*SEd*_60#W~!7vn|vjG&b*wi>er~Jp7N+xA!3HF z^~R1fm&d{@A2sYH0a9M!ew(Zv z`NLMf{}R%|FhCi-bQA)t@SMovvI{)kj4lPyr=-%r&LfsVyqqslmQWg1)>(e)d#JV5tR&a36sBESH`4(yOrwOI$R12($`e7jzB^bC z@E_}TNz!~ExQep=ObSXlT4q$Lv`&RV3_leZQX(LV)q0OMA@eHwp$F`VVzxDh;bw0B z33E^myi)%4b!@8TYtuI^qb*x=deP2YLjsgjK;U)jT_W0cLhJ#nXe=J$&451j0ZoPhat=lZbDH7^K4TDs5lmbVl@oN{ zfaq~fsd%E}H`o?16arbS2ohM5Pz+A`-5UmnF;%jJZt11$j-d7##yIxZ`R1sN0zzey zCYN0?(%q=UF@L`ANEdd=(pr=>` z)M5E3N#F@1XKbxer0w40Ma1GVB76pZbo;RB&cBYe`1ti;fQ0Nx{ZSw)___b@^>qYG z5GYDA8%7o_qY?rp2Jsp~tE<2+aL74}gRs$7P&7 zG){F8eP(bL)xn&9=q(*gFNyWP4osy6eq@aV`uy&R8wN50IrAUovIoI0WbZIl_RE*P zkcYgH5R5J_+6h&m6*4UNrx?4whQqtv$^9JV!ESXP@{cw`Fu>#4@g}PRQqf!gMPZfx zT~WHLBlvY0c2nmBNjd~$tJr7l&KmKEcbKqhwOm`C33C_ z2J*P4v?NrE%ZVdM^r?1mexX!uB)y*YlVmMrf;awX420%IGD)DR@VB|@LGr>-V97TN%XwBJ13si`boIKq1LE`@?or(uiL$}^7&b0DJvVo4tUHs}Yg3x;5 z)g{;g1e1yYw6;CL!72!-^!N5X{6u!8S^l|Ogn@sDNrvY%`E4};xb`bk*{MmK+Q=|J za9GCW9SlLLn5l$I1xecA#GQ2lJA8#Iw@SPRLnbt+5^(l+c&uwFngmM+Hz0;NEV|RsSd*smtGp^an7Oz3{^{^#Z_;(0q^^`h?!{n+QAs@DQ&}Ytw(me* zyoQT^UC?3;$g98aVY72t$^>(^`|pJiVYOEE&7-XTQxuAP4`WHnhd8&b&?Zqmi5$E$ zi9*hZXuTvNee2Aod{baTB8edJCgi~#%mh@;KJbUpJ+LP|=uBB zOedz#G#(}VHcmAKGbHo9%Vc0)*={=J)YRjNjV_>(I~WreR9ypb1-~C)WN+g3&Kg=?0IghJ z|1A#OGhzmr%N9@rtNgcTa9^@??G=59eeQjD7N*CD{v*zb2g_gFI)-?Ce(8Q=$!n17 zZJ%1w%u+@mU=>T!&eh0W|2Z+EW8ZD+ z0ymJI@t*uQQ?a2q^@Pm3V}0zK$uegIlCC!ANQwd1!kU7DCj0@2AsK23x8Ap=)+%L7 zQIV|7=2@A9JUHM$<;y^e-_Npk&zMwUtz#|8|b~OwxYVKtI19XOK6mAmzo&rfU z4@At$txl9hljhj5C036*C91D`4Us)n*Oo^tlGVaCtGx`=k-2C4(&j0cL0pf>u_T2kQN|hUr zL#rA*m_z8>cg#rxe;Y;oa2et2HEVsCbx(?^d7?r87Qoth^qELF?3CpmUv`|4f;%f* zN5hukAFW2Z{UfcK>0ME9QJdd?sH_+JFI|5dOM+P3E)%^C7Hae`$NVQgawjmDhP~zR zpcmI+X9{D+8hei*ia~~{Tig>*j{y~*6n4xbSiXM}J^@A{Z6@W#FYs)l`*p>2=}Obb z0lyxVraM#1{L24=pukEb6dk|6P=Wcce_N2#qrH*Z5p$JUDq(fx_y_VdXygLi~AlxlZe&b5qDmv_C&^Qz%@gn{F5+$0P|bD>OTI5X{M-M<46bGx! zor)_BG2Gl)Q8Ok`Kg@L=b9x&Jg(iM-y zy_0`X2mF(a4`y9Ip3Wp0K#JI_Tr5mGN@S=3C0m`#CT7+47TNXn!=)D*h16?DNCv6f zMuEPy;Zk05L~!`$*S5|?zVXPSNodsnBFcXF%|3toHR!gS+l4VdSMvq*<}m%s^#J=< zMlCd0x|OhY?r%$-x-t5Mau`kmoH}h@QNkD;n#}tJDj8d7M#t-lk0Q&6YJD15Xn1Wa zr**X3Zk1$SlW@G)F)LiGtz^7xerU zA-Ff(xB5mpkLHP8H6I6mOix_iL zzs3m46z2|aaHTETi%y&oD_$dudJil;Z-N*%PK3PqM)wGL=sh7pF=AVc^2wxQ$^1;( z`ezE~{oTEw&*Sx#T+-oY`b)MK(%oB$`}4!lf+v8vq1P_>sb)~J4F~m~i4|k4w$4Vo zAV$sR(j}7s(eRF)qKq!E(Z-Kn5=y0yd>;EI|Mr+Urqef}rI>j5o+#&e%^COpP~7|; zpF2K2Y`Jj;b}f-mz5h>R)A_sk#@kh_TgaooQs+8H_}aR?8m)s``Htz{Vz13 zz8qGx7{%V_pe(y%=b*#ttT6_S(v6;*{eh{z~bFz=z#k% zLvhaU;q{rXV-$ZP`0x93aQ$stmB2AwRZJ(2^7!s=s3Vq_omMoB5XR$|{_Ty{eA_Hs z1=^RrB?!;M%1yBVI|?fi_|uc+i>Ee=HMKy0NM^@G)jb8Mq%gPY$u{WP{b`HYhg&y0 zUORLu&UociGeGo>p!Y<{jVydQ9agg4D;;G@6+?!9e5B*eHkG9y_e1AKoAR9ZXKvYc zFP{lvwzX^6<5WHQrs})4b{|2FUNV63JYZdZ7~3mDU##6L`x8Z`xgz5ULsx|2ukr$E z$2>9hj1XqHbKN2lM?={WAp5bjs>>_WOVCBd?Vt5q7r;l16d<&EB7bwp)|c*n&qME+ z@Ys;Q)pNlB5dG3ko=BO2mFa6+*r(qIqRws*kDl6m*4!E$+vUY^HE*!c3yV>Bw$?_k zCnoUr|5yxdgZIXwzjQy^@tVvGty%r}5|ZhD|Fjxdv5=xDtE&fazB;D@=hwtMGD39B zlHyqaCD!>MI5u6OVXfDm-xfA}IE#~Sn2VoiHP;zWi>m97xH)#groLb2 z!AV3LPJu`y9aO=)?TqdXDHqPK5#Bg+b><<%Y`Koenax>H}m-n1gzvxlvAj4)k!lXfpz{WZj?LJX{G~B@J@@M(;g0gR$ngHSIYt zRl_S;<3<&_QR9flQk*GP6@_Z>(OOr(i80>AihfOUeGe#-ICsM4|3g(>PT>LDThDa= zxm^j%)t`CxV|!X=?5KL!F;~Ye8Qlry6zGmJyfWn**Rw4w`36{VxLLc`z3WU>5wZYK z^Wqy>-gc$mT^|>0l$kh68U*Z=)-J)kHcqzwMNmYQI;YB9cMopOS-=*@r+$dMn4y0~ z(4bHoI;&v?d!LnrxPx?i*G=WN;@3$LjKW93^TA;2QbY;v$y&&f8A$a0AaF);q_(laOhmkd@vi| z&OcY0<6RhG!UXUJbfr>EjELP-v8?3-r(AO6es9DxewxRT%d|y3m!3U#j(CG?9>TKa z|MR=fQUcj`&KZN{U?f%_In4!X+X~&wyo0GFN77F9)g9ys@1<0at{CGf0EA+3na=IJ z9BoAWtDE25-%YCz@B+&W`Ve3hyV9ODIVjX5qhxnSn{V2*Gp=7Vx$!fvXCFQMdS3V?}e(DKA>QL ztsg6E!UM*@WZ@^BA*C5mUe*%L{B3K2ozR4qx2oi8YAYX#!sh-=8GmQJAmsYe0QAv5f1pLgpj%80pN7~){)X>cjg0H+$pGtgbTiSPGPZ$ zX4~7fo5V6o=87gsYPOUs9db6Z=C09d8#-zJQtK*=W+%(W-uLaN-AZl{#I4-(2dwIkH`aitqR`1w=A+llD66i~?q zrCHep?;9%RM56(LMJ?yavf@-(o3CO1qbRQzn2h-fi!Fwo^5`a6l5U@2XpdPacU_=B zQ3*opV}}$2)7WU-#dJh@{GDpAA=p-yLJ~l!z07eQoUk9vd|r){)Y!4OH6dA|Y*Y-6 zsntcM8M)}

_lp1W_+#N5hfKn76n^8Mg#XVR^z0WWboE3=bi`;otT!j?B1-D?|tb zA*|3UWf8TQx}ZcOJnylA{h()rEW-xLexF361E=@EJM15xlT;^@?bUzk-`r5SL!Ko& zlb#EVH!u*N3sCMZ%-^>lymKF4ATgEmp_9*~iZa*Y;qlUm2Wo_u?zGDi;O4ry6x zzR8GcUk4KYJ&Sr8{4jjoPC&mp-Chc=Xv1Po(XyS=^fjp26G&Hn`uLA_U*&Yr_Q3)V z(7wX$q<`eU>e@V>dvr$P=-ZAcktNEh9Ca4)-PQJ93sI%RL$w;2Ar?|dPz{Y`NzQ3b9flm@of_Q z{mJ3B3o|wCGS&SXd@2GnHv=a-2^%weYVIu>?f*7H%Pak#M(F=T`-rOyPYW=y{(s`3 zYdR}cyT2WL&a1g5A?U7sAp$HPji8H;C1jSwd?h8)DEx{c)M{klwL26HJk}$XJ#)F%okxzZ6HoBJV3pfY$9`Y zysT~Qo1DzJTN%|mXzqG_+HDpb3;n1Pk^H7E;QP9b^IZCK$LQ_hc2chn)D}Gkd|t|# z?~c2CUY-Q?d>>W)suDj^KH`L4(hh!w*bH!UnmaB7vTOI&i8}{Eth(4!#kE4~ z?!4~)xYeDE)eh~pV~W>9?&nLmeqDxAJg~Xz7;3j}$aWz)NGT-Y}aKq0rz&w+x|pkUG+o&$>%6I#KTM4L3RJh&#!Tr#&Ktny!sQlK#DD z^Zevlvtm;7*m)~vMk-IQz@jf>65)%4k;qR$sMp*#FL-G z6`V6P3KKTUzRLNAy2L1YZP4=h%M>Fwz|#x>?91$A<$7P>A??U{Ac)cS1y29|Bv5Ga z=_PNujRCz)zFk^nqzRKwIINNo8(sV3HSuKlW``NuhysCEPs&Iw$h?I`K40IJNngrr zR{eP9XEVN(;W#gD`6o&zR)(byx2}kYJcS-$`XX8?TyT%RvJ9L~Of~uTRE0JthEw7I z^86BXdcMSzdLr`&K7CCB#GTU1{9Q> za*caC1?-M0N<8LYLp5$T!?9vY-ocV+``5-mdEp=l<4E4fzq=X6Ze}>KCC+9 zGYeV{Y7#$mqnqvM^BE?bIHsOnqvdCRSzst;;Ty-7(F>iPGu$dXb>IiM#;^LA;rYE< z^@$|DYP~Dr+>r)ayxz_015ceY-BlhYpJh7EP%~sYV0l$aEjl_0n;3tY2MCCEt--M<$Uz%< z?!@SYIW{0sRkk?|ko+hIvRS#Y_|{E~dKaPbPD1#shUzW4*w5-E(ta-A2WM+d38*YJ zA6N{tS^0BeL;lX`%1<_~!!0hqlB@rCmH7I7&yS?v4erEBQ2aW3_d1D7$14qA>=TR& z)1(2H^36}xJdts{<&SYby#Gef7u;fh66QglbLto}2b+fjUx$lYHR(kC1cwi(eAC5j zez`0Jw=xU*hzUC2z5PNAD!jFcAk982TBqSza{rd5XQ^8BS;x_JTjpgR(6`W8d%BZQ zIa=GVuv(+Q1R4`8q(U}tbG|677p|qpI`fOjwXVgxzh2; zD!fxToPJWb4|7>T+09~9C;GrFzTs^AnbqXD;`n-KajLBlHZ(+xh@}gZhqBaEwI8~b zDe^CETD9EpFPJ1v@chNr@{d6W9}%TRpe~&+I-S=DaNmK?E4HCBP-zxq8qF&vvXWuW zMDV#!+`AUc{mm%}(WZM0OD>W}aDK?C%;uKl)Jtmng(Y_=sA}# zRC+f*J*-#T1{agSk)q!fese6F+G)oxVp-Eoe>>Gzi(iiQoVx2fOn@EWAyb0L89xQPT^--wbc5CF8}=^K#Ue8wxd6$ zB5)L+;wb1ZSk-Kkh{^8gBD`*s&%r;bhm#9f1UR}l^jgKR2n_ormY-Uc?eJj8Lsw&> z*A+?A?01X4gG0D^jak_iWf|}EBB;@BD4hr&>}iJb z2f531A>-Gb9(vx9J2DnOf?N>r8m~?Rn z7t^Rzl+~ULnZonTToR0>a}p9KdPBb~(noh}p*LcRL>cg(TOLKFYt!hOfx2}; z6UmUrY)@o@S9de+`Rl_DL$}OKo0jg{hVKKJTpoI7&d2d06>4_o_!iM~^eb`O_%)n& zqZ+GXdy*G{uR`>h6zEOak0`J?Sogk)*wP;tYC{lFJXi}^(oMxS$_C?&+)6rt<5$$* ziqDd?AF(oOZEvgNMXS1HuAPQb{WBe7eB9PuCwzc)mlZd{A0(<5v%ea)Tgm4TLN(e* ze}|_Ccnz|A=KkjjYd02uEWPd^%Az7Ya*CWEN6Qgh>RG%>MTSx$7!FmCIKx4;{ELq} z1T=(QneEafUX0rz^!QYrgXC1eoh7xkfkY=adLlUbYu}G(dPG_-x8mn$g0{8MgWSZ~ z$;?uo{1%li@WQARMJt|0R{|Vkay?s@1V0Z4$lW(JfaV1=;F_Vtcs@JCeL;4jXAt8r zpt=Q1o Nbgg5nSufuJ&M&A*5M+pK!blm3U_N~^AaIe_ihVT*8sfGv*o36hIh7h z-AJJH5UK4?Oz$=y*W!XGO#5;eUO{V8Hb!!@Ui-#Nn^UC5y+`@kdrXIma9g-q_7z%% zp?ESk2N8A3Nve9Mb0NjkINyKS*mUVB0x-M6R6A%l2g&4rvogJ>G~wfZP4>Esa8Hjk zr|Sfnx&KbqS6n3gu?yJng?0;s=hhbW8?W_2arce0!DUJmufBp~rzI^WMrCKFso4@l zhS-u}PD@}B2vmQTM8PecxMs^7hY?OG_h^F`;@mSW+Yo=1k{e>Mw>hgUL5>R~xEd%o zVd0=9oC^zdaco^6Q9jKyx!IXj(~lUK6q+_?oGGQ|>a&@u0+w+0vuy=~xSC`yb?Z_4 zFz;iFjMSMDl(bTq+Lifqmau*>~9uNy`AGU`)ZItyMik0Q}d zTsig3X9<=gKm-DP@Qr8DH4)()2*YVKANyW+r;N6PX2mqkrV=>m#>VA1B;RV&?P{p~ z+duIcYT}4N^@i;-*>muOYcsC-+n5S_(RzASuEcZfX4BCTu>^)NltxrXWg}@{`Zk{dV;QI(FC4s4bb<4vfq&cKt3GS) zORiOpT-)8HNH9-;i3?hcvIV)c7Zj>lyljm34U^&i28Nqm>ZImEZ&7KF%P~GB`pr@D z7r6#FH&sqS;ZG-lUSw_}@78%|YUNi&P&;wQOi87t_z4rFh|)y2E=aw3p23I~1Hq%t zoQNnui!0J;&5!T5m7WCLHT8HBGb6F+RphYHJocS1uP`Q3@H=SD!PkvCma1oI=x~g< zpLtfH2h|d4^5M>&o&Bvc%sryr_MR|M9JW1{Q5&#)wfg!krfiar&*=u3LI1+?U0;cs0Qc9GOO7 z&AwbU9S_N&`yb;DkJ$d_zlxUwI|=4_3GypjS?A{ZJ8{io6q%qV7B}10!{8d*5dYcO z-$l+5_)kNm^S1f?tw;)ZH4$7nT^8Lac%T;e?a}^U$23~IUSSjul^qd@Sf#x%F#@J; zq{?_m;?1jZYXa}{6MjiT@1SYkzX{Pm-xa&naZ>x`h`pd3nfbNCbiy$He)2sG>9FmG zb>t#UcYQA(NcJ2zX*?T$>7Ao!n;Fc8;{G_X1a4D`Qk5@(LS`(YC@m5Rxe23>x}o^e zwy?Xeth(=}yEDm(0`yfZ%BZa~6pCDZ{01l$VvYxM)Zb`nwu)WfdT`{+A2b(=hZSPMw}%MpZPV-7@| zQVD;sc^g|(l^;)4WU!KYi0qX~IQbsgp&suKRemJTz}S<`(Ie76U*9p1UCsaju@`sT zj{Wp8c>{_`I|{et;+Zqv%Os1FUNzxN4B07cjz=$rwyMl^F3!l!$N#<^X|&_|B7X75 zyBMJnr!OWCF87YjlrDf#G`BbLjdxS%zV|0FlnICE3Y|fjnt3e(-#?unb~8z$vxOJ~ z1Y0TB6LM^+aLJ00j$zH32W%MY0+96MEA>uQXkRnf_Jjn-3I7#95 zJFq4&sIR)&hk`t(Z%L8fzeN($OgCa1W*|mG&J7Sdg?R~$E~x^d)7cF|F@TVF?~ha& zq`=YE1IjVd1*^it6kl&MzgPl3tr*VK+Pi07#lXd_upWilA8RJ+W27J>;cZb$!mff* z6oI{m$j>bEHbxY(79idR%d!O@^DJ$jieL-&$Su$o51V`t3TH{pR#ruYGVogARRX0Y zCo3CL9?1=Mb_gK#4f-Gvn|Jv7#2%=%5TjnIoHf)sX9C+#aD^@75-ssN z8y?F;RJ!7~ZY}|(S>>4_$nZnUnL3PB9l0J%@HuvM8$d^=Qc&?N5z|#ME*uX16{*@o zux0v#FR1@$46g5|J0w0wNVoIZT)3Fx-93FgcAe(fWLAJ*m;$x$wCT{TVo}w&gf{sNX8}(9oJ~uq&=8` z4(G#hqq)Cqje61NI_TbPRfAt~<&7c3E12htUF2{#G(A!rNq^zdG@(+uq8ED7b?WHd zrRWq4Nd;Bgb4f|7rTdV5I94;RLD#cJxyQ7m<#Rto;wmNrW!@G{-InRtyS+_ywhU^E z?H8Nr{H3V-L$Kv4n`63_;T(QK0(bR3O8%qpx^{J!O>gH$$;|-SX-F$yXXlsnkyPe{_G5^%>X}Po9+UK;o03Mk8VCJd!~l^nY!;Ix_Q4W`%zuD2+Cnw z6Ia?@?KhVlnZ&HH1x3VsG0@_yXJdaJg z=ZO!nZxM2Ill9y%iPH*njfA@zwwM!at~V&wuB$wxDqv?|1V3rC6p;Z|E&u8mHsJTr z0t@i3uoENRm@AN;lV3SAx{%kd!J{%`@EJiRlk%3C=03E$C z0PY02506TD^i>cGe|0dfa#!9lG4^GpMdaCd39*oAjq*qn<%8ejlzXl0;rjObLy_Tm z4{8>PUtY0@qpQsDdf5X2CKJGVKQ*WWGam;HGD*tKVU#e6MFXq}q!sFVlIF8HsF-6V2(v*-sBC5G4qK zh&B~gOJcaHL^4SeUG;8eND@ZzzE9p3N#y+GoNsgf-ahP4uJpsAT;#7#N*@@Q(>kzF z9%>`S84=HRegsmmHYz@$BH3;2ScLkTsqt>2SQrdI0KJg-1($CnNM zax%0=!cGaxW?mY>O|)`v0iS49w_m8->x70~&4iy}zB(V5J|Oj|2CFVN?N8{sjl+U|qw4gxmTrO8EtlhJM_G62!%IMuo7>np z1_(v$12_#X4u8T#EN>9cGLqRhG*}h$84d~e(5zxZ*2H9+7zELG;$qzn!PfR<#r*WU z5qbO86R$MUb&=C#e0=9{W|G0{ftp`D4FIF?aXwL9O87?m_K8xi19Sbd$M}_a!B9fP z_fuqU=vR7Q34)~j_SXREJoP9njEDLp1%763pl}pgX-HM~D9Q4&wG`HY4~GhJa_*8} zmTy#-?S-{fo}hEJ&|^UC;rAC}9y#}9pdL^o5zWx#pN-(Ikn2r zCMd`AFc}xrEXd9$z;=^`3LmPq?vVbLq?5?n!8c&Z@$&<=JK>nyUs{;ZS)bMjC%K3# zAm0g(fk(F6$h?>@Ij=iIyMUCQJ@sy43MO2?R#TeHrQy3XBZbi?Z%Bj!gr7bk3d;BA zF?N6M?!Z@|4si3n$9QYoE?=CRkyxSW_!TF*9ztKF6{i-bw&CjR@R360qkm@(L!F8A;#GLwP_8BE;GRcI4AVi{n`@Ea3>{Ch*YwtV52D%cM-ecB8`XFLRlfgJNCxX9GZQNdEZ!>R|$jX{Fb8112NvveEy3d->MUB=OO@%X8)@s zs7TP_&DApsyDTmwnI@=!1%TyqB@>%P^OJ8J3ysOy2m9Zgg>rlhsxGu$i}FPA%7%+7 zN`GNR%PgmMTN0GZy7r_egs?pEKcl;Pu3*t87v^IS5=OdqV>}f$RUXI*57u2`ab{hdOrP=61za8sR@@?evT+Y z$)EE7sy2FE4SdU&Qd zma|S~)BD&&fS(eOstIH?G13zK9w{^YHeJoojl#h{P&Ax&yz}CHVg>zr@XB}(TVb{i zKa@GNT6M=V7xMuGm}wFnE?LroVx!MaL_YQH-+i^b`5#n!Z>wZob?!9g@B9|&-R5zM z?%%!n7MvO_!B)OU&U1H!8f$qmyP}gdlQ1Y^S&Ce8ePBrNqlaM{vdsiL{{@IO^Y2k} zd8NAq#AX+tkvgMnsr*?OEvJU0)7z7?X}YdL>g3f=b;Z8D7I8ssMF+r&flld}Ci@m# ziCvR~_4+8QAVt13gWSCFoD^?Q9fe|*g?w{W)MCeYf0ZZ+l-v6mZ5Il83Zs`)V&f%? zMtW>Eu+T)B0l#IGE#g?Fc?w-p{9^yLWimtEdYNIKDX+LQ`3MxB0i*QQ^% zPF9065eI)vx`~KKQq$%|k7|3_2@EL6E1muVo(G8?V+Zu$e-yze**21&ShM;*pIl!5 zmNlai4|8e)OJ#Lr?#x%kR6Bqun_Z)pCgnk`-s0o$nBYX4;$smp1SQ{JOC`qs zOcyq#5CZEgcQwW<*d?7_eG@ioPfzCp`^U_iA9k#A$g4B06l%N)$8rihJraXsb@p8E znq{3fjH{2_zv6-7<0i=={|oA@P2Z9eWt&b z9b25DejDM6cp6e$q)VPs9lLlorK7jHZ$!Rv)?TI}pGg140+IEf?N_QaJYLa@3b=BA z+1;{8y}vV@L0?JYbvNs*D%M^TylH~#)DUS)_{>O-2ea7xi2U%EHJr5aK&=e*|?5uU&wu7Q3eP-v1OWwX&+uko##< zbm>R6R`TXM9$$LUKC*9ZU7Z3%1-Xb7SJYq)k$8M?@FoCC_w za2>c-FlS!Ox^jq&128Gfna&lxk^Z&bR`>lsFATNyA027iadBy{4cpx@b)%5zv|OWc zpo~0pqi}RL`+s*|nW(ulGpVglvj2Bb&o&r5=mH+h?TvKs-#r%E?C;jd!PyR0cV}j( z@lMCmMUF}a?%kqswn6PPt?mBq#b@yB=Knog6g+$J;Wtc1Wx7m7s#}Vr^-$m~mOF2A zjI%gFm$$!3gT!D{x;AcCRPE2lc|qtTFk z`sui+Guu0}7rcL_adVN>RRH)HwO2Wcg;W<541XxNRTIU;vt` z=;)g=B&stNP1%rs$i}39*;JQN{q0Sf!i?ZzZG&1kKZ?WqsIfq~xk&*R6iZ1M7{0h6 z&{Jnpq?S)jswbd2F&HB7+3ea~C(W1cRo@#M;tDq7uhy6HA_dTjkurKvOPwAz2x}5f zmG`A=NM$8v-oXc^CDlaka*Dr(8-O<5@4la$nq(ftsq^?l)xPTJZz8+F;az0<6AHyZ zF^0Xm)8@6oP3KyWU+D3ZRt95Thg|pY;K;Mb)%V+y%;W!ljDN1Im%L@(;sm_WrO0zC7#0&B!hhydK5=J`<*-BZcsIszu!^R z*hA}$eTOZ)8c9zdkG{rmW%D~$RR#R>GH=#KeODRWEtzt`f#=+RGu((Vj*}WIe^r}+ z=k}4eu$9W-1Qyhck4drAO|;JzUYz`nvsNWHy}nU}zi(V`jS{5MNkmp!6T!eG{FTu! zSgYRnkMZkmCO#yc7CG>1i24^9n>X5B-A`Aw_NdY9 z*i_fJl8FV;XsIL63Vv0Z)k?& zz^R5(wS|;p4fHnlI7Bpx76r^P6E{%}ZE%{-u2jG<&d(Ap-Q-uG<7h}&RV=bdS4zRZ zHi@ybAHJH>YdxQcYw66^h$}YE!jnOv8ZBjnclO_mT&3#M&6KumtyBgc1l_@a(;Z_| zkY&8W8`9_Zc-%9>?6~A$0d;#?Ah^jz)N9 z=`UST$(GeimnX%${>EreI=n|4X40@4VYA&i zWEf9!$M+*ZCl%WP&xG3@^e}{&9+do1HVy`iIIqtI3lprwzr<-Hv-&iePOgPB*v{Y$ zlbZo1HG$mzP)D?p1tFxRIHD2ZlV`fBTn!I}F3^Rof1Nml`+4_zxq_6jD;W!FNO0gi zPLcO@_R@9QK5=&e&2nZ94(id3=%e$(9P|O)!}(LBcRK^aSe=z;yHBdW(D6g^id`=r zOD{X|?b|z)%?jq(6nG{`Q+~c;9b4pL1p~b5K|cLJbvg1MmNRXN;d68&upLDH8(tsm zrY+NrUuntWPoe)7%N2g+0*faIp4bm+IR`i}n*E@hl;NZD^RF6ebk|0TJ)^wblT=ZP@xQ9N7VXkV1_>}W7>iZ`Y$HnAB548 z}hY1WC+!-XeyF+jY4uiY9 z2ZsG+oh`Gqrx?39r0!@p{tPoxp?`XpKJpTaUB`=u{za6xD8ZL!lW9O&CaBaw?N$(()#a{ zbl=L6Wl*7ut|Q&IUfC+g9~-L_HP4=Cjw<`M8J~+Nn!!-Gf|$Vy^a_hf!0ViZMWd0u z;t4v-J)BPS&GjBg2OK(oy!davRLr66K-pAI%0u)#&5%h3uKw71ZW;9xXo-mQUIE=L z<$z`mNZ~nD%!_r#p2nS1cx%;0-gD@6zK@`sqSv7B(;>C{X2Sig19(<$7yn#+@@o#? zdY^s4sfwc}pF5|UIqT1^S?0cY<~Y6zwoL7NfA@U3JEU^r=NlU&K)#jk^4D_2zRb_^ ze%%?%@@C5P(r_$)bXGg>9m5o^xcw0hqH<6Di<@AMHJ;9=&3xKb#SSHnqQRESp=uoW zoioCPN=BJwz&M=_-aOTn6Dhs_R#2BY?GEOg_MAL=H2B}qRkX-f7$K}CD` z25k4y6qOx$GJKY&J78#@V%J^sp1koRmV4}+liw+>WTIPFQz`!1KP;#O8BsB@`xsp~ z-MZYJnVKglQmcY3twplLXD6UxP&?hh!`|tqwLPryw3U)_04SNQ4{@)ndFN}R78qBW z2FmKU?GDt)yhS!QIcK!5M@I;Kue+x4#b{ZB`9WuLJvkLq^Y~{CrZT#NRJ3gR?89Qs z=gsTW%Z}^Tn`d4yA7VSjwg9<>JwSO%GK?%inhQyoM@?y*jO! zMoZ?|Q3kfjBh~1A1Al9AOyBqJ1$@0aZWJeU47@&n(fuB+pw;OpGD9# zI63!J1_eJ6dxE}bci5&$1~bQDLwQc_w8^Z{>iFh8D?3TfBX;jf^l`A5e^)H zF}c_k5c|RI*jX6y#NKAYL3bRHeONJkTxFg*+0MDoDDvE=D?RRNM`%0&-UfU0pxy~F z$ryklFWQ)f>UU!;#u)BAWKNE${X2~y`eNr6Z`x20x|TO$2y{7sWFZ&>U=ZtS4)$(c zGYL}auYh!MSWxm73}@VKgP6MElZzLDpE1&p-fr>nqQD0Q(-gxft~no(#v*zE0^fyXUOM zeZjQ5>S0xnu9u(&+Ld7iV0`8+k_CE!HGcD}`a$#G=r<_emP^x>B^MS`9jD-MHvQ1p zT#FfW)o>>;vbM;k(qXy=UOO1y?@qORyna!4;H|T7FFCmmTtIP#-AYfcC3dr^r2c*-K`F>S#N2JJ!R)ZrARz zYVPF&U>v+8fuT{?N1#RS9>Z;3(t7+Q!~GYFouTXVLh&VfG0#|+RfH~8Y)12g_7FZD zeUmVh^5_#2FJmRqP1@6c+lo z^##CeY>sX0VsTZwo$yqD1>-YS)jI+V3MVAZ%ojNdn@fP}Kg=l?`~RS)>^wv{6mn9MhFodT{(f?dBbh89!Yh)-R_=l#INcqgE7_ z+6!zt%BYq1OI=N=-aDIG`h+m2zeZBNKsK^qy}wVS+wB5cb$4eP{CaiIww#z_LiBdo zZSr=LHN5$AAsO;=_O!WKf=l(*=JQts`~p6#d)xZl?fbZ)a(6i{0#gkCp^Q}|TZu5? zO`K=7m?kX#boB=5!DEYB-1pK%Wcee#CxZC@Fw6ovs>m-CC zML;IKiyk_+Iq15hE!>KxDAHpy9?c!43O zYLSg`AGV#39joj)qU|qy&R{4FG9#P!OR$btlks{pO+^_PqH?aPB>*oo{Mj<>SSm-zEl_#Ts zhjudTYR|g^_uzB3*5=oF>3EB$zy3n~fUs0E!O?C%vGF|tAzS%cHLBwT-oB0qewFXW zl7BzHqg_*owZA58lv>8vn`KOH3&%iw^@>aj*l3{pX<{gTWCZa?fsth`I}S@mG$Vk1q*})CtccB1u?&> zF^YUq0tM8>Z|jvJ3XFIQR;`eZBASvUx9=E`*sGish|~!7UP|e&RlIH|bnTZ>}%Vv4J&W)g=o0%lzQMhksW-;kWj$elK4K zjJq1mkRDvXCw^s2(28WP+RBlW($<106q4;qeQxGmxoD&mJ(6RyW3&`<_ENZ~_nhR5=fwa;`l&Hrw8T`FLR>R1 z-Dt24)Dkxo!v`ncR(G|eoIh}_q|$TO$?12I=);1UDvyMHDE+43HNSW754y@@p7C8I zx)JRJrB3?Y)dtGs3;{rSh>|2h=MBP=J)>d(4QkM1M?Z6u($PP4h|1~6_ZmTI4BEaP z0Vo#tKZQHsqDA~?`+jGivT$Z|P6wl(|8AQX75)w;9AB=<>PB_5qeB^IT)!{7x~q-_ z>ysR4U&u+S|0lhM*&u4s;_*AhM0{-v)aR8IV1H`=_6X8vAZlU}aNNx4UoTc-6-J~x zI#_P#^A{4SlenVYYf{lHA06N`r&Rm0{iZuFb1tthTHO*M?ZmDI*tllGE{yzN_iBcy zjCnu5AVE#*WpMw~VXUd6aqMX*Rxh{-(#OxM^z5x{4?($6!|V#V@gq+w%B~U%s|~}mSjOWeIEv5L@5YlnpvnPgsX&dT&uCGe&$OWo_V$!tW#_MU zHO;D}HYFG7<$U_tj?x7JiuYew<5D*BKI%7-^pqhU3y;63C-O?)d052f@qp(bzW%eN zDY+bpke#maGo-WTGFR?b0O;|h@HAavuCh7d?f|91iOAdKkaIJ$1YP2*~wE{9Vh_8zY3`us!=7B7YcWrn1E$wp+PNHIT{Z>*KG#F)u1C9G3hy zRA&fcG*AAZ)a;lmC9U%gr^e+M=(~p`&noB9sj5s#C%&60%SnI}JW2ohx`vaQA{S^p z(N4D%fF3soccc%oN#)uZ&F`A2=9=k0qQpadbJZfAu(ZBlLV`Mep~E$NEs}BMX32A$ z;6he%ACa76t+szbLtyWZBsLBfSgWqluD-8bB-Z^qnQp90S!7vyQ=Sw*L$K=gGK$qo+{^#bN?YYyD9FLr7GeF_3RmRv(n^H7MsPgn0sX&Y+N(tM?k7sl0K9m1fjcIsJ2~X%9GZ1@dK32VXoM#IrXbG9>NlbF>~nL-+UrE7+VXjLW8Tyu!y!|% zZ73?b>@xT30XO#U3NEs;kBG})+6?s zN3<-$mN<~*yKw4DVW-Dy4zz+Mj!3GR zC#m)tJ@BwnN3*8!cM@tx1C}My9(C1U@3T;BywN{Uy`PuK-qC^(K-t97h%3eTn$Dj= zkG}hi-G}0HT@+6B7IZZ&v?|bfnlMw3{UnUbFi*BNB9ZV+0d2Ztz3Y!G*S?I{j>;JY zF2S(Nv+S=jrGij%D#@vLQQL6N^63enCAvphvkpht-&_50(jP{!(C}wVC;^VcMqxJE+J=+lTKf zp_~x0a)o7rWTv~~s#oSk%5GA!(I+%bH7YTk%qvUWL>@|x4HUtdkrhE2R;%r^#=mu< z?sca|IlD;Y|NgD#r^*)jtA>C6;YKKAs~*#J!rPIH;CG2*GLnb(?Sjd@x2Hc#esZ!2 z34Ns2G%Y_2nGDg#gp#4mF>NpmnHKET$bt}RNY-n9*n6lXARw*ydw_xmv)FVfDKc$i zlq}TB+mI?O{v)qdFdn=k`b9vUNq^I+MBa1pk;l~jumk3ZQ!}45YQ)okbzS!n_ygW~ zL)PjiRJ2Q7_=gxQ@eDm@XEb$4SZfDy)a(rSQEijmv1}tlk^tZg6Z#=bA{+b%l3+2? z_$@rWH0zYq-Yt+KO=hANM@uLQZG@wY$5%D;?e<(~e0jPi^{(t|*Qe8jgV{fKBdK-T zb2gWF%Oe;v0?t4jGlE|XigB8_fbCXn32yQ=Py~|zB8#ZaT)YGYsqOatFx*0#q1i^q zOo&F$-p>FyMMDthmwfM3jCP89)6vV`lK7WXOdL)U|~wYUN`cH zpno6XctPShAMB#hUUW0d6k!UBk7D57u~)ipa~k@&(BFLclH~e@=lg|U>%t|r1Zxk; zU%u_mM`2SExX*3`?gEIycOuXa3=wPObo71szW$tsFb)B9b|GRuG7Q5U z`!4mDz@qy8UdSu84XjlAbW&C}u-{&9CVrd5v$dq7{;$!h`P$OBsL&?yQYY9&T1sTmbTpNlq0bc?8+)^iD zqlgIQaNKX(9iD)+SD325Q8gal{y^=f=_eFTf17HDgtj*|aA*>`84mR3QG_Z{qZ)B> zZ_+=TLpL9?gZV~f4yqcCrfR8j*Jm{fq#zSAg@4f&VJT)94*xfc1QsZRg+fhvydGk{ zR0ZYt#4E4^;UcBI(4@?KRgSyC4FPb#&hCYCsBF8BqM2qlXUV8S|NXP*|3J`J3X(5_ zm0*p-SG2w^_~#tmETv+SGm63=W9mUY@!H*ch!Co~ZMp?eg85Qcs?h_$2WKs|SfW zz9gDV9k8AB$RTjCD`TdlMvx{LIxHV&bwv~rKYkS?k7hQK0&~XreRkWF)A+SWRpjz3 zBYG^7Z1E!n+X-sS5z#B$r;4l(DAPPH>pGFbKBio)tu*UEuvPhp_|b%jDOeufjj9c_T z-$`EZpA{-L_J4_!wbS@~eyP&2V)Ch)h(&h?{(-}qUG*OS24rND{itLi2WT=E*ikHP z*9b%sUp%olisu|M;HVHmNa}(7V}|dvdvx0DPx5Vp)8Q0pwpS&qsb^(b*umMg<{#n4 zl^^uoM!mU14V4Ei7qg-7_l^aS&MKaxQ}2V z-n0_OgAtCtrUQekFglrX13=NNY|M{kqG^Tq89O#J8xwY48_s1`^D-Fl;ko6gyj*W&i3{WkhjB&O>> zQ0EZ)fOI8Ba1x!})Su|KjfsCdhwJw6oMnX`)Rud4$re}6w`CI#2>+3`J@;sY5((g9X0-@_lsZ#Eb#)Vn=iEQw&0>!` z@b>OC=gtm0@GUVL+LNB;XgIi&*jzG>r?0_0n?fg7dn>>={=7~ciD4n}_fQVksgc|2 zc2z~#Zfy@PAK1P;31ZnFeyjMq5die7SV0L%|Ed=>MKPgO<16q(DFtVYR0 z@gEsAlj^%0KS-l_#V|aXhDHjV4pX9~-BVN2_x7+I$XCq+uJU#Bm=_lssW}b`h^_|H zR^p-STlf18fxk)EdHmsLOa9Cku@-4(5iIzrbN||?CH2#6-=>`mcsJW1#iwp7r#eu8{}S zUfiE_@2}nXn%IXI5R87O48_N(!Xy=z92zV-qaE&GhVeA3EaGV%ALfkm?f^@iWf%-i z!QlvN*B+(km}49mAy0QWNzOTPIJS~6qi0+?I=EJn$eN3PFJMi=Io%|;W)?0if zM&)t>dbBp1pq_(|U%vwGs!Dt>BZsg)j_q`%G@MmN4X7q#614EXRy^E^YT~;xZNyv5YZpFxCTE zz7;1D+y=9Ur3*CtDEu4wRz>~&2 z7T0Xs$ERY43hEomgH8!u<;bZKD=aa*%6BGd%9@RNts)&yrx4wt@s6hg`)STqWl~@I zx;v$mvXNREK56_~6$fGmN5MFlxrk%HB2aI9$^h7r+V>FavD)m2kJRMc0#qkIIMF3t;$Ubl5_Nu;P-2>6HAmi41WO zzZN54cp=^6+d?djsKMz2@gK*Ai>0GjoyE*Xj=x>wVm7{?vXl`Fo;v9H=WG(C>C`wX zRbxXzJB@@h_eGrMC0NA`<)PJ{zpB{YtRe>yH5sm=x3!Yp#V(d!*xW->eCvJCr zjZc*V&j4qz*IZbSDYnlXlK-LAU4O)BUMTy*Lk`t$S|yJu2ZIVaJ(}_xC0p0Mu!&(8 zN(qS)WUN#i3_^PZ>_#Sh+QlP94Q>nQ;jF+kD>exEeJ^`sI*#6R(txsfSe-c!*zO(g z%~W;WO{7Pz?+Kde%}4iWZ86I&)pr}r1fjLIaO6=KfUQ(WI1Um~ZlY;Y32fC!rf4D| z?}NNTzI=1S3rXgN}c+pUY z`qKa65ia$#0s}Z+be!qK(I~v9li;PAORK?&Fb&YumN<2&ZqsZaCU!&hI(vjz$^JZ% z78c$H*;1dX`)|D0BB*PLM#mRuac+Kc8j9E1^6U2+zC+dKh3U992qNY97ZgH6tf5Kv zQ4O%kqtWqYr)WV3s6_cmg1N`C5cG5PY?*{gdQ--@!{o-ug8ISU@vB8^Jc@xi94k2g z{kn)BL1I$!Bdo1`Uctk&9ku4?@nS7BK! zFEw#NX&GhP(De1m= zexy}dHNTfTw@A!4 z;&sY{fGVLT!2Ram77NeZtDBja@>quZL$`KTTcg*uvq4-MZBe2$dw&ks99`k9tzMo4 z+R)CGHt4IT)iDXjAN5EJu#XKRKy|+PF5|y=tS5ZO8cUCjV1 z8QSHV?Zd$N&P+w~j!9!vAW7YykC{kn!)!=`pO|ClB3%^XBEEKY?HNpv6|_!5m_w8eOT^1xLw7cTSf$T@00abD-Eu>Xj}m8 zVLz{(W_>tWccmuTa!S+9nrk4rUqv*PSaahO&I))eE?$js0Kt@Le4GulP+{S3)9Djv z-a3Z?Eu)+)LvC=hSc_b21hHc;6s*!ppsBLea0g%BeD+!(?sQ$qQGa=0{x>W6l=I2}`Z~*uXqa(QRu}7b| z$2J7~h_Iv5?e&80Z<9*8BE0zi#%s3MpZET>>mjl-%=YeU121A7l)m_Ht+QmX6X}iE z$#K|zyMYBmV4Rw=i}z^GZDTQo!uRPra9BVy#SvI`2FAJ4rrnNX!s*Rl3KSmI63|DT z^-=V0!5FN0`MJ|}1vm81X9eY1|BSHtmoP0q?^N!lXgbA~PoWEM&$!;o#i)q5|7V;@ z|Jc!se@sd#mtJF_T3JycfFG{?z_^OLadWK7v!STSU8~O1-$th3^Z|6;-?K_d;qcIm zo1~*C4LBqNuD?|2jnP_mjt=uxdEU7IR$q9UL87~KKgCX+Ru zqAGs@q@Nv-%7UVZ!eI8cjFiV4vVrR(Rk*{3ll()z6so$XSMM`{v3a! zplD7OfdlXt2a{Y7H4&|%QTXy)p1YUcits?=^Sz+Jk}FreZiEwv)t zG!~lVf;=&3CEF@Weg2e*>U8#x`F$@?BQ^}{MHrf5`qRmy8>hl`LUmf-j6T{+?T1YJ zt!B;!nySl%Ta?R_8F++T;iZjaA(Mmc@2sA^>ZpZp=8ftcHDW%r2?bC&|DSrY- zy65|10YR<=&>WgVWWIrr-@u0p?wCZCv38uXr_;wN78L@FPJVF#&hVGr%ocA3D zmFoUZN|<5AK!*(bt&V{LaS{*>vA%PL^CX4y+hGUGi9&@Xq|?C*{>S5DS|mk!@q6*) zF;Aa!_VLi-0%~OERhh8(i8j^f5T~^m-i@UVvh_p$lHtg9{@B0Lo!npl-v0r4^XF~a zdE145nYRG$$H*A2?H@Cgd4tGnnufNE{7F1G-g^b7k4>&uvR>vobiMrYykD(J;R&! z4_eIAM$IG?`N|d1iU6rV<;dtwacPY7>vo;Jr2|q9#L(Q4RMTjO=UtW(<0b;9Fr#YH zymc`&HN4bCw4XVDB22|%(*>mSBqdp9pJ^SRXB_uc7hd|is>S3wDYpu2^eAjFS^s-u z_62?Geha)HH+Iv`t~dTdh#-7A?^DL?Vcj42ib}F3M~yGXIg_@>eJRiRyhIa4`jcgl z!ASsTp1^d}C+A}KFa23`GMN1oh>e&ac9x|7}04=*-B z2uYnsbMx>LtiAB-@EgV6M8R5~|2%UNI`$vVZ=!pLoId#cYPGQvYJipa;@y)E!aMI+ zKO82c^4s`mW0D_IovqxNK>Y_!d_dBc>R_$m3twXRT=+M#1-&aW=y z1ksOf?iFASR>}9S&6NrRo1RR$H_o6o3d!ZAOP1nMRDzkV*mYr$)UX7B=0xRX%%{fu z8+>}D@qI3X?-wOCytQ%&ggC^KDEnZSOP3)@*iEmj+=qe-gMF*;JUyJC?E4r&pcgNU z(l}W|eASn%fTD$}an*v{duUSCr`-Dw(yA4stBR36_oo&;4D z`Ji`yxF;PK@52Am^a%XRuRM#hvh9^u%Z+cxV;_hygwsR{km;z}tyZsjqLw}Uq?HFl zGYT%}*X%c$N@1fN=9Hjufd~x(0(x3z0Ww*d()CA_w6;Ph(29>gDPM#ZmX{;Vi5eLn zmX|9Hh80C4Eu;vU9?bdw0IaIiW>Ndt(R|N!{^{waRoX8GJ^U=2mhZ(><-@}L{f?9s zQ+_}j&O1{wyg{Rc!Y(BZVv>MaD->iBOOHfsIa&AyU;5){j%WRDVi|xh7&zdKV((n8 z)g@V0GdgH++=~O3Z{hSSRMZZuZUA4u*wez{hwIkcVw6v^lv%T!xk}*}0kS1edwgn` zE`zt?hyeyx+%M|ZLDFb!5O1KT>h(j2pmqJo-dSMDwI^6?PQW&6QGze0ck1KZP)DlU zABB~kueZX7%X4gkM|fkye?I)&@kdCj8$e!4b1FoZPn#J;X83=^fx*i~&Q7jQ&L+)4 z&cVz3Khb0kK}EyQ0fov53!}QYIs?t@Q9ZMFjf`q&863LKO`NK!SjNL16ANTFI_G_I ztczX(sN2lT%Y*rrW|Ge?Ke_l{m{?hhH4}O0e|15GR@&YYY=>IPBdb$5D zmVCnFON}EOeV0%E8o~J6K<+#1LFYl<_?MBM18pP$2B`L0 zz0g668-M|dFM@G4_4NWp zHxc<@5suYV3Zt3!^(zXVdZ|VF{j&u`0{KP(-$f*|ifL;+*aOqoeS-65HZ?-~-keMn z5FH020uE<(*N5A|;nOIcm8TD^Dgi5F89D)IYRsQUS64<{=KpR~pNfRRaExMC-7sZCkeykYZ@mH2lFv z`H8V7+4aLF{cn5ZBdBnHuqe1AnDBswD)970nZC}7*9!INsV?_mr7pKvbg0F)KPZ=E z(LGb#qu2obz+E3pc)Sm=dssRCm|q~IJ4L6Po__l55q)fvtBf%^sK;-ss1Cl*CB^eN zLT!RUP_FpVQ4MG%MQa-A4ICS)v`$A1%3TheB=baA8OEb35AG$vu?$(1Fig}4cDj_C z-fP+<_Fx3jursON&&s9R`0}bNIs<9l5dI#h93N1oz_qHbM8AW`5-Uhv*#O#O=7jYl{?t|03l6%R48G-yoY;9*yMvEal(<{F$xZwO z$1VzQC{!C_GQU0vaqQj1fdZNd&3r{3%`C~Y0{t9zAA2MUHgiuSzKpMRx<~Xkv zJgesOdF#s7bp9>%nvPHFxymKkaRmnbggoh~7)cBF6N((&5WNP{N1@LHd@sFj6x5CX z?ZnpM)@0R1=OQnWu7h`|V;5IwP#}Pp+#WfS26hKo^Z2h~83jevv?3i&mV_9q%kbtS zpE}f5zGW=PTGT${`l`}^%_Cxn;Tg2YgbGXIiM?IU(WW96ePaB4Id~r?&rNH6dTnu2 zgK0>Y%vG=25BPUfD0pqg{D80tU%l%H#Ma)@iY6n2iocyt6o6YxK!CNd#-$*!;3asv z$doz22{xc|5RY>OkEwW&{5jTHdmpY=CI<^I0ELOGCAc^3^O3oup>9Sm3!+f{NE3_r z%~-&=!YkCob_uwMR)uSrC0RnbRb?4i5xJ~y3i7EYmLu=T#>u(d0mPSh3kOA&Zh{f+ zJxJuy$~ELt;EkvxI_r3z9e>uWu!*1Miek?h3?=rw?sBN4SpMLLM1x556p+TJBKd@V zxr>$-ecRL_Yos4+N%2mAK)s`E#Qvl}F2UY}JScaCw7YcGqV+f}-FzQ4qQQZ7u=CFl zZR`-3+{_8f<+R8%XSB|-*pFknIKU~ch+YB~YhZm8SixxBG``Rsgn2{Mp0i0IxXip_ zK2;f0fFI0umB><(le7|wJERg}YGe^AIfk3jChdr%8p@0pPgn8w=lykDyT_|J*cB8J zqrk{)55Ugt95$3kodFnST#%yO9k{G8o}*P(7O^0hZd@f7S8zSss)gub$yua<>k%2cbm*0D2CQ>nQFyM85=Dh-?WPT zk#PHRI`2#zBtRqQXkd)5;Er}uN&iYyxcgTCuYcpO`^tcfR59xvlOFRw|sBH7Qhx+yF~cKO-*xVdfA z6|@qxo1U|aVs`1PNDpFY3|%E?2aK>k=syN0Ky6h@Wi|^kG=#prF|kvd#vNPqQ^zg> z1JOhgMRSUyhJTl3=qU1w8fakUyo0+R>EMBV**ewQ& z0pJckpfC!~aPDOHeUIgg9CfMI#7BFsB?lg`-$~jwsB12M%kLI7zi6i?zVVD<4#^mZ zFB*Imj|cFIEP6|MQ%XFgP_5Sq^qpc9p5@x!4?J$_lRgRZ%TtUxcSEf#!8PFLT;qY? zXec*|xbjexoKMDC?9;`ML_gAdUO}+lmNqqdUz!j57`6S9wCG21`Gh}J6dPX?gKp;j zRE7OZ#R_JLT@+Rpd3IJeZmCZMoCr6wrX^i@0WTT>L9xK}Z^K(wEZyc*jidW{15*^m zti4=mlUsocebz!D4_SNt3&)l-8TMmikoEBbVQX7LSY9B(sxj%%b0ONA87nvhc^UuH zddHY^nbcNNMkn&tnG`M)U#c6bpB_)hF5e^)MrhK98lcd4aV1@)&q_*@&hXT&_F~FH zXZ-e_R#QX?u3M2C6Qy2jgW~8fmh}P5@7RBfE9(`JD;U~m?vBa~lj?0yQ5=kc?bc6o zZ3JqS>w1fAY!ywa$JzmD^#++?dw=FB!WG)V4gBj!=&D-3w3t68PU2RL56`;8GE^+S8B{8b!*oI&`f5PEpa& zhV@I++R=tIL`so9u1B%{AbrSLQU9GZ)mb?`1gu+@*S}nsM<%PzP89-w^6qO*OWABk zueY5Y0x=xP?rXc!ob)(OI7ofnS|3B^t(K@vhHST{s(xALzn%OvgJ=HOxrW@1f13T& z{&qfkA-^2BnQqN^fL+f<8`2#Xo&@TI?%vl=1D!1CeEfRP>!Q3y}^;ZO*;T~qNtA>6T(jIiL=_* zQ*}78r%?_EuZHtf4Ue|-yT=?_2dN~(<%vJHWexcRM@KXYaGWY-wGq2C$?Y5cQZ3*d zL|}|P|C8+85dQA};@70tWXLW%kZW7vtSZCjb!|zPQ`5U9ILHmokHL1EW0ahCn{=OI zDVl>3I&NAw3wjza+ix4l*~YwMdedp^P2DiGQ+*_qe;^p|UU2k(Um<%gviYFH$v?b5 zLI{c3SDr^C!FNihW>;BDin+Z#-{il#5MK-T7O*|SRao_12B9g<5-xM8MUKz%fPWkaz8K;*o_>(MgwTN-+VLcJG@Myj>jEd30E(z=F4D z?N_V$UY$R2cSV1SNvPFB`Jx~cnuj!iP3n$G;n-lpM=BU zA(;Pe5GW=D-n?@*ByIOiw&qlMhHSMg!9hzIpz3il3qt1WVeIl^z0((kRobnY(I3!= ztlYx;vz!Pa^H&TR{v{6y1>WZnUk&@F>M|~`<2fLL@|N8FSKIdsSYPrfmL3D!Tmx|2 zSiivWzNw$iQ?bEI^J<4Hf3JqEvs9k@R`bwS;!89b)AzT(ezIS66d{J#{E2oF@(Kfz zljkm5@ZGECOA$KFvv94iZKC_}^tq4qw?05QKgO#B5?nV#!Pc4T(HxP-11l++zmJFL zjG0DhURkzdu4GQXf36kxaNcwRO+!76r1=-077!~G6!*6vfoi&GzBb&Khk90@YBL2^k> zDgwYxMZQ1kc^@<`yS(ToV${u)<{E3lYdSO4+&-Xh_jkpS`jnqtFzUFG1`cdx07d^= zL#QRZS9L4GHHP%#83cqotD2 zH}od1hSCwl<^;EfSSSOvB@>9~Ky;eJVp&?tQ@*lCo%5;1L9=_wTEG1tQZa(vyC$vk zY}3M~X(#5LQzJ;>Ts6zI8YK5fR}bBTdueDx=WiRLy@^-zun^1LQVe?Ber#2sp@COH zkDlBxqI7zVd~4M|mr{aOylVT^=Lgx&uXd4y=5T63n~F%qrc;r#@xVAQ9l+A|Izx%3)n<&{?Iq zD3psMJKME6m}6kZ=+EdyARXmt3)%;&@1d-1=UXdCx~wtWmipEcm2WW5?5%!4Z9mB@ z6k{POAYBD{d9ojztc^rvs6z6NF>6kD8G5lKuL~uFHt$pw5m_=nvs69ngL%yTy{Oh& zYBzA3U`%=o4Cfzw@q^v<$$EoelNuz2njyd)_iN_yjt7ZzZR$@SDZyOPB{`1WGVN1d zY#G5Ur@UmbcrN;EslYD6r*HI4{&Y|#d+#v$NGXMX{%HpiD4I?fI`**WFr z&#oxN|F&4JuOTEBRp!gv-`cktOVCyy-3`Kqq)3d@I8}TUzbte1m3n>9BqpB8r%rv^3_eO1)9UYbjpIRk zxSV3FO#tC1Lgt-C-<1bdmEYu{M&@vux9Cas3VORznVV`}N$bczk*aq9b)UKXeEE$- z>p6&`*0Jhly}w4*=-Frsx~Cua-JtP2^AZ3-=UrBkX<8=v23m!q3q?9=9grxtM$3Fg zxmgf5>jMGG=!63pR5LZmjk$>G9wxW?*kr)AOj=@nt~PgPL-DDCBzdGQtH~L~@LVJ} z(lCv@-JjR>H7GmE=p5af+4J?+Tef&jMVy+-R?5%iZ(vf8pCjo{mF1Q7&eiJD#Czl0 zsD^uEte~4t?8~)Lcgj7w3-oX=Lf<^mL|kEN_n8qeW7s)Zicxl(7<+o8^V9YGgY{~8 zg8R%B&ZG1|H2z2RN5p}8!!DJcL(8sTJh=*Ep6E}*^_<4>L6B(d%MP*x>ThV_G7)~~ z_e#QnG=%O{+g@G)3}js?pqo@rVeV^KY|E9Ha6)^wFrwgZkD+kew>SxTfBny7sSjjM zTW5?*Yi*{%S|bcT)sQ_o3s#5@LrdG0guS$q%(Bc0Q%9e5rrY_=wF4A+^VNDbWKSKT zNlJ&p5}#D=3)eG-d4iM-b^}WrsjT%Zv=rSpmNt3Dh6CAc!d9LCZp|piK!UX`XA__U z8D|!Z)U}&kSWnW6sxFI`nQWagw5+$A(vr;(0Ly%uX2Q-FkimA`%dYsAEtKUlPa=l_ ziVoigQgBl;n5Q!6h`}TAKn2n?9xWT`c{UbzhVc0>wuh`Zp zhN2}KXGC4^hr?# zSA*|)BEIIRH`(XN$T<7>`?1|;*>i8MxejEwmDlfg4i?j37Un+`_3}E#9?I12g0 z#7cZ&!>pM-xe$&Rl2Y*96aeQjzQMZCT%yvohbN_`Q^5T-!Q&x!U*~CqMQGWT=SsJ> zCal7=wv;sPTMl?QcvR9LdmM9Yz!QN{2#RN@$&hO~#F`$bNH)CfY0FD0xgAD?E8NA; z2peca@symfZk0Mq0&XCDA^!vBY~6D+`L0I;IRyqeMi8DN;_82>o)*V`mN-}1-R}yR zIptIzuauau21CY(joXd_9%?5&J_E_7)(B_)R@?4`f@a|zIiBG(~hb-A@_j0xyU{FRIZ=34OB!f$|n{YaNG7GKF0e9 zIkR#9O7>?4u1_(BD38}Au@fJz>o;};kvv!6&sFp~0y?2PM#2hjXSn;v>@WReqy39t zT74A${qw8X^XC73^|oKns&^~qr3t5^V*g@&W)~6N8tU5 zn%V29CdGUSsy(!>zoU?>6UL7op=UwLT(!?gPMW%e$AV2Tbs{Cp|A(=+3~TcV`h^Qc zf(Q2!+_g~LrFfCz4#nM_;I6^lrNxW8yBBvU?uFuZ(*OIs*LBXf=i4T`_wMY-Z}y&S zX5>kHac9X_ zp?V#a*IpZ+cI3$Ur(J&Z!IzZzqhKr*ctdw6-9Zfga^ToB>>4VfHt|}oN&#bMSkGq&kTi0P zi|MrA*-B(Ulm$TC0)>ZLUf4f+3dCe)!qrPt?wy~!&Ah7v^E86hxwzrOz|c<84hq8! zLLShDi%5gUcB&;y;0S}I8&3>Xj{RFFcRzZma(`~s&|JU`J}}9bf}mL?1VOMRF8ovF zmX_Lok>3WAB4$M4MA2jNhIx0ZCLI_VQ~MyU(uy?uo1i~~S(_8qi&0HCggQmZg<&8g^F9j)}DM^v9@C)mwnTQA#iu`;h#!`)R!)~4gIEKuJyo7p&`?-cN*N0efn6#t1L51#1M0f%b$a0jki|_eAN#Hh_)a>;(a6@Z33=YBylE zQECOG0@3%_+C<-p5yH*E{+R?Bav|w1#}jN||C1?xDq$R&_Q^g%aQ&0a5#%}-hkvhj z(9g5Y;BTkiVK9R5aM1$UUZmdQFaA5b#W0Y>CiqBJGwk~eL$I~FyPo}+92cH0|7wgf zl4MFgyC0vy57|Eqg<0EwL6~U!w?b0v+C?L!^)V~yN>|d;>ilHWl*E)7@4Q=R)N}-yXua%bytHl1r=NQWu0VhZB2jK8c@UDS$rF)ICNX zbK>vBS|3kI4V+dJ){trPPfL%lk!%D`@U0Sq*H(*!+n0w-P@Az;7j3a9c643sMiQ=? zx9;YVTClI{Y4wLfKQ`w{@(UP13r}I(oPn{V{3R8MfL`2VN-F04WpP$8f~O>5cbw89 za4K*vwc;Oy&Y0e5sSr4uWc*zMFfN?szc)#qryo>R|3Q0F!erX&G1avdCIVLg zTMo(?P_!1IBi{d6kVV;xKj0-)DP@}8z8vJ&>vcsKqsC^v?};ceEk`K3umkC|W&02@ zsd1TCi2Tk{<|`?%vn;U3bO5y)3%q0UJZJk{sFL~hr`Lqoxj#VSutL^ijY%t=dH74r z3R#2K9Dp1(&OuHDPE104tfig@NDOQgDiSc@*tR5jHFu07qTLrUh~-A8y^CL;Q@_)_ z?^VY6dSB2Xf5Ci!Fs(DcmF>Xxi!N)%BQMDkf3OK#PKn99vW%`%m(LWM^@rWlpCTSb zvBpLe!ycTJCqFTp4#3SGdfS(NCx^ORNFU)h0m0D*iiYjBukX{2LC8h@_~&~pD_mPN zFZ)hBsX;!qt3OkTV%W+9;QknV&tpwidmU!E?)f5uYb0vHrAh$19U5MuMDQUN&)*;1 zZS!LbDQU#g!$uF5B3?~)6f9-C_-)>Q+R>OHLz*-UMCo6|FG)54Ix$0VJmfi>Gm1<1 zU}F4Ge<#+WOHsro@WcRB8-}L!IY|37f3b)~b-ci>^f?39ok_(!0m(u-C1f#LNEiGkE z1QCiBz$8V-32bXozhfGMO3uA2mnjvG`~jde8$U^%c7}ySfNu7Wq$l9q@l9|OfE$=A~i=)wlQa-3rirV3S8u!nGUj005EoTRC20Xn{_9&G_ zRM_z=akWQi1oskRBg!(F|0r6$#u?t!;la^QuW-Dl3VjC_2mN)DM;){$K@llo%8jyl zpr}8j%L4?PhgbkRft8b^VjnhIpb&}Ov$^Iz_t0JI#~|EHK#QSm;T#Ww{nP9ARr2_& zGUzX^0m(^efp-$`x1$tFBnlwjqxb^RHm?p=a4f0nu^L-`;!uxqk&XmaxJdXRrs+x1 zJ`()SuVrv1?}W<%J@=5*m0XpeiXCEmGlI{@ZeACa`VXC#C4RJ|IzhmmFi--btgH>^8r&dOP z1;#sJNj>BOJzDEAuAB17lB0%O@`x0xl0!K)bpCJE`nqopM@&m zB&JD4%TYy%aPmZkMcA#w3JZp=5RCEkuS9|X!67X8EA=&>qKM*i+g>!RCzRnm4Wr?p z&f%0R1gCgL9yvHRNqIIM6+F57AK)XluEUhU=;>zaF%N@WSmV{% zz4bh$3DB5Lm+D$S#jR6X4uHCr@_35)9@rw>5l}lxz^YtH^;946|w1 zivs%LX(jUEtVa_k3=zQZE%*wWxZIj_F0f|j7PsG8QdmMr3UHU#v2l>A#!mbGpw0I6 zLp6R`YOPD`=9`%}sx7XnJM41>HcE!G>c_#2r-hyBB~BlJ5^Qg}Dxx%lBeo?;ChYf8 z+!b`k*vJqcS}BSHzTzM<1NHX`a-ppvL#EETS*dsYulTK`Sl*^~-~Q+B0JLRqY=z8` zYWNo@luG7;hLH*!0CcB5pZ@ReBMhEF?<4SXvvd7F_YuzY)?@b@6FUA&hLiB{FBy(Q zoM7i<@4sX?NdJ=zM<(J~8_RP}joK3u6@xjIwti6aLpnk2Tf&_EkLPP|y;s~i&!<^~ zuICpyW~7x0__zC9R`B!s>Za@w*2`ntYHk;+@YkEg8y)b=L6@KBDzuz4G#}13{>^PF z7!R+~N6B6$?8ZL%c&f&Q5osYMw^9;J_jW2d6ZL0G=C|;%+Rb89SCRqv?Pd&PbCk7> z`d;@nb;IxF8vn(pC{W??Y_ZEPVifvQ?@ia{t2q7H>-E{<+Y1Emtl^XR!&DcCg{!_i zI(>(9(ixbl&REl|Quqr*4ccN33D%06|s z4yi3p?PJEfI?Vtk#}RengYyxNnoHth-%h3@6YYvC?hrB=I5&B-T6R8PIY>Z%&+DNQ z2D&Y{tbyie{qu%Y>7SDTHBiaIPm&XY#FVcO7nSM(o4{x9 z#}Zjja@Yc9NJ|KO z7MLO~QcEVft=W!Yc3Q=IKbc%-B_p|{qj(t{Z0}~i4r%D*+CU|_r^N7q$u^L^C$r~O z!o~{tuB#uZgL$!R1>)_me)5x!K&GKQ6NV^c2e)qIXf?g%KPxU zk(YIf^^=vzWi^t?Bf5h-;h4eno5{QKPSzoDJB)&L-S`IEPMiyCbv@D)7BN?XLrnVC z5>%75)Q$`+%kY%Z+~i1`G*$8;vb4}PW<=OElkE?F9;e)9KPJ~~Ehjdy3w%ew`1wvj zMO`m7yTp#beU5SkoH511hp*T)Rc#JOIZ~7n-Hn#(A#%NvLK0UO4d7rbon{j2)(Fn3 zU@D(N@50oqLe44)s-kqoCq0hgzK`qgcqD)_M?K4{QjPDfRC(U7hV#Gy7bdVZ&|M9{ zTS0nUT{D66QEpaUQ6m_EK{o?A>L@Z-ypYfyD#ffVk54+jD@m5Dk%&any$_FkGIX}_ zCU~)(@q65p3zj#nHDC`DXDmLmG)cpeo!h6=Ya?jRiKzlHADxN@d$}LHwqb82#f?1~ z=MOjaoS>z=aAel>ts)*jsSl%Ke9<0H7=+b6`S2{9`|0-K5gb8ezDv2H?*l_^`_9tf z4V5{^9mgB}%+&O=uC)%g#j#$S)I#ryd5AqPC{K%*eKB!OHoz`)IgK+dsIl5PhG^Dd z)}|M0T*%K6OP;t6dU3*DEAc561FIJC64RZvoEnj0_&^5|q2BCb%@eU0{+5B1@Q005 zHVA+z`PYsZ;BLhRBq}5MH1f!!|EDcem0E)Ft#$9Oy!5?PMLD`wCLO9D5b3tIYmq{5 z4B%QW+)AY@0}iAL+`n|AmzAv>1x7UF@fwzfM*U3^S;sQ|qUa}MM|@i4u^`oofGl%g zxjU9>Uf*_egHF<4+2(7U^ziV0=S~JYL%7P@9M8O-GY$^|sL(Nv-|5)MG?Kzv)mv$u zwdfN-<_~^(c3dCIFi0)pH;b1r>_1HXmejVG^&ZJ(06aYk)HN3K55hm3JBU&_9ViWw zf6B7&Ny8bX` zZr|Vo@NT>*^~-Fj$iqWCT#mLeN#Dt?6tj$$mINFxTnfkD`xyQ8$3`iL$)~+@r9JlaD%RV-Cg?`Tlhz^0x*qWcAW3ZlWD*FmI7 zo7X5+uj#dQXw<4C;BcD-^C_9w#(~2VS^?+Rdp4xf6L*Nt5lmVLWWt-1(!{k|<3twx zab6ZT~{-&n@7Vt1rabpdC({2@!ajQ>Q{6Lx2G+;j7Z|1)j*4y4|p{Jqnq zt@TNWlZ+P#214>ng|^g-r}W*u-r~wvlJ;MBcJy2j!1&3y3I=4|`XE4pO|Eh%<0t<4 zFB7Z)h4$)}#NHsg_}wFy=aacg8Fj=lgk_db((YC45qVrrNVS#8EN&ny7Z4a;YN+hy zzR{J2RVoVq7KF6fI6xI8qrCpOFNL+!FUjxt&aMbrdH$plwWLauDIwkQuH*(OA}<@F zC+ou4?hOxV&Q-F`L$f+p3aK6vFXu+MdH?q%pIGkxiTU}%jxQ3gyi(KtA0(u%Fb}e0 zN&Vvm4?&2bNiA*V37ktx)d;kB$7drxRvJuA!9D7v_`@6!ZR{7j{heX_B>JE@yd2*? zDjzv`+|ezQ^~(A9gx#k0+dK{JyVaNud^1I9xKH)xgL;PX!S!GH&P{5m?m`BFy{(O) z?h)4lo7h zXV>x?<=DW@HeK9R9d;X2hZCu91!pc26q2$|4u2<44~S8PO-H*`6V^ zUA&|CUAytcj1%GgKI^`ui1;yyS#wL}`~{T`_{5F?`Qqz>M4nv{s-&8;X2!lhPQQmr zg7H3l3n78UZsqXAyL-z)Ld5a`lF`VE{w{cSYz_`(slcsQ0lUdXNEM&JLJ?Mxmv!{p zHjISy)w=q0sM91@x`L1SVqs`+lNoepQB6FEQ1z=;QXv%@7%%)n zMU|$gQ5%;-zBMaHqhedlc1ntK!qKgNi$lEBX!0O>b@WFW*BSP!?5kxshM5aL^G2 z{(|jMq1T(XY^wL^5thmx!A@s45}`kaa;O@*Ok3n2=dw zWH&$d9Q9G2mAp712H%!0cQ?M?d7l`%mG`^sG{00Oy0&_qE@~xK(K{_QV3K}z4&Z>qpATV8 zU015BHkI`=u0vgx1hiE&L=H1VyJ(}BQrFXR@R=hhGhURH#?!KqnhG;bAc=kf@d%zN ze3#!q=9V-zR_=nzn&zqzb$LX3Q67ZUHPBHPb;q)1^(O(YEAdW(&#IiO?22&&jI`JV z)t~Sl<{5_V`TqD_gB%2p7rOp!F$zwSSE)ELlB!?N%m%(PFUIYrv%F`EJFavD@s{n(Hj#ag z9>tAb6kgO{TT>(pLpiLCp|w!KK~PV^gY#jgPP_iDqe33e%b=Mf2PI#i`loSZC0!Z1 zUKGRncR-{Q-tv!@hCwkMYr40U%uA&Oi7Hc7YqSu=zZEGo?#!9m)^yNX8>63oC%t7X zo#+Nj@J3bqUDGx(dYI@54*N;t^xqJHJo5(57VG6XZEO`M>9s!gqPoYj6}!U0K8m zvLspN<)L(_2TcA)^CEbvf(z%vbRAebW39o)sxluq;>=-0|3AEosE865f==jdw_urnJw=o6FO%uJLqCe3E?D1yQ;6b^;5D4YQ zEp!5_#mCGbFwzSFTE%~=Pcq1#Eay(`}wpDd`a%_LM!S!T>F8$R* zY|2V&Z(|f1^TIXuM5odHCqO(Sr~t!ez)?9XuKz#d2s#eG>wWo8f^1$;9vVY+1J(Q= z6--bn_`PPjtK7mB6-^cXzxIE+-$dGBVfY^_Zcjgdsf?8HOn%9KzP@ASYAJSU`G)_d z&dswqK6*8@+3`~O?9#TQ(_ssK71}p$7Jh+7PrzMeONWYjI?=r zV|}pL@c1q#Dh*Yst3$2qgRhwr5nMGI4+&WhTnjMii&V)S!0a%)&v<<=lg8zg???NT zQx7O?QPKlDJ-v)TesL|8bpye+8q0)W>zar2gYm#OQ_dJZUEBMQHK-`f?MbXRR}BUT z9%DYmi|4b(b*bPF+vNi>$EO8PB+pc9cyV)Uh0atOxyo-A`}8R2C#74@dyB4brF~5xq!Rb5GrK-a^TpF+F^UdW?HnBUF~nU$?>wN9yi-irBwv^2pRT0$871? zXH-JX&;@D;-SzK1+eTCe!Jx9RClhv2CP(?!jJ8aE;~nSDaP<}8)2Mbj%T8%M@RaW) zrl*=;11Md%Q#H3$KaQ774=!;{Kw!!9gX9CWAiaM1^qEJ`h~4LjInT+1!%0)V)_0rYRw zE7zZ>-yQ$v@ZWGh=26t7@K8%SRpAEwaah{_mU>Kvp*S`vD8$SyyHejy|Mzfw?YJu= z-Bz{Sdm2$~gdt<6bEx2Vg~>V1rozC`{$}O*%kzoziHjsDsWd;3HN$X$5zL@zbON7t zW#s12G1+(R2E*n-h7&XNn_XFj`!87!>Pyrr%_8_6_8qAKoGISd!K+&e7N|}+>sG|I zcK}cql4LC2^Y2YkVs-38$*yDkn1=RxWhaf`A&&<#6=(<8K6vPY?l)G4Z_1w5C6-z? zT`f)Kd%^O#zJ~f^!kb#)(|UbE&&>?~BWCD**JIcZvs|AI-%Jd~Ehve7C9WIqn*v&z z9bn9s^6awaeBiVu%xg-&{7O|B7~gp7(+uTOIa1`+-N5dD_i@NQSE1ujlXENjp8`ll zeENg;mn|(pqtp$7dk4K{$QqcQ~AH|vTwhy!4X zr6(fiEzv}*`V1D2r0HQP0-}#;?B6o5x~}Wb4bT{RiC4E&r8LPQ)sBBzStMaAZ7DAW zj!&-y@5OTre7^&9I25r^Us51`2qbLv?%Mb@h*|{nn9bJrmJXbTF(TAn^tJRm^zW`d z&0mk5Z0*mJ+yv9bni3i}_b|iFo?+RnSDWv18r8hCoP$|3!m6Gh8eSe$pRR|Di6v>{ zavH6bVMl4PiBDR(N=;%EWumw~h2)@q@_NyTh!OmpcemSVzIscoFqW;&ew>~iOOv8T zWVU`02$^8|B1zqGp2<&|ErpY8$hQ67FMwJZ3C_6?qDU1f%LcV-I)(tlA1Jd(63R#j zAOGS>QbW^REgxAJYJCmtamhA?4wi!smX4KeOgI^-DT=DuJUYw>K5BQdT=eQ^XMZt* z7JV@n+_K=DMGD<&vwn{za|`szA48Exl{l-oP=Ekp*U~^P>h7HgW6H)E#;6 zjT|hvHo4ECEc1_PCRk|Ilqp8g;9hb-dP^S|p~uc)b@-dLAJ$Ud3jda38*RtM8Q<^E z9T!qESDodb;#xNWl6Qgc)Ge&e|7#Gjie;eBjP^k5S27T}a@jnFcAjuskhsK7#^HEgwQFONE%jN*F) zn4w#_Mr_Up$b5Z*F4n>F2XO%wBAl15J=~K*UAC;#_p=Nc zYRZuX4E}p-W3#*zTp8MJM}<9eG(DAuKa__9=>a9&xol}-hGtE;2&zyh(7}@@XJbrT zkq+*`fuagN0yK8l4s$Jecsv;RQ{J2?kkG9RAEIL}X|f2|u$)R6%_;aa&T62 z2VG+a0@HBCxFBD__!lkijz(Hi=&!V8Ae$K1&zFappg#+ zjW)So-puJns@MZbqJi;$8`F2bH-De^rL{Z8DQE^G1tH~{BYyl{f)su1?^Z@<*J~JB z1!+by;&oI#01YYV2>Wt4SW%q5r!_LDbPtYvI);xKcTY%t zHWPU6xvjgs2{nlDQ#eEfH?Y{qnG%%&N!Js#WR?7o$k)^iixLi-EY<@v&FCUP`JcJj zuI*$swAY{o@&=gD))p`8a<=CY1`)QlZ6o_hO}tMd=5Z?krhYY;!IohUBz#;XWhG9F zhy?neDjiCE?|(f%R(itwMy9zEqX9=+?v>^ zS#vx4`MoH&z!2kUc`tOp(b*6>+-HKiYUKB#Q0f_w;b0b!CO>hp7?5ci=7QOK4O`(y z4-Jg@rrM8?16fG|8Rc5~yZN)SjX$ z6mZq0YOR8F=vPwpLIPMMA9>M&jvg0-UQSB`*_*rU>Ly`tO%zSW0oH?=Iw#nr-_+zTAFOukUFSasmGTHkF`Ytlk#8Xd9w`i?=SUIM zwIK)5{>P!5cj`C-0}hlPfl%HA_h7@;1(ixsq2xd(>SFQ`GklyUh!**wmSW8m-|S5a zly6clJ12gEAOorbk`^+vUFxRj6;4!$u&KQLfa5hmBZ0eL0eJlLF>FiawBDI=dRdLM zf>z}pzyU3);9mmAYPqze$NDexj=4h@@+G_*3Y>}8SIdIPnR+=_tvUnl?dOW*SFP-6 zm$hzevnM&-Wp?smk?nS#ErQc%L}t zz)Jny9TVqH>@SyMH!AU5q4N+UIw2Rv)(Z>zK#QG(=)7$lRVF{wExn2& zRwjbFdkjMtq)_a(gADEN*CQ%+Ijo?B8i--5*+*l~3;0tn8oK|KMk*EaxV`-1S_{sN zEhVC6&RK!Jb>vyy2$L!awwKTJ*RNoID7G~7V(PSV-HfOv3SsIDG#pJ`?Ox+G4o(nU zKu8|YfTExpjsXmlyGG%)((m%hav>tapW5~s!0{I}NmS7M9634*a=KoUQ?}&W4IUXvYYp z$~Dw*KkUSnybK&xE7=eS^|-F=T8#T+jKJ|0m4d`M{@S`f1+^xyW{3J;#523wUr+*( zA_P-^^*;{!!tg)}hD&5!d4<*nMG}TGgc*-0dPDDf_|R)geD_?IvSt_SO3}<(qLNjg&ptn3KJLRQgR2lJp^L2cx0>VYZ-&$5<_HKS zp)MEeI^@<`7fEfmO$&L3^H<-~^3;53X%2A;(%uCj8R#Q^Gzo+{TXWYkI+||qKX04% z&ZuRmo)3dP#^L1q7b$oJ|2~BDZjDpUf=UL|k|tx<2Jv43+;ZYIeZMD?ar7-k?MM-3 zZ&E#vfbtWR$8e@U_i`79pgMGuFQ4dnPTni~lYw7DFGMZEGanb>Ba@Q3lX+UTuUHLL zVp-z6Ue#Dzct+~(S=|9wmIgSkO(q7i{}0=bX&WBh{UBe+##Yp`2k9F4OJ_EEeAc}% z-Cxy&Q$=-kZH?17ge6~=_u3~=<9Jnc))7BP*6uEBvoMkCx19Uhtrvk^oYp0Hm|BV} zXY`|hevAI4?>QUT=}~YhiR>#t{O^P4#gz~dMcokK+Fr6laSjSG!Sm4;)oJ_#P@~<< z9H7BZ7iWW2wf}eu*8||-gub!3Uk0M00rdNd8l`J_f4RswAx)p`XG=q%79bic$E0$d zG6?c$OAgk3%J62X^o1=s>DbSq?OS6HHPjmvxBYZi80VWMxTdH(WfENO-_-(&v)f9! z-*$YXYK&hOIjxKc6d~-Q+CS@RImO{LWfBrTciJp6$4QjrguNsI93| zzcy%Q>l@;46LEXA-(;#=z;-Y-OPh;@u2}fm7EB=h@6YeUu+A9lgh=6@USpK^qoq_9 z_m^3TP5vG2C^o*Ohxvi-Da#X>dKwpi>F$h%YuPi?;yCgOZLXwKL6F1#j}f~ zmimMzCLYw_9@NY^QjS|A=ym9)xR^YeQhe2szaM%~J51s|Yyr9^WjBsB_HCYvZe0*2 zwQ1$c9S(%qGv!&@2UZqwhr8T`_X(bN?mL6-v{f2JQnv*(P?W{oDZuqs#)kgHD6JywzEBbVQ|WdU;(318cP-2^Q&}!u z@K#8)W35MztE6|2oI6Z(|MSAy+r+Q3{LDU~g#OZk^1{3MNs>;!hH%GVJ4lxgi{fuc>o4+hj^?qqdCGU0~x7QD-B47-%ANA7C81>*c3Iplq!ng z;6%)`aU)q1d%img9Q2s$o{{Ksztx4baMieiO(_Sj(eBZ|`SJ<}iUmLKV+5d0|!**zEwB zMu3GAG}Ak7>HfnJ11EL`3VspQF`#&`I&erwa$yS zk2?bl`bgj0?t)AULN*SuNc+CeWei3G>HQ|G&eS+>?x#r7A$jo62N}t>(^_eATt|cA zgAXHzvM?Cv4|i5h3|aijM5T!woy1YeSUM+9ux6xCAC9SCWnx&08v+CZ@2~PFsFC?) zE>=+*(_gd=vy+1P=yf|b$7r)2Hi}>FB@veEzfCg7Rpv9pWT4)DHnqRNLINWd6HBIt zBo(Rgg2KNs+Jh=a2e9hB2@5Y$j zfwrY6nWFWKZ`|j7uz}6L+!YmLx7oXiI8c$x{e23?;!z_>1e&Q4Z zqCX$gIBPcOXbYZC#c**}Rew4plGvaic7<6to#>xn>R0KZgEPx?G@=I&Jx$Gbma%_Z zC}9FvUqDz~t_IBQsD6{;))%M-*5ZA9H39CFIyJB? zj^FOk;b;2nj19QWee;yvF=$kgB>LPsq~SNHqk+;x%H>mWo%;sGLyX94d|u$Qm+pOC z7g&A-Ox=cUG|l>?yPH@!82_Cetsk*Ghm(8iQSs;$aH87RVm|J2L{oB7g!Oo>F9$vK++Nyq!6WWv<|8i zI?W3`q8&g1NWFoH=zai-YWI@wI`oHI=xV9Y=RGVuNrJinoR%Y}gKR_{V@NiEO->X|?^^*W~6P*LJ4p?!E3WG#0GhKZ453y zZ;k8~$8f_a#|t)iNT}2Nhh#^N^1w2-))CU8zU;&@F(R2ynG(FLM}*kG2P>+S`?^X` z8BH=#{b4o;>);i*a>fcyc{;Kkn!1>%5+OcUj9-3+IHe+aS(FWGO6=*<>fi?}bkV%p z16jE79>QAzhFdSXn8YuPI_7ii_{{YdkAswKWd`X_+j?~;Uj2)(55WZ8#k#Ebj+(s& z7ZMKiL|@!4_*qs=2_%1Rb0=91dohPef^wg;$PBD&ju6$^HktkPBm!S)uQ~7T7hirbM>6dNa0zhK6>f9oX(8jQ{*c>rU?5!zJ-({#j1V>j&;x)& zSy55iB3Ww$TR_Vbq`KI;kK`iCUrw0HmD54nHt>lk!8Py7;Jz1;_IV{RRNaS+a55C=Hj6BkQMm;CyEswNeJL-$$ufZu;TZGEImOIJjhn!kl z9r@_T-<;7BSTUU*;>%Whh|t9;b7O(+3&1E5hkBB=xI-gEJI_OYdSMhE*wbGE^%`Es zp|dtNXkcZ_kpR%u#8#b2iwL96yXc_Wg2{{cbkz!rt%>-N&!P{=aH2R=HlgxD$g+|c z0V4T(Vl-Wpj*e*u$zT0AmoljO$?>Q-)G7_o;1XD|CCww9wfR|K0~VA<`pgi&MDNJz z8INNF;VaV`?ybgFexQL|4p0&+RPU}gJL-OaMghx&PF1cRYkx;S8~X&OtW-Ow{=>v^ z2o3c5gs{NBNVIeZ|5|5smYcR0GX zkyQ!^kEumFDtU5*$o3j1)mL+F;@nn2D&x)_y%zG=ua?HWMv@({DlQh^QRluk&_FAMsGVX zceVVZ-~{W24H>tc2oFG}YzI*vW4mFsyV8niiix`(XanBpG>8kOKW&7n+-ES8)0w)4 z2O`}@GPLP*wOr+VEl-D9o?&s^&N=G&At2;O8guDvRXD@pd29>&)ZtEFPUQV(P>i?E&}z-S6L8WF>YIw@oxnMzDdrm=RzxeJu<`Bi$dQB0=opoOTBC%xalr z$bocp(%)>Hv{9&FTXsVDSHYpb<@Td|*B7yh{vKVCeyE!j@(}?J94C*%Qdpve0N_?4 zasjK5e8jPg=r1d&o&XA3V~35TRvHOZg51QoEtRkS!!#>lWFu5pjz`d}=5%;Ldnq zinnyO2`L%R{z{J9qorFyB=X|y1BK9<%1d0wRK9~f`NY7uMHm@)J5n2L@v?HQ7+VJNXQygic94T(DTgPzw|t4j?v{pP7Nhrpo7fspFJMU=FzxG-w` zb^ekj@rby%g?>KjH;RWQGge3Yf3J>YO>y%ILRYL0bsgZb4fIW)Wxv$*g+{PR_x5W3 zSp|m1+U>-zg=X-#?mv_S6GPlI{V%FAIV2QtGCspzl_E8K5YEqU2R~81Js@HioY^^5ymi**Y}pflA178f zA1=V99@ zoZ{%GVC|lsMa5x_wl<%Yi8=fd=6GTi#VpZ;@+lg~&eKZ03a~mGnHpu0W~afCHooU- zrQau`Na~kIv+5V3RCNm8EE(It!I@PVNi@_gA`wBZ@6tpl`|GlDm`8kmHmjeU@6{W3 z=Gs+z!QY9PESb_gw`RgrCjVlI{!UroY{Ulg554%g6CrTHzQ^b2S)Nsqf(*iXC4F-O zl-{7h#gOs#mU)ZU3?mZauJW%HjE}saRL|^$S?ms$%m1ELEk4N`cy`^M zyWgF-mBv0`8an^{urJB8_WkZp*OkiId+DJ+2CWi}C1NG)mTn<>HWQkUAU*M9Wncm?a(d(Q%%Z#q$$-2V?_Zy6QG z^Mnfn!F6$m#oa9sY;o7%?he5{gS!U_?ryYB=+cVqK zQ`0?NRnJq^U9Y?|UrHKGm*_5Y^HrK^QAq@}%y4ryE(})Tqb7@EM2QVl$*JL;>NRQp z*@uW>?GW-NZ1Fp9j_xWFeWjx#uq{&Sjf_Y5Ys$1=k)t5=*|xf!+#J}$&@TFz6cLZW zQ$PG(r!<7uKH$sp;M6uk2yKS4T=_*)Nb9mqUN>L2s_Jij_;{D{H;3|m?`7G6&P=oe z)yI^PkjJJR%4^?(;DW2JR@dS7MToAD)si1|U>kolteaE4zxe>Z!Dj9vzTiD8nh5WZ z^mG>^rSdITc;KCh?l{oh_wR>&&b@QURa|R*+uA0%rx*vvI|xd5&*4Y@F~Z^7>EP4bLeY`?R)_mw(sp`@eod5aZafgs4`5 zm5Tg#shn0Vy)!5Xo^YDyDHC$oOMjz8ZAIUZmk74!Omd)t$T|UpquAw3KfD2c@P)=? zbwTxyKsf4hj<=t*^)-*NkS*8mNO-+$-?L~kLQcmp?RusD+C{HDS2kAntJUBt4%J<| z)nn{p@8Z%}Z+vh{R%uwEGvpZ%6nY3cboNVKbd>e6&a@X;U|=NOAQ z*T!5dUoT?yjnN=fnd6HRFzMw2)bQA;9DYb<(M&>C*AGxHKv~z^+^frH0tw{GRitwu zkTDBZ`vUG}U*1KD3gBDi@s5Wae2U^UZ4ZB+cgCn>0-y*6HRkpI_R7{7FMIf!!F~%h z&1uXmn`tgB|Is-WBX~;DVF~E^=%-$9B~mLZEzi?&Y!|+h&Ycp?&@La%cSVwV*nQt2 zCO37z_~CV_VnrV7N|rIGc%ve<hjWxP}2AQ_*o287-v=mQOI#5(o?g_OhPX4*n{>L3{)P3(g_0LvGWgY z`26eYS(~vW9S-qtKW1ki#>ye^DNVO3mTSA3XbNz^cmGslP*5;+{ z2mF=(oh4O#v*Msf5^SrTke?*Bps_R|_tjLsiynF#a}0fAd?+OOsynMJ&r(bcasq}W zA$#VjIA|o=d6s|tbD7@<5Du-o&^om;m$RwdW8&ye7j!U8AtZg<9p_vceOmmo&2VQa zSAS_41jey$3TE}?hVo8rtjK`{y_wPq6$->~A!A490x?f>0 zy?uS=d%(wO>Jaf!*gBPN-AOdfm_V-M7N|H6NIdBcH!Hy^f4;k*2>W7;L3;N4F-M8n zrURYvzN2yJ-)iN&C|V)d+QUI*TW`v?SGH>-;zHBsR{x65>uY~n!Q6dWV^FDH6B;az zL6df_9vLqxsp4RWkeul+Nq~YkhSVhAUs06`izGar4pK}i$MQmpNirOd;C`=;4Q<*- zZR_!lLj@b!5Y1L2MA#OurH6#Kv!x#Lzf0CeP1Lq{{Kgn0XZ^`l(0^NdRN}{U+M&Px zyZAdu@gscvpa0AkH5Q4q6Mmayquzfvn&kVssbB;D$r2(Xkd&UHM#77_hH9-+f(#X; z6e@^XTug!bx-RFNE*_-#+m-C>VN1>jQjm$&FlA%&>&M_?DVA2Rn7-9jz}mpyB!tfZ zN~sXFZa}mh&p`0ywh?I5-|Fw2m!H|7fG%d^OJ%o+XWb$QUQ7x7`o#V3?DJHN(JJ5u zRT>QvoV|in_3^vdQpQqoy38S@ty68SAn^lS zqP~c3-PxbL-{g9BeS2n(&x4AZH8qVpYfda20=^77s9)~RKe@B1TTM?e5TaB6N+*>w zmv6A%`;IRYtOH7=&U>(kw#N6BRR^v+H4JSSQBmvnHb)tCn0Ji6j2uq8+WbNqYDwI_ z{v(0whK-NupoN+6K@iJrh-I5CqpqK&VL%oEWV2rtj|qE-#?#8 z1}O-jvLW4-Y|62-qK5*(w1Z()y`v=<$R(z9TX*{yShT6${V^26JFnyU01%3NRd2K$ zP>;oERCN3dN4+UrXccPD`q_y#5jbZxjD!v~7_MU4i)jF^kOx;JoaBN! zYlX*%s19n_yN=&m_#y?{m|plt{8lm|rYFRAeEUXiUhDICt3cImb)DQER4EtYv|LY= z*Jr!M>`st_Au{+0Os|GI>Y+9((~F z|JME`%^Xe!McsY{J3E^;rxI&nZH!mZn8CvWB)BbdW4$r!-~r`#Iuv_UBOXZRqfv>Z zAT|3=5K-3L3~c!PTb++H>zz){KUQf;K$4K}YVnHNI^Rh`4Ox;=oO=|pWT&aAWGSSt zSo`H9)EcAh)B!n$1ar{iyoRDEPO7$a7_5`&Y)SawD)y}R%|!}QuhV5=v~Bq>oqhTK zcQFRJmgZve?Fo$;E*BKForILRyt+o#zkZsfczo6A=?i$zy+oM(^OBiL?j!-}Zc>io z0*y!qHB_`zm16TA<7(pAp)~UD?AzmWU|(FlB96Ojq$ki#PUeDP^=ls&4<&R}tq)2x}dnnHLd^LeY{2M#s?-|-Q z&x_WNU+mS(di%ks%&oJ0y|t++VsHb*huHWTHA_frPYBv4q8yan@{lLdP{{7&kno13 zw?2b*LIYsgv|+GUw^G9(P7T)_CbOG1a|C7X@D?-2atv%#!@%$3IX-3k+)c4${`@fm z-Y;1|gOc2x%2AcQd5Ca~;->b9hyK)D2Y-#3h#N}+u%QA_Bd%R1F`2-F$7WLWJxPDm zid*X83e$sQlA9X?=9q7mB$8AEnK%8M#*ZFF0e#YcP_=KasA7U;{4Fb4IHac3KVm=7 zk@%n9wFuTGeoBB`G+>^_u0tf%i!aei@2`_#xs46~&!_O7qoHr+WOr&Mj;{M9y>1iw z;c=P&w72-7=;#F>JSehy=(a)d*g2tf^b>{)4-cJ{lEEbduL>Lfe9#5fD)}d9ec${Z zkR0m)_xXpvnU$+G{*WNcxI2oXGI7q!rz-#4AO$vGM0e%uAj+=LGGkvoFomvWHcHtH zC*#gynWV^h@n!KC^@H@7^SMU*i_Sb7YfZyXGkX~(7B(g+$c9O7?HpMSOdJ8)#~wsd zpNNE_+UgMK4ohgms8ru2+z-;}__V75P0b@SDZh-VNzo!UK3EBJAgZ&PVvgu&AlgBa zBn##W*)irxw|m$?hEJdLndPm`6aYAM>T+lQPV2HZFE!buVy(KMsJ`MoIq;O@ONzj> z)qEx%lo^N%aOu)WbA|`)#ypF~&SGPTXlv#y&ESSYjsI9`)!!Q_qIpJebS&KBQpR^w z6mEbWg;kL$(=1bZsET%mZLQnh@m@(E2LU>5R#l7btyllCuOaa53=Qrfgz!WT;QDf8 z&jW^#`F0cpgy|1Q=GFsjx_jSA5tA>%bjNhdYlK2M3kWxosBQ)MUGCE*EaYLcf*2Wx z*K!@TmxRN?`Tt-R{FUok(W@qOJkY5b0CN_qOd2SJ=LreW=uvf*2+O~Fku4-FU**1M zbN&N$3Kb87>s|x zMouun-evtYtLT5Q=*J1ww+;IJj>;2}l*l2sShhzQoWQZymaToAf(;3D4*rN(E9uE% znFZ9LT`W1EZC$%MG5i<3p%s17GT_94zDLFB%#mX8H2Y$-RCdYV1DAmwl8kbiJOm>1CWQ%HJwBGEqImntgYqj{}^^um1i^%W zk+s_eCf}ZyuHGgW`(7R|@?Re-1LdbVC|_?gRR3c`#2%{0T_4ZRHv4MlBJSMpmw?yD ze6jA|uakYRcSqj9Hy7YZp!j`$Bf!GmBS@+l`j6$=K7%8g@z+|p*tOVG*?*CIeca6x zXe7VwZBPt)PR!4X&s&s8U(ENQk$jW4f8#x9(dx`SfiF+xj?r%i%Wr{C91cbg7j5-# z_mxD1xi?)Gc8{+wIBg-Er0P>-E#Ch*J{HaRTo~rC!-rR}dwpE8t9a0yknTP;a z(T%=Hj!Ex7+j8s+_tP?6&jY?YPUF9N@4@N0K910mIuEd>;V=qA-Op4+lOYpaSiF-o zjNU|K0$_@aoXX)nZ#!K9(LtgxJU00enF-M!e5I1XDOk3mK^MB`uH=InfFr7_j--s% z_Xf|3p^IUh+ukfokq+YEyr8ksCEU!^(0Wa_Bk`?yJz0f?A&_!q=JiKtqJH={3BEMX zgN2k+$Ytu9Vnc7DyV7+T!>j!Fe0x8vB9J*VJ^6lE682zp%!!hxEWK-%n=_R05Pq#frr%gEEw@6?}6&nEA$LEJN#8Mal`B2f~Dz#Q=bqsrNy$QY!H z?x}8M&;~q2?c(P}|BXs)`7ebO)exC-oaglEIb;i6nui4CrNaCUnvNTNFIZ7?=|-|P zJO7j}FW~#}JF4jU4{m94>;>2lQM4g8LXN3Oa@RM;*U{U**N>s{a0E-Gmop7l(#?jV zlWz#W-=Rc${`3zESQ4YuE4jFN^e!jr(^taeQg-r%lHpgAOQfPVGiP!lQEwsIvT4Ol zuT{xp>lf^hm@_gtlad730g4vw1G4f!k!30{t?)WvH?K6ljTmW|)^{EfV$oEZ_lr@<vm)S~st*CpYcGOWSHj(aE3wfYvCc?PP`Oa|-` zd$Prj+XWyL-1IQ+TK?qha*pT1eG=cJ)m4X~u2aoNm3)nZ8p;@E92$++lkYH2gDhNJ z;4boyJ;P~hZ{50oAq+~%PV!&+-Ayy8s)OK<&Bp^5A}FG?RKET+fIh)2+>!busl)6< zd`miLAsKJCOH*z!Oh5HLnMjIiU5Wns$kzF*KLD!0N%n`&!XERKJJ@{VF?8PXPx^vo zGqrf>EPv^|OEM(Z$tG3$-NLTZ)6^5;fDVK$q;_q2N7nblI1U%6WzP?V-5{>Sxp;JAAgB-sm!0wks#l=0vjbr>aGnNt`G zYPBcI5bL{%p*I9 zD=d{!b~82cg1NACZ8l}dm@JJhLCFs}yFeb{m#L0XY0b2&HefsS#iBXRaqETT`y-Enfc z?H5D2@xq=yq2SVL%#g8RiohHBy$+Pw&~6Q8A6DyY6Utx996j3_+84E^bayuv}npa*h z9vx!RQHZ=MOwKkaP4s*wvVJj^-tcwHd%vXt^9O4`+;JN*&`smZ1@SDM>iv${F&zHrlQ^eV3T- zWU1;!O(JQk@getBt6DMSVDz4HLHJs##2n#N6%Y1a&wc~$WZfbjjrXw0iIHu;Xcgt{ z>}f#Z`MD*455ERA*QNHz0omCVG>C&(;$$`KU+NkvzE#X0UgOr3lL{m@fg>a|0%p#+2+0upN+| zb-^N2XP9l}4=FiM0LF)q2;-1bE0$%{U{n@DRLx>2FikQu<;$@6x(e|Jk+C7^h;gDW z-8UcRo_#yfaXm&0S8^R@A;$$taVgMcYn-i10YgD4B!X)9DLoiRW;^)ZVkV@-YyQ+G zX-ecoQta1Of1@-Er)8XO;*(R<&^1@zo zX&pve@KRK)qvgZ)2NAVMR|4c`IVf?uf6g^_%M>p~Vk&OCUugLg4|Z2V8Fz`YBI|A6 zbzzSsdVFu-j}+i!ZdLl_4_*C7*O&xF9GYvUSlo6zi666kQ7$)P-{sXogj&07@GLAe zjPw>+(T1#n`dcRpym91uMrEztc*my|&|@bZD9 zBdbtD2`sv*blZZYF4uD{IQviVWg|4e5oY#-qRHBavMeY~L1?~3!%9l6Fb_e#*2ID# z!BGZc%G&kI{!T(&^&|}|_pu+f9TZYi^#Zs_9$qx`$*?qEOL{{gMAr>bXAIJcL?{r< zMv=?iq5<)GuU%Y`Yl_3;&*FSW$IunMCo)@(SMHccvC9X$$>PUKZ#8dRApzAUDK6dK z?suwKjak2n(k&;e=+0Qhl@*~XO396r4G{dk;I$MQ#YeaLnzVya`}wh2qk}7@LLE_7 zfG-i6KUmxbZ*fpl$|VUlkHy@$2(;}VS$&=wh57S+E*0GmG;E7!)2O_v`yL+7MCuRQ z<-anu`JDaqR(9s!^DPIn&uV!CopUDil7jC`Klg}ZE5%?88{kUJr(l?+<}0FKEdilp zV)Fbf_15facou_8QuO(0i0cTbe@;iY2e-(Oe3kJlBl9>5QQJ9A31`KkO)T;A?=2m# z6v`Q(_6=$C{jj;3eg$aPf>P0OQN|{PO#uxi6q;E{LpgW1%}|vt974t_Z}5S;&_&ul zQC``$Uq^Thn*`Ckeni(G0%xG07`RSU{YIDRGte5i%0%Mx?1dDBnbz_q+Z|NHJD@(d?KEzwI2p4Wif~uXtB74SN zVNct0NS;znrO!z1ycB(CbKg5Kc`Q@HMo5Fi^=UQ7%=HCcc z79?94>*+Ofi}4q=zU*no=*4nNhY|A?T^e(K*iw*ngx=uB|>+6Q^i+ z;iq4C>U6~fvHYO%3pkP8OB7C4s`5TPrDSfMt#X9eTPtOeQTAyUho{T=- zH=4aW?IoYgTi6D4wNKhST&Dgd!#*Vz@Lg>B$aVxWH{WKt|)e541di0>K-Cp2nO09w2K3F+-OYvPBqwg13RGDeNq+sn_3SHN`h_3q+H;xZ8}h_$-6EaHB8 zX=RDvt!poj)rlkEZ7Khh%Tkf@{Lf=!r{{$F7KYc!V#?#q@NZ`S8N0Qf>>|76y&pk6 zfyK2B+jsHTt5#jFB0X;x(qv-mpGn&`AJ0jStK=Q;vQ6tt{;Z)qvE!Q%V)v*qHcuwC zdGvd>jsaFzQuJ2d$CY{?)G*1T&i6!C&PeOl2H0cv$_q% zv&XwC?I)p^(X1eQjzQeQt-Pd$?(9K$f1mbm;Zsz!7E9Ln3qcdn&V=axgKVzV_O91ShZ7o5Vd|@}$bCyBy8}W9{)Qt2x?CKy%q@y!7F-qq+IyXhD~+Eg z%MV^B(-$YKv8oNUCjUXl%&yG#8-$O%v+?`Vcl{0D_#Q+wG`};SzWs(y)B-%b4TG6` zrwsUm8hoGatq#i|oK$?dP>hrrogtV zFYTIbGsn@+$Rx8@Mjx>eo{*)afmY%jJ|iA=Kz zdA5NX-)-1l6>qyfEWiw$H_J1TzwEcevizEp7dc5_ueR|YPOpS7I+tm`U|H-|C zr|T#o*o~N-EOfQIlE~7QMnp~P%%-k1n6Psh^~locIduj1JY{n68;-mCp9=^cZs8|c z@*{~iF65HeGiR9m&}CaVx_ZBOU)Z7~eA4f81mq|Dh>ryH8g6OJdF4#F&+t<0Lw8Z_ zBjTFY)>v)@&LrF1-GFFJtlvV>1miKZcu^3eC8=*voyZbu+>E%lnEG8&MALY7&!Uw_ z7mRw;H!fIhv9=L^P);lc3U(kRfY;kXzlOf!g(&`yR^WPyeD=r9%Oi914zWlpqR^(# zNYCVi2!62~{anQS*OAcJ2_yWXt#$I0K+kXneoBqIi~%fWJRrOuPL<>je)0M))kGw> z$;OFOuy#U7Lj3_M6mq00GpnCDhBAI7RnJkCNvc2C0JmnXN}uP1`GY!wdgyTFGx`wC zyQy7P$a4S<$wtk|e^B3~20Di0Z* zxsVBpcCUS;O&(0fR5OSF1M_UB92tcjZs?Gdj1P#(DBU+xd?ipnH>@$b(3WEgBqtTC zEoZ~D$!W$3zgpE7+-f_pSaWfZU;!0qTcvweQC^>e6V6v!qvAv7{m61b&q*+}(??52 zz^JcPEok=MRAqFgf9ByGGfYLIYw$%0!j>LG979}3Y!RIrn?7Ov1J_^Xe7tYL9;q5D{wp2v+zn zqw+HBTi$Rlw2ES%UKsT;;WRI#if+9Sux2JDHs7vm8J4=_A6?(8XsL1Zj`0eS{nkq3 z>vUW3T}cWFXEP(AJ708aN_}1xIO{Qg_eOz_92C^Xp@yL6R=pp66_4>w+wr)Uz+H04 znOLhyXB+5lDrM9qwRQ7M4)hc8;o(g8t|noBR<}>E55G6iG3dAKLe{+t8rq+0ru}z3 ze?smrG5Gfz<|=a(tKYr~IgdxWI23CN;_KX>sX=dSSv*^-Z0>}*G+4ViljS_FBA+GW z1+6k173;4!JO6SE;hRjDBlaZ$#%`fx1sRSDa`(>oF2+!huF7$K7VmJ>MdOX=WT<4~ zMb5qxAnKqc<%kf@qC!7Y<$rdFb`;Qh-1M7R#Ov#{4a;;|+~?JA>~yRxiRIiHI$d=Ir_huROF9+REBTMbu}rdcTPSm~>xHOF5p* zw!;^}iCn&p;54k(7I@-ncy{3p@4PlP;B=3#xZrZoYECbksDEz9z!q{AXa?!?{a~NT zuGLh_5wQ9Bx)ZY~&_qFGY&WZlD(Xh>oT3dL> zV{NFteQ}BYG-N3B?Q#%s-*q{ms`=nm9CjD)S)ai5xn?U~h;HcSBQ??o7B<#U4&J7* zo*W_9&;XU(c6~j?a$_6I+FQ!F8Z25B!)k|!B|ca4rl$E=J>0g5H0vepfT^iYzP#0| zu`ziY(=-1M4yjyM#vey8J+&Rhf%RA|1Pf|b*6pEH@d`#FTvsyyvYCy|Y^@X)P8SzV zDp!L#B4wyMd%uex7ya#$g$P&Y@-QZZ3!9K4LmsUFn}@!ru{bW;z;{W^?SBm&P@y;I z`lNHYzMGbx{)#+_T9RB1ZBLMArDPav@GW9};(Pe$-kcoLa9ngnjk&iR)&Cv~nUPfI zq#qo_0Y-)}XsraHLa`kBw*J@ILkQOuP6fG2ogCH-+LsSE?(#%v0?5>o+roc#Ly6HI zIfb$7=Cht}bsC#TS&s7cl7{Oo?TQ#0~vgwErJWIQ%9dv>qm-TIQ z?Dd~6BH2ZX-@!4#S%r#{M3fTW95!nFpVae<_&zpW&tXByQUS!)p=x$XRzzO}o}Y+$I2YdCC(13~ zkkrRwu&@Nf$JI~7a{>T+bnitve^11DsAbXUu9SZIM-f7nhe+l@so(l(M1IE!AJ`xK zv+Pc%q&x@R3-L+n!eGncYgUoSm~10~b6SL@c|j4H+z=R*xY1adof)MLJXT*5Zt=(E z*@a)5E}9IALBmGgmL3qx2{f^;!&p@o2E7J$Q)yX2l2nyj%FMz{WhC>#&lUXo3QI#I z>^wtuP{PQG_(HQvli(B9wFGG`KxfXx24hhb4rL#-hqETC0R`WCu!?w;H&W%uuUNEM zhosdG`8fyqvD8SxrXd$<>CU4i4{g5@oaNFSJR)gs7XH-sT?KWGZS&L&HG8MaA3hCy zR;6t5>UeOmXT#q#Q^X-j-+vx`eb&**~Ax5$zepzrEFYvCfjtj|QWQGHNT5B$$6Ub4DnQ01Z~nM8lT zyOxj5&1uQl0!fLkN4HtOM&IF(1$Vm<+UCt`JX`UWBSOise1kuU<4|ThBCh{CUij(z?K%G$(A-7*hDhUGMJNR)j9;SMMnP6^EHWvz@O}6ro^G~ z>Eu4fsTX7u`RCN18LHP)6H~~Wc&rT|#7GP_l&-QH%PWMdk8oS5470qEumpOtz)c$> zc@OATcu>B~(vZ`XdSi(dT*U~~2NMOkfEZrvy8vG!X14R6t3`1N-=Uj|Hvfn^HAveC zNG4^h{2=wKj9~py`Su?r%}hMepmG*15=C7VAf?Il>uJdvk@8nJhn2!H1K6z+sqrkv zV;biOBDz4{xJbfQJy=0Y0bMs#t)QixRP{2@E+GkR@14M^X%)W)n)w(~y)V8~jJrbv zfb=+4Fqt?_gBDt3p9t0YQ86v9=XIUy7SxYXu805Gw5ThS6Zj zNfA=;7mPiZSCtBnt#Aqw!DLORGi{7S0G<=4P4|9U|6?bb*hgCYAcjv6&h1rDdXIc5 zw)Y`Ds!a0KFO1S;lcg%7TaeXZ`ok7m@D&kKm;0C}gEv^@Mm^ec!d+yf1|2*Kj+v_+ zrUjJK%V8c@@CF=O6bUq|F@y%dZcKj0cKj?RiPY$1uo!$laL?~5z2OXadVL-$7QH8}ryQhmHk_8hTsqL6`l5~7WBmm8{@28LL0MyR$Z z=smJ)I^w3f$w+!QbzPn;@VHUz@@ahF7N0>Iq6N+nHphJSGev`fDi1JjKpvB2-+%}ilf-2*2!Ie zdeqyfmNRr!cE3J@;9VP0>*aEPB@c<>kT%A5M6D;19OZgwHi+$7A^1R-4OOCy(vvpZ zhG|#dK)Vml7JaCUMSTzGZ`4#R1S18?4dHA9Ag_ z4bl%bS6*&Hw_wx;Lhe#OD<3|1U-^Vz7(IBuD6Ur~oy_8cuShsH#2SrY4h_}&%E5&9A#H@SXS`hZm)$4JlP<;!+1?HLK z*uWIZJ1LJ6)r6GsbAY>I@q^?-hN@A4i=lGmT|mx1tCJk2BO>u0XR7YY~5C3_C$$y+;#+mF7}z9pBpM_hmlG+`g1=b!~qv{(y7mk^muA0tEi)h}@Eyf~**vNQFs6pzCGO67Xqk zSg4fmQ*aT8mXciIugcM3KjS9*slmeU6#X(5D^YXwB2d8Imzp06O9sf-4c?y|TJq9# zwz=jr7oo8MX<$aIGWmJo^bB(8Ijc%n0capR;{8Z5a#V1J#+Tp?Udy-ArlH|2$yXE5 zO8eqOWXuGvjY52W5M!7w8l?;O50r*?kFCM+VibEXzu=Rj@-^&Bq$gGk(WQ?r4E z89iH(F%~#dfy+P24eF1l2+$Qiyyjyj=`lfY2-OxqZOamgzK91h26)-IaPOcf~&`KS1~~$uWlKO31DdPLfN8E-ST>dloL_fkXTws*YUE z8UOe&6X_o)(5uPvouslVfM%u06tLNuH+CCpXp4?Q*Si_rs6ujc@FNJm?)qfyt#a#6 zE!P0ajDo95E7Z=n1}`?DWkl=ZgEbHV;hZ-~XVKErxHfHKn{X(P|6}gq^x&^D)-_Ig zFh-9hu6<6E{(ppTRW}kj^%p*9Hoz?Yb7+lBKTkfzq}KU~A}DV;ae35j^p<7AxE8~; z?yETulg$A_jOnQW-i7jbnw-D`(H=2fZ$+}Z;|(DrYOwkqjWgKl8aeK|Ap>AC=xKPY zQ)CsoIe>#AUMYIt>VP6dNFEUy!*w{%Ey^zkti^+e&l|y6=x>qxWnNg+lvo=c@v72~ zhKM1;T~iTKenqWMrreaC<@@s}&=5*5(Nfq1qc}2LcsR!~o(6hL52ZSVFm%nwB(J_p zDRO6rfNWFH=|;m*GE_rc09ErFfFnbqtBys**C-l-w=-9FLd|r84M~dJnn+GhQVtMS z+wTu1a*Ix~kk0sW{eTF$%%kaD2*Y)?Jf=v9y3U-8_`nie6tEBpy?F>xqU$VEUs5D0 zM+a3CZH$ukGs|G^dDmb+%FyCc0s7%6__`7l70E(Jry~rXtcn0MPaA)#Z*SqgvFl#x zc)5Yj>R+-)22s^tZ6afl#sMxZjap8DRhpxJaX}p*8iU1Ff;}{9Wa{anhGjE05?n(Nw)1xePU`L=#D95g=yPmN0w1>9coGz&xPHR;WMW{v?id&2|@@T3cA492^6I zh8Jo|$$p%@6G85lip28Yru108O4&c~vKI1}xRZT7c!P}xre8C9H2$xNKU}|1G&AZo z|2xM+fdBpf=Nu1%MDmXK&-e9*2Qca$#q9m&!FDt6XY`21u*T?N3FLxk-zasf6g)et zXpf^7uHxLsP0bTKAMvH-@#NK0eSbd8)MLDwOx>Mf0gr#%R7>fIy7-=767xU5Rk!t- zSI2yNIe$HZu`raOYx_qwQe0|0W<6>X^o37-;Ln1No5BFD9 zTl$vatpCr8%X}UV89g7W50_VFMxO)U&|d#NEvxoDhV-3k1;xE7LX&^~jt4}cs0Vz0 z`j?@q{^5D1{_W|`M4$9+6Z+qUrUqhML-}2M%iG^HSck^J-jcsCz}z{E-3J}yFSiEu z*Hl9CJmDU6o9O_?yUx&;vr)f`NFT*-ORYfDBp`K7BsVlRpiD` zj7E7@xOpz7DJcQ^2!PXl%(e9_?$b+th9Dy{3#QTB*+zds3}Z8#UBjA~pJS2<3{g03 zk*wuk@r0fRqh%NNet@9#s2?Q886kp5kVHdzJMVZHbZHYBUgBXq|JfUvu(|;1i-(@E z>*mh5(_TG}pd7-qbxjZ@e%z2S)K_I2v#LXSE6nEL0q&neZ{W|O+iui0C`dWt{nY_lGNFLVSuLUXJmX41UmpjWVObMO~Q8?*Q?ACN80Sq@NN8Z%Z8yzpyR zr`LRD8MMW2fN(^0X-hMw2Yt}MC4ylER~Q{j0YYKvn1DfGGiuKz-BZCZD2f?z&$X46 zX@nq*S3f!vGa&7pry{32K{2Nd96%hhgz8_Dv3^bvW}KZqV}6Bb&acQ)^o|;oj$%ua z)neuV*^=E43uRtU_24wU7<39%3b26}&N`kxDXr}VpzVa-YqjRnX?7yGc1cWCFi^eE z@01Y!z}$Z?3uEMN^x8Y<8%hPD>f}WPvolQ)gsnG>-jPMRd*Ev+4X{?0Vn^0F3B%7fn z0d=PLf4WGfw$z8(-LWro2-ASPe%*OHJ28buejfZbRy`X;q8TY&rVYVYnX#;> zxD=%Rgi6kYBL!v^cc&narQ=%&nF=@G4;{*FPQCfGixv0@vs$8rfZ=BHVADI{0mhD~ z&+)08iC%cmz3Y}TupK@kpYEx7ex=VbPC`eD;SyJKYaQ(%UloH{SUe`0*~&9JCJtuxD^d^|0Xt;3k5cm&asu4Z{AC4cOC-k+W1 ze<}@KCDJIz27Y#T_{DGad9G@G%!%rZEGcUx*#Q8_BYVcZj(vL zPHerVG|-gQU#8DW`!KonuhE`#parhGSu4GvmZ7HXOk(XxX0Nl^(`u0yXMG(Z3YsAF zJDXAaoYi16Lu)On&(~nEt#yLC^)_tre_~Y_X0+DTWXXhNpWti&Swi!jP;rD;?@sLI z(w}TbMz4_`uHTlF)-|fV=P~&l4Q^xKwfy!Gav`w-`o#iW!zVCb=JvDwt$As=4O+v` zf1PizSZH=Q>U5>uo^;{Q&{H>>bY5AUDKKiITz~Aew--oc-|4&KsqP~9Z83CeT)yV- zpe%|}G;=(hE0PV+8`vn}vJoYJXr__mEyi@T_uc7zzAc^V0_DXm{9Y<5bkkTR5fifC z1_@|W$e*^TWA-O@n;>#|*z5}nVE)b%7IoeR@$7E7G8M-P#|Usmy|m(Bmvjuvg$7C9 zeWA3fcaI_tj4UW>`i#eD1M=UDMV^D9D&`@IkQXE~m+1p03HEL|Q6eGFD`DnFNNURx zT`2MGaJXrsT68J0kv_&06+^S~EC#*1lNb#%T8MYp5jlSbpAgvf&1K$1gfdoxZONO5 zUKM{6KG&g5)SanOv}12;|NIb6H4r*t7XErPIlPK$75lle0sr@8d@ZV=i=$IdRcm^7 zwI}EAhNcc+@7NN9PR-Nt@F#gA;#k4pV$SNn8wH0d?oW+nV1S64Ug;hdzr(FPdETN? z@1p_I#Ac3qJz0FLyr)vrr;5esa6_|3=`K#0GE}N)n~!4@bHnetpGx{*&zRd;*@!9Drhe}RCYXd27Q`Y|tIW`!~Y1rW=F~%U>O(NZOze>TrSTos5ei=~2Ry z6X5Gj_EXMDe$%-o!i+Ip=<&xPJ;kXcc^Rz!CUT#c2gi74daoK_bt9M>g^X;~UPyLs z{uDGbNwa00RWeyjx3Lp?V}ewzVsG=1gtBf)E?VViXi`~IiD`%V}oQmFg=&{a?l zrt5-p5C6!O>5f;42RuD7SHin0!_PS}t_zqw>|ItLwz;Y28 z7Lk0ah4`~!U;wC19dmz~6lQvv2a|GU8Ei+aeIHB}@V8TyF;6 zBVJ@$KG6_IRK0LNoq7W7RksoxiDi3n!PLRDAe}p^PsO( z*=iFfoVi9>KHT9uupsirJn6}jQmem0h-riEUOb_?AUnbSBE)cqTv0&k5ck7Nh}z^k z8610J&`jKS6;{-i*&(d@Co*lp6ubA;jh_qfEHR_KsfEDSV|1zh?CB>=YC|8tT0PxF zR(_g;^F(ReIxrz|2wor3cZ~Nm@o+YRHKF(WNHy0mJA~RDq5n;hV`?oh z;4NKFLkZ*I8M}8=N%T(axpIl?B z>0`CKzd8c3=cxJyrKNh;t+115$s>$Ylz&B0I+MoX`De^u z?2wv#v-jbuHL-u!xHHrz6fR7d)pVRH@1jc}I=@d6S1f^TiisHD3plOTOa~AW_n1p4 z2-g09cr0<|(&mkM$w^k(MA|w+m49ZGBggIenbUF=FI#0?@7VuDH#dao(z@MiUheE9 z{!x$qNgMR8(DtAd7L%3>6!U=X5}9Zbc6I@op*<4|Dh6Bmh)*TSa)(r)Ls(YG)l``2 zIjKb!p_2H{h5$8$Sw1(7&n2?zkQz;H@!BNFrYbvrAnhrw<8wxiG_uM=r6Htp;^zAca!mW^+9j<#hsSE+&E#| z$%z9hlWWY9{<^AKsa}B6+q4voeJc>>hBu^YXh6Xa6ddc2~&Er0y9@G>k~eJwXgu zC8d~zNB|QZ=@d~IbtP=SN_HN#&?=t)u%8+kh%OPOefrwy@>l7C!T%s$o63*_cL4^M zG1cs{JY>RDo-?M&0{9Zz#w&Ak(mlnt znEGyZ+bSyy@8fn`PWGZNyS>*i>6l-_9X9$VLbIBL?=EW7ipUE;)fBw5D#bg431??j z?1cc&&_Nu!plqTgEL^uErl^3{vbSj8-&F(utrq*iwC4WTQHzPJXUGidf@@(;kcgn) zp@`e6!`_BcMl&h&O-uDGzlI3)LQD9xG5c&Qy1WCuinHO5mqN<&{0u&#uh9q=Sk0iI zLkq&k8T)#uXQUgUxn(Y#p;546-e@~8)dI@x1XAGYYZ(>H>YR0mZQ^sT?sNk6`%x_O zLx(sPgi@~dy>#NlK+2R)1I)bYkw>{Wpx6FRXnC8R?*Qyr)4h`}>qvzLro%}y6iH}v zqaM_shLe#Di3WU<+bB~Co3utn(u8I4a&onQHoiPQphCX5(wXhh+0%|7884xzi_td`QI=XA_MdCHF(owckD=-zp0B`rnPRPL4o zeq==bd*G)u+BwT7n@9&8w|e4)51eS9S-?QXAZkj zv7kpV`z3x{2z=;U>Lvi2K_ar({MrcTsCRE&C*dp%d{{Vcdvh!9!cS&)v&BwKC`|!h zfXwjvq{omw*#&z9(Tw1Ls3Ik(X^_YS67cMBKs)Av44X@_jLFQSFkH)=hBA0nvq`6w z@PlZZHX-0j3O*M$^s`}NoYo2WYTc)r!U@JTTc;+9Bo&VX&TjT2Ow;S-X{2q zY!49HO#5Ng(thbv?FP569;Ce>~~KW-dzyUr8^BeVG+3{^kdf%BIV(_FPO!J$SbNAv2Kw`>rS%i#bD51X~mY&Pw2t5<+dk`Vc@ zZA}GPXjgv8B_G@#6GwFNur-0Yo?QRfif*fl)hhMq7 zQNhxbEOl?jcxt2i-L=&L7zL!GS^F~Kmv-^7MfaS-g)T2E!Rg~SW%1t3(F4xpDI#&4n>Drcb{ zaMEb*JXhVW`lZ>K{h&%$YK5;8T{yKXuU**NitgG?;!p#mf=2)11B})v2xF@Fb$og5 z2A$E;%T(aRf#`6hSiK9G<--4F$td1NB14zzMO6j8wC50r!4wB;K!{{@3I~20Z_Het zHLu#EC#T|nJb=fHwtPqe@B!cYAz~*`r_M?xwt^Dav%XOmfP!c?ptp>u|L7l}1tP&e zI|*re?=Uyry$dH;NW8yPm5rZK;Rt7cJW*hWH9%NrYVD5(1~c zss+w3-|XVW<#IeG!0gCvriH6F3#P@w(}Djg`G404x75?dA1ofas6bjTad&nFz))D)rpEN>zm1L77EMe#d@TYBoJb94OB<;cAH>4&bISbLQSZ^+Q1dyl_(y)>O~U z0XwfC1U_|MVNE7o#+bheV9q1gZG2BUWK;t-FJz+krDIJBtPHs&_~K|1mx(;7!s)}U z5}Y^_e__+$-)R)O3I#0D1y4H3*tmlYOtVN~UkisTArjkajw-?(6H|h{*VKFf$4|K+ zfVm!27OiZ(zcTRCf$Y!#rQaL-JxgfY^a=#Wxl)p}IJZZMu+K?$7l|%h&(-7ZdX~WaS?(*Hdjr8Hc%w^f*=q^dGohe!RrLoBG!7 zN^7}fJWrEj<5A%G1*e81K&j}Dh!$HbpKBB=E<8?*j4&LtrwutYJUL#X%j5PJ=Wn1i z@xoJ%Brawj&IIlbwtIVb=g4Zs=$GeFUaGz7r z@B8GB_Q+9NQV|mVDy3xEBaK@PPUHKp;(p|^?fcSG_r050`8IQ|J)Z}rd zM2?SYEET_&W}?9HQ?)RdcX5dE1EEeF4z6QaH1c3FWf8j8OtwqrU{W#M-|u8STRkeH z*deCPEpqQBFpvlG5sr^(%8OYRgoC;%MSTkRh5d>`!w)&Y=8UO2V5t+T_qUQjB^m|6e6Q|}Z=Z&ur6V%$iS%}T5N+Ml%Ofk8C_ao}Kq93<6_f)U2PTU!U-(Fq(kEp2vb%bvll zVdGz{jCZ~#`g|**XnzNnGf@^2^)V)|LIas%Cu*<+Y^lK7RD$>kBz$WocLo2Z1*SpQ zIB$!fOSA3PHT1l94#+}_reBg%D3=7t(6|$&xmHdQGh14fGD>TJAv982JK~F^SwJuY z7NAxwFGq%jjR}Au7bMo_rE2= zIpxi6H=g-guw$iT)ENA;1HZ|A08?qh7L%7P;~2Anr$6n<$FatOtZvEJa6YdOOE0BQ z0!VV_cMY@!qfdf(q1@27@xOM(loyFmr)}K_nO7Hm(kB&JX&cj0{c;KW*cs6`0 zFqXI%dmALlgAgj}(r{$pLi!}XFVXD-W8sy78-reK!AICsdGzVix(8-hnw>>p6))vh z^vlXb1Bejq>ZI1dd`hA zNLM#JH{N5O6o}F4Li z-ihcFqBq!gD?j#{0+(BfP}bJM0u%^`r;2Npzbo{UmiS;6ZDs=`FOc?roJ>~PfEfC0 zwtn7I{<2%2zFAsIUF^A*-F%&x_OLmHKi!gaxwT#wSNjjVM31z};o?_Mznn8qTkrdRlUP&F|x~ZVG7=dOP?(Yh3Z8P(P=J9;qE$iv^jN8`aEra_2ujw~luo$FJZ8id8gzFFK*NKF=B~qEcH3 zlgLJRec`L!Df0Kl`mB5RVKx^{#;u1pfM3nAkHl}HF5a~N{Rh(&t?My~AQ)kGG7GoS{SUB{dq-)$mK;??+O_ZYYuNX|C$cNlR<>UQ0g;JvZ*bW&`qjlI6C{!7 zB-wvYS)e&40bctg=!={Lo6R=&9y5#hl@^jo5sqJOR6{D zo0-86W;=h-(z+ejru{B{Wa1FJnMUL+0qzPK7OPXuD#C7}A8A+%1`ik>gKo^fyPD<- ze#$7%uFIO;z@{0x@%;Pq2Sa$q>}N!FB0dTA?|G8e$yPcw14wrC0Pj@gJz;8o2E<`7 zXbP1=p^h2$*oHS0gbiTk2r5QTFo3-T;S%%Jvu#Aj$AOBOm*ou;4vdE)(K#Zq&z*qh4VGzA(_zo?T5BwTEtfV4d>XX%yPPmh$+jx6DNF8QvnLj3Nd?4Nju?=-Yh z^44dP`OH3Z?k!Ffh#oKA6%Jc^dUAyP1ie{j{C==oDe_+)telkoHc~%ih2eB+_=+i? zb;+Nz&2-mclEe`1DOpG~bTE53hWw#A6n|xRMy-Lwd#&R|+#W~>W(l+~2-15Bc|&>V zfW=Ksn0-_UoANKm{T54`G8oGCP&ea?n{UD&qIw?cFw9jVpxpVBnUje^3FfsA6MqWf z(zF?xQJsIrC{Zng#?8s-vWtH%ksuF@u?q@|My^En46$oR<8(gL= zCD#hL@>S%#u~1WkqsoOe-7qy5n*!a0Dh1CRbA2ln?HaIs8ynhXi=7*op#&tvKYUcD z>It^F%3=@~(bvyr(R4G31YcPV;9yA)lq=C9Ih?~*S%#Qwu<(IAoh85IhYaUgqXn81 zSKP3jCvDk?9CtbI`;zowj{n1KzlpkGxuSwZm&Sd(su+DXg+jAEZ_6B;=?6#7BWf99 z115;%2^v2TK)pP+$PwmlW#^tYv5Bx^z(lN+7I#lY1_-iz_tO0IlEd{=1haVNb=MNu zI--=0QibZ_zwscF_6i7L?VDg2GUi{ZW<%H=!aGoPpd(S;HE}*5RAKspWNyeMTQabu zQkVh4o64CU<=QXHMLhO!X|CCh^+`;{)}K;nx*sc`Js+^SyCq}_$rJQ->NT|J>37-F zHP%A=f*Coj?KN$Al9=6Y3Uoa@g5q<$nCyYCs_!FCw;?DpKeT+|y?h23>i_qgliA%c ze{QlBzQ-@P{BFA5h)F0zrnmIy_GC8L@sX)gK_TK==aU%~n&9Sj*F)xO`NG5Q;S>Ct zpkHLpn3m|TI^TDE#FK?fMw~hP0+t^i&=!>mD6uyK8E-Rq><)Y1gyhuU`1#zNUc5r% zE77#-H38CAmUY;3;Bd;$yfy&^{>A`%u2TPhKM^&eFA)oRTgRT`rEE}_4u?fYI+Gky)ky8B6bMHkADUStnX1IeDws)bAo$&*|tL=DBon(j;qz(D~Y z1j7PU1u{#r0$I7Z(*Gy7q|N~zDfzvL2!@A^oi|-D35^5<1L?kIX!KPZh?-!I4C55Q zbBP+lSISpjRZ_2*SY=qhb8lKU`fvAZWRi4L5zTGkN#8d93qAJhH7V%%p>Nw(hT}oy zYWef!;qvqDT1dT0)zi1@?Jbv;@93rHx#IJEJzp>l^mae9?f?1p{rc#W0&h?4fpm2U zwOFi1TWAoZ`c4x$EzyJZPXFF!AFaZ*v66FDrM*0p4*GMn4SIQaB|ROb3lsgEBo%sp zo9bRM_g&iAEAR7_TbuoSKLPJv)3Mw8JlHG${76fMA6ZfG@=y7^{t8<|JCP>cqa)I+ zC-O2a0Jt6KZfvZ(OeubeVea(hvCY*Hvojxfuvq zHZg$2{$wqsqU3%2QTlwQyFF>=U@cLS%|^4ws~Im<8#$!Q*WLDgf9&azJz1=7;l8)B z6(}+MGVg7D+Q3*i(*{j!b8{^B?<{>i_~7wFev*hK;HpN}B` z_Aw0Uag*ALviMC0@lNTIa#m$26{m<x&KQH$x-+ABST6yS~j{#;v?3z9_JXXwg2d`hOI@zXd)O)dyP@C*7jRby*gBxi#4< z_#_tF83lFX3O;$PnQB}uTOBUiLjGQ*qSIeCam^wO{BNDp{Y2olw_L5r?IJ0ovCYvDeh`(ujRD#}59^1+p z$MeiJ_X&~{GWvt%k?ykW&W9W%1wqE-Ah zw6xsxo4hI#T-pXqZU+$f8@t9*meNJ8eH(0n1c2VUsk}~V^9lM$D0zOlamebIA)42r zYFeC5q!8f;05V95Ca6-H>`NdhQyTn5rB1It64^)H>MGQ=JfH|aMO9>qM)esi8y`TULM!>Jg=tHs$M}_2vK#d^Du$S@3 z;(tUX-J9{rV?QpW@tSG(YI!nSGI4CKH*JaD%HT%}#;&6LeLDYeHOQ3W`JITvz*V0s zj=?N0bs47lq=NJx99-YfdYMzLB~mYQ0_^i0a^|>Bn_DPU7!{IZbYu8B92SZZGO>;< zRl*qQ$1x)HNB;ciWn)^Oeu~xWv+0-xI%ZaGmVS_0y`HESLssdv?aGBWSeU-iiGj+F}D!SN0%7tbC{kl-2x52)5XUbduv9ThQP5XC1DD^(&i z`_|3r9*{qJ(t6GSpdBx0?(o}!JQVp~QySUiVd^zEW3+Dv41JN2BV!3EnYN~=0X?`Vsx<*Mhd*R;i5m9Iyvcq z5&wm5mCDUD(@+8};sY`dWADD0krh)PdYvD`1%Y2JJkc_waC1;yjt{LnKOo#%JHl{{ z#Xff7@;etytxVSnFS|9w04dsw%$kJz8Zzr&vaz@}>KLU>_h{i;pM4@7;_<2LRnU9WBr^Ob!7r%}pUyqn!Q-<0M%u#@(JMEC&IC z!0#m`TjKH3x|C960YMDp!_Er&MmAC~BJIwNNF3~rAiSYS20IoF8=r=jeJhoR1422=v0eU32aQ=bL)ATa1Zk7nsHJqyaA8??W!aqPM!4*Q!V9$US23h4OYE8LX=Zbc#su#?zY^bQcq9_|A@1&MX2% z5)}@R1|(GWX;E0*-ehrVMC5Ht3Gz(1R@CD_~F z>&IVe;!I>sk%U1o-;hLfY(j7b{)S7iGKZVZe{Pgc?ff2Gv<%(pMGF=Z6`8-N5#QP5 z0k}-{bnqt_*CF!Y{E-(n$z_pRQe5%2-(H%EgfY-bkD8G1bV6Z;xdkToVE3?y69irD z310$!*-b@`{Q2tIea`ySUFv1n6g*?k?Sp1M+N&c|lhy?)(!a8a1MhMS2;ZVrEpuh~ zW_tGKJiuOu&5uQp$IvYuBm$EYrD#!G&LJ0meaNBQic1obtG~T@&)c{CK*z`nJA0N97!C9hwQJBkVI~pRDMhm{pl@T*Z?8C8{wi=m)YvzIful7;saI4=6Yi(Z|wZBWhd1 zDojxZSmcq&jZJHqBT9G^SAu_O(3>;4nEve49m|TCmd~VwMuVJ3%*15M>6Isk=rB*w zA7k(tr(AvASWT=n%A74>9h1@}r7fprLItO6pQ{;=>UL&I0k1CLB1XJiwL+ZliTDtB zSu<)uM*Rd?qq_>Wf)1*@3!0>r9v@xyRsFdE1VeTDS*W#wYF$LWIDBJ@%6P7~kr>v3 zL$_8glr(Sl6U$rGdU^!5@&>H~;z3_&pthunt)bS(z5WynEAHk3x5)y{eywuTec_J7 ze^u`49h7%fM^uZ*54alL)P!@EEw5*X7cPhg1-cH~OQ1?h6eh+4VPX*OpEYb6Q2;j{ zXc|9zE+H146*W!-D>^**|4!mN4tPxGMjIpShI_&G4$o>|rF;6-u7uOb|B4WKVqdl> z51JYnBLYC3TRzyg40c^=W$n3z&9oRmG^nNN;>LUw)rq)L^XNiOcf^nCWeC-Wa&W(b zL|>Ak?p4!jE+!Znx>FaoFA$>fu`Vj4TJRdz^)mgr%CR+v>d;z_bR=uEqmm3{(#eDP zaSF?bvgLCKT&kIUv52(W>FpHiEW{k#LizuxFxGCid>^a*?oyVUazoQq>l|n|>eA~|b4HCQPGhfcimXm@ zU>v~GoM)GCaUwz-{`7A5i+T4g1HUFcf%W=D_Votp>RyupBr-AZ0gj?R)_G<>COxHJSbG@r;W+jXrYg z6&l%Kb~*dWD)2?V+0*y;*T(9M*rEnOA^#29-i@oBnA|jqRPXYrVuVXgXXKlrsN#=} zs%_nKy?0BH9-QF)?U%doxLZ+!Hgy%u*22oZdAEf@er$tkV%p9hDzl6%q7rbC^$Z`W z+9k(mta`JYz|5jxFv*ix#N@p-#{>cLvm#*3*dhuAop3}O{1gmq>XaR$HE7Rr{+f)6 zqg?LMt>ZM#F0@!=t7e&w{#iHhM3uqp+PQ@!2O2qKH)0BZdcj++HioNnu@%JV5>oB! z)6y|i!d{yZYR(rzbBr68Q2ZsQ$<)KiARDXGKHuuJv~90flYna2-cC0F3NUJsqTi9H~ z7z8F^*@J1gGbx0r4Z&7Np9;^ zE&@y=QVZ}0#&$!jVL!8du^rB-k5ZvQYi_8?dh2b0_v!JY#|*2vf|Ey;KPl|UT(KTw zjOM2a?s*?`aPvh;HC^3j>vd^X>r(i8x3x0k;-XI_YkrI|J69U$W6Q?A`K65+%eQW` zeaqKYMgA~oNQcjg_|(PKw^dV+qETaG7-Ykk*hq#Y0$`KVQ$% zFwmc&d*S2G^20_hNh^F|Atvo^2#JK!v|w33G%BK6)ZhVrSx@;ZgLATtFj!2sC5S0s)8ospQ6d5)$#N-)$4|O`#jyH9y@CXz%ACYWs%Sgrg2%x^F z_UyZBF&v5_wfng6JhLGP2^JdGMZ0~b@j5zVtc*~!O&U-z?H0Jo+J|?=gLY%~wg z2*VILH@_sesZF-Rbv(fA7#k`Gh_rKsyFZgj?bOnOy(Nbp4sDe~T^E@C_yN{B>$+n~ z7gw$UkbWrG0M?j~g*hjKw=fzLc==AE8EA!gu$HS9$R#VZl4vn=+FyiRT9~1IKxo#x zU1??r;|Ke0XUMN_v~9o)(=^HOtDg5R$9&tcJGCK8z!oe$@kZ)bE_o@KDbc19KF z)TKQ)26LF)6@vV)2`ybXMtMyrNk~33T(>dEV>>$GjDxQ)K>L=JzFdZB%IUu#1Ws`E zp8;;!>Hu)N-_r=)&ZjnhUl+mKLP8 zt$WMm=!)eVL_08^yr|tkc}qgNs1MN~bx9Gu_Bqfi2a3MLD0V8ljbc0M3Zdz1{ib6l zcXVT(TLADBO8<&jeAQ&%bhfMMm|8adrO*IL1jd)rMz<|$z@7xEzoYhf>(R*6R|rLbb_)TH{dXaUN419r!!d!XmnGwH0*0-oegP((%H;q!q-+0 z5|w>X6(=OVlwbTlz&+0b05y8yR#{G}kr%-|ukU}?%f@uOui6VJb4`fw03nlkzmQw+ zGRPFBnU-Vo3DAIHO*Z87$?je(AbUh2m*TuB_pMH;mlig;Z zvBT02`h7QrM~lrh+Rn*zC1#I?UI;h;TMG?uqb0G5TPDLoZ4+@mR7|4;XeHCg>EI## z+%~AlA0%M4ZB%j#yw(8UM*PpM-ha2LUFGx*(nluXg+>WJR17&cL+I|h+g^EZdyOpv z4<*7M%^(@4M=Y>rLwgaidVU79Fk6>s0opf^rD+Q9x%PzrtavvkDG#xX4qtOV(K~k)@ss%+5xuuE@XQ38pgIL_P@g zs}jMg8rLM^NU;PtEqx~9osUk3_8MYpdz`apcTFgAJRvrBu}q>~l)Y2ve#iE|bGnxx z8+@MRjg$*guwOcmU8K*Xh!X}Y(t8s%saxqm=R@zSiU-E!j+5y|5c9FZfPDte9YgQ; zI0GqRL;+VvBEZz$+*UO^8;Hi#@B9>3QReHCx_&#z=`Hsv^hdE*vRvTh6UiEU^_*PY z6oD~EZvED`$awlwDkWAgFr;#!oeYxrl3ZSsO|nmV88$f)WtuWm&fLH5UEfk%9)(IG zvQ6+^y)3eQy}{xxyY-uOlW@~=S9)7p&$cM>&%5kKoy_UN?dB2%feiYH{Su49*!05I zc7JZ+J&Zj;i*%z=D&F1Wuu^-fI9uMh722lSruY*IM2496(4x|QiBj>#m0*xw8??}F zDK_EqDRbvkd*-aVk@xfm+{&sKKx z9`6m(r7U69Iz&r`Y^>{4xrUmLP0}96un0_@C2ymDOCA{K3vrEU00nuFwa2LL`s53NGXMO{Qf^c^0(uPK)@BO$p|#=sfVIyj z0((_Te9AP+men2O)VM^pH~y1soeJR`5Hpb3OE0S#dKikUi-GpVR>U2{?yM^mJ$-D@ zlEKBeXzAvCWS~G}xO6T)Gz-uH#<_CTZEQb4vIi z2|C*StIEh(xRU_#8}-~~)2k60y*u=c-z>J-8mPBQvzwWqLE`pkGAUL)lI)L&Yn@43 z98L#d(zQOcEns$)l%FL)Mi@WY=G`VlGep4$<>2kUfgr9g&kVin)LXgauRS0Jj+kv! zQllT$-p)l<3{3-b9`c5u8D)1YQG);(c(%$Vf<17|5SjBq!RpC1f(I4ybT+aMD8eus zj9ECv=&;FRXvfkb{0`sEoHn7~6eOKOAK*m13*bebiqXfOmZ(E3HI{=n5>s8jpf;D- zkWF1zfxx(F6|5W~{qG5Qk-xrX)l7kXC4$Jb_jj@AFuqeV_-hO^u}-K#LCRSIp+-Xit8BsUI zn)cOKv6Uh?2<=CK95F-#)jL#B zb7!L;5(u4XGJ$pM7kZ1n6gbVkB``T@lFg|Sno^<%#?MHF?OLLG0Y+G%K%Q{qZ%jd0 zpba&$>7IiY=!Pr-MbABgV8954M%P!K!f4XKzv@pk*)m;ZTm=Dn)8~>MTYC5?*hpMN z0-^mo8x$Cey8KjyaKJa#A0@bI=%nssXc>rRcFSiSJgyhLEzsLJT^DMvFSx3D*;twrpu{)Vxn%B{Avx0_J&?(u*g4Z1)FHXjX_jG$klDD|fXr$NCa!iscCK`l zWmx()UPt(867cunMyzeTaq#1C=_4)RDjM9}Y`p(>6^&ejddfEEu**lSoKuLh=XXdL z$dc53J2^nCQ`YK0;Oe zsOI>5NZ%HGe=Pqx8XmTU#g%sxB%{r>3Hx5` zllynZ20a$rLSwE><3i%;(k!=DQnH~I(gRY;ix_}QGada;!JR!fvo$8Av`sQ_n3Vf8 zjM2!=zXtTO1jj4}KJGNr`VBy~kJm^$>jh$~rJeABc1)p2d1F(uu++#lTYDQQW}-dD z$9^Ygj@G*BS`7~$ynPR1$XOllyzwuNz(10}mkyqYoGu2wIPV%5EpzL}+KwSo2;dr9 z#b)^Q4%LfN9;T$T((L_Ns-%uX6V;q0aIDVF+5}NhN^-b^M8ur=of~~pFM`e65X@gA z-r?5aTUfK^t$Kb`9e=9srZ~aE&dN<0%+YdCgqN)jWUyW0A%LcQI(8Gy!a>yn;0}kKG;Q7 zk)SDpW!$;{AxWE&V0pv54LKoKCt**^$J*-QyCnGR6Ab=037EXt&6l6AkiHK}!jUKG z2Q;p15g%EN^QgcVlKAngKeE{bJ`|Lp^QF!yCQ#e;Yg@sj5UO*`Xydx``Za1@!O#)C zk4dp*i~8mAJLo}&NI7*ONPg_By4;)~XcS-wk{HXl7dI!gB!DQwIyE#Z3eCa2jQ_2y z<^vi)wviL#NT!6}N&&N){3obEscZIeQ>?|oRw=bM`8*+CuMQRHePT%;)R3&X1PG+S zqB(g=Ry{Jjp+AeEyMitUdl@P6&a8@+zo7xMK9!lOt{GXS6y`@}Ynjpt+e09I^GoA$ z{cMV0G>vP?t?$#M+@cAbP>a%wLd{gkI-_p>Zu(;7M&eA}xn%C+LO}v_)|mAwg)>@7 zm1f@^$P%*<)i})TO2?{4>Y|U<*pvlVY++l7|9SLlZALnB#wcmJCiiwf_??VRlvHps?)mLK7o(7=CyEtg(vfV7R=e` zZLN&t5WR|w82O=d+>n9Qm`xA^hbF2$p81`=%StrCv53{rxp6Z!FU$57KvtsN7_*Ld z7`6e?(R`c3zXNbP4X-Ceq@w&=`1r-IfK~2xcP@_l@NnFKD&)9}WvmgDzpL{E-yg7E zOy9MhD=9d;NP4pC)tla(R5>-J&rw$RDmTs#0>-U!@H^I4IxH$6}E@EWdD821+s1*PaAW znl+6+D(Jw%p}i|hZxMiWaMn|7Nyw7<@8uZNGnHN8)%51TqdvGIKyB|J#wYsszdTZ9?#G{&eD#%V0D= za1p)O?-}PQ>?R>d{XMwA*=(9yYgtAjVL;~4_maz1Yc!Zuy)%#=JuG9KkJ`sy+$z{b zprytz9NAHV_o_tH9y#U{1RSGn%#IbJflyU*rG(353~g3mv$7~l1D3bE7{cA+3BSc` zPSx_nR*L1`z8$eL0R4!;JpeUUKLB_TY(P2bYIpL0ODKs#7DCi@y0FCYbp*0;*=rqd z{pW_ZlK{=K{T|3gOtY=wS^ADxTl*!g~9%07GNwVfQ06 zb`v^RXRKK@mz=qXCfL|rSiKUEAvdP_ys~#S|EBYaaFLCO>#`2?F)`~i{$SGo|XsjD40Z& zICCk2+}9y^d8b9qI5_`iKp#de*4vKDU3OrV-)%yQGe7KCqxZ{m?S~ekXoZOs37s0z zNX*L`&maLq(Clp`v9?k;1y~A>+^eGu2pp!2dXbzbGwlt60uSgHn@EfSvmT*u>nT_| zs4PLg#~qJ1e}GM6X}pBH5Tau&SgR{7yo9Ep5Z`rs*>T*IIK%v-fAT^adAgFQKyl_p zbI~8JT`5J!!3~{;}tSq=BSJWf(zV<$q80NVtg9zD3wlEv^u`(S?ZPH)~ zNk~(oUezs!-2?Qi?6SBay$PEr*PhD+Ih%f$?^ytl4Q2N@b0+$O0IO5?t@z+{?OzDY zv*LQ=1#(Da<{DLzi?GvrsAQ8LE*yd&Zm}PigaL}s61vf)y!~D}9u!^%kYaap$V`(} z+1$aQw&V2s6l%dWsIelw7}B5EVQ6eI!&pjr)8r$Jb-mbmSvCzxT2(9|Xc}p_H)%13 zfoPsb#9!8OjYNpTzphpOV=S`H9w$qLM`RJ-#-07bYKh>5gh2L^;U*c?o0TvQDi#?7 zn&Wv38)oTIO98s!QHgQae)D9_r?zAkK?LO!wL=Fdc%e{_mANS%LWl4&c}htc#b5Mg zWc;1TF8zT0s*=zs05ExT_P#HCVqVoAj+^O%xGHaTn^wpF&WPfz>Mq7Bl`S>peU-g~ zbkH2gG_FX$;NqUFiHxUukO$oeisa2RY@3IAQ<8QVr|1~w6cU5y3{%(*V?tUB+Y;gC>{ycoe8cuo%o%06h?0%y_b2-VI zoF0r=Ha><^JtFNVndSFYsAlnoiozJ4f-?BGk zugoj!7si%@&R&4sup)5MIf~}j21`HbZg#6D3P`Fw%sWBwc>gw<+)sulI#$)CESEEn zOCj#6;v5=*%ckf*ld{*sj8K|mJblzsNSN;|`q(JS;<1tC^K88?!t zQZ_KA64D#2hge?xZ~0tip(8|&hla)EV1Jna$P$6j18FQRrm<+&={fOLsPHLwh($ zYs%_=sStR~^)w%i2o*-Rb$Rkip=9D9TzUiSqq5%sGF!$1f6-aemqoTonCl|Ba*i9Y z0=p++CN(85mIdy&ve+-+dRRR6I%DRNdf^{Egi-__&q;waC575TNyx64wyXrYd6S`h z@DksuzxsLH`BmPn`&6oMjzc?)q4sqr`A{M!F(>k)%g@FXrK&1OYpB2K>%m5WrrTSI zL;@yA)005-H#l|YCnC$6v;z046d?(Y@tr7{G4(+Sjy%{Lj<0~Ahu*|!{*dE?3wy3m zl;V&CIYiKw$hFKc+*8HLL{S^^`63>}B;t{|sjT@XIuh9nGk3Bt*`=b$81~>k4Pj)} z3FFwVzb;E=5Sr+B4b8`2-rZ>CUEx78dG!`d5}eqV5ej;1q@wJrI*oKRVaHv2=qmaG zK2`C+u3Dw`MpuFD=L$oaLvN4Q{j1b0ZqMmeH+6%i#^=b#H5xdJc8M926w&+nZK&UXHs4v}mV*;CKk8b=uZL!I%c zH0QzsJbQYeHC!hDFT%bus*WI769`UlhaeYs3l<3Oo?yY<-5o9-++BkQ3l71#Sa5f@ z;O@>&-h2DbdAn!Np2Lq}ZclelcUARQHQn_kSD9~`$F2kGme*}}1~w%O=Zv1bhSZMGWi#oc@TF6zX9CK;gXnPgUDOid9|%+;ccUl}ooFq5uG^3&$Q zOxHy3xslJqkW@RhK@I@8l$XVH89urs6LO z0B!>m*wlFZJOl^>$yP@5L#!4FJikUu7k9o~tsoMBz`-t=Tz!k2^W*P!WOdHgoSi_` z?sxB!Bd-@nHcY>d+X+F5vR+`=jOTUtpMaz_ShH`kLRuqigz}*)=aE6wD%wgppQdjy zMWt)Z;f6Zoqn9zAoIkf5Mw_gEF}haqItAAHMj3?WV;Og%Kp&Hr{=a#XT-e4rAM?=2 zy$B`A!17MXt8SD7{CB)+%WzvKZVKHmb=PH=?ul8Z2*3tov@az36kYRq{xeeh_Tt54>rLHg z6f1kbbeTubEYmWpRFJQrM6V?ex#G67;y;RlKTIYZdpD!jLg9q6F%Pz{^=BCofGnQ7 zE^d2DheCcm9kpn0xBGRd;W?I$1=5u)%L8Wdd7 z>x3z0Upo(vsCRHmlxH#2H4&t1Rq#9dVV3b=W!ky0TarvHtm7@h)i>TsW%mftlQtk9 zjLf1Rk4h8M&ij35{^JLoER9?s;nk1Y{2XQ%y%hZPgo+Xj70w`|B9m>=2%CMv!hIC6 zBkbYw;_a!aB>5y}Zq1^HV9^0Vu0+x6if_cqiYrU!*O%Er@Uz~tCd!N9IXZ;JgYInKR;r0XUg;i_;Emcdb1?)A@mxsc&*y?U42EqN&ju=VMVnu? z??GM+YSTW>&H`M*4vR`J)p(VZ1mlkapkNGj*2)t~;;=yS`HE><2#3dWpwRD8LAC7j zoxd7|^BL|HYKWjm()W2`n3xMp@`zYD3>%oRxs44*H{Z}td7Cvd7F8SvJu(s>!GO=C zX98r}ZHN6%?!a2i{Pu%Kh!hv!$k;wdBuuX{HUh=Zj+&65Nx$f8`&a4W-)v3JpZqau zQ8@~%YgL|7FrAd*c14xuf>#!(gfK)A1zeZmF(ud9u({o#Ko?0Ta6=v2p1=jt6-8Df+0$iKkkHlY)Bud)57OCC=3TSPrWk%=?xcX zOdF*;W0DGot^FL-kov<*Il#mCg_|J?|Lr;X7C+UC50z=qdEg6UDB_R#sJy+aENnQn zd}HhZ!w54RW*mEOI#O+IQkC;|)P0{2Y9j;R_&emO6rBB@i+DuDxbUn(RpfH^Ww2&)#KzaUOHrFaMQ;TvZg>DRvu)++P3BhxtTY#bK8TZdlJCb%*1pG*|Nfl9C$HnXy0bD|j-_~0ocv`s z_@ii;U0Gk4EZCHC31i1yooah=WM&oPQ(vjOfd76`P75|g5^qCS6o#wjFZh*ouPbV5 z%~D-cl3zfR+@{-^*~=wSac4ML)tn`&+kJkyT1!A2#YN&E7-!Mj2{9j^qJ;_es);@_ z1oM%4xMfk+?CM1X@a3J(^WzvZi!epjj;PhJTWN*C#fvk-eEt~S5k-5a=4auQ1AmGw z0g7VNY7HK9DZotw-SUYUMaehQONI%y=HGTzmT7C+B#PjF_~23!XQPkq)IHwSbogbg z%+%Q79OW8%YzBVSeqft;We#Rt4?-Rz_pH>_@)YBmavYn<-h?{U1Ox*o^>SG~E6dj8 zljp%ZoSdO_W~ay(5b2UQdVaaLQ^P@&RC4>6a^rLmk~2F}`*&!HGbXEHy%xz0I5osh0%pcvHO&S{FH3Taojy#^t3R7r3<;yMM)~&3s;d zUPrd}4*70kBxmxTFBGE|d6cR~x7g(YF#w#L@6hilk+$);kaH6eliQCW8j(NTyOXYs zDHTQ&WgCKHZ{jUB#{>aXhnkp-L$eN6^jfXf@0;RG+nlOrxESdTA>nA~a`woaMfp0)_5-Yv0!8OED8FBZJ(7 zKUbWe9#_Y=ZAAgAg%5j!$z=riV=!-P4SLgEO4eH1*u~fBNco`vKqt2fisyBz+Bw!7 zk$x_v+OleKm}djhAT!9q04LR-Di-#thez2r6;&QGk_FU;V-22`G{XppL+20cn94Fr zgm@P@2Z9Ce$v;C5RX@{(m(ny^SvI2#4*cScm!MRn%cyBkeuQ$h0jC(qBMs|G;+0_d zu;^@-C$nl()25(J$)#s- z0>Imr@Kj`udnz>wO#WyrXi{Po^FC#0nR#Hz|zYW`VXyLu>^?HDY-C z$xB)`6s2nKnbVT6H49OJ$c=5^PFFGAcZ{uPRbSFFcldRTk=*&iy_Z=S@5^_fM>P4G zc{Vxc{!0K3+#boEEl(>iTF?R3Znmi;ywdO;h|GJT{&NFOqAyhegdGr@@$gj+LR2&m zSpuKUAy_rM+9PE~-lUlR{p8(LLPj{#@H^0<9K~Tl8!-!gRV8@kfYo+rpWh!N`=X*z zkjogpzwfF=?zj}@(39y$OcOqvd0#V^o5GUyje~i`a7;y}v*_gYv#d=2+~LAIX=zXl z{MulZ%NH$@N0P}N!#gXEs0!9q`)yOV?H~eieDH0n2dH)zB@jbGd1D2bx02x!rmFKc zh{2))O7OmS?;WxKWL*v^>?itcn3rP*ij}x&AKRY`nUkKEFn}sMjgN}6LrToL5u2%Z ze3>t8qeorh(1I~)%O-#CFGO<%V%*Ga`mU2fA@iBqU-(zxHfM*|7Al|?0g=rDQv46# zGU`YJk%7LQ*5yqL3n8qBAA6HjMNtsT_u;`^=) zFX0NzBjaUcl%AATV|MDhS}A=&4Q2G}gp*IF^JwVHZDvq(dHoon21KL7Okkq@jfbAo z8`TBDfwkpjw^~0d@EhOo+Ji5bV9wvjnV09ou*KrKRisb0ryf4Binqj(t6+H4o(hR& z(&t|59U_wx`BN&cu~H(se8F4nMWN(j5kZ9ggMilte&sw?=HnYrZKr@XT@TT(Ok9jb zPpYPT@q3hMwW>zyy|?u8f5102?Mn*C6(oM5AlUTY)5J+7J>f1Kog<>%%m5bskZ%UI z6RI>`Kycu5ayY3dr~65#aG6gL-`GjSKm2$kv90}wFajemmTV(VjGF4)Wj@uxYS5qvB3clSme1G9ELshkhn9A4~pB`dds$pCwB|lp5FF8PZ?=7c@HsaIyaeybe3BUuMvY6F%ut5*~Nv#NoU>U$gP<~2F5-T zaWC<}o(H_W?=2sct!||4`*l5-zf2$+#xwgLR~TE%9Fp1zm6vY%A+=-&%zyO$&OK-V zVAEPtJ~s>~rzw8!+>5&R+JJIzMN83;SQOb{HRy23T7d44?V6zi z6K#L?yU8~Xh%10n;e6**q^c6g8qTQz3Xy(tkkTD(5V_f8b8^Na1qJ&b^%(Y&8h{Wv zE8<<&ouj&c-UXc-L<>DWz_dqLHB|5uv0t}OD)m@jm~0>i>$I?Y)!0Cig%fN`-zO`% zc?N93u4@#)h=#q=3H*&Qjz)%cq*H|lBYwjctrM)LrnFa@^FE6ge!BT`bM*Ll^u`Ls z@vYS>eqU^SNjl|I55{P(2Ixgu+f1MXQ8Wx+trSuqQuldAqJf{%Dp5@uBR{qEj-xV& zTC4*ED~qWgnb9VlJOxMl*)#TLBMf<#_eF;Jb9^TKFH(j%p<$snl#2k78sLj}s_z1l z67;A4PLFgGvv|NKg=yZno~+1B^0igz4ZXYK_C7P@6z{^=70>cO9i8>0()>sbh+ zR<=w<4a+)lg^LZQH+1#mVS9>r3QM8**V~>h@SDNro0BWq+wHvl+Y72(f~z%T{dIe} z^R?#>SmYpK`*HbXTu3AJ^3nS#;0^qeD&%YPcHY$K^R%5i@<;y_!NP`t%NHk8up%6( z`Bgq8qk+mZcSQYq{CwS5`*>?BXf#|Om-zYN7XAE+tkd^tTj}0WL%HHS_wr&nw{ww| zYf;tq_5P%4z4qd~s`KUPj}Vb@kC5;4ZSMMzQ9;A$mselrw;LYl%F4*{(j;(p@4X@i zauduZf1YYXxgE~X_e;Y%$J-wBSm|d?#wau8{kV0Wj^mLpyH*yaKV-cb-gW042WQV3 zZt^#BRGg?H1{;GWGpac5=d`~r=4oS2=tll5&dO}F@+vF0-h3R6gkd$cPMohzuVpdC zKmNzTsJ*EAEmgFZ%N))w+ZsGG*BoXyq}PbLckIw+_eM61C6r|vb-*3?gyA%wmx!7I zSrCdEAc#hSdwqW{bpO%EFFC}AB$?B6AhL$NnU^poQ+}?M=BuY({?@J6yLv%B8-Zt} zDUYNv?!lI%bD=x>go(cTG`3uOZs=_7y)^|%{fjp;+$rKG>YY6r)g3U(My0-TqdN@M z)9i^33*BfPR&UiQ=H^u}**(1?)&jprqg){2XCE1Zhpkux)}Nn#tu7x~bp(#zj_qfqS#|1Bna%5yk16>Y9y;VI)Ys-OxD1{{TuxA3G3bO*zh?2?@CEF znxaTKjaJ;w#i4&SRrnSlNugDQzKL6PFRixv_q1a9l7wA4=eHr$?L$|Epj8GTf+;!_ zEei|rKQrp(^)GdD+UR=2vP}|jk~iwva%fSt@{vn6hiXew3Wt?`4Kk}6I*DGkZ*_Qp zMnLlQI^oQBEx;30^^~-1V>Xk92C!bN*-i8g$J>#{T-*s;Tx;);@CNj1`@Mg3mH)*_ z$GeiO&Df~%O1`Bv=s1S#P^+DV%)!9v?d5V;ovN!?IkU_MTI~$7()7reTP-5u?NbF1 z8U>c|zh9V*ad~d}*aD?^D3)LlFhi*8Pjv&LXM68IY7c())Nu6GPQIt4?1nM6!Xa|S zNvVq7hxtv#Ra(y;IDgaZjeT=I9)6(9y_JN|W|^ z2SH#4%k?WN)f-r%4YE+@al31^uBxDO@#p3@KgQ24 z%LXpxSFm8FII^aE19g?rK1z=}9^~mDEAi?i+;7M7uzxqV`n;&eFKcBmGryptJm2*o zZC)HTe)4^eG^;|;h_xO4zPMn|S8Wzf{o6<9qYO)($jX-d;G)k<^pojJW}C;CSqP7{ z+*x7!a!x2hG&S*Io)aUk$qEe+{MOz|7^zvRv9<(DhmMVsmu^rNdCd>vQn7QJCL1Y- zon2$M@O*Kd$o=wKlocCUe(Ux)88^_G^bTRUL|aaG3=^iP%+S|MfizF3SmU$;8#P>1 z?RWNxb4T484pqq~$`BW|xiSfr*y-^a6|&GjjyPFRe;#h0fvuYxF$ldzCms$2koyXI zOLI{$#hc<<67{D$JGoy}HDmZe#^yqdcYB*XkF3VbSh8d!Y4eruNgo@US7T=5=#oe| zuC4LU-fO`jS@#Q}qk)%;sO7`&H)ej+h(9>~?w(>GekdWm)P2_NGKQ_ANo|7f2^L=y z3q%lcW_Dl82@IY)jr|j<8OA1R^jiS#Uxi=-!{Fa83lQ~&9a&K~-LmpT8t1UiH)U)E zy}-(|n**fqXJ>ypxu16kGsp>vV8`Q@9?3Urr_bJS-*)V({-P|txptP*_a(J%?V1`N!)3|BD)7M~Z ze1cQ@`zq+!74!2x6+Wr;di#&%yLI&ZPcVru8+>6v>Y~@cT`Ni(7)PvVzC^rKij$00 zKP67Q@!X<5_@pAq)GX6uap~e&_1p%}(!YIv6%i6_nl5;Icm(=_hj@G$AuIIczH`Fq z0YW><0Z3ma9;PdGc$kn;gD}4+0P^p5691PIlzZDny3U0?sBNHFI(Xp5XMq*6D;MBd z!kb+#p3r+XGgi{OWqXZ=ZWyi9qKls){)-u*&SmJLa-7>C&iFArx?Ha`Hj<~N<0hS! z3K@6n^}`6h{b&)T3{|qkSk0xvJV^T7RqSK`F>z6(cp}}k-Uv*}j`qp#FJHhkdyaMj z_C^yq89wUgc<&1=?6(m)shnoL%<;C{CY!ma!hKj938Q-Sm|jE%ekp?Kt-gP)sT1dw zNILr%irF@2r65;v7w|}g1q59$P;#Uk?Oo^NgFgh#beuZFo19n2H7BhnT2Ou6$HOaD zmGiQOilGYl&B*Y{_-JR6g?k$;u3;>_?0%VgeK5S545|L(F!*IkX#`~+O1^aa~g0Z-lSb@Sr(>)Ln;-M-E(R}JJVRe z+17q>7R{e9^pD?n_9zF(P+c3mQl)^lprV%iQ;*ee)u%G~@6J6|7qGy2SGX?*D--J< zXa4wNfkl+FE5@*m5Rv^#mF~Y&@8!R*{vks}`7^P%NW4IY1_`at{c=XXZC?#bbG{w( ztX`c%hGL%2F2)3VMSC4g1!|B!tBIq%rrMg-dN#ty(J6kq8Vv7D+0kN%k7_ZAQ}w#N zX6a!)x61xwg3FBEudV^UEX45h95r-eao!l=?tf0U>v8M0UPR(A@7bLiwz(f_{7ST` zAzi++vM6n`E7+n|)-(6s(Vi{5iRShH_h6Q|#YE1r0>Q#Vth0;d45; zh!WVg|G z4A}nWKrq$S%3mo2qSuo}PPXiXM0gq?JuXj;tcOOi81KY%xPcZfLE{4jW>lrFU}{e5 z<>FD5RAeaFya6Kc7h2Nrv6cip0T$CB)U=F`s)>Id1ZL6qtBF4d zvhtoSoBZF8L`-qSp;e#Xy+`un0c!iD_OG_98_Z~xm1L^_DApzUpT(B({?+wt2cM>x z74)xuynRai|EPWxYC0TjWoGK{Sp6(yBlZ39H_0m9gWEO3th1R*`J090+f>VeowXg! z6`yHCJ<0`wHs>C8y26%$V3m=8l|a*B!`v0Txz@P$QSQea?Y{`y>E3;(aDA02=a$aQ}Kv7IIf6+I<7~8v{ zRY)xlA{`)swk?Up6#5c@FNHOdD&SuPJ(S22gX5tqE_(E|Zpw#f$u5!M6%LQ$g3&cp zuQ`7uS^b849=Jq_@taPbRU`$KpJ+s|cMSDvbn%vcw8c<~~VQ0A0j@n-Km!&ERMxSXU=*m{sx4lcNHd zBY|R`9LbMj-hdJvLhpn+WzeArGjg`26NHnJX47bu&6=+G&Qj1c27QrnEDvGJq8@R3?ve6Ac1(42TAtQ4(f2oDv92uafYyd@1o(o=M)jV=?MX-;8Y| zRn+Bd>I_Rp&Y6NCWp1x>Qo^#B9;Ei+!$$uuChz^>R$XJekgW)`@T9W~mbWq;JYJ}* z=&w1B%AWapm#gWG+$-6V7iBT@1VgPuzQ*#@RsAf9>P{?-E5(RzqJTvaZ)k@y=6&x=L!*%*aKZ+!<|H?)?G zC1J1jzenUbzhHgMo$0o@nlLxCI=v)6o!@n3t-m##t|qP09G~_6PtLK8f`ga|9cyu6 zkFF1JgpCzTTu+EgiDJhpO99*_w0uqZ>ZVM4m};7~_Qb!nCf|bh4mdS_1a0A6 zn93s$x8p8c;9dpMRy|!(YLL4!N2HNrRir(@m@P)A6X+=gJ=7wgjI!P#*}`preS4qq zc819wK*4<(A5`1@VDR?Icc}gG)YieURhV!BOLqEj9r>dynk#1m7ZHDT#qH~wutGV6 ztn6k-*qhp@=bN>c?jIF(J~pTi=G50W;(cJQT!4X|AD^W?IkPd;afqbl*v_r^rIsWW z{c8@Ya&mTquOJfEIaK%EQ4|X@_`|`N$2@ZEIFbizmMa~Tz8Csj3xcyQ-jGz_eBL19 z_9<*ypbi0#ln5M$@h%i)`?*3OZu_cKTMRYoaz3ywvE$9k^fXGJ+wkoM+qiWH?q!S( zQfL5H2c4P`%P-ELF}@koV9WfSb#)nnVwX?zJIVEkMBlg#*V#+`yyImsS4@>QS61Au zB3g&s*krj`K9a_d#4z>Dh0UU_mF4nOehE}$r40CwlJjUR$V%W0SZCisN&hM<;=Lf* zQ=~N3rY4VF&?*NN1WT?gk=H`-G59}Sb<&L7cD4{Qq`Ak$Y_>qlT|0d{ECV<#>5YUw z@-_^az&q0O!7B#-_`@y$R_x4wSopHQyeWRgOqd!(ti<-4Brf;>#ga|`v0CuXCU~Az z=KOJXbW;@UF#ZK{hU9?;5*h$thA!-=2pW?5NXP~b%O_LA94Y{3ki0jEv`+iA%g9U0 zF%z5vAGc}9)opRESLLLT=KtUoh8G)|WZjL3w*)!`xc9O73SI0_qLhG*)j=fXct+btT;IXHwyH$CD$>nRPyOh=*H1B|A1uKFF-c8 zz$v%e=eZ<meUzP}Q$zs9Reum(LQet9XTI|bt#xkg$vE%+{;yh_E~V?M>j|C> zg5Px^<&_n_Dl59XCe}7;8>8~Zh0PR}V75JCH;1BD0Cx4W)c7r`3S_IO?`yJT1gZ+37@3Gv!}da^DU-&UswRl z;Kl{UudA{QglbhgA41XREO-D=kW4zdcRN^O9eWKJ9iddW^!#H~EhLSVoo8~?6K zx{MXI+~j~mZDBA(BlFOtvXPX?bQJ^Z)*m2DePMToGS$LPQO`Gb_9-Y`r+Xme>uOE^*sf5u7eLu-gX=JY_!;lUktU@6)jUff;tp#TU5}nDdsmqxbx3 zR+O>?I0=Q5x`2v;yMKV=%5=OX&;4|%dCp$1j^zFSF7g;fxe1d? zIZk8Lab~Snc^G=HE~T0CS#$mHTW$pp@0AG&@tcW*SCt-N*4k#-h6~XMp*m^>vLY=+ zz@W(dn<*hK@uHU^NpQ2743qvl(rH9f%U_yU&$q>1lrb`nadRSYkr*Fq>B2v@rYODaEA zIYg=PA#^s3t+}aciVX^AytDhqm>z+KLZJOxQU|3h+h44bQrcX`os#J~ai-Sax)OVC zt_&T^4dGWm_GUAF+_dp!9eLWGfTtb~nZNMqll*e(umH0e^SV|KJy1Z1_R8Z+vskf) z=l#ckf6pXqT(*A7V2cI8J$4l!r-pc!Q)z7byK=Mzn-$fV{afuKq}-;K`Ki*50#9H! zdhiYe`B8U=NzSt!_kvm15)As}3C?HVA56QWtx-VGM`4!hQk1_Z!J}LU zRAq#NNtCfF9NYNP4@cqwK>r0Ib+J*p59mU!LpzZtEH;z4r5geukw_h&6D%gj zc0QyIOf8kkK|x?>N`8d3&_I;u%dv4wc;AX3Fb{?@$+>R{2Bk-{VOa3v>t2kbcd|E| zstW82dceVE>6NF+N0qV`v~`!z=x>kBX6=hp9VGv$_wt;QcTp~&^fX;w_N0Q?Jb6=2z>xwD(2BLuhYL&m0N>tMyA_YGEcAP&08+sG zEc{E&gFh3t?&M4|PPk-Ws@#eU@FhRe+$Ed2Q9>fr*bTb(Jl@h;VVUCEi6rpIu$US< zdGf50&TDMI*R9+~=(4tK)}xBQD&o2jwal4RGWhE?(eRSJ9{-2@c;C z13jH)*8O0wOws$TI$v;G#^3}-x1Vi`ms31ONUdr|IDr`@@#yR_$DzppK@yH$vtgV1 zdIbpqQyVjA6m*^c327~Mf04S(9<*JUm;2r(C3IrQ_41#Q|T*HG+CoyS`v ze>Li9yV@MN;@-<_bD^QPmPXA>_HgNaW9MF;-F~t|m%a4XsABIlY)>#4Lp%ZaF=PX_ zC%hk+A-d^lg&(<*0C=m}hiyWoVG7}{g-Ha*CYz-ILqLMV_Es>=NAlhv9*($k?Q+WR z4ZuSD9e;~nUnw-MqiLp+@)hn#{feFT&a{zkX_+HCuv~3INT8m+abv61x5|D09w{I0^JOk+-fiyT)sq@x0&GZdeia2yXU zu|@>^4q@2_wJ(a4{zYSG9_Tu*Wdi57{|Gcwcj68*$r4-oBbz80I&PIX$(*CeJ*2$H zrd(q^CL_aO5 z$7^fNowEG>M4$O#-0tT!_Xi$Tv~_dvjiv9!-c6i^%aLGM{90f!Bnk}q9drd_EK7i^ z5ZL4U)@CaM%gz>(R7MThpCCk|V5Siy;lSK5Wvd+mFKX~MpfRpk=k$H#?QjZ#&1Ocl zU2FpszMIJa;_Uz6&V7L6*C)H}!iVl==E&j)j0!2ga|&M>=l%Cj)Q3mfV*<2Lv`XTX z`Y%ows4V}ix*#~8Mlidux}4^AfGekYuGt}VNVZNC2ou5kd~K5!4z$m2veOPAX*JnY z{|98yNwhl}qyl5DO^zGImQ}YtM00Nidz-Kzi@^il8X3}em81>@vA}kLC=@@i^cvHg z^!m}iMWJ0ECW>a3=~Lj{g8^rdy>>u6`d6Y!r64%)rSXnfGW>Czfn`dZViMOG=M(_@ zJw4j=0HOK3W?_(M8WqPn^{t|oM6br^s6!-DGl5rv7Ik;OBPe9uJNRU|F{`E#0tx-P zQj!nx@f6VOz*sM#fE<08Msrpt`7oF3*YopEqA_HSVc5b$whnL7ARvZ==y|F_f{K^4 zwgL>hTW%Z8R8ch~qY^o7(18}n6+tXWwQ%Q;G3K=*-8QQs0~p~aq8nxbC~C;lT*pRh zkf&wz^_LKM6cec{WuhKg!%i>3&e!+ZjpCa}U7Q-^o|D1w2^+pNKJCL^^JQVX+4o(^ z|I~l4_p-u~Dy`jk8c|f4Dz*eLlVZtW+F06}_0HYb8&R|xvh|nbHM#SmIa1-Kl)Dl8 z>d>X%7fxu@TCK{(tOTU!)CqOtInu$KeFfiWv2t<|t{aDx&#n?0dXSRt2NT2DIwA`{ zrCV^0BqHH#Z5oHOwZ&b})$~f1d`=;UWQnXo%8ZeapY3Xw6tf(v^u1hD0So|+pZtE_ z{XJRcoKgyh_#uNzrbAO9@PQB7`)i%1Lck)59_6_t=9z2|oYT{fFn4Omo)~g*>-506 zdLyszCm@z-aD(5c&4#1V2Dcc-hTY6t`VIggoqCPXcX}2#UkonrOeni6Hq!9qW+O0} z;?@mcZ7JJ^lme*-Vfm2sXq3R}R_DMsxnl$7OopiCyy^>IM(Erub~PU##lVLQ4JGzo zp1;!PV(OyZ_+3HQ4_<%?mx5{np{S64)woS@=-Cbr)H(zzCQ`zwSJtn|AKmPaZ>OjM zqIl9VPqb>5-q9OZ{j`~MJx-z~v%euR_|psU8bN{EM}6onlLj$MV19z!-gv|=e5Gl;iblSUSlr(9zK{d4ShcufsM^|9K+&= z5?9U~`u=k7x7tz#LEoNxqc;~CvNnG|+~$3Cb#C=m^i-b_D+unt%yG6c5@Gk~mVPGBfnoG&{hlu22iPPOlRxE4 zEYeD3bmy)dyHt}WCUD2SIKeXFfG3Ior-FxLi1ig~M4@0A$qL4M0_m(CurDiVb26kM zir@gUPj8C@?>anac|4`r^l3pvz!?BQOI{|B%4iVNU;)GSjnx@vw}l)M@ri9C*~4?6 z{a@fV+-N874~~Y9h&g2hx20$-@a$_CdRIhU!sG^7;Ao2ERu6G)EFf8eouDVETbb9@ zMBf6qf6)iz2q|xA2XuR6Yf|hU;a0b)0pt!yf!25UpTe(JxZ{un1520#$)phsBX`GH zj6{EOd)CWv-}>r8jZGm_3(*?*%rE8$rW$u|FiWOc8NfacB<26P&xGcGvOoM669fl2 zI}g`?U4I0wIa1@Fki5aXY#(|4j}0ig!_>{u9cTI%dIhKNHX0jFY_uy*^Kmlli@cye^azAiwDQ zJv~&Bji|^6C#)<3t;f|DfL|WK>#uSEO~lj5-rG~$KbnZqJEh^fTtBm}jC>p5m|$m+ zMN{B)Hee=v^}N*7Cn1WO1zG&uSzOT{xpcO?BS9?8M3qL@d`suAk>j!YQA3lxTe-TZ zmJifFjl`~hwY?dD#SI`7Y;T?qedRl~?x*yT1`8+rFXS=|nD0yrJ;Pi@uu}9BIF`Jc zzCtgX5GIxA%eqh+EbGyol98kQ|=g{k`OGSCZo&f0zCp_J{d z#ikyzSl`{R`rMHs|GhF~(Y30Jl!U|P-tto{NOfkP|J0U?HCCbZp|)wzz2`pdiSO^W zhG&tbVoCLZF+9%hACgEje~IlV3f#N3&-_*kBm!cNFnZmNybTBUH5`Rtv&00al-II4 z>Gu~rK{FsofX&>%Br;Ak>*{CI`gS5pAj7{U&({U3V0zJl0Zl2g9HE7QZ$@tT?v?zg zJJ$UCE=88EC+pT>3K{+5cCd6`>agSHwZQ$6-+p z9wZf~s@6$DTT1z)7eoF94C%h&XGY(o8<3N$rnD$qLLVGMUK~sG7)kg|vceRXd8PMY zkylEFsT~U<6xpjoj#+8`q#i>~dOxYnSWgy5Whkhr=Hz4<@c`62kR%-$nTc(J0Fw&! z^QWEo-)!(FRX>yLwbynNSWBfJHVmIeq)%YQIRe+d>c4wA`oJm$j;owpLY*;3iiMON zN981bL#Igi7FHGqBoY8R|Nh}SWs2v3K>e!TjY&H9NXi|M^2-ga9yN~~GRIQ5V6Q^< zD{r*wY4nuT#=B{y-@IzmYMJ}z=k`dgX%}}DG~-xMIy4o|Ums}|?oI?t@AG_RWW!dr zPj}Ctsr;wH`}d*XAp)7EEVZSh&wppL{lmnM^C>E`w8<5P1)*`>&c5O)fs@5bZsc#p zCu=MzVvyUj#F(_&Dine*^M$Mt;e+DM(^43C77vhopdc#U} zJ0!kkUDD$oNWv7HUt9OdFx)3ZPJ9qef(mgvVPIRN9p%;pYaiIb6ods6zVof0Lu`7$ z_}g^8yt>(R&ga0sXJnhXE5+Hk2FqoLu;lNph)!hhovw&`y@xvGmd@p)tG7kMB4Q0D zA&r%?9?u_JrSJap9iDed`V;YV|GclQcg*j8Dz(cF`>Y8e$<5$b;t1-d=&WJ#&!PTw zY*`zV$KEF`V7Jl7A4V}XBkbTn3XH-MLVQGc7Fy#r7dq)Uea6e!it)AjPP7+yUCKS? zhbVVKvC9JySTVJPq52r%PSdDFO6h4EG+K28wL^mu2Pc^B)bOG{1@CXg^2+EG6HGhF zom%^v?Ke9x-%6azngqgxPjgoEtuM3SUC1>estV#rz+Nt8zcy4pxDmj7?GsNK-Yke@ zmy98A>LYU(vcXHtCT>IOrKFt%n?&|c_SWT@DJz8S!U9|kF|WZN3QO4!*=`#}W#lLnsFSChj8<(^4 z8NkOHyHsZKywX^QfYfPF27lRwfOgUv16Lp_>nTgCBn-Qa1B2=&qtYRVZbYVRFU0~r zcX1FuKK688@JDy`R~6L%prCK0;rrRHYi}_3%R-c)p|*FuB;yhvq2cv2Oh}#tW5n!` zHxX(2UFcVXVz#&5wE(h}g7DWa)Lih^D!i4i`$|(^_a1%q_qa-YTI4L~hC)0O?WrWY zZ2xn$$dz&{?fem?Ao6vS2rc`hMwVf46eGYBIf+mthmn&mjKN#_17~vb>WhbU>O(A3 z&ygIFZfArFbwAZImoWx}ZIZ7r``0AaE2LY_ef;!m5hMue~ zGMHsjeno=MEgdIxW-ypO`!n=r?2jf1fXyIj@>rz0T5#3OsEw7Omuh4kNTLUVFUeR*#o9K>!{|vV!cGqYjcjwTg06gck@i;G}p7A2u6`JQn#ONr@8u*%F6R5Ui06Vv+mGPWVBf z8UEmK5^+nCmBPpPow>^Im3_&Sc$v zl^vKDS^r37rgjDSz`DU`WH5_=#+CKkPj^g$?d$bde2oV|b5_=pX(ACKu#^c=9D@o@ zQvqEg2hlEfAkL1Ln!XtgvJMTwUax<8hQy`IHD2n95NOOjk@~`kaqL3L-1X6OG$p2> zy$DEzQCUt4(8@c-Q?a#{-IA}fHTEA=&NqyeEEIhw_h|-upQv4GrEQ^z6n^?ii}KhN z9bY%&or2->lBg>gE{q5a8}ERW!W@!wCul&rkIk&P^w;E$MPB&SPhwci0XAw=-;^9z zatybjrAUhv5;v+DF9<|V2@!;-zwhj5=kK`e8x!9~lb6>vK zx;(%VRP7=}ipVWDn-pogAW~o?*D-jrwpGK5^apYVdKrsJ4LWST!(E_}<#f-d+j+%h zZG%d+K1MJ#Lg~tVu8yv? z6?>>o`Y@%tA4OS`*+60|5Tp5bYghgiDa-)M8rTb4$RmIerj1YyORNiv@NGMu+@odi zpq%GMf$cyM!SLKv5k8lxG}pP_D=u#)PZP7{XQ1K~*o6-0ZT>t%Aw`8Qw8;B)dQGDd zMHDjCZgQCPnZT!S$)?|Vf&9#Um>zvdB%T{&!P9TOzt$b-+hr*Be<;%#$}R#L_>S16 zl$HLT-t>G)riZ+h0?xy1j0-r+RPlsarkUIwzX^PV<}}f{gJFZKENdPD=!(kzmjhj zzFU;|dwf*0p6gp!w-VVM)1lvCGo|bt*aQHHY!;){uO(Mxdss3QKB|$Z&Q6 z1t+Gzif-oHUi3A?2XVp{Gj=M&&oq?NCUj)rc-&qKT^1QNeny>L5F!|{l6xkvutc&N z;UT94B=@<&OH_W!m<*AEfKGqrA z#Ly2mFu~H%4Roz6W#o3*wzANjE1_u}IAI@5{(Rw(^4``_`3yC{rxVveY0Vtlg?AQ= zkY9M_vT$02iq>$1Y~K9m(f#rsiSzb-va5A^=^?FbWR)RC=uk(HxI~Nymfl5Zkmt?CL#xKa!?TxPoG?DV0*7EqFt&i6xjdEF_HO1RonQyDQ~`A<*nKo zl6f8_z+Zqj!LbvB&QGf@@(Q;ci3N=A6E4F?8<=`W|#IZ=nVjrivzJMny2=Pe6 z5F=p5S9$mF<&0f1hWz~g=lLh9<*h)x-FO3xfQmz6@;SvAEd-;k8g$xiD>$WwDfhIj zQJ^pC;oLDa3S+xyCUh{4cp!!C^A4(yN#s5x?}E;Yep7wyr2;a+ld~Q|V!-CGVc*PB zG0%~(!FHuozXQKlC`WZKy#d2eW})V$sS%GISpD%=DEG1UkNB5ImZC^|CW=v(%zN)OHv+!#sBYV$`+L(7#}fmrIOzPe=z4q1wt zNVb77B#S!lC7ABKG8Uh8sy5ACB)*DX)jSx4kaH8rchz%ISWxZz6sbh_2RsPBz|ct&Sb?ThmeM zDY+#wR>pW78tI1n^(~4Y{1sCCNsWQ^iSm0N^|KeC!KJyC6&7BJ>7(Z(W<*Vr35&ih zFKAB6xWP3j4Q+^9gs+AoX&KN)Q^_|djZ79RE#StCDn!KlpOY^Q{ZO(bplbP@P-FXl z;HN{5$P~)G_bJZPkE3$@@XvlB_v7wi7P_45L0#ZbOQIyNamA*8X6f?=QiQarc{F`}1_n+ZB7}y&!+x|npx$3Q z&lw@&0N%4vha$BCPCbQ0_xUNTieY!C-s`8ImbvEAYa7nZj| z7#Q{UG+)CSB~ikM#0I?GQwo=0p1u^pE+zL476Nd8p5T0-`rX^J zhy7uqVufmg01U}*DAk^6`Xdcs`n`GavB@P`LT%{1fR4O}?I)5_z@YuHfXZbh{y2FJTgVF-FZYWkhVj5U#G z9I!Bo3T-&e^KcMZGeI`~y% z)vkX11Z#N?w15A)RB5pd(mY^TG2T|;bVvqHl3Fy~6j1|UjHDz6vFSTYVMK!AD0k}% zMKiH0BAe`O9)LC&LALVR1Lpcv7{!G$7=NA$pKXpeDPs6kW0|C;JVggEJToADH&}Cr zV;~jOubE>`Ws4TToahdjHl7hkk_l0dX+#GsfiYrD;(`@H;I(08)(91fv6@FuOU@IL z`Tmh`+9FpBoIp+(`NPV7bozn(AXT!Yv>)z4 z^o|Sihrq%}1`$|`ha;N~q|j?IaEc%JT!o{FVkd~#uP6*Np<>t{y; z33frU@SU>kLA){nM*Nr(30WzXkkK8o%*XyC)83 z^64++g&>(t_V(zamlvG}rH-IV>j3rWxZj}|{ApQb`+w@lc-8{F>Jd<{-kuJ0{&2|^ zFyHTcyt`CZ9f=9eIBpSVe_RM_M9LwdmrRbUe2a+yyqK3;LAJgxsYCUjbzhn*teI(x zYB&>va?RKx&t=MPi}u5yh7(v~gw;oEZ;iNtNavC?75kEdQzGE|ZU4JU zZ=MvD@3^n{gK}4}4R1?^g%&mg=k2FPYHRlD^OisVf4#FM=;nk%q^eszfX}$ES8CXw zMK@Sxb+EQ9-K&uM3O%0h(4WQ0tO0MAx7$KE$7LyiulN7&OEVBQ;4-CFov0UsVpN2}AZ#R910UQW>cIAot8?B`qf{w|3@(Po& z;PMAzS_c(w=m9Iw2{-kRl*_~K6#|ezQu%9rX)|2nIi2PW0IDYd3$Y)BWma%OcUTw5 zM(?v+`0nk2UUEo&`yQUKMgU_?^gut2sn*AB{P5UuNU&!QTw{||(#8-ksc<2i;OC7j zf@Cjp9+4T5ojM0ls1RciF>?1X{4S~j|Ek0KHH415vh=_tr(Oi3i_mX#{Ws3gBB)z&>BEU9&pp(Exlrl9I?ixnfFG`dUz)fz+_%j~=YT(BhlGWsp zVYsYPO;5!~?aZMopUMk^=lQQMGonbyqL*@xoX!F-XNc~hkNq%Q4zooe+K-&^eOw}X z-6xZz0HPGfhg&zJKJzy6uYU(783nA>mT}2}auwO5)0rr2MzQg%w{LJ<0dA+yC7j2@ z*i-6CRm3hD6?N3V9@jTCTYiQv@yhX&d?%?lE{Pb9X)gB~SrSqarTAG@1q`a@6cHJM zq$E{nF)5z^hoO0^)QH`2Npx=umH3!~SL6f^fX-(0n~5pV>ot@#pmq7%=0`h3<-3ln zPiWUVL;P-seNAd-n`ceyPo!(i6r!doL;0502EC4-Th@NsgprGNFG>q~*}sMjZae*3 zNC&)bH>2%O_oDEJm%5z>TH}#zaj?JEedgBrJZm*XvMQF7PlRrFr`npc^tu<*j4jJ& z0r%VI*BlHg-qax>s)F%zV%BpTPKxB0K&2Je`@1g`EqoTBUscVH$ z+)pI&+LDk#4*s6NV)BW#AkBuCGlv--0E@LLvJ2dLZb(#l#Ms^SqR-)zb#HUq-OGFU zetMPG_ma2I-imR`x{h7Dq0mwXFB9E-4$8CSAUVJ8SV_$sOhy$^oPM+L9;!F6qBR*8 z$WXU9KWm4Z7?|O5?11xCm4G?@t}Tz~xihU8-1#vUQRf=%^$37ZyVisi;prT}V-iL8 z;bfPmnP~Hp_X!$N7U1O=(89v7{Dz|iaQ!5@s)-W0+yWJHCeyOLejrnbCLI5Iu^sK^ z#Nj%TZ;syZ`iT7%O)P;u`gkBL3q}Tfa66TQ2P%bcUzw#q6;^XCBu0dm7Zj1o#_k;e zY93sBEVju_fWh();;?Pe5CFKr0_Gsv`)T_Z4bU*SYJKK8z2dP4;G{P%j=iyFLpO0M zMb4)k`G*crm@B+68+h6C8T-Q-{#7#BoP)wv7#G0$NS9U#6mJiJmT2$$6XdHs+Dswy zJpeP>S$E7)iK2Z}YmDXAcT#O{ev{p_aRapnrc%$(eSatGd9#^hg%5oEl_HnFjb5Ep z(iKuR#AXZQKrq{@&EY5tzpIYeU`IHY!?>WN=#9>^(i%SbYO9rgl)BEiuUbC{cMFr@ z(<}pQehuG~47i!CvM~P#C>0S41$~{7EJ)b#9_N5IbQUCwgd9I(jeaD_FihAsn=8~t z_6I^3wJaRNUM`Rvs4I9-^nek_j%H~~tTn(wk<{5thA2czl%f{dI6c4Qc%FNwc@4^4 zwIC>Jn(Z2C=I7`X7Ds=ND@5k}Yh$F(Rvl#K@WE_+xzh>Y{b`65;${@6x|cqgVmEbt zo*Xk+us(`O68JxCQsdDQ-%f~2k&FA(o1v)?(XFp&BTzD_TvDXz(jLa?Kh)d6h{gtY;94(NZ!Yl92}`T0!8AoZm#27HRjS5-{3 zq5VmhnH(KYS#DbiLNzq6+S(psSH>Q4x9DZ#GPZ+(gmlm1c8@q{dK;9j2V`im29iP~ zECt_Xx*W!mLMSYjRW>ATFi7~o&Rqws#3&X!Nv_p2msq#)9w6Rbck1ui(<)M{bOEX; z@N%-<+!WS9#9Y0B7jJ7QJamxzRLAa<}@7!@wXa8f84>~dpi3M?$_URAGO!2QHwFOSvUAEx(1MYO8(a?a2RBE75p4rW(g9h zslxo^+D*mhn_h*zZI!c#9X6(Zx`IPp|FSwq>jkdr8R0RPmaJfR)f5)+xqa`#U0g31 z`GzLsXx&dC#fAI7a`s67XU_gVx%odS=y-5I9s?d8?*Ah}f2gxMO$bcTKmP&J7*s9& zwC>dhS?|&|ofRe`NkC#2hL$@1^vf$(KCYn)ql;5PicfP{@2PTp2`i+CU!%F7e>vw1 z01R5`0lqF5wuO@7^)Hle-t`1OPmybS49dcNUa#Kn`M{S#?!52mdcFYX$IEXi+uv`e z?>Ud>HQ&NG2~EFhjQS_cK3EMuWs=W|D7dj7G#?~CnvREP&WVji0LqmU%ga4G%RL`= zz?*I+a{Xss^gKTA&Z+P7sKn}CA17>c@?BnL^uFF7i8b+GW|o=0?`diGqv|^DYGhwy zdYJX)RXIZvw@B8kNdQ%LL9=G+h2t4#nt9qFANdV84uV+YcTJk19+vR88Apd3npjmf zan<55u8jHWJaty~VouJB z7|FKTm~ISO8jQvQ##s};8nbv+t5fQ$tEYo7xTqnM^P`)8i32F;O_S>)T$~rNpf>4l zeyeH>*Js!Nw~^>^XWH|#a$o~I^e7R$YrNQsm6__Cw9o&oI$f>N6Ow2`HCa|eLF2d{ z-MSAa}2qQa4MXi9Q5KV9kH+)`Pn(cxtMRpe5&>IBymeNX@xvT>5}Cem`Yk^)d1 zy5)8Nn`Vb*5wHtdDg_z0YjdIFBZnhDaK!w`nT{ z|85`wCGJQB4#bg;WJsEZ!52uYGh4VCQ>FmJ-d@C7Xtw|%P@pJ6IGE1k(u2~nld~c> zaPL;h&Yi(-=77Xa&yUx(hX5tc8Tlu=wS%hAjO5h3kjx~cr3pI0xwlRkB%$5yIU?aw z0q~~%o?rI|brGjHk)_tWgZFDU`j|LTbM1vk!ESK^lgn3Ah;3Si!5c(2qnjuxE&!&> zm;e#a2Ux*HRHe7!k5U+3x`GCDjS!^UPC@@UI1tm0{B-<1@vqv3cr(&TzzMNsBHX_vbAxTA%Op)gAU-AB`2-FW+lV_%=m9a$aFQ zq5xbjRTW;UUsZt4UV^nuneV>~*MK)VQG5@j)#Bv&q(0r!G+1xlhSRY4*>6Zt<6S_aI%U=)O{l8M&onzklBYz z-1@>9BNGWxd|Vn+^koO@K}ASFsQlL8xshqsAx>nFeLTAE5wr|H6oo1cYwZX>5z*)0$^M%3hoh-cOlSMwlP`)2G_LMPTDXg@? zR#AALIHoyzT@v4&t1>sNBZT=%DbiW6Yh3YopYf{Cq)Ii=WG4fB$wro?tbH{DjX4sbt}srw z4Q+EUbriiyP9=4H;ySPi4dWO?m136=kAD`Ve7a3Q*E*6J61L9zwcP4vDENC9WS=Ne zkPY9DBHKJL3a6^`esUFCx^vXVGP7q;^FA{dagJAV%K=3mIF@@yL0TKg;$O(72^`{o zBUt*L@=6&7Be90>0t7}Iw^4dhe5q1;>0+6*2v|mkMMB(keQfLXG5slY-@m;sWjo`H z1ZqVmV><@%i3WTWrx0&Fy+I|-qR>D*A4FEnOmiNszxcy@13{dv zz&rR!pQ+f?dZi3cn}0(h6jvI+TmJ^uj@)Mf$rxbv(KHB{7)JSL?xFdpZ&KWbiDJ6J z?Pm0uCptMB@JwfN6;2~aVIi;DNO8Q3grt^vMn346K1Y3F{w%saP z>q>+%-Yslto|9okw7k`$q5+%G?=${6Dc;>3;0Tayucwb)u-V zhn)wy1#9ttvrDPM479o{12zHK&;x!x8=@xw4?N3_g6!d>dQ*WZD4tXEaxrAj^r*0| zk~Z!?!;kDuaOeBtk+mM_bjJbN#jJMA3s%ex*~M^or6sFwC?4ri+6U%ld$4?WRLO35 z@h@8L>6&?y3$s93;@$D$Q_s!mVtW@*67S6&J++pjKEd4j_A4m&#yC#iU4) z$3}Ov6k)&ZyvUs>jzE?R5kc*7O*sY_Ls!h)5(WeSwVrRSG`4NITx#!`gY8e1Rk?9w zg$cgfq<;ezP`{|h?q)Q9H#T@;;(If$BQA{=+JxaMrSMf4tLduVr@8g~{CMiR{_U7f zAJd%H6(TY}Z8=cDw|{LAJGjo%V0_GY{S|%4rgqP@bASQGH7Pp=tdsbV1c3PbLMl#w zgT#&do5kK$-F(k|Y+|^CWi|9eNw%{RruRU(++UvroHR63RCXeE12^cCeVooFG-Xb& zK>5W!8$MI(&0G)&pH!U2k?2<9BOBKiQ!9P-dWn*F-02Sp z9I&jBQl;^M3~aDizlhw#Ur)~S&752aOt_HyNdveGRR(LIyXRd-O9Np8HwYCVfe1;% zU*=ojszu<=;RrzP!D$UO4+BbNaV z4_)9MuJd@rU}2RuD@VLmE*X3j*0p`ha&4M1oa!x$NhBCOwJourK9yGE9MZSc2#eEssBkeQMB2#v4~w;o!jve}z6yx7Q7{a=K$gfY z65P!=!YgGs;Ze$#t{=QmkqCbqRkY@>A%!|!$v{!fSOAQYjlrf!5G0J(5@qX@Z?&iU z;KVu$*!c9$CtbX+$Q>>O>gJ}ZNZ_8faL5HCmwV99Nwsvs^5`dP=Fu?&Z^ELiN3V;& z%dJ{cnY6G7JnRt%tQBBkdJ6ny>4tV035Wv_>cUz@ng5Y;BV-oBW3h({2ap=7u?(R9 z0E?wArUl@;)yq!0P2e~SL$u2n;D$fHd4oI5ZF3VO-}fyIFuUeJ1lCkI7_F?5Z0M1T zjH)CtO`eVp-O2IElS&G4c<-*OTsQcWY?P6(Kv;(a4-Ihlbb^TSVr#6EUBxJ(B`8b} z_YIp2x3xPDh&rR8bT0)gjT&7{B}>tMY}sk0zVtPu0NOl{Ag_Zqu%}M;PIXNudXta zuF_b&h6e*{u=qxJvtlT?HVL;2b-CYv1w-khbK>sZa*lu~R`X`s7=w+v*xTK!qN2ue z_YN?H-K!fmQlE4RoI3yu;@Z_F#-Ejz7MI&%4~}(`xAo3xFO(%%9Sz&9^q(J{8MV9J zJ@Bv8n_0UOoq>n^O3xM=ue#&yZ@k#?9|U?KTHzjWd`WSWnQ2syix`aZb_CNS_2cYi zHUAZ>=uZBug0}F52gx)S!-cUR72uw7Su?1{#p7f8Q;N2F-f0R!I1VX$F&kB-5&tyT7lwba!V;(Mj3d)(KRur1Q(cvj=;SJ(CEbF-J(2_TTP_A%Pk zGJqb#NtDxOK$;teq1OjN32_evb`?)ucvn%j<+FBGy7KEX4 z+;3sXPsXm9u%iXL+lEtQPu(_y>Q_$BjLV_39R!n%j?1AjnRt3eUY=iV3pv>$MfcVn zXA=Fs&=nj(RqOm$aJ6)92XJXY?k-?0pVtI9ueW&|s$7h0+^K$V{kX4sgIW7ACgS~! zHZzU7e55T<$2P+c(^wa4;@GJjlLH64l&@^#MieZ{&*HE>sN3ey^%LlaQtxl3p!^ks z;5Yc3fgZ-i%%RyH*r6DQbQP4E(L3H^;@8mv;LFbu5Y^dPxu0QtE2KFnJY>A zO0QxwL|y-40Uoa#pfl@s^H`^tv@{&y#BJ%@1ox@!wW#srHa@u=6kPUF-h7wcS&7PS_}0WLUZ;NAXZRbIp%o&M`dGVucYeB`$IW+3;Q#!ZrhTM+NdQ# zP0F-$2h;$N?q=xL71p4i6F`yN$=mIh7tuNDr)M~_7L?jw1E1dNB-4V)E*ZfcPM{JZ0M z2!3)0+fE36#K_jS0FVc_I+);gpp1JtL#Ie^~)deKt7L#+<3R!4IFNeW_siW8aUGHUkdt z^{>VqQ1}zovo}rJK!=i&tUS(pxN8y(5_m!HuU^8BZE4TGm45Cd3^5K?LVz@)^|u|; zox*c5_-Zpg@CqyBKR#TrJn}Z}0*(gOVYD>m$z4;xo;aoRY_-$QbL!XF0(p0lI>3gM z7<=SoWAuU+LJaQAaL%e)UTrB#*7%xJCJHjD|5OjNi2v}yaI`-+RLtGPLVH)hhcb65 zXn`G1Jh!$!`sCsTCjcVo!UHX6=nf6bC{K?<1mY|lm%N5VN54S$>snXNhm&kw9{UuQ z%9JYUtU*Tt@^9eks~L*VH{EgmPk_U~GZO`go(s}mEQKu~0)TzF5N6h6d=(h={abf7 zv|m4{AB9~abUd8_QI#eZP{Q7r-q6zohj6H=vNW&afEKvzbC|@6e$mxh2$`4cvl>Q8 zOu$;JjgNSm40-MglNg-`A}rIwZv@}3#+zl7;X&p%-S)BZ2S!=#Wm2`V1>h@EPNZ8F z=X;Z}v0lgz1<}&Kigl22^t^2mL@AwdBLIshmMdnf670kTWiGNZ9ej7~l&y1wkkRz- z&(OG{`0Q7*?5XdK7OhzU(mV`~IrEn}Y^6=n)Oss)fnB^HzX>fUYNI$0baIyyUo=== zlB~1Sy!CJ0ov|Y+Jib5eTmX(MUzl|Ayz%|49rKYAKg-5u#gK1i8o)GB^=+p|F?m2o1&1zX(6a z1TB|vEeZ8MNsWx#=BttMgF7uR?H;B=00}BpH~{28uPp_luvTsew0=6TSgeZ z*xfP00Wj%I?uSu!Em8fs$Oi;uiL(%}3nuS|h()i0#{%(mDgclwCx1`X4)A{40uWyZ zsNF?!w7?$uKBUhV6VH$S5tWW#v|xW>N#@Jtd{>Tom*lXs+9%waTJ5eoRS!2>ee*D+ zE;(TPPnR$uMxb19et1pBOWgh|!_|kk~WsG7?C5neP z_!}^VM$d#?4-eovGe`0BzrQ2txFOX<3+xt>bNQF1?lkQb`z%}5E`2|Emsi19xs0<+ zc`BC;vCCEUc#;j$V-Jj-M|VM;mAd}D7Yx3icD3|q)EnyK=zth>3j4z}M#mY@-OdR7 znkIQjrfthrDE%ZWw!KDFntC4mH@$T4DV;>>H38!+`~s*tCh+(X+7F#5jq(*wj``tD zsksibf*|1@OSB)ejLTZ7INcPenDdOeO>GJOi|8l*Z@dCDs3}~$DfggY@?OT7@J~Om z`(&^H`HDG8yJ~xc%r_lGhWzkR;q0>PLA=WGg1)fA7hw zjwXLDmXQJWGGjuQiItnthaO(|$&{R%fp3z*l? zVfgif(ST5UW2H%;$`$QMlC4mSy0YS;?Gu<|_T>Y-Va$p5U>;^cce%pE*$4wri43Vk zAT%jzrs978(;x}g*BfG4D_P1Wc0+dhqliE!{zHHg_=Gk2PwVNKyl&GV($e@BsC%9h zz|U~NE#v+gFBl-0u;jKLGVqdkRq=hmK^@Lh0^r0vQbLE?*$z#Pszz-auVBl!%mI>F!=0M;tXMGBHt0?h^Ppt)~HRO8?ER z*C)Yom5jzq@^M7dHm>6`u-pYfa=?RVK^o-fP^o&>IKL#_G9`uLhcwYZwF;l(MlG^J zjl~_I*rXKm$CZ9cRXPC12}e$vjh6rHmp|Y_VS5TfJLbYu*~DS2nV>MDfFe}51-F1F zqi_V321P04K>DTZex+Gs%q^e8%iSBTP#V)5#mCaEcQtYGD0$ODQWvR#$ z2qOtb$*5r-)Dl1w8KHsWj*>p)776Foef$dS6(&_dC)+bW0KPw_0tQ`vD(N)i7T{HZ zB9p8ft81Ar@=}Fr0s)O%og z!F^S1^9flAQNi`X>gY?!hFP=89oz_uo zYsKQ8lnlw_KZyXC#FI=J!B)?zRo_@ae@(28_N$3_S|iN*hiWuLvRNA^x?oR%&26Y(qw zn2vZsCu*^AKJ!Y-b*U~NW|~hz)$(8Mb_HnRY7aez(5aGrUWuajt`pmYbGGJVtqjlP zgT{#$pT*3s^R*a%S{}{%n`AV^eqzi%UX^T=F5_`cl=^P~=`g%2fIty`YpP*kd6H>W z`>n?Km+zoSvy6w3L;G1M@`wFEo;vzz&E zB5l;%Wl*6%#5Zgu_S!C9JDv21{kDUi$2!un`}pQ{T`MBplwqJ!bn zcuCS#5_n1|8nDff_;uCwjL%$gRDNFZAlJsL<9PI~jV^TD zkQ#5SB(Qg*6{`5W5SaGGwD)DeuM8TLI%3UN$+#9GCRhW-UT2erD|5>}1&hoUDK0W_ zU+5wS3q9=rssM+zo(kJu1wYmbydrG&M`N!iWUigy3?L@-qII6#nIZ)1p&) zYwEMp5Kyp%nlhm6dl>P0IIEPtd<}SgI9G)!`xCm&&Q!9@+Gru4Hl>BDYKCMCvyww4_{wI<9EOfrC_kC+4w$7P7A^VX3+*Ra+@BvGCMML#afRL`D zjE6S0r%T9Ixd^smD{17gk7J z;kHD<4v32IA_}L72{(I&9_p?pYl_&QaObf`$;YkJbMaJrN^zt`zQ2Cru|t-3;w)ho z8)h__Vpc;BX=OQ}U~$1e>?GC|GDLZ|Ny$7OPQv&1Xbl)6H8}y5v>P0CWRLobBFYC5 z(j>|g0mB@g!2`?^bcq*H;_%o(u?XA7i-SYN0CqD7f0=Uw&xk6GXiHV5&kWkCp`YX2 zI1@Bhn+zs#RT~*U6tKw=0B3=2=omZdSf>S)!P?IH&eUqWh!Ag3*gsfAzv8!P4h+h@ zpjbYXKS3(Hb6YKrCo;&pmc`9>w4)1NckTKAn@${_Ho9Y`hYoPV$4BvqXlIWF#?f8? zmX?>NZ%E~r!hn=xp8u!B{VFdU4Fnel7hB3B5()_*bM-h=y9Fl~d6o(ku26X48Cqs- zeyy3(Bd$>)K4MzmWX7&4hRj@}kVdAS7|Q2+x?iuYJ?8smqUHNFIMHZR=H;9i$fN)y zQQ-QWLa=;oBLpxlfQ9U_6}oxu`P}{cKBD*iarq2jCI)=z>F-BM?-r~)7|6?wo-0r+ zRwe=tyjk&2^>&|iu{v5`a=C9S3oT$26J>a?JmiiU5s`a@~neW38-~VB6z(&6}WTguc&fwf%v}sqQ zMGohyjs3h~AxG#e#8g-;A5NBzGQa;aZwNrHeEyIvmEe$iZW4xwiPqt zMxizDHsjzx^D=RzFmfe}%g+=?a<-|6gV`oPaLeV0^W$V&66Vu4wPr7i<7`?KrYPjW zN0CCe%#u!|F^#j%UbmoF78CPQzEyvsPL1La^xh5rCI{;CeSGU zB72WLYQ_tFkw1~NvF#K#Y zAGu-wA~u4%EJ-A!0~-G$^=rO$ahle-T)r4jgcTK%tBuObk$x|DRhX4T3?IiCD4%74 zwDo_>f2KEpPVG3Dau$j4ghk#?|5F7=?Q!SaiE9pvY)q@0ZX|bE8m4-b$yhs+D=g%} zMfu+XFs)%Jn}#UfKe>YKjPJ{9Z|0v64Y!ke0h)&NUo2b|?IWRPZ`gW?UvLF`%t&*{ z|E3#{!i%kp4M|INnj3lRv`e({SE9-Vcy#P87Y7C9^x*8j_1sG!mzig-thN1Cz2q;; zY=Ar#%y41Z*^Z$*u^_^P5Z}8+U4_TmTB9s7>Si!zSO-I|#cm{Uw)W{Go9y~|*mAOG z2#{k`UAzJkBAkuy1^j3aR#@4JBL5bL_~@uk|6HEkQ|k9QzwA$Ib@Z&5(QD@Gj`re9 zZr=$_R1PNS^QTtd-1Gh+vUmrA^u7xnl67q*?H>T#t}hEjaG7iou`{?G^Qf_WMcA_H zwcQj&=2$XOIR|1FwLo(n6{tM6qjvJn17@?o6<$7G;|n{DQu2SrqcYTr1V<+@zZaXk zgS_i84?zJgo=h9Sqs?#9HvN&96YPar6u&r*tcj+*pf#;>ND&2}i&h^Tv0D?T7WZ8z zskPQIKEU=fYVfRqOb}Urq-1IODzt|nKDt(?teepvnjnbsUes0gCn10hO-INBn#v91 zQ9I8*ySf~`a?eCpIHyq82e(VSxf0twQScl2 z5_-v(4Q^tb4g0hrSTlvJbZ4dp>|_FXsb@7D9KlMFO(6JfUt_E01!-f`O)uiaV`%gT zgLe)vbuv4TFg>y113jO9b|hm6KW59pK0H0sg7%5k^>vlWl4WigcO>%7bzG<6RRrX>3pr<{sIhM{0{F#==OC+=M>f@S)@Ygg=d+o8K19bE z{$;eDO6ds})>AyG!qa?f0DHO32X7~JYp{*cMoz4DIeNq+1ZF~p2q5u?O>vW`N}4JV zJx3+Myr?$MM!|D2o5%B_lZCzy4?nou*+5KSroGN#rIr)JkyXTtQR z3&;P5GdnDSJyQ9yC)m+Cz2T&)_3th#@|Pq=gTioLbm%=(TjhaC00hJAX5Yc+1^k=X zkDR_j`if1-=SDKUemHOuKUWdTT^OvD;$X@ZZDUwRw9Ynum-8{Vt}S$Cy=w@j1kGzy z{%dqEbA7K66z1~bAXs(%5dCDk&~ymIoVr`q)cpzNi+Ibqs7v(PUOY-hEdEZ5M1sBq z-;;O|NT@!!0YCT~K&u@cUe95^2n;ECPtvfdgChkM<%)mxPf z`r`K@K`az}c8&#-l>hai*s78wxB#^=y%skRLd#Pe2j^gjh2ljeyPtSDADRkjfG`RI zsL~xFeq>YzUZVbhb1xA~?xD^D{mk+Zg>|K5+!%m2=}t#TfI0C+k(xn&g7C97?-^*E2=5TPpldnR zW^qmIKsg`{R(|?Jy7ZPch1}`_jZZYTAHXPamt%MibRVVi>{JfetQdk|OhI7bAzLaT z7Z=n?VtC_2G!WA2$rx5u(?imqay5LKVt5Ge6kx#(1gatu@gfeQtfp|ARJ}PvXKrE&NB{TpvUX=mkW5yqo8-9N})Zt)#xTCT>F#a-edY81AtPO~|*X2a7( zU(Zn2z2YZ}bUD?l@`V>;90}Y z0J~UjbJAtaCByBK6|x`qiRfhVX7x@g|nwamgEqP;`{nv(m zti6*I_GsNQnd_j1-&fC3)TX+WW&CE86y|qZ5fI}M(3g)vUCBY#r_@!^_1{;ev;Uu0 zMPu5*GS(_gO3(J3Fb}%`Rl0Q=Y5p#UTYQp{x=V{kFRu)QAQU~(#{nD;b+Aa^lzV2} zS8dh1GyIN7>;IQJOxAC1RJ(GI86ua_L1Mv;2&^_FctxwFFHC5WNUud;?yb$?F=(48gg^ZMM^w9zUU2O^S} zw={4)5CQ!O%V+75CrE^s@?SLNAbkq;-1l}X5&_CEh?%>uC+5E_9e;dQl=kSd#-__I z*g)?u6BrO)j_j`dat}c#qqXtDp%Lt${mUOw8D{a@o5<`%{91;1fewpEBdUEw0EkTu z&74*tow@`l?6qt>a+Mv+@dvJb(!4P2Ld~WY3xI5<5oyR(@MAjqp%$sX=PF1Lf!YM| zCzxM}$;9Hd;L%;1XalDGQnPd{%$h(cLe?aMcgO)-v6ibJtz=Buit^!uRbd z5+6G5IKcA6K&uzvfY{Y=P@Pu;C(stS1-YW|yhQ*Q-0`t^dz7IZzVomgE~?#e`ntqz z&B#}%u6BjBsjTM0YF~5)8U=7Z^&?Db=BqQ0kaE>!AaA`aKt{cw)3hg6_@zop?I7~}Aiut&$&TgqNz zrv`zx*+l!!*07IADY3-$)dlt{5aV>1Q4c64D4+Vva167HRGiJl9T415M}-v9PbCOL zx_QF&ynZGa!+hnC9*!1I8(S$>zmM%-5C8+?g$tgx87hes5~yg>xJtkE?WN+%ISW(C zU(@MD;ovHPm$T_gfiCP)i-wzBERc$ujv>%;24y4Awu6)~Kr*@v&eX^ac?jFCVSzuJ z&wNqYO1?KdI^THBcY^GrXjr`o;%Yd7CYIcDa=$xm$@@uu%3<#+V@`*m>;BdNVEI7( zjl?5tPL7k6L_{Na*BZv5=S$GUJZ78&8o54%62e<8qP`j>RNz6HBMMWjJ_Ni|2n(Ic zwQ(E*tRMlZO~&yGWjhZ%bC!E`ct0&3L#?#^T|X_{gpS+AOSomo^jRZtJXg_I6H<|D z`IGm(A7-a)dyA)8m62^hQvh^gDeAl|#rWqGI!UDcJ?Bo^5%gTYhbP=|D0#E&Z^IW* z&1-v!)G?{6D2r?1u0ig7DY4DlAP|o%qg4==RCmkZDBR>fA+{LG+5FmErKArDBr1g+ zZBzVLp;QLI-Mru5H{&8Bym<>wW=uuk3UT_tKFJ@}8M>5$AbLy){{mJID9P=Nho%&E zR`b;dDfDA2RHnH4;|+uKj4}GE&Zm;R?5pQ?BcHT%8yI;8Mq9KHY>Dz1I5j)2*$XP% z*0Y_Fya3(&Y|;ZpC)@~BupW9-j~4&t?O@}W)hI4od2lmhsq~LZMhnkcTLsa%_W}MGxuRd8(DXLb!@9nt$2Y7Z^BE?@DiyUU7y1~jUn=J)_G|`l zIP3K^r;MS-Fa@!H_lA@?j9@**G_AEc@V)K6->}Y19Y67~mmBw2{;|3RdyS>Wva1+`@_DH zDGFF`puTpiq>%n(NO?D8m&1@4RBzIrdBK!JnzrzQ6hnjBQQ9~p5FQXSs0a-)3!Grj z@`pWT=k^2PDFr|^D5S~?l=45wQ4OeV95Sd3h<&A^U4gpxZNd3VQWX~9-mP7y@%8+( zYdeK&kzK#mA>37d6nVHjnX=Uw;b zUxjJ+Q8TO9Rw0VGW{#P{#eitcL>gQ zlGGzK>3}Zj7kDxn>91nhaQgUZqfP!Oll)pQ4q1@rii}?g!2NjcNnnGDIyg&h+jK`> zP}qu06{PHP2Q#oHeX^k5POv!fuxW3_WbUljw^aB{^BkV3kzxRq_gsVgT9096sizjN zsZl`S#YLk1v-jo|9L>oGZ(o@9_AbM++&m20UymFt{pYd2} zY`;XU;}UO#=0i0Me+x#`*2#&X-i?Wl3=sccg#C3?9NiZMh~n-L+}&M*y9E#K?he6% zH0}_BySoN=g1fsr!QFl8`_0T-Yi7N--d|PK-F2(#R@Lou_C0&=KP^8&(o67|tqVaF zQ4@-34b*9GRjRd&>X_r2#<-ndl;l%sqqB2Uu)SFzh|-kD>I=mS25~fOo&q#2?7R%C zpsxGk$i;&>CfOn2tgHI9Fkc?f{ln!tyXX{q#5Z%gPgooO@@7WM56h&{N9P$_>>N!# z_Nq0j8D0Pp6ecLd-qs+R>v4T{IQXpThSXKit76`T0VSRF_Zou12Xx!a!3GQhH7M#U zt!SM7dv>eT-S3Fra8^^UN9s;XY|t%kIF;F`T-g%Nq#-NaVIqV6lQi>*bKvhjF`6`T zQuJMD$=?L4(MA;2X1nroOV(D*@tbR{-J0<;$q;jT{VO1L7v3ZTf8R=B<%+V%u+u-B z1EnRBl$g&2Zk|WtUF-fVht9a^o=UR1p`^15I8I_0E|$rm5xplpOe2OQQDsJAhw&qi z5%TP=80GEj(>vfVURis9qlsA~z7s;;L`l3n)>KV$5tN%yl8G4g=05a#v|E(+c}qVW z@n$gL*a4{Q2%q|9XlF-(c2h6gyv(SVohH6eNa6n% zZdO0cHfhg=VM>Vnf1`Jx|6lMO%jyT=U#nACgVfh~bQ`VF_q`u+hWyc2ZV3~II5Dn& z^eypjep)OY$oidXLq z1z&bHz5*5}#gWdx^ep{{sv<5C0RN57>kh7KePha}19KN|*!*X{ab?gnDnc?Kh!RoU z1L2J&;Hmjjh7;akNc7_gCkA?^C`=nrD&J&XW?{|1A+`XFT!u0VP(==-A8q&qzNI+F z*;;1i1`T|7djR4JZ_2;>C(I08(Ayu1P=n`CS+dpp8zo`O=muhM*G5lT@}7J?XN=D~ zd&P^U=w>)ZB%&Yde4t~7}68V0k+!C0T>{)8wt#Stu^e(<&) z7(Yh0ALeux=hd6(&HeE@R4+TsbhY(6%mj_e;p@0EuXv_<>~;C~+pid%jU z%he(UJb{j4dAK8LEJ=Hm^rog$VLSTed;|e$=`|=vVQj-G5#!b+jvoS0tv9E5fGGWG z;+G|kxb5~O4$eWq>@SMuzi_jnl_eW$t1~+f#1X6F4D5`(Op#r)8qcYB2kcAC%TR5Z z+XFEXrLH$65=aH?O6?y9v~2R6PP6x4b4JJaNLlC(Z~q+*FyYu+z}`K@llgP^GjtM8 zZ)NNBXDG&PO#DFn)X^u4_M5^t?2Nq2B*s~Jr~y|NYMyV{bi{WTV$O%H`k=94mG0Ib zL@9wVSND8>ZOZJrM zwJz5(wpC#E#q0lj@$Ep7q}IjjX;R_rHMif0-}Ag^F;zF>U^AJly|x7IF8=-4726%N za3a5>=G9s{wGtgs%a;4v_<+i_8A;H&8ByTl%$Vtox%1*Sd3RqPpI@Nh zj(1E<3V$39kG~}q8b`(qlM{pRIqT*dedY7@3c<=*49x9$0GBWb50kAed1~A3gixo( z0z1mhVus=36nGg4`Wpc2t^{|Cj;@JlP8Z8K{{W@l11aEv;3trT_ysj2gyM4(ImlP= zJ()1j=|vH^3z{7}ReD+dOyE}T2ZF=v2(j)7eMW~Bf6xvdbmM%+@n1FZa(&bp!wScT_lnS=-IF`|~b`Do+=DE?X+ z$c8jq5qS8@1OebS>}Ecbp+0#JJMNRw8gkv4u@$I9D&* zj~N{CE)<=a-@~gR6O7TlH%4UyO_*vY78k1R2r<>!96qOvd$HWJ6}RwHc^%sY1Ko?>T{F*^6{BqAAZc%jHW9NZ{YT{TC}q2-v5K-q9rKTl zqD8G#n`s7MR-;Jk{^jC3b&oEQc||(r*_TTsTLXx3GB+h7sM~Y@FIuh1V?n`C+nOM% zJbTxa1!^B_ADusnItO`xvlx-lw*Ob<^w0e6Gb9O1WrridKpAZysHQa~ z2kIIg#axV%*{GB~5W4eqTF#BU@Ei@TR!9p4lIOy_SfAx^)Bn@|0`w#3X|^ za7(#=K2ndG0-z@Tf4>5qDzHNIxx$D^#{YD?(TU5W(au+5nm{2o{MsfR;7^qK^J%T= z{MhNJiShhuriKXMwT@B$EwQu&?;Vf?JEp0QUiyJa7RZ0)m9zJ;+t2g5oP34(B~$ zakh19h}!M_9&47Tp!1LXz#}1sgoeBvjB|x^?IEya{3$<4Xn6}(ye%kgBIcJ-W=+rb z?5hTpu&91xx#fAyT^)MBe56GBzSanXUQTHkBL*FyL9aPVpU*6gpn&g5y$>7jms@FZ zor9MdJa4xk5|HN_=y@$i==}rrq@0|u;%h__mVK^_3pLiWy14|c);h)TC=bpJBbMdmg8pE`?KmS%E$Bh->naI zTg;F1^R-XE(NU<&}W27VFH>L6KO2)1#>C|O&R%4EumWD4W= z-6fkm)GRTq*^CO$k(1)_P_?m0ek)r%Fm7|4RRba_V#({Qluo4WboRicUv<8Blu>=A zpMO{I+1LV4JbC%Xxrxm6`(xQlJ{}EDw;xD8zxZ`^D~0A1HokuuJvYEcdK1C(v1jPp zYW@oeO3d;@4G+6}7V?vEuSBHhz5KankrGO$NHiOcS29;{^JfM$TyW;Hyc%OKdwV{t zGGNxW2XYLHdFUkKrn-0HC!{SZusOs0Y<V<=QfDr9aaK3b!V0!-Ibkw*(7?-o*740l@=F&znOPk8KJ>ENKY_C#QTsq`xV%u8{U(SuY8jz3hz=c}C3 zJ-uLKbU5(RM7v(v{zys9IC8yZ&x+AaghSx55q-(8hW}b4bc)m@#Pf^HWypS-N7u81 z=s5c!Cg8+W%RJN6kI*<)vjcoH%r)|;HZ8y=!Qj9 zJslsb!Idexb?kHC+iZr#h02l(V9eFvAf`5pveB`sVH|}>I-lzPxIBB)a6Dl1{+`bb&+j zs~>a&>W{AG8oG|dMNzpzX92?pup`@~dLlk!j5v$YP8d3kr0p=pG_c?c-L5~Cq4&82 z>C)gZhH4r#UswcLO!iU4P+O+dnA=yV-6=?(w3a>%4ec%B@p1{*9~ z*wL3}8g`8b9{w%{_xns!46n{R=wy+b{iaQut|H&nAl-ooO_as_il=^3PSF-oZ1P)I z{2dkT6>nHA6rfh8QAC^3oBp~U2sK3DxbJVF>uWODKvtbng+M%ST5Am&S#%e9%EAg% z<$Y<`$7&|62_7~<&s5H+G)Q*^PX13fyxV3{ql2wT$DwO{e4wmNvV|9{1ZjeuTDUCB z#0~cT@ybdvh{_+zR?msX`0cdFc*f-Fm0YI;0nVmP{#Ss|)=#PXYlfE46qF0~^etG0zWxCcD?m?7V2uubmB-3X^m{{TLy+C603sls70(a{FY^q0@(#b!7f7-G= zZz$d{t&J^2$K6R?W)Y<-=gR4^EVyWHZW_K1;VaN$v~2jge13BhoL44Gh>Q4FC#M$s zU)eHi0x6-or@sWWtH75$cnTF6ebJxOghMqNQNJrICqP$Pg>aIjGSTMH9q_gNa#3QJ zFI`_Z+0^C)3wmuFVz-%KnRMxANg;arMsY|R7%^l6eYV6=8g&rM1;k0YXx|lS7A@q?=iN4~5K_-v;;u%kj?bGXz1`XPUDwg}Q)K&$a*Cb9=ca!UwfJvNGAPQB7pkYq3nCObw`$#fk@6gqA zO$X}MJWJ(RABR&SpiLOKq~oLG+6y$NofPg7gyUTW{*2C$1{S&S z<(O9#KbWQ8h>J0-@DK_pHW$^f3C@P}p#Fi%scRo|b~W51>}h4>v=?7{<`36KLD?~b zpJJhjh~dZkARq=4@m*=$N}Hrp(pN$D;X`hmz#btdR4lfyyuu z|7i}Ut{hm9f0gZ_Vpu0HRQbBsoKIO5{bkd#kkxPfVf%9p@h($n@H`~5eqNAT^r>JX zzdTCkgjkid@Evra!^E2(@s;WIjN39z-)0&&v4lbA=;Al&n}ZulvLfjS71L~BT=PX2 z2KynSx=oR2MSO?uUI#QFi4LW836eOjMMv28v3bKMpvi>4F%o#hKy+J{Vx8@DFHfZu zj28*K@*c7E=`dDE;KqG>6;+*_Yiu8JqkbK{8JC0LK!jc-w*I0&%G!0Fo`38Q2P4)r zs<#dePlFuJp=P!-fS=MaHg2uPiei*$XakJrESp9c7va3da1jtYELGXzpgRqR4wXFI z9a~AD(zHdW6gP`gQ6c~--y|>(w=>Xi>7OPr+E%3|!4kD|V-dvV)Ys^=(t&GyjPvgc7 zovxI^yq3+Nz2Dtr!S@7hGv&n2tn^woNOa6HcQhRmLCKW~M- zl^*iD1DQBpB2Wxxw(M2Dk|yLM@xJ%9)2g;ew5OJR#+>I}cMWnq3f$j{%m;e^NbNcz zCOAA>vONk+aDx}5=egG$>2@Er+`HgM5-T)O9%$tAkzQmzt@R!INA}1x{<+D!q6O?;9s+cOQTjRMMNCaq_oDN8mDa(!>V|Z& zz>Idd+ESWoZ@hu=ENlDMSsTPgdr42a3VCsDB|U|eq$XAA1N^bJSsMg+hYRxl{Opzs zfIiFvD)x2pwdM+WnrMfsG3TGtTEtxHJd;{0Gd=vtaQf}kK*re>b4OzybEzuY?B8U= zqpx*i$kl{Ya0q>e1a--rNWr_mKW*1|DUM^qf8KZ=V6zE@8V6=Tl$3xOaSlh`h ziUJ3}+GUm@drxVFYT9WdH_+`m|5kaBOi}C%#mOeVXc~)>yyWF5(cRYbOcG`i=phT|7&v>yVzA1b?n!Pv&+n|k9K0jz3*&r*GVbL7;jnzNW3Ph( zViQLpvrp-eV*3VD>qxWv$K3~v{O6P$jVva|Y8I!%Z*K#7$#_qtRBl7>!Fuw=Q7J>Y zaVs97TUXz<7}eXXr;XjrSr~^~BX(aCXc!hHJWgJWYCx;#1`Y*hWIec;^12xI@Sda; z&B)gW$zOcj%42%X7J@y3r~i<1*a~tQq`dd9NMXX_E}UU}@X&aNE?ycCbs<)9M7>5; zT4oFX#k;d75RMGS?((gi1~2I6;%~+aXX!dIMZS35sO(#c$59qPGaCL@!MY6MR$^hL z<}n!QP4c#vU%F$&ZX_Nk{THTGIqoFQFaoE78rYMYrgMUrx9(xrgS0-(alDSQpk2He zXSATTgE=RH9MQ9(KIdWhr>9)|FcuQma6I-al~ygJxv2bb54`auVuajEcgTxw}`iu#dv{!(aE51@R|1_n&dr&wpmU_p&+Xk^-XAm^FF42K7i-{TB6>{$@8U!J;0z z3P;}^C9T_9iE;O-b`tKw3*Ia0HK9*NRmJsV7#@K2%@eqLHspwo#ep$`RP_Z8n=RFS zXa)<9bZ2iV*!Z&Ge23K$0*5gHM!0mKBC^+$31QgN?Zi)z`9!o)-V|SI5_nlqE5O4BRDPuL2>U_gunFYYys2O0_l>?c zAi)n4%13@3R~jeNWMyLuBb;l9??>{YOudrAS<$kKa73{vty@W2<<#uKmlvQsEdshh zfIBCqb3+zGsU81IcR>Bg5Z)jlC+p6ix=x3JTFDXKEF|39pSJah+f_$4^70qRX2ClK zutu+p1cE#(NkG*4)kFfjVxhxYZqBXUT;2~)8p{bqLMLwO!@M=Njx(;YO9sya*Dmc} zhJ<+6P0twKHU@uPpWV7?I?(%QSBz;O3;yeST-ALoeQk6l-H6~Hw)EJwLCn7IphrEd z`kMIJANnpj+E`6ghbQO~XMT`r>hKiTzmsapVek)SR{<37nFjF3*Lq-NJLDsud`0`M z+Q%OC9bsUZ*b2@!OSM|U)Ma)RVAVHX9OO(F+7n70;k(-Bng9+i>f<`(IwxDf zdukMKZSxE*AciA-u`y8?(4AYFcZd}A#ktEDy%Ez(%ve`T2 z1lxgD3P8VckS8yHO+e|8pVuR`Ie%i~+`p(7A| z{h&AkGYp>EiYL{RlcrAli8iS3{Wtr)gA( zTNN~-U5*ct1v-}MFsSPP4uMpaF0hqpn`w-Y5Z`P{*hrmz#naU#7lbEwJs|P*^tr5Z ze4T4i4I{dK6z(_?RFFh|WmXtNo=fbz6y1-~=piEDiJ*v!59lHUA!9;j&`zLB2O`Bo z#c!TN9{ZvC1*-R)>|C<~$VvxUx$;@OjRPx`7rX|>`m@HDdI@DPYV#eF3>fquQX|{X zHoz*>jwQi?E{!9?ks3?%${eW=+0WBN1{GXdN>M*8&sfmHBG}l(SunUIz67b8&mA|E zad#TjjxB}*?aTGsEMXb64|zQj$rz>);G%j77EB9N%mr35HBZU%wDRX=1_#5wK84%R zTaQo!DO@M`94VBs4i&=QZ{KQ2flwx~db1KfQV12Qss@6sGi?7ixF|dXgBN%USySLi z5@TGG0tGl(CP9%|3JYQh-&*j};MkdC8s6V;|6y)ygzQcE*&qp>6^wT(gJwe!l(@s9 zr!F9LbRA3|yV9%0-pk64Ony{|Bu8)=EFCO^Hfw3NA0gD;vyqZRtke`ipJRDWHFO!x zz>SklhN?chBg5`v<7fV({QYZwG_PKW14m3R9>@sx+jq$nO620-w3QnHkr)NDDwfs~ z*;44k&~|m;9He(LbZ9O==Fo5OGAI?44W9csR)Io8hM05zs{sc$W$Lyf@M)vB?)m-7 zCcX+zgJ&%pJ4Et0z6-;?zrodD&@M5~#Si2(K{Qy~ye^k35f63q|3rIERk4?qib}o!Q zcm@5&)Bw%p{3Xvy2Zh>3(&D?Yd<9D`SH2e)UNK8WoZ~el&YBfj$>*a`$75L$sM!fc zXqwKyB7tu~11a{%!?p)i`g2G`z#zj05)EUSeU+me)(MXH)-?UL_X%mZo7&~y&8w{U zN}ZeTWPp!CCi*0fOfrYUhj7UmPn!IfwC{F?TaL$)4k`P%Dl{ zTZjkZluSyVUs(p<`=BL#91VeCKki{@PK^p#O(omx5s*Qq!NJN5W<46O(t{7r-}jdF zWvk*K6)C}~eN=_qyWaF2`U7HM7k{v^4TVs05HbDV8d&Acho!&BB|8|$kwQGfRI$1P z-43(g#^W^dG1^i66*D-kqjdtLDW^yyuR|}`ED?D1I%2Pc?^RYH5`de})8+b>TL;-! z?2p*CSPa}QeIKLQZw2{KgTm*$Wu2YGp^XtU%+|3$D)`7MS?0EaKtYZ*JoQWbPcYh5 zK)*@KpcAabG!ZL$B~ghjhJRc_ke+hv5MN`tDOV$IQN8w@5rA$^%YpnKS~~Wdnn>;P z5Hs^~qeiJ^J#=Kzy3nq#_cF&=U&FwHf7qAW+kN-GU4XC{2D_#8!HfgosU`1*U%e@F zfXD;0Bz%guO;Q_lPsF1Cfujba9|cT9Ekx##>-q(47MoJUJTQ6Es^PRnVG|KvnM2g8_X4?{>MftY!l) zM8IL7?ckr`VWNJbA>^KFe|C!M!`TA&;zcM|#5bE4>wY#FJMvC5%EYz=ML!YPgyE|> z3d^+zZamZ{bhYMb>^a)ZYq#8PJ7+36o;sOC5}XuEE}j4eb5PYhBDpA3;FMw#c^8{v zKpaa+lQz6zK}x<4{vmt3|5b>2qiPTAjw>@I+^L8YwCGY1C6nIKZ@_NM&TA(Un-3am zSa^M8ezdgtDv9)-UluK3-4`l_4c;)0Tok4zPdNZbxb zfgWCDxY?JN0rZYwP&b-;lzis}{FgG6RM8j1875GR9=W#lqhqmq4)`eq3RKYhoWxR1 zglE_evf%Zggy$Mkv`B3}H~QI&WVb@=&Zt7+W+gZL0DzLpN@Ial<4rd3;YZ}!{x-UT z9)7L8j)Co{XF;+l;4cX+C|fd+72I}!YP6T@I+rH-#!rySU-kS}Lu^*;W+sS=m8;DeTlp%+$IJ%QQL-CdrsaSNONvNv^KY+?ZY zi-#H7rw!)VAnXtnmxLLW6FM24he8jsuPAcaKP(vYZm&P6HX{*wIXD4Ivv*aWuF5Rz zoot-uP_H(l13D#BG!MW+H{Q9PGYR3@mqi1;{J?J9;kzak@?BWySY=uEy?AhBrA^;Zga8d)7-ptl|25T0FHm$ z1_n`vTL`5>6xsHIB)lm^p z3AZ^mVOi(+Yfw`%xRI)R-uZ%Yyx?f1V7M(ASW^fT4~h9fDP>Vm10ix3pqjj{HA!`6 zzJRsMa|zLre9ma9t)%r>$6#L*n{`@M$xz`9NG2=zYt8>&tO5j+CtZH{YX1+f@CWb; z_Qd;O0IvX;)c?aPD*nSOK+GbvCo-o7616UtD`{Pot71LU8#)1L zWv#^|byXQBR~%9-w?a3Td@V1QSC6M#O*E+DPSowcP|;(3%~x}uZz;`xyTfdB-%gwV z&nZ^F|4qWaliaQ4e0)>~*;jZ6t!Rk6*s)E2%`Na30&i0y0hxETT6`0KDeTtBo{I;S z-gn9lCKo6`)6R%`*C~|1ius5*LOc&);&#I|P0cqEod=V=hAc=CWI`BL+de)}>r^ak zidoM0W&LXqdT#L!TJ`Sc*!&=L~_TRd6BZ|W>))W|_1uZvYI%&0YA*`?N z+-eh=NVQkN<{j)Xvj#1{8kB~@IOXak5Wz_Om+^V~Eb^e#aIuAN#VC}!lFoZg<7bd* z^4c-f&k)mv0W$QN*F77?-vnX)2ZG>KJ&bzubPV*6J{VSfJhmf? zK%PTvcAsyQ6$KdUpBV~#PLNp)Q}7{WB9q7)p^>=u4td2vZK~n%QY?fZJ!|8zw-4zL zBk*2|iDeMGkugA8;@m9piERm1ZRoEzsF$C=3v6&l|7xGk@xfU_2VR%cmL+C)B8KON zQxM#`@F|}L%w)Cc92;grQ*S>QREx{D3HuP>NDt12&S0FmbrJB7!_SPN-6p zQ~05|e^@~`EQvvh3ECyQ(L74Jc)bF&?6_5Pk2=MgnsR@J$$jG|C{2%BjTO~>C?NP%%ac_i2-nepjV z_*_Jtnq=4e&I{mR;@{d`mx{QtcFlt_PJDcQH}WB8gCKrb^zw-(WH(GozgwPWDk;FV z3rCnU`}u?tb#igZ^EmT$Lo)eHe_L8D(s&`wX`1bRFVJ`~+BPdf7D_aArl@DW0Z~H| z!m53vx4`sj3Z%}SR)cls&cGZ+1fY_PLF-t&X|N~yP$ClULttuHpLK8LYdcj?YI?5y ztN{iVb~OFUu-^V$|83neIkgH0&NJn;MHwTr9corP1I?fh*rk$}X&6r+K*`tMW}h3{ z`9ccA<|_0QjXi*zlfLs`i`^iseNG>}4AC>xHG)f5lk@^G?4eX6$@DUD0hTC#>2e=D zA+7<^&9}Izj;1|K1&22y62PzG0qjirYTt}&E5esI69ehtj1S$dPl%T_2djT(@I}Oq%h&6Vu>qfBCvC_55_i{@?rPPjJu&lK%P68hVk864xlLT^7*I z)5&(u8r+~Hi|`fTMl9w9L(r<1`0Z?EeW**^sLHAs<|x7TKZrr~KZpT4wCXUsGCu0Gu?Lsd>wkUZ3Q+#RsKy8y_;&+f@*1BpEx7(}pCkuV zW!vTsW+}UY2ns2~%5cOf!bS+rXl$IE%sgDA92^|~E!emcz;UQkjDiu6AUJtb*ff#p z{{Pq2fb*uzXcEwXczD>@{~x6_=lW~aR6Gv8moM zwMgbCteAS)WHo)nD!FKP`t1My#rSpO{V#}}tmXW1LK^gZ$RZ3n13jJB7=FCfe>|OnC}J9^Lw}j| zhRvWMEY+BmZGH=M6}^=FjQ-4AGf51A&48?lbbG#kM}0aq1U=szUcU5sej(laoE>8M z>&M2zMJ5+Z^7rjrZXV_HW$dr-TfrjC$MIgu=Tm$lxT&4$#~cfiPD0WIS&kcYXu9Mc}{jLY9@P>9OsO>DQ< zhk-J964c2d-R2g3L+t@LQSVoqYC#aPFp*MZ2ltZvyk(_2-{76eQs~AJN(5#DCGDQ8 zfVIecV(7r7I2FBR0`I*d5h@WEzTcjpyXx#<6<1duxiaO~r0(6(hWX^=5Vh2;!;U^K z{#>Mz2+7i}SfgY$*_04dg}=yQBJCp;!TjHJY=^U;hI>+Ji&TZdN>A;+@jZcDiMEz! zcZG_4fN}?!HL{&kq7*OaO;|14k*q@Icj6_M_1`-S5}$6B9vW+c4ouWkf9D^PC2}S8 zj9nH-DjW9|P5Nq;#BZ?E1)FOVkJx@*{Ia{y*$V$5#6mTH@^Rik&HLFU`6juASCJ1- zBQBOZjspKzcLuB{h9Zj*M@0^FL3!2Jsyk<`B$z?Ebdk&VP$vxqTFs^~)Dt0?O#RaU z;~@hT2`eJIvHG$c?@s|!Mm1_l-J^Y+VjVho02NrCF6=lRui4dLENM-I;rHl8xZ1+e zGmGRPyIIMm&}xL>c^K7P$GM}65&)y$+euozV$KB5yE=RjqH}>+!*B$O5WPPp;Y|>c zKIpub<0upFC4r@lgiw2%mA8@gp>BA!@c)zUkbnU5oRYp752zji)V>TVf@Z3`up>W2h^64bmQNHzsMI9F!@J@nj4ZxRvNkYJ~H@)(JF)jBD z)B?#oG9M4ufGA0fDkoZ-yg%|Aw+@1&Z&lA)7EpIY;i>Pi$Ze*aN05#YcNuvfb&#LW z)f?;#`979Pxo&!E)_-equP>H&_`Z#y^b#>6>@6N0VZ}mlO$?H*cN+ZWIq(rAPT^9< z#Ds|Vln6BXh3M6@oKYh8J+zov*bcW?vI___yYkQ~r^ZHM-}n^L4QgNm zvQ*jG>*PXLWud5Ac3SN6V3dL)xqD~l&*QGbenD56O!`?rHBdef(k+nr%GVUYNJ>MO*RH0WK#kW`uO6g!Bm+XF(e{m4S9eWIy92 zrhUm0Ir*%^v&r+s@AkEk8yO76)m0D^n8gGauST^R6g2yR-uQxwFF9bSrNgZoFD<5& zv~F`yH3yOtFZl2F-;c7`oJd{&t>p-Oq|)j#>uMr|xPRU~#jQ6xYoz=XMiI6-Rn;I1 z)X#Wiipb@tQ>`_FVQefU^K#mRMW&ZNPqv#ufj86y*Ec#ppM{ur(tAjV*L-yk0_`6a zGz|vL9xbrgzY$>sIQU9M>DJi40WU!s^rQ&|=)=hBUgWxi>tBbI#V=0B6RSG5y_@l=G1`z9*I9au3bY zoN=hQiN;fJa1yj1NQn$b6YnI2hmGA$sm3V|eq^zLq9-H(x;Edo-pf5HYQ_02D_?An^$d1KN`6df)RgmQCFf!*L`){%gNq%2?4sW49mE8wC zP^yo@i|^e}X7^q&wNGq~dh7m@H{d<9yDUKe-r7V>NZUA2SfMx71Xh;a3S8z_pe%+T zs=-4_nI-C1KW+O`E=68gSrGPYk?hmYW*C0dB5izdCipVRpIV=ac{LT+-Cbi!2Z*qjUGo>v+Qf1gCRrX{b#m`Rnokdn|s{fp7x5m0bCXeit zcB9qHibT{a1xP6@u5=Q;O>tHe6^tZF+Ycs_k}@7F`ROjUbwfhuC!lgV#=q7=9l{J( zI!!#SiT8?K*NJbR;fNx4XBwC;c37KPjzp z&stesqMu1`htTH$8G7>-rQc{b3Afy4WoiWlDkS=i%@wrClkt{2gJ*kvctW!2r~JsB0fAGj5{ znCRGL(XWwN(tD6=u{%6M`FxUk;Gpx@j~?FC@A8%?J*+c>P{w&SymS@6ODQOouvr?P zmRnNEbRsp}dN#v+tNMlFnQ5Yg`t*%gaJxbaHTG#W@HYJO10VaN#MjIb6sx}c&w*Oj zR$m$A1!vr_pabE4ofQbXQEw4)i2gM`PsQG@hCc4C4@krEwn0shHV?ehwpILWa1(f< z*8M4?eUk|XvVG?pR4F`!c~W`x@(-gAt`01s*V7(!4B9&2%lNxwPdcCDxYpBf#eEoY z&?WP+%vj1LXW0XulMTK6zz0p(X0G(jDIIE!dCd$DIafP`wQI5)oM#6NKiZo_gIfUA z%%5z&u^B!lj?!Q+ZjLw7?9%_x{Be-}aO27<9elGGq~p3Ni>XBk#u4q}+Ktr8l-O?C zcZLSD{A6H*uCN_P+P-t!K*%cY5Ee8rxD!DI*}*hm=)I$v4kaR)bwm3$1kPa=R`*AD z1z|4Ge))01M1oisW1h*9!BNpy#)Z~#F$r0IwhqP9fW~N=)YWx}+@9|* z48(;2X!B@CA08z&53<4C#LGoNa5F#G10Oexm;o-EY(DeU4vMhBbkFYPR`k_WsdQx)SRjiR5^D^Pt6VJxQCmzUi-Y=c^_C3?vHt91KG^Z zq3?K1Ry{~7=Gj!xAL~OC)@yL%ogML(>q7a&7NsuTNLgmTP-a=%Er|Jvc9yRX1|S?O z(PcNlr{wfEf5$Fs=Bt-LJ0`F1ED(Bwsw=!_-^RfV--34TNnw)nkVV#(EvhA@1B6X| zu5KQigu_O@DpO77PM6~S(*Tv)^cEy+ zoe@9ozRngBs7E+4$TfY6v9-V1C(B|F7jSLOqda#s3Et(~D%+wK}a>D-=uXLj)VDRCLq9kKEzxqo%{7Fbm z;qinP1B8#G1O-T8-= zJ4EwGO)^t}lP$T<-eF;HRY)^?9or+l6U)iBC2WVXWS-wF=8ehU7n7>#I&!@m&+-$g z-TQ4vO9$60mIFPBj#qmz4%?|pfB}=KsFFcn)l>A*W<`=t;VgV9Q6&b{s;(l`z6$Kj z_}2^PS*K~KF3GK^9mim%Q-@on323T4<#$Z0rb=M4;PI-MrcHO&F5^v6<>L3zwpp$a z9N^sa6KDHlJr(d4Qgy!s#8=ZHW%O3N{?`(Q%<;wl&R!u=B;13Ag21%~LeH?R2~CgT z|I-5K|J8)|m!|sf_xDC?r)*1gI#K79YQBPc)15l*Dt7H^ZVMt@#Tm$k*=)4%qhM2# zw?U4R2^VP%)gxwrSkjmx%}Y&v$s_T$ioKu5zXn16Ta1n1AxV#t++E9Fh)8p4NG;fy zu|QH`a zd*2l2ZJ$R!t`Ek-EN`#qnG!GQWneX71-1r^Vi3IE%!OcZ|9ODQ0aC{Vjfkqkd^z^` zH0;Y8a|rEe1kAYJCMmh-Lmw*of1{$Q26~oI+B)(w$)VamPM-AUc9~w~Vm>iX8W>Jb z15|K(Vng!xy7WsUi%-}ns70h4+HHS4mo>&=Z_1v7d3Rk%NZSb1I2m;2Cf<+DxneK7 z>T<=je?wc2#~_uVk3sgiM`|r`#}!Qu-=$sv``Uz>{q`$C<7d%t?PE$$i?5o0#=n(x z+c9)vj8y)>7>_fwC{o=%Hm}4O{@LI{R`~;gv1!($*Nef|u+yF5 zz3kLqnj)Kf&O;|JO)>EBRm-Ya)hO;mu~;ifcPF=maat#dPmiUA4JxvQ%y}(j z7Nmg*8GIN186yKr?$(InF-0vBGFDB3uUk0OW%7rB=;-K?Xwwf8y)7HTbETZiz^B`e zIZzF(nZ?r1%WjbyJ^q;dOGyvMyR-kE@8KaZ;PKzJY}?{Rc;_EJY>}LT#twu8m53Wp zQ0t;p)9&|Rg=T`YHJ`l%0aLqAAEASz*QYwArkukz!&g4lxtBa;`*fzL>8FK=6MKz& zfn$e7?n+_=B2IFT1Q;cxcSuGT9$D5U(1t*`#0537#V`x7eRW3dgBHH7fIl9myYCRc zohF|5-|wth#Vvlf%LW!*SWsnp@SNVC*loyZK7DPl8MCM0luu2Ow7T*sd5On2 z(%bf8qx8JTEyWP`!jHDr`abQY4|W0d7A7Wh)s=ewc_=XBiWaIT^gh&ZYYk!*N43Ik zwG%B41D?5gGVPu@N>0EJ&Z{r*of97ZL43`jP5l5SPH{b|5qQ){@_b|-Cmy@-jJB5R zZka^qGS80_v_fH;OzDgajPiR74`z~sI8#zsf~l2Y$EPKk{c5K7t$VW6jU~_;`%hyP zc?=!}H`%U5CPfp*G8~OPK?*^T*)#7bp*x3h#YV4tnQmc1n@4apS=Rqd?nR>@b&cTS zjY5gV;H@kfP6DvkBi@i~S%@Li6FLf9fL?0%M0&C;mXrwK{Z&dtNo9n*4r^n@D(=p? zuK!IBF$p4tCY>k|b>TrsRu02Hz^1Q5OwQ!6Xlr-AyHiXquqF)|bX!G>vqRQN~40H&f!JE<4Qwr2~Nvw;u-w(j`6W$d1!c zq!%qf^pZm4(e}6hZ_r#)O=s`nh{4B^|4EbLHhC0t1chx-766e)ty7rqLuqlfn4})> z8WwnF(l8)y7dwh@m#VIp>edK()fME( zmDYJ67VS08&{Teeh8Kw!Apvsc!gRxH)hd@p@tCA7CS}oz?Frh{>+a>>nf&_Q#;jCw! zaItV${0q!Dd02N2|C?14; zA0c8u=E3pkhWsBvDsc-iH_#&f46*iq#Vip3V7VsFyUe6%yUCl^eMm?Ff(1bORxKxp zqM#4IjT)EDqg!?YM({hsn#_YesTw7Sk@_~&igJF}(-)+A^e3mbl0u{5u`?u58=^4q z9fJ;ez+sLD5fS50!5w&J4MQ*Q{60s@UPF((Ad@Ju=($*m`+%4ciYou8`$aCW4e;j) z>gRg?CtMn^cRgTzA#x~m+?9f(KduP%Iup=x{1iw$Jtnz5Z+*HsCf?1RNbr*MSYzI) zy;0R;PLXiZazp|xLOmfSKG9$&pH*n$CKZVL;NQ&rU?H-%S7`(Omu&lAk~?3pmqjoH zoYge>jT%k!vg9)O!EYSU?Ztmyyhu^mPMsui4D|KA5umqIqrHxazH7rIM*8N&TTZ(5 zKD4jJCrq@k0DTF4lSv37@mSSBap7c$_%V?5qd_-WCZ6mMHSh(zhmXDKb@sHGHmugd z$1&yIq$X!d=XO2cg6PK^CXrkd44W5}!+mxMPhvGg9|ho|T>w(Gqh@8M(g{JYm-YVJ zJ#g=(GbkG~S<|m{Cq0DWQi|0(XKP5xG3h3D+2iB_Z1<%#D1@F(@40brG(gkjGZLav zAZB;KP7rxp}1Sdn$&u0%??ztbPsA&wW}K8of;J} zM;B{Qu+i!OzE2|kq9pz>$)FQnt!E+v7>qW@BzU&y)KPYPDJD^M z3PRJ>dOY%KT$tyNTB}&nGXnZu~!g)iizB zN3%{|cOO5Wx43Zq!=mV8^;Peac6F8vXi-$n8Yw=#8BxKg&zf+lIMi7;#`6_z;<4D~ z^UY3_M|(5x{`Us;^@e>_^4YLXc5!^|rC!8$mc4{g*=_+9HOgPmhf4YnBw~{lWzua1 zkt7b_E%Bd}0MmRI+4$fjFOiU}hZt=ZWFEu(yuJTRn*Nv6JkM6^_k6K6=*oVYj+WrN z%u>@%bC(DLn)BnVIKy!F-?8DHtT>ai0i(R6eF`2HP;H~U1$_@Zah?`rsTW!JVk9^J zRgDQudMxqshKX-uBbc9x0uHm{cC~IUiI6>ko@K##-ioCOU_E>b7U*>M(^9vn+gjv+ zn=EuWp}D8Y7n>W@)7Ic=_r?uMfHJmi?Qx>)ThqT@f94d-ymZ$0 zmM3hT#M1=aD@T%KbEaRl{>~h_@A~t}p+((er)n}h9+qg!bBEUeN1j9)EI_;4HGe=U zL;6UcjU!p+a*_i$y5`?;MZs11{jhsI`}zg2z{-prUaqJld5*|T1eowb@*#`+fgxF; zeIvdqEMG)HTR|pm;d>4*PUihl8JvvUF59Dcj%)Y=d@T`@)AC(aXRBBE8vntf2EPT* zIq-8zj%e6$AI9oyj#LvXNIuE!%RoxP?FLYtFrv%NQmes~^WgUi6-;<2?0;!!F&vJAL} z7({@X;+_`!BYq;4MfDi)i_L4-v0GcJ1IzB zgf{MCq_519U^6?}e(4JEys0G1ZAO)L`6Vkm5aw(njvl#I!yLFCQV$0G2GrbZ9 z2hc-elLJWfoh&z#O}!6H>uNw@0N})+=@SRIy+2SY-stNj$OS($>-|M@e>OHb=@~3a ziHcMeJ!-*n?;cZ3Q$N2^40304q_oV=EF2rVDE};{w1{fJsB-cz(pn(ii}`8cv@$=S zAPUR%${XjR4)F-Pj58k(%?9)+o@K(&0<6cfg4sT%7moMa6FA_GE)vvM9TH7sb(Tc@qw6`d_o$9Bc6t`irYXYjg zhHiq0F1i*rNMTCJuJpxV%FC(M*vj z)*->VA}XP|64uTtVJjy*812n?P5g|YV~;6BK4l7=pGFdNXCV3+DgGNeHb+Y4+2%t! zyM;xE4Nx^*@45>L(*sAJ-gBx4zf+GA8ym2=L!7#H7X;3)Tu&&E<;N}y0BVOgWF>AZ zk2z7H{@)Z3I;B$*0b}*9rT={)Y&28W&mT$t!SI1TzQ4k!bL$9uVW!05gKNb8JO};0 zi&yut2W|$x66HP-Pvx znA}YYtJ8}9ZE6umOwYc^b=eiW)kMu7BoqGXWNhPqs|1y=ZXF`U6aBT{0SzRL=q)K5 z6jJejwSDvjTZ`4JN57C1w#FP&uF8S2A8a3ySyC8-VDVC(gJ3zK*_eq~nYkD^6YObd zQ)*lhs8bXbL9tR~gJ4+^Sh=~0*jbnu*ooMfnN#wHpczu$CjL)BBbZe|rGKz9r+~U6 z5dZgErwYoE5*7kW1Jf&6@lqH2b8iu4rr2-ZSB4uzAmI}bZ#mV*m@q=&a z>C}*M+WX}g%*}u{SAIZ1|Cr2d`obF!y3d}%fv$zw{{#>jC#mYG0j0DohEw^+M%jwbg zD_0QE^ZB{z_xjbsDEL`P(DS81Y-0QNAjQMicpqT-l|-**BVEf;T6Ib|kz=CsX#7dZ zF(OE-{`hqD=l;n7SnD3;)2uy=K+5<0!Ag(coB}gC&bENx*G5XI?c38z58pq1>Z|X) zyNe!Q>4<0T3{g+b3BV^hQN@F?vy>HOzAb=so>fxFW`11FK0m`~9P>xf^X^yfb`@je zTm(Q&=U+XslDlO_ib=`he$?grS}60n^3G!R>t4>%!OS=FMqg5xKWT?^;=pvQG_9y- z_#D*H`1PX`EGNJj zn?$2O<<(Vw-}oL!J=omkm5uSs5BGK&>=3RTXhCJ+ECiz z_IWgDT=+jnr@N3pFF4M5dwi6lK5+o%J_hNu+#PEp1yd1KVg~B=0lrM@v7}KeG6IgP z1tGpA>_0V=AsO2t>}}!ChvjRoOD@)P67!AuH)xbz5pRpk^QpLGGV~cr@m~p z*e{$Eq0r0BLkeacP=U`0jM~-GZ5<*gvD<0KWxDCK7mU&Du)ECeNqUl!DxOxNR}g($ zga=Sr>HJN?9>)2r5L*{J<51R#O=&fLly}2a6L{s{+MhiaTqTpTXH(C(ES#cswsJCe z(muxah+(@GV$fc7!b2^tJK2Cy=@jlLEs37}qG@VwT?agRfvX((`E;xJcYkaKn}>MO zzob23{$V{l#6+%#a~!RIoM=`h-*C8tMjsl`ty9(bDxo(;+Q=HT)@w|rn}8{p=?uyJ zKOE}GtRz!V^vP{fTZOKIejiF|`I`91f;3|xLgKWjLxY9O?7;QizC!)SpStb@B z(a`@*1o)52gt2e*|D~!VXepvCbU2rM9D&T9SpHjPxtMCRhRsuMO#5I(RB2RkmJ!l* zz~e!!Lt6~&bG4bpY3bjq!d@|13sCi>cahwIA2-Rb%W1K2HU*u&$T9MGN-9QDNH+aV zY)MhF{IV^{;-c*F6%}mbRN~*O{(u~_)L)>`;^E}qH9Rz;h1dxgayX1<&4o%!_d?ds z>c@hkutZTke%sxs7w*PidJbF)W`}Z<8}2JRJ@z|pI~+W!JK8nd0`96%b7h)4r)O8J zJ7+0i7;e{^h1PB+qQClI$;J59mwuU)x-D@;R_aqAX0J}?$K9*CRpf4t>Hww^Mt^fx zWTFT=uTCqs_DS&kZ08>b?Ojq#Skz@JBsX=q@u7y+oNiEAy!1IyN-(*h{M#unz&OXl zyMzSBL=?rss;YH#U8x4LY3hHQ4I7uZkj01z3f5Ut+nOIbi4cN#c@elt*i|dmc`qB8 z@ZbQF{BW(N-*|sL9R%$kkOsJ6XZN=M_oV4>qK8vO{oA;FpEk95!R^D4i zCZ$lf)uoKoPzb|pY<5T}_2LV0)5E|*C_(zf-~`6Jp%rg26VHo@=+EUDoy=5JIAZ4n zv3>bswXqwNAl;ndLA)-!%EcWBU5dD)*PQg9GPhQ!8WyJeb^f2D_A&qn9DmU62(`Va zF8)RE-s-aD_cn=2oB$tz;7W{}#`cE|5@5sPDVeIGHM2{bugh1V?qvDJ#WAFN*O38^ zOZ_9oFl*R9q-_r~mm}&&RG{PNG;0fya8~Ju#MpNs#{%4|Ohq88sWi4XA+v}Lg&-N| z8VCGY{lRpGAK5V%S^!AlhO~F>w!Gu=;l(54o2`Fm9bJHnf@OMczS3LWB}T=7-CmNV zqCn0gI6Qc~R9*9pFtnClbXj$+i1T0Y>eFotR@6F`kZxdzo!sLaQi(17bLRQ;sxwHv zAm7!O6lMYe)5?hO_-Se+7ipyDDF?M6C*pu6?#$&plcR{{=ey5~lpMm8_<<_j0Z9M) zq@}Rq{C&V$;-gaV#xj0t1d6LKW2%qiWQPMD`NJns@qu`kpMJM-FRdi}=>`msaN$kO zir9X9Q=6b>Z}=rq3_qrGjpKP}w=*llO*q-oThCmdvI7!)y8tuc;sJaESyhDb z))pa_Pj4Jgw5knaa>4;5nSzWSxsf$kX$WEYDO+M58;~ z7x_{3-W};ymp+x%GjehiH?{>z?b{LXTb)|4Iy=PpD9UE!M zU_Ainxp=xC&h5j&5Su?v`anN~0&LjfbgXSSvZM z%MDatxN3w??Fl}{LTXHQ<#s4QjXp~OljXXq87XX6nM`Lg-NReUJ`lPms9tAYY@>?0 zV;WA!F>q8)_EdM}UD_^#v>&nUfPq4p(*uA$<23LU;s+B>StyRLOfm_5B4eDNFg}dD z=uN93dGK9W93vGaf)Po7KF4c}i`@4ybI~}+g1BuvmIU3gg7hiOSeDVb>P^TjXDp(a z96I>*6L|BFj+SN=^t_l&(Kf?yC)au^5eu=1fh%jtb-}$8NvndT#NRpkWuAv^zB53$ zoD?%gL2pmTZ&$I)ZyZ$5LV2Xij(=ef=nH*`7!d9^20285FGftR&K3O`^ld1fODc+} zc2pe^91il!pm8upYr5t>oq|96!*3xgg|>K+^wohkF^x{)b-5I)Q%I~aLQQ{;n?&0B zUsGF8eVFy^SzW63k9Yr^dljT}l@|e&gbv!eqb;#&uQ#tM(BYKUn^bAzx%|AtLuiC? zi-2;DPi#;Q?{-0Lh)Zn?A2Ws+k>&k;OhEycyg5?7+m?~ar#bzwC@+Wj;iWpUA^zvx zu@(Xek_=^^h4YzVl)bYo#2e;^E>2RV#YGPhXg2H6&?+DMy|?4qNm7x2w3ILae_!20 zl$k|BVJZ+*a~hDwXNnTovZGmB(dTEkl(K1MIq0L+=Qgc!;0FR}x@%=o`yznD?SW8Y z86Y4;Ypj_mKA`Qvr0g=+W{ICw@dj&tt-sYwlydA{Rfi=?0Dqe;`+!Otkp%Vw&jHFrkx0k zBf69rOhV|vLUEx#?E|@q&Ij&cvME2N)hx`@s4ejq_XsiV1DVNA&w2u6HuBzD*=^IS zc-pXR5jvLo^#_7-C#ua12cJ{oc}(Ff(0NtlcC;l~&bj~H$GuS?1*z4=*q%$0&+6TZ z1zX4}{CX}Ml&A;}%$`ftWaKqwrIPBOP)r#;oq0pKGCQr@q2nTwCK@mf1wFU}TJwIa^_8x9|c=rmsIN=5ve!_vwG9sYn=FU*Mhs|-#c(;<7 z&f_IZ=D8p$Y{6WD*BGeCsoyR70b>Eg9fc@$MQ@Eca!t8VV1Q1Q$!K-##Tl;KYfh_Y z79y~9Wdz%@dZ48=lT{PW)5k@mo6=c?o~;t#0uUfUz835Fnkq~Im441w=)HQP87)Q> z;-aV)Q?DSt*Py>wCD*N7cBaf^Mj9U(pC$v?-(@9F=dGJQ(+EpnEvV1uhO1@BqRDQB z#c%gD{22=afU~g0PPc0>8YWn+u3rU<>D*=l-6{vZz5w9V6GG4Sux!f)1kwX3vAr@i z@K1V7Q%VxG0EXIJ}Y6(pSk>#pUJQ(?{JLnRpkc^%^j9S^lvRDqJ%=sq}jn@zSoV4OP-?vq`ka#_3#!~=NqMk z5Qqsgz=2&l_wjM>h}#b=TmdY;9LNZWRwP#H5-p}fno_ax+jOp5GvE|%oU?r83IZFT zSdb{aq>p%jLGUo@bN&Z*^kbYNC=?b-qJET(M0_gEF}L2(-(B?N7KXq5uy;z2k*B^? zZ1nqVZV{aiYj-Q82wt73hz?GFiPwcGg)t8ukY8{qlUWZrb509HlL@-*Xwyamfi0wX z%mF}HeL6yOgTVDt7TuxvBLJL(<<}Xx*y9@*0bQIgSjv@-_~UCBSWkj;$4@se32!qX zPRh)f)91dOvukKK)#iC8YBZwVQ-$6Mc6Pw1Y&b_Is1Y2%lHK9v5D)9p2G$<*zW&Mk&VS|~by67EP%4vsWv_OY$ivEJR$X&SEe3Z)1*AcgFv?< zsvs!&j%p9sbvKjir5Jt{Q4>FEwgKQ}PUJHy>kO>|ha`H3!!_D~-0oUzw;FAljuD)? zFKy+>(wnMLL?KTdV``QlkcUD>Uq98PwQg0g6I%=sE@BMZb$|l=%jgSxDr!0~E;U+) z>~#LqvNu7EfbN9<)EK86M53)>m%sZ_$4%uQ8S5;raQkw?53H4eAW-gCfbkYC8@nLV zKlP^^7Np3VWq%#x@J_+MfMY}W>l?nyju_u)={apxuyATZb0LG;gTDA~%U#XIGRt0s zG_aexYJ(;6pItbcOK~mn82s7}CE9C2pl^!iA7K)v^}Ao}b6&;e;Ad;Jbx+|rTG;Tt z&e*f4;R`IMeX-qM&^9yN0DoFYI7p9@+TS)etWl$V)luJ${0=ECVWBR64GS5NAWfA* z8#r+I9!>jZx3@$#tWd>v=nsI}YCU=t`C0G|N!w=}`>*lX^$ z5mJQ>;ul5&)l>7bC4q)(bH*pb)C$gb*q=Qe+~}ZF$0s{?QSLm_eQYdMNOljei6C;7 z_K=gry>d3J-RZz0;^ioR;vd}8cUwWA-STs3dqfBrk%SD;Q$gCqTc?3L=DU5)+@3|0 z`XR=BcHuwUXlQ=w0n#1jXpMlAC<{_kh!jWjw)&pjvr&t*`M57NlM*NrV1zYDeZ=er zefp`*1wX^Ahs8$%nTbMRYkT1Kq&C z6UgI-^5X$F;Ptx)DxFtuG%E}e<4wUrbpfpdK(2de6#xYkRJQV$jz_eP{lfZ7uR#6q z`8s4%*%!${hlGM65xY-SFqG_jZork891`3%BS@3e8*?OCn_Zj+FvgN66A_#P<@`{s zA(%d_eek}VE+0@uE3i7<(Rt+j$r~reZ&V)(=$BYc(2gXeX)tW#>kLQzGY^lE_`lyUt{^VDS5;X=ih#V+~LX*kBj7($%&Tf=;}+Y&saE z{a%Z+dgGNWZjwZ)kP+fW(Y`Ky>M&eh-prrZhiUYZDHjuDrKw`yJEvG{^WiVW4bP;g z=D#!Sa~-FjmQmmf84LW0n)@@&D?T0ytP>NT13<%OK?IjQCNLW|chSvbSV0{DLAD$5 zb*+|J(Fz4nVGOz;N6b?Pg%IieDF!qsm|m_pJsC5BFK*WdOImf8m5pj>m-+1J4Z%=g z_b_N!!NZC5yX?^#$O~)GikkCpbH=&PK=I^vqZtd-=(f`RY~w*lH&M%tKE_}|jlj>n*1q~t)D>wT<^|Mh`_9H4<2V%wPRR+BLhj16xLvUZy4Sbyuj9Fw{)Z?DrdeVm zkeL<_CL$=WiF^>DqcE@twFHcivg$3@S!%msY&QCD@zOY1s2Xq6CBB*cdgsTA4Pcxw z&(?kOx^2FnuqnA5T@LsO50oR`!ixhnsVR-xDc3b2ecmFBJeR1lb#I_jl|fz6)nr0# z^pzyT7{UiAlDrtD69C-sdlGn3pkz&VdOi1j;vqz<50bw)O~ti#pP9*+QiG!U_E@3D`r)x7|&YC0L4LxJr6sLvnolmI?+GzFsO4p#z0 zTr*se%D55nNvPJ4`^L3BwB)CGAAJBf(?4oxW${(~kwDOG3jl+r%W9cup-cn{ejjEG zP@q6HilZbS_G%65dh$?i&k(wSedj#-%0BJ@yGc$KyarJtxC$d0-$$?}53nCBT0t7} za-TeU*Ls1zf9Wc(Bcwho(RCLLT{Gs*p3%VD7g$H68~u~i(i%+~afJ@;L?%jp_uedd zQ8d$a6_>UFAeaJU7>!KbAV=Vj<4lHA*h3C9ORe+NlMy z()F7DE;2DDsMZfohM0&Swu)Z~8IN+kQv$~N*Teu3y%p2#^3E|KnRY@31XQ)!>GNq&~?^70O^9x(!#&@%xQ-n2AQp=LulL2u? zNu4>hK_FR)Wzx0zt53P>4wE-dICaAbob_@9uCsrMyv4QO;5EGSt_o;Ur0qd!RiAh;Y@=z}y}-h?@331CT$|AvGg4XDT03^Hpv z>Pu9at`3cEg|O+TWh*^_q&wNd4T5^QHT-^>{VoYUaL&)0$mUS}8OV~8g)l;W(_Inq zl-m9;72^<@5-5;@>rty$6?AYjGHjJ~2X5p?dbM!QXvy*Yu;nMIwx-}8E%okIe( zTnPDa82PBqM zVhwD+bEAXp;0u!^mzfViaUuM?JiI-pM^5C_eC0{ z;~aNB%eVT^4R3NY#vqpZ#SCeGXwDx1 z*P2Rp0N?WS?KTkIUG2-ipvWl2aO>Cs&W!_f2s3|AFV2kSpGj+XtxNwsMQD$qBQ_I~ z$=}$ZB9uTD%dQ+`Qkf$EF&*>UzMDWik`>rl^MOjbg01 zaGUJ&L;?06CE3?AAuynNPmXhhhL_Fj2f+9J1>p5TXo=ou*R%EgMv2~Z|MqfD{|z|V z`FG#^J+brsel`P$a{zn^`p>D4ykhLR%kbpX`HAWrE$>I&IXk>-yw1d7k~en5;lF&= zP73aPL-_qW8YvM3q&SSj-k^LM_02@au4ETN-0d#*gB#wVgY{Y#3 zLkn@1ITQ6>UGMoK>MbX8z3;Vx0K^psHul>E15cI~mGh`lRRuFo{i#ZR8yFMpwiI+Q zP?Zs@@u^n`upRuj|63_bYTeUj{s75q1wpEMk5T#$WvY1J=RZv9&X#!_&OU$XQ+Gw2 z58sanbkIc0NtKgd1!P<{H&|H3I4{vgV>cxM1;ctJSr7t24GLav*dD50qJa1A6cVxm zl9vyJt_>)8WSRb&ez|X#;mI-!S0BW*hg<|nNCEp#M{}wMq3Q=K$U!(W6)sEv zA($MnERV8B+<@rn@3mx~p>QVLYd7XCsvv{i)@A%F)DWY4ieu zjU;;va^mlJjCf3KX+h0GEuzPNv&yjeP42XrjYMXN+NoYN5HENvX1+vqrHzjMT&qf2 zMDS+RsXvIpn})~G!PSz#SoHCwI&m4}Rjk6FAcOKmD}om(7!bZN3IUgckbI~}HkU?v z9+Lld7YFBQ6YM9Wh8w6LQKaGeBCvWjwB|+N`cGr1#Ot-Irm7(iODhskVyp#iQo8G~ z&w{0=8LaBSL{><+BKzMBQ`AE-!10~Rcl_8Wr?n+V9-X#5fTxes1y-XX`diVGCu0zy z3o<$}3?cuJvsObmSpoVJXQMV|X}(PPFNUow1#hE4@mtWCW^(`@l(bWUm?nkKvRf;l zdG0xCOlm=T4fs09su$tYd59!P^W-T-VEwb`9^Ts}?5GV8!cfa&>T~jme+S#aQl=Qv zq4AMJQSd!%$A^lh>LBW*!cg>FMyg?@^RdL_`YNRt1DRYi5&=>IRZ~Z_!%-@0(zL4c z=2mFGg-+9*SzxcOv~!w>%o^jkKzAUP6*?NxU4^iC=9GJx8f6DcAo|QHc&dNgd%tsB z81~Hz6c<$$0Q*8ur#U>{^wa|36viH0ZC~od+UzHt-~Yo{1W)_|I4DJwl$8mx)p9{j zu#C+a&Ku~ffNOo@Tkp=5)u4vSjr#PRlwI!=upS-Uc46g50=Qa1kF?t_BY2ebRv*2X z_yv7J60n!xc#&|E6EH(u1Q*<1C8~wue1CQ%+H7Nca4J}S`$PEWKRU*5Au1^|d->0k zQee^jvt1e@;$@g4!V!ViCLG!%A9@+!A9_-cu>F*AZT2vKm2e_+ z?4XXNh{%vmb~pd@gPAgSfYau%!&%PnnmUuwSqG`L;+=c$26d@vrq&6UB?W1Yg65pz zP#oMw1L%=&Wq@3-2iG|ptrgF%s4b)dJk@sF>@2ujfM?w7co&|#>s-2;+}zyk23y;x zm^j@U-K<2kJR7f4S^}qA8t&U~wmYX^S{l<^`_&k1m$-8?>TXn5F`PUjkx$ZKz8gI+ zCV0;prZ`e+9i?!CRjUQ5-Sf~Y&5_DT9wXB_0I3}GOM8{Lm)1=54d81a;Oh0kZfj@rkt%a7^+YM&)`^2*0e8<_^Exnhqipp%N@G$EF$_48I?RqgLJT)+7xXcLW|I zRir5OI63f0dKDMOqw(}%of?Yv2bEwChC$JP)LkHsTiI9s$l)I|^2rk6tAVQMeOUNy z30Oi2yZR7-Ot0_;LoNvTvXneV4@o8R)*p&&F6c!HSY6Nd3nZnapolt zOiJfm$JrlgMjhvKG-GJon2xPDgrHiwdz?c-eT*~2`Z)A>w+yqR;h9CUun2{N%Am@K z0EX85{AE$H$hFL88UDakYan%z)6nbZ3b1zNlOv`WMI4S+w(@`r60+?{@tsX}yS?C} z?1RPaJUGiGr#J=Sm~Z8WGW30uffxO*BRF)rt%dVpRQ~hhgReGJ-IBSgpnapUxs18$ zL6<|k_~rh)Vt!_a(v&848OCZc*sKf2t-?%?D{RD4;Vk#1%cXg0YrTq{q9X~J z43f9)#W3-0ApY$ZKV?e-K}LpUGme_#oCy4OY#AeRo9)c|Q?afIxTlCe(B9&gZznTF z_!v8qBwkJ7oi_TzTAoVis*y>5TiO!+ghD8)#*9S zjx{vSp*VcFxK+>Z?R*tB==pc;rM^=!3lj=>TLxH~kTgba^@)!-F)JDe0uGs-bm1ep zYC<;<^NP7|Szs^zaH7C8KE!`~!YdFcBvKLD{}&;{R`tU!8xCw>IX=h+Sd$;v0Y_|* z4c6VjSy)1}DrjI8-T8v>*U;Z7wnC_5%nNkEJeR%#N>|jyGnuJY^8kHHqD*j12{aEA zfn$EF**rS5eyv+Da-kYPA({tLgkxfx=uX*z=jT5NFTR-VJHtnHrVZZ*c8DgT$Zl9+ zO-(V+6?R4BasGMOAGliGd($08VL?o;KX5Z%tSph4gs^7jYFCPac|}6->4O}VSP4`1 zh+MA%VUPstCMUG0px;L`ou@kT2UxH~XA7p{!1@(2=mN(mj#1?SXy67IvgSWwzHFcF zFxZab?7ylLY6CxvZj*sjCckp?4rW^n{U1JN<3I>^z<9@aX_q0@kk)RTpDtNRSga^|Dgj4l}M-vwR*!c)NHj z!4D=@o1VJCL~amg^KR!mib4t@JfGf!2lLfMXc~@5-Gs2l=YNf!E>CV@1n>RO1S@CH zej9~`GCCdXwI?Qhh@*rJ?5UKLT#g)a%xsCj9k0AUD^dhFPYv5LW68Xz`>Wt$Vz&j# zi6cxeCkbQ7@}S&}p*}|<0F1xlkoNz|WV!WkuyrO5f#$^^TRc<=G;yfv#3K3j>i58A zbjVFghEPF@hJYUbK^hQMf`m3P8-S!TH{FT#DXhKe>j|*~dRCS|^Ik&#(i-P! zbcl0EHEOkuCpr=gtpuU*i>#J0#at3NrnIZGg^`nJo>XDaqyFAT=kC+TaSy2N2GOoN z5ru#VGBXMKz`991WiIFfodV2UDRV?>w8PHm!N>KC-UFIZVfb`on22OzQ2a_AgTsJg zDsHIZcef>{-nAXQJCB_=x#|KAcV@33kSf~Ck_xw3S-7%c4LOW;f+LcgEtNOK!xN< zS%|sfP>i84(!(B%6LS9%B>$y|6}6F}Kc>5=gdDoBBEX6`iRVN$I#Qg&n6qR^B6dnz z{1p&5+f=$oIfmWE<^`M{GC~S60C8o}ZkwcerV|LL;5p*AYBj~*R#rB`=FTNAD1g}( zfFh1lzQN`y2{o|=;;hr_Wj64=qA#6JGys!|WRSq;G~H(vC|nQvA6|lXD^>CO4Hi5^ zk$&SVRh?$rc@o0^gkuu^cB)$&MVjajj|iV`S&&bvVW)<;E5`Do7-~48hj7MgxkCXZ z0rv8nsLh@|@GcJ%^jxwE^mPa@w`|CSmdYBuij~s5igBoMSXVO{Ocftz^G^{tb{n6L z`qmANq>V)GzYY(br3ackHw~HClAO8KuHDekf}P)L{r$nnDx+*TenACSqn_&SH69X3 z7!mc5#Q2&)F4K~tvntRd{tuZ^FflfnVD(hcJtvK&K9H9hO;aF314NIwr+zapI{0$r9T9#5MU|MQu9S?j zb3oP8GWe3T&@}i0h8B9g@?Q>sto!EFivErtQRL?abM8_!;)=DXR=2aE6Iwm$wk$8fyK&0o{R$diuG zaJzWh-ybIy^AG5yE2>x1dGD;KZ$S6hs(M({(w#I{H>VGyy4}!*+-xo{sV{`xxhN5{ zxjnks^=r1(+u9oF*cH@O!7A8=9R07{BmdgB=r#+m(Y|ht!|caE6I>kKT`iAAtC3uE zZBt>F*siu$R#lt%zjB4et{Sv%7aa{9dD7t-@sQcYxs@gulOmnKzEb+OxUKt&?SukW z%dRz4&Sk^WSX6c_)$x0@y1*G2sT&y#oi?tamZRjO9lxZK!pMpvtnm`p=}2C>5fFkn zfJa!yrCpgZE!ZD4i$vABB))NtGUEguc+u6g>j`un52iD$Kkj|`#(;PCL&SLP^$r|QGh?{%!SFssRBcYKZ*(*iz*QzMyq8w%stf5==@(4 z6<8M4SS+kHWhdjn%Ub#QhNAqzOkigwD@Lh+eVMuF9gvV=9Q8-3!7wfD^)!@6Gi4gy zvbW^jz*>($$EG>F_zOQYyskIVtQLl=IaN4s$AO#XoB26Ray67 zTlpB9-X7{&m}Y=~JxD4kVa%gI)zZM)jnBR$q|8ps$3PbX^XE`KKqIFZwL_cC6k`9yyw8EU;m@VNLN%U(YaBR< zvHBcsooYO|hRka}y0Lx)I01DrPj(s`-Z#04Sm_e@y+_=oU0#yZ!Cm$HGaCq0cdFD+ z%K3()7%Y*)wmz5H4rx|kWsE#FVnyU;p)@%zVU|%c9Nt1ax2F%)%M3qGR<>2_(H4&~ zstq0Myh=s+YTzjQ?7aEO!vx7o4>4CAo>GY4F;Gc}`D@^F$t>(Pc<_DgzD}!3^I6YnsJlTh}t2 zuqmpXpx@}b_N0#GC?yFAf;zUPin3+0Xk)AX)WLlM_OMZ>S=OyVM?ICR-K=@^PD`L1 zW$QToDrezs(&88ZZHoE!Yo(H@_B?%P#Dpr;CJ<$2a^=_V@pi_o`T(Nv}tD4e`z-l`NP(r zt3bFZr)=JcX zR}2d~sFyb-s}%dl8dgb1}P2+=iOC`^ zRqA6U4i#5FHm$4C34R@~o0>g{Sd-g@U&YDO(IK%+l-fq4s93M4$5t7WEfoxg!_;5& z-cl(U%a}dD8q*ila{~o%3sS<&CGjzu%s#G^|kTiBz>nz zTA=VY?Wbx`-B|-!FVVZ|xn*Q$Lt7%pkN=nTyqon8kd<_$lt=@31r~Nk&`P+I z1`;KORCa_(!p(W!VB+{O`k<8;u(@O+?$@|SATx7Qy(a{0fYKTsCB-Ok-%S?)ShHM} zt-ik@=7(9*RDoMsh?25qRqvw>%tBHvpXk)nb=Un_t0>O9f$bC@pPo(xEuh` zU0(e%1X;MW{$>Js7*EwBs?v!-i4wainjKvq^yIM}RO4B;wA@&B>eZiHEnSNoCEFrZaGFakfmI@IjJEaVc(!$0mPkVzo@ zy;(VOjb1xU`jc#o%b+P*RTgmSt;~2);>Yb$W8Y&{A06DrInAnZpb(IFAk!;__qQ0vR5; z^4~;-?c@hCKgPGSrM_WhBD~3Mb&(1Xz3`fJfYD0w9J5!ecU1np2;)D$>4jq(r2zNb`f7gV+o%t*GaV{x38yk=2O?rE+=;zNASvl0GvlcpmD=CurQs1Eg$K) zNwY>g*4cWHD9n;#n%r%n2j=MDP$NmB&0}#iV}%Hq)muFMf6wa{10WqGc zY>!r5{0ZD$>Yg)-Qt!5_&gwiKIcjMRzy;zqtn()cfWI$WXG}kcFv5>XG+|d+SPV4t zcr*deu13P&LRjtc>fnTb90IY3Jd`|~Et|Ud@8byz^!$h$8WmfxT#wSPXyT8uxs8cD ziY^bzHzGLP7k_cfG|dntsc)JXq6Oy}5QxChWHbo z;%1FN1Q>bX#{luBBi0qSB>c-R9+>b&Pr{Z?`JaDz%=0AnlWU}A+Up~{M3LJO!eW}! z$3n;ZMLx5YCWsLX2<|$trZJ^qJ6Lh(v9j{I~p{PKGNP zKh!B5*4-o(DQy4g-6c!h`RogX@wuX@HotC+cRyb@J+Oj%Q)mvrB7twrnn?|b?1H^_)4{{M~G3d8wrP&u;&2$&}>pf9d zL}=gqHRND*YUY76tgz6Abo>}Cf%7Np)uhNNX*jlOXqs4(q} z@yPqC@oNY}TuAhUmP|64wJ=tDlhWuR7%M?kz~^4Qfhsr!rw?cK+9N))SImhv_ILoi zO{T7}0N<~%+fzQxc4?#u8)haf8Yo`QzE90{HtpD@-Tg(4frv~3lUR=^uifogz$AP1 zP(E-cAxM;JY;>^=gPwogI6P`agCf;IbuO3YuO#Npi)E_u8E>H_;rz{LY7{d1L;-<} z#AV4%>)i`F#Iq}AJnL@YV>w< z1HN+4q69~6MAjuoA*?NM#1ya;fTLY68_{XAq}N}y*#cB0?rRf5;JmF&HPj3q0^U=( zsbLHbwZ&KWiaVB7b5_z+YozNG1zhfKpVQ~6z+d?46ME!j5!-0=u9-vlBqP{DL5!e> z7S*EoyG!z7Mh+Rc^*Tb@{n$0}nhD@^W`xftf+zQ4tW4P~K!pc)^KxJVfXKo3>kRl7 zgaqeC(b`8Hzb4v5o492i~S&s?(XjH9^CEB{k-q_an4%bTHmkP z)6>#FK1))Wp%C}idWEAv^0^f>WRE6&U)MmHa@UZu*BBxrXWM`R;kk$cDKW`!yYPWtKGQ6Sq)$;hn=DBj@jj_fmwob^X$4+o*bAai+C)6xjyNC>yij9G=5R6LhD-XW7K!V|E+=oxak@>=smTfJV1a{X^s85#RxqXgrj*%ydj<>zpo{iws3@NfI8NtppJBX9BFQ*f zkdu0ndVSnzEzBkNe`i{W!ZmWr~9;%o7ZSD79DCXh?R!dK%r-5+rB zL_T^Mtbkq{AicKmpJMyNelYX@Nw>YVTuXxdzZA@jW78RR0v(42`fBcWYg(JDt*fnE z*`;0vE6@Mucm7+ZT51O0OY7IX@^7or3(h4L?rCyE=wU{XA5i^y}(kQg6J=+lCV0BAFXU7v0pD2eO9k|Yh|Jo3mO{waS zv87Gq-QKUmzI)?w;5Crk4AInW0F&wK)GWLIi53X(MBV2&m)dg>xgnTVJCZB@eipb3GCT=|Y z#q&_xcKJ}G@uL39e#G0c(per`_h5#8qVQT<>(EYp^KRv`V&C@O{O(1kb=fH=TdXE( zaFGqN86jWEYBV+TvyxT6(bB1vawucca_3o%KbrIqNML|+7AG#K=Y*ok))b?!nUucA za6}dfyKrYk;dL~`I5u?8tnY^+;$eu?2sUrY@7LKlKa>GO0n^F-8g4nU4Rpr{@#`k? zRwP$yp&R#H`$A2Suo0ctv4QeUzZXs(7+dSe;(O~V9!oLl@m6L5KA`@2loPwEUUZ{WpsTl2~ zj!+3u{1|;?X3l4=)`cTUqN((ty&f+w>$f7n>;D2v;j5{cpxlZ8RRC!EfEmId1p1j^ zcY?t>J7fe4N zI6z!G`hiYO(=(X<{xmT~?gC6n#7;jJ#09(^B}g~Taz0yYBMV>wjg1=@?ydkf(Vau_ zaHxYL6YU$I?yWh9UeR7RHmALJxdh}OcWF##Hmb2VWuUN$;PfC`FMz7?Dg2hb$BYte z)(=>{pDhH_6FVsRXdODIE3kO~_+bDVUP(^RN+A zA@5eUr?}aRo)`#TqBk%PyD0C(OOh&*Gr@WjkcI#LKE+epg)c zW=N{+G@GQ( zfoXae#LsH%+FSsp5W;VG(#pSBQ|HjC?yecygr_?J%fz3y<0w_e8a7uj4{O_V*48iG(1(3A&tsGjS)JsMCMA$ zs)dU~;J6F&cqYQ-?y=mY-^6H}YPc-Zk!BRXPfnQX16dSjh;#19wp_rJ?Xunp4ZoUvkx;N<@b!GD`@jC8$wD`DwZ*gks zcmMi}-CyH(Mnoc1@s(^U<`%N(L0MiqszF#3GwAH|vBi4e3oR{r&yuMY2@xP>df*Qj zt;sAcrLW8U!7$S&9iP1 z`MKs#(O0M#-euCaVF<3HsTxmy>9;hhdmP>cjF`jOkc)$u0#J#mn7=9wiLvl{o{Sx5 z6#;`^EaW0RS_gDus#8&wKh*N?dh%>uKy<87*a$~^df-xZGMwuPZX=JMex2NxB+Fik zXp*5N3h_XK>t`^!L_k1M5nSu_FZ)C#vtg7<(Z)ekhTvgM$P=Q5;9^U0q=dsp;o=}= zB~>A1kz^xfFzHPa&A&1WdTM_azniKJxuT&CZWR1_3d^Sq&!-)2w|cp?7W3RxC5xM+_=Da~#z=hcAGqn&=oq*3Kp(4E6~Ep)J<33!k0UqxGnUV%v6QVhg|7F5 z94M23+YhFUCv)e}FK1KLKUk<{TK+8MZ_VWhut=_4k@D{p80&R)eux@;zU%=+xm%GM zY*;TWUGGmvEQexpff#*jF`)PO`U23$QVMIB@Im zTB^f06j1&K%q({$hG!Q-l}-K`!9jSH0prQU$`87;rNv%DSp&^3tIbTEvG@hOH2F)j zc@}d6P4u>2ihDJt;MJ{B=k?H~Ug&FGxMvR*hMF%k7Umj1b`&IHlQ_mG&t$FcgE|+{ zZbSk@Y6qQ|+7i_@+;cns7G3L&F&8a-A@|)JQwQxR%>=biN`xjo*1E{h=p3EDd>U?+ zr=>2~qSyoHd=rM|mPG;Q!R@iQ79>xe)l-f5F+9i~hS*vin-B)TIio&M0@&u9NAE)O<-{Rtk`)}Mc zXog(uym$Rbyy8{uHG{)H1u>T#cgDOgN+A--&w{dnoUMscEUo0$Zr|IFduoz0gIBlM0UpMBH!aLe-zMldiOyhXmTl;Qfz42*e}(mZ(3L{!;U26}W8{@?pYF1?GAo??^H`syY=PYAexN%t&g|dMp;wPi!;YhC zPLC%3#+F&ao7+L^S4g?L?eE@sVT%2yRf;WyhP<(c$;_x^lslm$Im2VpxG<>=cgDS$ z)O?t7cJ&XDn}|sNPFt4eYu=g)5-%M{t0l1|92-cDN&2%Oo=i+z<(J|&ix=m%M6!^D zPI8W5t5i|rU>kDVJEv`C>d+@q4J7d7`-GBiD;j5&?TFc86o+~6hbHbsw*Up@S|PuF zj;tDVoRJSG^twbhNII7U)%M5$V6a@Zy@mrH$NfS>%bc`rri=UEQRgzDtSLeCnE(B^ zrgnht?&@}^yYh5~@yo?Gocfs}-XE#_5>n%qT_qz4C8Vy=F|Am|&-(+KDk?IHXjVYB7i z-1veamo~b|i^GG1en-e`V|KNCbO3awEJ(jke>%aYqe)BmGwp-Na&~j;E4O9uWcot^Jzgkas4>-}0gfjo@5DjNKLBsV*ut)_ppmEo$xi55j4RY`lDJ|DZ+%i8Ha z4K5zDSVd3>j0#PU7z`*EtlAPKz?B7mU11XrY4fj&KYEDQOZU%riN@+lE0z)J-Fy{t%#F3WP! ze)Yohl79Gntblzc9-k&9=?1nNL|~-zMenc%6Bztf-sZr~yU`nXiQ1yLL~$b#uOlU? z_p`R_-`>NWno6)jI{qrB#hDO(Oms!=AKyXSSFO-~^9?I!nqjz}Xd)rv+RaYwBhs)= zXqTJJA1`EjdM}`R{{c_eQ3*Xs6eA!7Whk%OtNk%4=5JE6e+^F}p-QL3(pgoqQho91 z$Pel|EW%GJZk#-7C0^PUuvT-=qOD#NhF)!@1|dGUF%QIl`7zu#z-q0+sh@OIjzyr} z>N*ti@p_o-8jNWcpSSw-6v#D!dj2jdG+w zfKNib6~6-wXArCaE0N_Wi|K|tY#uO4zSvl#_Or~O2bJQ8k`w~H^;9GD5tr8lik9AR zLS75x0lVeo285JIsre(tpXenI1lnS!d5??i1m?+2i_U<$HQCeo`~MkESzATtraKGN zo5T_+R$&3#@NiibH$C{VAA)1ik?jEmX)&@8LhwSZ~I*s z4NhU~7Ynpt;r;Bx&v=1D6bgZ1-!m*%ufKhZR)dYgV+X!fnDJ-5FU{7%+z5@oYh5go z$NE{_H8EWeU^V7?T)}JuHVmH@9U_(SGVYl4yuf=&>e#HzWQaGZ(0>y)?S`O$zOS)c zjr8`d_~00buwe;Gx&G z(duO82by5cp+j@UPQQ#e+jpF>8p6$6@ZsZgL_e^RnHn{t!t6vWo|Na$^*WHivF};( z3}#(iST|*S%{jJQZmz=lX7zUzrHwT-mqYZ&NVAu$I4Zfz*SjGBZ_FW3QNBN?dy;dQVh;(}jAth&~mmIUTn#{C2RNu~F-i$j5)lOv?e@hcnCSba-HN&qgvN zfWQbg1v4cHQbs_7`X`&`pnUv=+jJCC&71Wrs_-#nPq@}b2^G<-6GGui0Ne{Fjl^Kz z1p1<%@DQf9G);baA^18dY9zg!HO|FDmPGIOl^L;3KD^dV#pb0*GkeH^H;v4nQr8o1gw{J*#BtA;4H$w zqM0njYaV0M5W%5nnLzD!7U0yD);h~Vh(Pt`H`Hj_{(~=re4Zy=uTanV0jGW15=;s~ z22+sV(90?aH+z#4Rj^!QHwm9E-X^yy@MR|*NrWP*=dt<*3#0@c`|_pXi~dpo>8zpP zAd~JSbV}4z{r*qP6~_;oA^Af}*%4iW-&6aPUR+VjroN>DkO|L4D3nLG<4R8I2{qfh zman5lIb%C@Ga0$FWN+Q9H1OTerL`e8Z_R%q;d?WQa03ehK=`3c_nRwMX(-^sG(>pB zF>Tudf|GGZ)*|^#;!gin5}zhZYeW;I%!`W=7Ub-0TR5#(8^AJ}L_zAs$)8jHB8pyl z4F^S&^ScTA@Ee(`t&>*KK5z&Djy$%qsXhov#U2B~PeI-}-jh}Fjaiw1-BNStchrQZ zU2^!6 z+K4&0h|{PYmp@399|?qj62uDS9Tc9EH(LM+W6e$<=#-FvQn)h8@^D8DhGSn9$78Eq zNlSTVhrED@*6EzWfS~VP9U%PiC3q-4vv=Pi<{m^WPTEh!A2c6^#Og5Jg?Nmau}xDn z(g8)VA;=Zg#mB70V2lCNVS?tjZS7skpfW`P;aIkN!Q%X8y{|)J7`iA6X-x`e&{_ET zgHah@GeDTIe&_sgNj5u*1#0T2+SPpBOSZBLIC-r7uqg`S3lAhc9yJMs1P z4+FbN{XhO(kE^F&Lim5h0T00}ktT|N_l!sY22+mE3a}g3RKuB^3Xad{y>mfxs}!uHD+84^rVl z-<5|tJRs7@ZF}YL1()c-L~0M*kGZe#Q{|I0#t}nAplU}u|Lq5|J>%{()QUV3tfoO? zzfD5+xokZl)!SCI@Yx~HAcD|3m(SF`5KSD{aKpoO!UX+b#D?FPp2NTL|#>-3k{tB0T9Amc+GvwXaCTA${`=kGm_0+uRByJ;(ZS{6`bC zRw`~)dlNPBA~Se=Vt=fVkM8ay-J7BWo&7DwKuVk~6B4AicfNZec@Dw}1W$V!&=|(Y z2D72|<;UO%{+r`{QR8Ce!#g&Y?Ek(>QJizf%Jp)5qN=gXG9&sD@Pzsi%&T}asd`gQ z@yyC9*@ZlzSA^m#H7nM z?kC&#S92b%UC+cMW*J6_5!B^n(tNC5&*pR}loNc^uqB zf9^%hEG{Ri0fF!BQyPN@7w}F7Hy%?jE6d>$gROrT=wV|hOy5`3(NOk63MX+`*h}hf zM=vo0h7DsThUU%>)(SQgQ8`Q&F$mtSh&+ctrY^)0-UdH8P*`5mOJIQ;D1@TRK5EYL z&CHLqE7T3dNAQ^4xjQGn;Q`)zi4>oUu!*<@BtCE`L^M^~^5%kr5P@MZ<# zgaM0n&amV!=@)StD5D(B9;a9h40-R#I;^NyDecW8#>jzQ(znUb&A(_3tl(r&jv4pP zg4S8>3!G{US{XwWjL}=;+3)60J9355IkMa_TOGfp7q|6^X!=Aq6H32a#5x(B`kv}; z@`8r3{$}2OwKzLSH}7AjMC$D)%{*BYj#M=zf>V7FM!PN`#vy_TK}9OG&_b?&&pULD z=$+pO76l42x);q4NvFF=}IB=T4z6#5xHcl#f1q%r&28`FsQXct$3 z49rkFh-HF`I+h`BWow>j%`$o5u(ej(h9Jcq*B~l_^qD|%?|GO2IL|Qi`lXj_|5Fk3 z%t6(#G?H7quF>R4^zWgEuRz68 z?{8>UZ8FB|Cj zHV8g(Nc|_T^pn0KY<@B9CV*qnmj)TBrALx)P$U1lwVh*aNV!R5>R&Yd*lz>Gt4+Bw3CcUZ};PBuxRI%Y=|(cAGeE;PM!PXdvY2{Z;NIi`NIW%ft;{nX&6Qyw%~ERY{t}L z*4^Stt@wrF-N)?=KHUk=BFQ~%)F=-}C3Ve`ab2d1uj-Fbk;}}hxwA5H_L<_$-T3E9t z>BC3XUKf4yZHUx6O`J$dI$Ti)4UXRf@pf0pH`(NE5_gHxJdAyznTtX|)Q{9(L7ua6 zLOMnXEi^66N#L6-i~@$fZppSonw-x)X-q9tr10(vH~WETHlhn2Kj^FdrjQOEH!}l{ z6&|{RL1ZtUGxC7WfgT2dEt&+W=aXNqmNdg&!rf0Ws5pn+6chTLa!Jx<=zf%@fGW}6 zVfF{r7Dm*&Ra5J;jxz^)T|hhYnqDohRp@PsAcX@2@U7%Ru);&9tE6Wk63}0AuPsY$ z#7jpfm>v^Hi=T2v&j(O(udxv3NMe3J$}?_jg1k;VoxH5^?{MFuT~?QV>FjV=qM1@_ z-q7kyCburg{F+L4ww8Lpg+S*kvtfS8hT})GeCvkId_ovpXvV3VawaqC0CZ!v#FxAD zdHwICO({%Jh_v8`De6#&oZ?;#pU`k1QmB+4q3Za&VZymNei=&+4)VVUC;bNTWqB6r zQvWeU3IyjS$o$=*p1q=jg3ufNbK424D(U_KRictJ5O1F{1%-$WVlFt2y~^yg$)Ck4 zjp(mzUvIflN{!t1uzdSKygTfX;Yl~L#S)>lmy6fG9{_U2H{?Mb)XC1OVujw&8{tHZ znEn_wPCv&r*=^6mZJ!;_9B&kdYJllSm5JB~(r)(?;%H z4CC+Z)Yzh4QAM2!O47FpAcde?Orn=TmigVo_uUq^P%<8VHVPUFU5XM*1zRNtySq7w z$nMnhK+$D^g_}mdxXN^A59U7!GO3xAne6$12Dho$?#_8jzJ`M2y2B9v0;Y7^HFuL>6Z4$gMHym^X8(!?^FX>&O6iVOxkJraGO2;8puf#!BkJ}IE?A57uff_nS z#laXZzHr8C@Zq=CYZOrm1q%km&;e3+s;w{IGBxT8T zV?;UIi2MUGOT&jHh0ua7$*-%Gi^7FEZO_RgHgEr1&&h*Z;*8$;KtcN0}Sn( zv&*!5YM1!Kq+&h&+~V4X^#XLba4*~6OyhV7NMt3DK2dIU>bSx}0jx4>FPJ!KWu~R+ zI@Tf{q#eB=2ZHyWxyyGQt!BW5gGEP{z+twlwk-)4DrfB4g1I5~h5UlJEv0%n050$# z+^MKpN2V1vZPj|B$T=$i3xG+l2L7DC-NMzx;)2auW3`78el;2-(^Li*VUdP|7z zm+65@5=NPaznw#(b)sdlaR!aaEAYkorA2Xt#(cM^>qqk+m2ihP1S3C=#c#n6(h6i7 zhUEUf)svuBthut&4e(orl@#@1Ugbi1r9v))=O?HwNK< z#b4@a$XH>}6d6Ojzr}8M(a}=+$28Cn4-$kXaycU-U)<5fx#ET9szP)ps^KN>W-~17 zV@(2&j9FpVR6Gj}*Tvy4PhUjtWkDFwJ)TcExJUW-^ppESiCbA5k zGVQsdBc=5iBU<4q54Bbik`um$PdHK>xwx?w4CuwL_8xpqP^FI~e&a!;gyi3fzkx>d z6}!6c`XSH@)XA`XWHEJr!@bbGq-)7y&xMKPs>Wt~eP`&BxF3+!uK3sR2Nr#}alU^; z(v<}=K(2F|8!{V7E40?a)AGh8Z|62InBd;2T#1OXce9r^^WUmcZSA6!7UeP6K!r>h zs;6V7>H>`YS;0f2c;0C@ErcJhtO4lS*nmL%nbKlyo?n^==B-B<`v)(@;Dw&|y$o7~ zxhNH+$Wvd>PcdVK+Ia}v{j|Diq?HFz@G-*`9xQR_8>niWSTtEqvcvksW0a_Ip#)OyN znyFJB(bfvi0}mC}yuUBsHH$$tK}$`z@E!fEP+>o@DtFHVVH;gh9m{p-VVa#_u?|mB z_&S-_y*x=gdSxtAPiI=Iu$_oNK%qy*7^_W7c*gz)FwUcw%)B#;%;q?Xj2BO=71dht zJV-QOmW8E)+NN5DO5FW8P(ck0asDjZ@T@Dqb#1sd9?h630$Xvud2u4#XEn~V#?f4@ z{lwo(nFX37`;kM4z%A)}JvxoZ4zs>T(www`mySixaN)LpUgeJfim>P|MdL*bX58Hd zwr&wGNQ0O4ByKIcW|M@d|DgW{CO+-K8}Eo?KRJN1AEyJSV{8Rt7ZU3{N^Aze8T$B9 zc!jab5M#7|@bs@q3=dQm?KTc5lsaAk6;t(_zY>6{(HfKNl5@_)@wacArbnF3KPE_I z`}#U+W3#YgRN}iOLX^nM*V)&(u82^zW2>yQ!JW#i<}x+}i)mY0X}q6*uvf>? z%uc=SsBPiTe%pa$CFQRs5ixzEm7pL{?%%laORd54w=){f#lVs7HRGKZ{|WiJ_jEi# zAVBRr8r}Qz?-hxl!kLazXUcBB2Y$C3YtQ^qz1s~AY&ksT&8a!dD#@xbeRgZA=t45Z zcR72%trO`1JFMLSr6%br2*^l0658>sciq;h06GqrFmDivIIXk4Q{W}JZHi1Rem(%G zA?Z?5sH7ed7+>8!-&n*KNTUTL!x)RA`N54jl~W-1i<7e0iLy5uuL}?jF|FTx@TFt( zZq+h)A^B>!f3L`E@vv69Bdt=vh@-gitzE-WX!R0|TGYk&7&!A{=mF5TN0}e1%kE=v z=OQrh0ib6T-VYcmO<7iDPiG{Nr<~* z3=;$3tlLrW&d+c}saJhzLiepIvg|gHX-U0_0l?HclF+eKB$ML}74apOzK%HeWmY?9K>;L2#Y}QXuTQT0cXO@Kt(_xI}hh^;# z%d{ab7R%ce_jO@Z-4>3XnAua>{Sw$mm%~Q|Bz3$-ilBrrY@hNflpmNY#7-M~us*tJ zfvB2MNEE(GCqUA{Bt^$LcpCvbpSA_93MYqN2WvQXGgQDekv0K8lIOtM6{kFW60xZo z(C{CGeM4TjNXeqe%Ud}s=JwiCIc(Ri=*6`%0u;b;$Hq@W8SJC-b%J(Glw3D z4o`XEg&8x+*iq<()32Ap)jFB46j=k-VCH-BZ;71A)+rueLK;)h~48 zgYnwArP))&tbY>jwAPGEwX#+&L9nM~+W1@lqa)irq78cO{*@hPDricL>H^#oX&Lph4@$6GZKhCz;JCV+Fq})q>e}6HbGt{qFk3eD6m}Xz`YWkgKHot%gCxAzHa>B#TU%hY7-%2JJN>rfARpKjzr}5OB z=)KhN+RRsd5Kf9zzOSd_$iwwOk%$5dbA^^73v*Od+Q2~w>cttTjhTGxvef7D%(={V ze$-F?Y{-9B`|a4jc9BJ23IBQDe-{4=xO2K1_Mgo)MMR*?R;D4Su>_36AFP5UEt+<< z1BTyytx&GLUjw4)la0SykRurjWygpqoW==9_ql_ZQP{*_m>E`yqsS$2>kTv#@?)~Q zaeFo_Jru_+J?=eZbbO0BliJ6KgHBBN&I}|E1lS4|!Xi=6LVC!Mj18Uy6f)9Gf5qOr z1J%7IPn#ole|YCtFw}nXS+Q5*Dr4Sm5)^|Yh8^h;pQ$QX5e5&CR_cV94Mda`&uvW5 zBY`COAO*huVkJNELM4b>d@6|=Mt0f^)y=rCMsKO9N%$LM>+WlfcuV6>qusy-eLu@P zga1*;wDLD)HJ;$PoT-J&uz@Ni{wTe=iTX9#OJIx}H=U0y$*33! zRchQt{%daT2(D|-l`dwgd*{1I0z5XNY8^<-xYXJh@=nr2pnZ8T*G#Hs4&$Kq;DUzq z`ZT+_buC0hRAn=g0&ug6Y@Cbcn_2%d(UI-GSiA~`ai1R6r{h9sEZLTD)Y?-?XTfwF zmEM@MnYh!Z43tKUV93?)B}dgnr<#axqn*-2kVVM#_CQ~IuTj`~y0GQLZ_Y3yf?QH? zQ0Fr8+Zp;y?EtDWrZC19qe?uO8V8pM!6hiqT6B=exFx81beWOh8mHf2DXVXndu(F& zdC?p~jM!8*euf>%dl!vkUpar255=Slx4)!(j$*ek?1HD+$U$B%;&jErDt(cy>~NzI zDq=yI31#D@Fk&(2DsK?&Cr3NTxt}ciBu3H(IGiTdPmb8`=P`o*h1z`hH#N^hvC*kL z%r!espB>}4W)3o=S``q@0dONg`pfaH`iP2LpF82U0jEGWtgrt4zj2V|%(BWH1w1T5 zF1aEC1wIN~j)a3e6aZ0XhE@g|us)=NpseIGjO(EeslUB^J$xTK1MzX~y|2>KH&SO3 zWVUf$YRsM*9cf6#@OR-kjkHijHnqB_>u4jF3 z4AP*;xp!lF6Y_9g#cjR-VqdUZ-~b;1Cqd2dN>FIaP%#18iLLGERTvivTfsXO9S-3w z7%ax)P;mlt&KK5YP(I-jB)Am7AmNEsR$3fStothXG*~;u;0ggd;Iz<0Bd_1|t2TYA ze@-C>2F>!ybj-zD80c$R$fUTITaJ|$b55{wmf3pWPpL6W?v*`L(&2g=#c|%R8^YMH zU-{y)+epppJLZ2W3XH3akqQ#0D?mz|O?_`#qNd=yH%b7-QJ>CHn*?NX;yDSBMrNjf3=c>pDTF#Z*Rhbxu7>4 zVlL6x;!~I^BGnCb_P)LJEf`5~PAnL1y?*ZA#_6R{bN;{c7{lcPJjS@$|NqjjT^xVfm)uCTPRVDeiev}UsUjZ{D5>S?SZ&ZA7tZ$E{? z3r)lFX=S>w-d+iiKXK|j-q&(E-79&EgY^&HBLAhwev9Y5Z3?E~{xeY&HsZ^n1mX7TjHH`W9- z%M}#KTk|YOT-sm%7HC}%O!UKSh6b5@|5ot50?-5}ihx^&AqMm$ixNLQE|q%Z)_8SVd@f+6$|K!$I1+9cJtaq=m{1jwu5+UXEMFwEun-UR%@4j zR@@+?=`-+##U$Xw3_gq=iITNm*q?7l%D96Mt+7hVmEiHd+-qE$Xa-d>kL0fPdxZy;C0Y|Chmkq6FGy6vj8_^%Fe8_{;x?N8RLqc@2EV&+@`$ z1@Ke#^7~0#^@~aFk}=vV`}$U5|6`TkmQ#TY`P_vpFCU;4t5;_M;~GH!O5d{;Mg0`E zz+hvScCyZfO8lkSWU_;Z?Uw&)0O{?S=wlvqC6wAr^w!iMp!bUYeu|tw@e+%3c20k{ zfVh6Q`E?Qn>!I;!5ViEe+sc3>QwQ}gPq&vtj=lfCQ0q3AY-_F)`|fd3f{|JyWa;$98?lpAd!D;`AEFIfgZtLctZS#Z)(t z#lb2YYmN0&&dWhzV0O**Px$IM2YafoD-e*?X7%Tbc}8YT20i~$7X6A;PgDY(#XgD0 zr%43OTRw=~iRRNbJt1HQ`O-E8QuEwyBJOAKw8k{5QSOpCLT&FInT_k$1Mv7P&x`J%($jyXm~woY$COxW%FyPu|X4lYC?Z#BB*3)kb|Htu}5w-+~ynDoYzv%G+J{D zZt63Y7xX4%q+Hx4B&(i%6@)j2a>U)g9_ud9nQmDr6iojTU3lj)I4Cub-<^9}RoVO= zg>ltT!yM%ygp5av<<2k|xn1Azp+;-o3HD>#Sdoej5u+R-pVJJ?d>IUzvLwEG2hr87 zALKE0b{0C!XdTGjWihe-%UH9O$v-TDLlA+W(|<{AVp^vO@GxM(kAh?svoA@;%}+Vm z@EhXCYyCRI#8$`s0isPc3Q5IYzBik(Sr1sM9y6k8`q)Uo>z%Froe-dSY2vV$1%&8~ zVVLhr{7cS#_1mBBp=vu9=d5{4z+cb8P~%Y*i=^#lgvz*#;+Lp+57Nc2uw~D~>hIO> z+EC}mZ-%xsS?Jcw!b27&f<1pqOa!B-1P<#;?;WN~!q8b%`$2T}!XT4BEh zdUIXmL_W_yTn>8U6DW_v!eVyL5HW^5=Nj6Lm#|?BcssC)fq-&oRgL07VXWJp9;6Nl zHWDnku;;JUw1)w}Y>zM&q}9Z~Ekzn(%dx##^%snG8vD)XA%J&d#VA2WLMV5st2GP@ z%^_q8TwpdbE%=Cf;_2tZM6FV{#0Z+gK}6mK=TAZDXk{Pjn%j~Ks;XU zN4XzhbQ$bTZ=gI3J1}cYh6phCbGU>JE$Bby?155fe&FOX?AH();<_k$NpQ;7h%aUq9-x)nMkc4%4nMii+Vn6qN%nvaijD} zlx)k%SB(DtbUriPD6Ynv90K4-at}T90Z2%-4eT9WtYVj(WUShUTquygAbpaQ9W6zp zgK_NpdYs>lZb?^WjSS;ZRnnkS=fV0jk(Gdd1YfktNV2>`?%q1xjQH5-tMvhiJp%Hi zgU8-@gTMN7)w#sNP2F5X4CiO63}rl0w=+Rte8K2snRrjz#}?`tyO}^GQkI^L!g@Cb zg86b!5S4ZxGNaM98t4Tdt-WQ&6V?3qBES?j)NiRFXV*;w23(i+!qi|JY<#*cGvjv% zdHSnY_3-E4ai^8`$jc=8?ro5}o{3Q&@$;hL2N%p)juro$($+~i$AxG9KNAp$)w(D&)nbnxg!Pcgs7NbXERf-8f~!`MoC(u_*@7(M3Z^y zCf_`f?#b?XFkkKJRyq{rcMifmRXDvy!6p*RD;X{TqTYZW|oGr^GSSz|4r!$vP% z`dIeT6DQS?7fY^bBHbYY<2IQN!FB4R$vv?$ev(B&W(u;D-GWNHvNv#I69+J}L>MdQ&gmxJQw~Mf=hj)XQC> z$Vv5Ovqe_JyNqa=d*><&VdqT!P_Mnk!;(9Rfx*t20vQ_Kq_3-ZN*r;}0;2oe8wRp& z%0e5V_ShQ+dhQ-4d&+Q|{X;{j{<-YBL-O*L!%V*tIZ>i&Uns2btOu!$G8H}1r1cU` zT_q;>hF(^`#rXI4n4cqDdpQaUF#-E`8DzbK@%ZHB+5&_WHY!q1b0m?d>TF2o*+*^X z7$oJ%Aa{0QT%r9^Ovu2fC|cpr0Qj6!lw>G4WmazCW!x}`K;Vn)0?PeMW!+3j5zuxG zgE#ZR$PkL5;0QFaNc($`vLwJou^5rjB=xgBv)Z%ARqZk0_5zTZ!%=q)J-?6c2GBl@ zJQ>!!2BMoEpMtI^Mh@wm|Jt2Z4tpLRv-dqc#*Rl%J@45Lh+phbO{FA!Dg{|PyVHY$zels z;EodO229a|+wl5Y5^btyPA(hkspS6{g|Ec@x1oR~*P%F#n~3(ke!Scl7|^yro~KPT z80_bRB(19mc|R>4L|6_RG(!$6tY6O()ruSDpg(UT7D+oNt0&jbYe-R4&wtq80%uR; zL(go3cRA)M{x($gKDc3S4r!ERplpSeSu-X5d-vB>7bKJlF0n2e`sjtg=*;M?c)bez zA&>w!wImzuGt2IwT&gs+eu`w6I8xYS$kljm3kCCV!BN12nk0=B4~Ywmp#a?oI1-F6 zh$d%-YS>UXr(*m?AhnWzm`Z=$%C04OpEJ~n7cb7^cHm33- z%GZHs>4PRVcO~?d&Mfg!6Qw8#58ejd`y(wdXjL17p0k!9vt(J}p0+*3a)fo<1BZK5 zW?$1DC_^x?xHeSZzf)I=r{YqcJ`wZO?aJ^~TV5LyVMMn^Yz~2~a4GnbINfJ6Nwm{MFpAmyXagd^BHjANouNa!z1b|bRd*(f`LLiz1xEA*ASK5lcX~~;RO_b znNGa3+?B^Z0Xs%b+?d-_=KXY$BYs!{D>^RDVP@*BKuDp5zpa20!3~b2201cGJ{JZx z1VM1KyUU!uRzLq}@pcR)%$KlQt@`P5uXsu`3)bDP5$2%i<*`8yb7qW@(RJ$FWfaW(8r0! z;^;1*D~B09`Om5aOnICzq?S0EMXx5K8#M}{8-Iryh|17EtZcp&d428&qJJMMzyvPKoV+FM%Mdcc7NI zGrZe19?9zKqt8v{J%0eP*A5y++@TGLmxt6U)cN^VX3|KJH0cYl)P|NReU2pz4P zQ{Tgy?bgS^pdVE;wHN}BkV)5qE4eaqoYiSpINB`Qb!bebJBwvYyw&^g)k^_SZdRn zc2l=F-rfG&HaOjI(gA?kW|mT8ZnnJ}*9w zmYE#D2cja62tMAys;}^%r*`V)`rW0@5b!|)r>VyD?T)_@;)n8%>77iT0`cYi@v z^5$G}^~QgYSuawm;tZb&(vu!*ez~ZdfWl3Il2eams|iO_p1XQnK(L*rmR-80@~-<; zjaOF0ufkp#GKIh(*#jFf%GuDfJGHojug26?JxB%1RQ3DYB8*pJKa+oHN86XJgWggzTJmJYt!uUdKGF{eqRHcB)v~bDXz(%viuQfMStfY3 zS4@bHTPBk_W4`kf+zFYa@<6eGSlDA=lI%PXakBs>1mDUORn5u#;I9Zdl-vq`nTo?j zQ}9XCW?=93!vGvo!?&9aLW_Yv5tMILlmr(Cxt`|Ik3+)6BmB2C!F_07V>5ajb5)SP z^b`S=;~KTy=_k^)-7Rrmmy7K+4GCVCROxr!nst-5BYk$Y-7Ja!Zshm=Bh7$h{6Dg$ zbrwj5STgJwC9K2-Ve?FMxx>>vuG5NUt{5EC->ehTP;_&CChrhjAoSuxEWD|mwwf9x z>=y}P3W#pp?gk-i{JUVyvBQID)b!;2ko@I*j)k~C|^`zDz2SBnHNb*JQ%4~Q#h z$p%GRoz;;SW5E9IF{tbgp__jILaD=@$JC58} z7+sIQbNrn<^VB`PJ7=|2TH(|yOFiJ_qYnZ*D)b+#uVB|pF*?f40mJiJ&01thSBGbu zQv|M$mC&Vww?A$vf!3g-_^$F>t)ZG0|JMRU{YFF{^=^;{uOH0Y2%_-8~Ap8o$(0fO(U+|7JQVGq}T`lVZ4XP zeK$SkRCn+TZl(yX1<)03X4cL6ZQ)X76Jj=?{g*_)RQ^jjxNsw3PhUO!R4|bx7*wr} zZnGfgo?x$TGwZ}74m|!F7Kh-K;p*QufUPI!C@n%#|~H*y;oSqIIug;ETEY5fY2p?IBJN-%yfTQk&{4uUEm1T_D>SLt!r`u zYokhkabKDqEk*)a2zsG*&=kjC;ZLdRFe=Y;6yBisM=U>zBVj}!9!c=d{aok%O28i0)&rZZ%-c?a=^p93_&$L0)UC3h3n3aS( zqB0DVk}egJrs$`}8>S249zt=^R^=h~#)2CB4y+|&!BKq8q3JaeXN*q_S*3+L<<+9Z zN4&iLu&>XZ{n9gdR0+8gc zpHTdj@!ii-pYt&ivr8>pk=3ex*{k@aHw__|A-#FQ$fqZSNf9G~$(U}77tN5RrL>$B zlmbvFN$nA67ogvpV?dtDgtEHQAI1w^8L%(szh3%zk%ig`O0KyGJcwnFMiKNmifM7d z)on*_q*96&OQw>bHt#tetqq4KCA}_B_HgEu5%#G97sdE-3A=&E1|P z-1P3Y@FxQz`a;Mh;IojlFHp=)fOzOL*d?gd38dBFae5f|#7Kp->UDWqce&4XH#g~u z;Y8Q7dwz8v3edvf%0oLqGRDD3MqZ%AI2=lH(6(oE5`G+cHxh~{R`6juw)=DxQUg@J z6T$lx;*mP>`G>r4jhxh$Hyg2qi$v&-er8ds(+{G+(2>Dk3MqfmC_2;FZEF47QLAD2 z>)(%?D^4>YDJt2pp7zsdtC_myr&pD6c{(IykM-Z?)x&_Mm}3=yYE%63c&dYnu?Nt0 zp(l=LVON>^UCyBotvV9EDWRTc9fsGYP)6TMRM$;REVB|M7+d?FSp-`HoxYuqyqZ%W zt=KN{tReXt17k}YH8OIYT|B>{_%fJ#T>j_5eJdcVpg&+8s!_jr} zY-|F7V5{`dTpci9bhG<--t@rY_vb7N5}r=<{5z(jO6iOva~~&d1;_9aHL<@lJy6k7sP|y0 ziTS&KD6)bV3=V8{&KXTnRS9a0)(RZL|#&v|*xM3c`qf$snUUN70g%?w|3${P;ZvpNH~%9&wqnP%j@@^SIym^v zen7#Nbl}GXj$Zct(+K^5Li}M)mcZ+ljG7SR)&3x;n+$t+qGwX4P&n5!|M>OoIepY8 zEnfEj*TxxG52usw{9KCr1T=SN644~m9@?|V_cRJ2{PH@(l#uM%q<}jO6Q0HiWT`Umc)+_312{@5hpHxe4KuKU=QdTW; zyx_wjQcO?^gJ0V_Z$PaV8sR{wo>F4S!^V?zyVq7b6&D995$#-LuInsX{z_A*WmE8aLT`@kLiUtXM5uYh8iU=zQ~2MNh$+Z@39IqwfO zS74Ak)#UL>>K$QYu6b;foUlY=nKaDb`G`@YP?&Fdv0@rSRNZc!NCFF&p~@T7m5dFD za3OmyW}(6LCJ%DM8r-`-;-!m1%WXu-Qp@0C&utPV!muk0i+nnm_ zz2qYF-QhZ8?{z3Bn1fXLs}Al!mTu<`ry4D=2#kVf;ZVgimQmhc1;M<*QwlM3>P~M} z){Sg0Y+{L<9R`n$S12U_c?_G!U;B+9+c`a>fR>pQVkW^v=3^~M&V)|?~h-nie#c`c^MF=^X zlW_;VT!#kbp3_3@I$+kXtaxIfoo(q&7rAS&{M?B03=yKoZS%+y=rJss-o$I)Hc|f_ zT7brszn;OS^#L&1Go7HtdYOc)^FZv{MNxTH{gX+`fW5X-z`4Ijkd$zdThnJVaNBAZ zLde+R_lpb3kG8js00PiIF_r}WQ6uPxmID6q2!|gfPrH!Lm)sH(`Ag;?UQM#} zXKxKVP;LSZqWc`9frR5NM5%{y2U>OVE0P{gyoAw{3`hW7+{1#*91Gn&+tO>TSmV9< z>y1AC=>2f#XeGu)hC+JqTk>7QJLg2JVUKn7o`vL{p-zQqM+$rb?YX9^# ziTX_F@=7p&??FJ7V3^s&78OPeY~1i1)_ewBg$tT@)Y&8z1bjPMI;Dc#YL>78**h!M z+Xzy_N@N2B3eXCSR-MS&nIOEjVX7yAh3J!)!ug z?IRaIco>`U3Sfefoh}I+6QgN!W@J}Cm$dC!*1C}lazCwUEEBM%C%s?R!r!;$H9`&` z++!&$&aTz z1{nSk%_N@~=w%HGAsnt`_Yo}6besjiVWzo~20;(G8uV2qk6r#FfCWJrS4-(M81W-gFuuN9zh2M`q%%*JizllG;Ds>Q}M*SHNsvufq9TCI} zosZK-% z%zEbN!}4-Oa{P|h-=`pxh{+1Ql{c4Hm&oHsxCg0^xP-?Vgg!sQJ>z zKM4#ln{Aa>!4%=+4GAX9i`QWnb2*oHovaj>f^wx;YXMRAp1tf+y%+>w(xIlwXM6G! zKtCMeiqLPGak!?!-BdFL{=~!>H-}tgwq>DxAANE|?X)>Fx;q)rLzo3I=Gy8%RCFnA zfF9PJc~;LrVbNcl_prV5AFu3jRk(k$x8WJF~S4M|wfB&@mx!FiV z1>N1fb@y83IyuDxAL0rqED!Re7vl1m0D&-m9`ZT$xS)rE2R}d8`pxw>y?<2XB5Rw4 z>!* z#_v)~=B<%e8v^WxM^pUlalyzE^9W{t%DwQ8suibdO-^z%dxeYvT+UbjZu$7w_%FHs zD+R)e^3r4F_@|x*_1`wnu!l0oCcKCuPb6|Cp&>*4x}l=NJ!uHoqzS}7y-5@K7)vN6*1}}xD$LXz%)zQwmD4mtXL?@$m7|b5MzwYZGFDl-=Kg~1F`p4 z4}Znz9WuAF^x4y^mY?dl8U!z7dtHOKtPR1X7YgEqc)GE6{SBPTogoRh-C|JsK-Oo> z=P^Tkb8{N<8f0P^vD9jWL|Fa&&-Wr}6wlsGi#Y(!6BfX={74IHhH_cBUyXi16}=$5 zYFqVeuRD&c#qQ=6Lv3@65(S4IcHNCiBg4Ojq>~J2T^Z(O^&f~x_(Pe#EZlvF%KDN| z^w)ib0tOA#1q%hjn2li%BvidBZD8$l1_>#E?494h6wQ~k|8N652hh#+rRGHbI!ipj zxda$Y7XhY^Yw~TZpCx)J14H*2K+=EQRloBb`ozTm4?-Is3vn z7;}sCJ--R(S^oAFZr}E4MZQ(h+iOAd(hv~u$o=k|pK-6Nkfx|}KYs&Jgdk#aZHncS z9QafJLYj%!+luv3^lVT<`~^?ZH&^Ef{g>n^->zn%9lH`nX2j79oV}aS0S9jP>G=!!0}9<*ifSh=$&4Rkx>(mMlcs!L5pq&v~;}_GxW|a2bG( z)WPD?WX{0m;R2k6)Ubd)0UQa_M$41FbnE=UB56q_1`F(c+t$QEh=$>30eB#{q@}Ln z-Zz~{$B#Oez%--guz|VDbDYFo)_aa`;W!{Q62iRS3~f?8{$4&r(uZd3B1x&CCLg^N z8n@K6#)W~2o%T)ZE!Ux21Z^=Lg<}Ioj%x2w($lh=DGYR92NR>hoY(4%u)0nSw|Ug? z4Ysx1xK`Bg*N9YO-rw0AnJZpW=gKiQKMoZY=8T)MvasrtZSFkbCH7)Zd!2vh_ zQ@iY27qB+P>Qp7G(s5kr%k4UpjXkj-V(!ySD(bQ$DUVe1#hk!D`;!&4D$sp&tXmi;AL}Jonz}a_;dfSIWlPX#QhGl0&#pRlnk zoSa8W=bZ3`f@g89zxsS3#mYXsES229UAIVZu5UEuxE13?27CyR>bZL*Esab4`hn`* z&%3~6u0Z1Y*Y6ysz<>--USK{lIdr-CN{-L@si-Jsk@Z?kG=)2ARP`m-jUJ_EE!{Uy zojPN=xrUga%|~Tk;!lQ0iSc;0_~~kE4f&td%>Vadv9jdXW%i->sm3u$fKEcgY{zm= zgydCja#Mo$agJ3PizSNiW3_F>&D8KAShdVpQ;i$KZQoW>B8SRM7b}A5G2K8#&;RH1 zg>24sR!~!Z$P3I?B+CJ>k&!m}sjW#LCjV!IW^BL_ntUFw9Rf(JrL?W|&!>k-Jrrfu zrTFg^*wiu_p;yXzI{Zg>?BswP(ElU2{_iP}8%*Yon$4*wyoTD+FqG6uDd1I?+(GJ~ zkBM#iZv@uqEV%Z)-9~N(yHkSmE)ygU$t_#POm6uzIU1Y#+OKu_Rf~!QAX?(K#lHc! zk=Bh})yb=LE1dMx4*O4W>9LH{wHLdUSW)-Ghmy1vuRM&$+f72f6-HZ)m(jJdDz#Wg zoR3ELra#j>Xs9M@(@t_Hg`Yh?pjiW7rZxg9jZSi)M`wZvNtQ}BuQIU;)RS}l9 zBJlOU>?(B?;@b2g<^F_@v5QrXJ^cn)CCtRm4G0hvihub8H=Xt&&W}&SsU&-mNoiVW z#G6byAkC9_a!CbuFpIcY<&v;%WVN=W;SVyBzg{U6saK^+L?6!C-Pxmbj9W-pnG?n- zDSa;ARKYq9x|myrQcm+B=i;(b@+lvCgj-_p;pJMt%*3GB{8a*aeq@>hj*kG->S|K8 z3T>%%RVCY48R7!GEO2k0W|$w>2-5{%yj--rj9kjc3A=h3+WisCz5HBJyK}p)IM%cE~jkXQ$@1;o0~uT#l=Gn_%}x^n*a99((SM1Yp;fjHkJV#%rG%l6SUX75+YdQ z#E!=&BjuuBE)%rDkt9oQpA-Q6>WT7Jk0t4Ae=}tiM}`=T?X`IBCSHzgR{R3B&{v@f zWM@SAVLx|1C*fdClf(V<84OMGnBrVd#;cB;!%zQ+!3KKqJLq;?v|&!Ktr}^g$7wdkT^|H(%?FN1$F43a{`whB9M2s|QGm`qe%ALqu4uyyNe22xx=D`MomW!>;!y6GH5XlU(JXPC{lkmBr8f6Jj#gYXqYO8?BNdFTfR=DS-N>2&OI6pWML;@r-B!P6_fAkNHNFb^5cX(3zU$MnMvYpx+0#9L%$#E<5S0(7? zdsjo_9qTmTc5K&sG)ph9pl1Kz3wMzZR$6mRBef1^)Etf7V=!ImmhL$1QYyBS3%oP$sSPw=f!|#Bz>*C z3pBRmj>UB=Yb*-(Le5~#D+AA*z(LxAVkCVhcPwgmPtL#qxq~qU_pDc(=0t9+(q_HK zSzi8NiM{pcR{hhApq8nN4-m_WBsMfYIetLJ${trMRK*v|igsanCDcX%BxZaWP1%1INwtd?GD!a~dm~Ni6rB>HgnVJHynl34}jgR(??pL)&H5o zwZR&W3Y>$5iz98%7#0UGcj^yfddj29KEna=`E7&M=zH+U7gFqKva_WOtbHiU#FlAE z)PkFgPi^tfS$eWivIpY5nQQcSMzW7v2f)kSjv>=;+HUgq2f?2Ab3xyCtfI)>mg_6P zmjW#sy}zN~?k~X0!N})?;n(}o6Cjxo@JX0AHwPlG_9-fTl5h@CG^^ND>0&mxlKz4R zOgB*FZw2qSX%3_I_I!c_Z=9&m4+qmlM3jN0h5@fZE2qocxFo`^|b&6UsDD)DIGSPiI)73Zc2`L#(!zSw;=B^z;68fa!eQEHE zO68j@EYXu<5VTO5ftmZvaO5|)q4YH4YRY>`!MR@{nP3TM5Oe5aXJ}$0OvDWz9Y!oV z$Dufm)K;Z_uY%O4@dQ+-nqc@GD3#Sr3>gL+zB_$>Yyfp$*3LfZkln7Pjv8zq0LdV& zAQt0GdBl72vPc-R;e|?l=v90=gmjk@M`#j6s+hHw^9!W0tJ(>NF*Peq&kbfIwT$@{ z%#N`(QxPi(4}$0vy|zy3=7nzXk;YEF*{&>M)$A)9V%6xjBb^qr*mvu~*eCFEX=g^W zKEqq3O@O?^2J?^ckJONU!8T0?MGr6rQj_HEjs>W8heeTz??HU#A}ygphYGYJk-r@@ z)}>KY8d_oVMF(mT*8{nO8(P;rWS#5Z#@L%E)09i@%%{P;4 z*Lgb+RDw^x(M#JT$`&hBJSOTK=zR9s^eqI+Py!s>2JlgPP-0R=ycw71rEwC+rVsTn zA_CK8(so`tI>6g?+!R+*&HDdr?|vs61Xe(u&&bd0#c_x8LHl-n$Dd%D)h9z5pu5E) z93Eo$T|hsWJANXB?jD;2lwT!GGnvcQZ#Sv8mygg; zNPtC3=gE`+VQ?|JI=6*t(RzSONo@O3=h>a2;m@}36gR$}}^OjWxf z%z*$WN5}3SE%7F+w`_yaU+4wWoPqAh4M02>Ytz#9wNU9xPcn1?XXxBmz?O1?wr5L9 zeiVlEA5UBTLeT+62ZyA9AfD=I25FTfzEe1_+E5wd?LUjWWNKQcQbm8;DA!QmPFCcJ*3h0=HVy?ps-T)i6 ziOz@9*fZ>4zp)iB#Y|mOF>{{%Yb**|Mi1ZcyL;Cg!6u);iNni?n{4E-&PaidJXY@8Ts zsLmLxVySzx{V12P2$65L=s)Fz52&MC-KNbiSmZnxo)FPVyeb%5V~faJ5#2`Dv}6nu zi{}-FN8;F!#w{zHFaB*DN4A&N8P;9`L%dZHL=R)VeX-sk<|lsxhp8OfvsqX~?Og25=USHJpkL zFR8v}4@nI+oQn=eF{Ej4;gv~@FP3?1QA1Dz>_#P3DGh;-e@8Nm=J8EGWm-lAJ9jR) z&k=hrd1c}TWwcr=I#Zjsqgu^|43S@l*q8v5Xi6+m133{RvO|NhHn1)?yHjDn2t6m0 zNtQYMwtT%_AwA@<4B1t32_P}mnbC4v$Jm%KP4kvLU$0OoDk_KnDUENdE?q>`JSy;D zzeF*>i3?^h-!K}#%&L*(-v4+vs$#0Mq9IR0EN?F)^+&5xp+Jm#{t0ZTK%NtvK**qaxfniZ(7CU@SyTEb=VUKRo02f0F%9)S-zbru-R3j zm1Q?imd!lj**th{N?>@+!sv@i=9iHrDB;qnsZ6ZMOz0k(*Y4!aky?74iNky~hrjn; zHdCDMVZUee*{YC2Y?fbvT-}aaPAk`YGt#_;>+ShEJW8rUP!?$n9&sYJ-7-P$QboHA z9??Lqx>cSuv0-jP0+J4ycoM*JTZ4ZGSlEXz{D55bzmjj+Vkwo52ERRU3{C=?L}RBm ztaxFIO#-SfrvTQV=fBzMvXgw^EKXzg`ZN&JB(Zl*zrnWSw{2psgIG~vJpabjS<2+s zVHzZW34Tq|ZIlGt4y%~~`nSpS>99uM90!~{xWiUBLR*v{0h*28_~W45ufZHgIS?%m zZWb<<=Y|Mqv~U<19Q)vXz)6!It;-=>cIPP^Puq0%U@)pvD20ZQ8M9^}s~R&EC?9h@RV!8iU`#`9BkHb(xlf zIFO?$>e}q94>Pyvfu`QjTzQ_ctjPqUP*2`poxwV|08dd)2=mj6zPBXi>a)!N`~5VJ zfCQDZHjRJvd8d18ZK<=fZEucg{Bp85uoA)d&rdzkxNv~y!vmi;+i^p;FqK-y4z?$z zxS}#9tYxRc7^e$hX1pUg*m6mhb(1D;S-*6T&ibBUVpxhH&cCzoQ3c7wc}H-6d2ZM4 zRFVN0gnoqHXK1$VO1`BPnjF~1=jz8#u300QZjY`pPLo=_m7SzF8b088Ja?Ty?+c!D zSb$9bIIv`-as6iQo`JtA7oK2j1Qq;aTO}7^H3gDmLE8fL^xRJ^_pB(zN)^Na#2QV!JRk4@}wd>#a=>xgJUL}v#;G^ll((xYkwCu=6>>d;%4q7~7C52Rxq zV~l6lD=V+pyjZ^i5y4&8&5i`mif^)|YJM;{8;?oU_Vf%ac}b;qAt)c@0*+-zQM6{v zbl!KuaW;5jD2GaA)ytNv7-G_`4NV+YPp{Pek~_!$$;AgHbd?)K0AVGctRLQ|jfxK7 z^C@D4B>{!S6t-1f>|X(9VTGuWts+eyBTN6?XV5;x3h^U>EC6}=t++q`_q6R*F^ZDn zpvf@1r|rj@XpRoYgxLDhtrR@94$$ul;eo^Pi9q^>c`rRj#GK^&ctH=ij-~*eiPlQL z`Zg^-DrT?<3g+OUX~mo%r<}lv2df;wzi$81{n$1xf zT$r3T?Jmdo!`(E(nh0(3@Z7(k5fdJ!SC%*?HVR3NX5c5%+ML;s)$w#%6G9Iv#@~G! zg;?q^-2@Kam~x7f7C=i5qdcx=$>5gVJhgNgx7$S%>baMUUOFv-eRNP#Chf+d#~8N*)}R3sFqnvgonhq`YizL zgs{*S&JW`%V0W>QIBePBarKG37WfS5!5nFsm?(FJ_%?MJND?As2pBl0Fv! zE^I-FVqA{xS5%A6H}vPt=mxQARajEbNx0L*vx)T8ugJNJIS_+pR!wWu4dmB?(fkUt zM`Dh?>tfFqemB>dCF*p*Tzq2^wL=q^<6Qw3WXu%jeVn$x$gD_ z)`}Yj3(gGb%S$!VU3mbX_KON56~%6z7}OFUp1CrzP07R=h?HFeBYX@p!+QCtMkp}Y z!aPi*!Qb6m1?8ON$^Hg#ez~3@4f&~s&Fk{Z#2AoRNT!*tuC*ln=0zi*<_*xtc*|mG z(jJ`@s#-@OPt>;@lGZmv5_2F5pgn@wJj{JQc?-T*Jg|e?S;YY0iIRGZUE-|bY+NP+ z*HI5UITS6~NdGg*ix&DvD@jzptpq#y=^hgOY})+Ln?je^Y76)?HPem!GYo_6C&uV1z4{l)m?ai)^oigzO{1XhwDgIfX^u7Y zuCzzL8bSdubUA<-vRx3+ds{op19IB)ZR^Bi%=K<@4?}GkmS@;!&il=!o#jr8B#32YwHBBVq*U z;nN#NN5A_5%n?K#nuKUviSp|B8(A?~q+DMu-Niy_z$sM>R8UE*-L06hnr$l{B5-Y3 z71d3{mpZ|b{iV-8e1u&4QrMgnXw849)SL2Og)V$@)9S2t5^7L7q=xymzwQ^q2J;dN z+q}$o^~{BX9js^@(yYl0N#?tO1H3NUvkrqu^oU!j6LUrNK>n!qZxn4XqRTck!R@A$ zmcIjRc!QnBvtk>+?@!MJnDt*!L&FKYR6p({z6<(+l~F~9?{({SA$kf8Fbe8L+!F(1 zC9WjC4{-*>%K4#=r#EvVK$5|6z$SV)?_4hKRUU)pS=ZJK9)!(mJ%T0Uo^|{xc zT*u$g1_fhcFWsbm7l2v|RIXi7VnAIgo+kvv=h7Y7*XtV=@aEAH?TFvrV3=>-z%RqX z^m=>pIWP`(N3JKv$0X{?n4N6eU38_*gLK#1B27>h|4C`t=^K!E>wjQ)Hp+rn*fYOL z+MnKn1b8urodH<30o3G$x5;*T3m5 z5VjS^A^pB(9XC{R8G4rYM%zk`xzXi-v?e+rVOd3S8FYD+P(0jJQ=KU$lDQs0Wn^2; z6MeqMkxtF&B`ThZRdpsa3pt`w&OeI;zEM46Vh)Z=AaBdP)#lxC% z>oc3+TGAv_aTYpSY*1mWZNLhEb^ibXua24dTZ;`^iamm-^#5~g0N~)7L6ra3*vK0q zYaA*mlkER%y*^FF!EWBl4zRdx326)Zqv9~|L&kuY zI04x1QVCyLCHjKDjzl6B7?lvv z4loD_UTBM03tVbjjC;*EYo2Sbu)sMnWWUv7VCZ}Y+wRs#-Wt<0iF--%`JDJP3!8aO z>iiqWliUez8J_r}G$#yVPSlPBZV+b(|7Ml5LValSeCwTbs7gaHxCK9 zUL=lQpeUwp0H=66?`7T~Z1+q2EuXxTJl`)NMfX^tVoUx)y1p@169YySswNJH8Z2r9 zWXuUuhS}Vg-w-;yI{>9nkCV4XUT_<}KX8|8hQ7qV-XODVml%^i#7gcgiqk0iSwF-; z-d_9oC{J)E|B$jugWr<2ValR50bwD^kY?H$F0cSF*`-y2%zdOW42{ZH+pFqi9-Y^> z5i~HlFHAAZ#UXXozyJe$m3{elyR(c(n*msVx*8L{aHfF{+gpLpvs)}_x718Ni0KhQ z-~~>Tcu>I56KQtn_c)~>&$NSt(_~yR+RNSl&?d&H`4;X?A0?jj9!74_px+JzH4tEa z0B&0bk^8C*#@j&}k3}-T6+6P3*j8J#!j36miyc}0s1I-^^%8JpF!8@IvO&^~(X3=p zHs*Dv**y(W;vZO-NKqYgj#J|X-KUld(a5Yu6cyuHj{bsMul!l#R!Pk_;HUVZu<-Ol zo_1}Iwqyw|ZpfDg>(ErSg8xghL@mR{9U#+edv{u8la{A#e3iN-Mmyu`2|V+@si6>L z`I-j*xLZ=j-cIeHFJD(`s z3c-P&VTuG?PM}z;=+{&Hs6O{sBf*?QocS7FY%;HVRNRG23&G0y*#yxX#RT|KfJo?* z2Oh>a57;BK2p2Vzf)1yg$Gf`&;%+lF=t#DVX0%{L+QVq-mySlx8-x0JCxj?=<0 zkUE#&zg1Zo;A~u^F%?<&!}IRW0}!8iY{_Q>xNS{B!Ji^MWu3tj^WFL&=#M-9vOUKt zCQ5e?m_rW2*BABQx2#^p#Yg$6z-`+pdCQIww6~ttas7GmZ~$lZ=V}_i@Hi9r6KgiE z?LlVyP$igX&h-P8&F^dNPRQ|`!zJ#&f7JRbL3N`ncxTns{9u@R4inqRVq?LF zfMBsozIz;;Cd=LgacyrY@B|IM4sSSe6oBn53FjwnRHGEXtNS^o@TVCCQ-{D|B^7dJ zV?Y$3;|2atqH6#o!gTioXak^-5X`>7v-c%)l0FoofPdwm)s9jD5^uN8u_zvL<{bXgc~6QMrX^N?+aMpQcv(jmxG(kdc}H{ilz08WE#o|N zjSyCTk>|m00s5mF8Jt)6sBh}$Z7EMyGe&h$FgPKTAX)!HdFW|h5xb*CGYhgxO2C1* z&kU}<@i{o|ouw1f9xSMai*WP1tu}kRJ}Q}Uy%|!}dieG%4|52D`!@lq-FgVpvwG9X zEK7rNdy};&(Ax2SWhx$CXd)$IJ|7Ct(|riUFv-w$0n#ML9W$hSr@1E~Y{)8aAC1uP zhe22ezF$$Gz_=IZ$lJwWpqA!0l*GVc;EBi6$rdAG7z<*f2uM~} zB!A$4a6<}7@_4Fd}OLlwq&;2h74CS=pX+sD5wNko0d5kB?c45%;r0 z&A=Ct0ey8yCxwde1mMQLrRDWaf$o$<1Pw8H0CV0&JoM{uW{thFQ%uQOz(TYo98CEQ zy=SkaR#y`;9P1$<9w`(k-+e*oc)Z4?p@sdQ**PG>{{_!t=lmmc1HN=@G59_Wx^I4cy#hXLKhgl7 z4;v2tjD~;@LZZT?`&*0@0QDK){43lVO&X>{bein~U_emPAbIvm*nM-me&|>27pUOZ z`{yO6;6z%(KqvSYmf_CVo&2Q_RR3%sSE6plFHvaHybki~pGM1qRHQ|*ES}wHy2YmAOmjGmajRn(sAAtB=cS$~ z8tp>EK9dlyvCpG_>y=c~a#d$T(?G7I*FP-~$aP5VRGCPVfS(j^0gjIT8mEjo#%uCD zltR9$>cC-(Y?jOZw&)NZl5^Y-ZJ@>@WBM&4{<}t&1iG-0r^Z+|LiskMl}TQi#wG3r zG6hDMhqPd!4rFV;xMZJ7SVAT~aK@KuK*sdy)&MO7*%W#J((;PgIX{8iWY0yJy3Nm{ z;a3R!AL)fP>K5&5imM znv^|72C^)d0_<${WHrVz5eu{Y^uU^>1B-LM@HMQ>SFoI9KA@?&biwTTfQN|sRuCtr zAfS==x2{N8#Es>k6n!EB_2ym?h4Z?1qK)jz>c^Az%RJC}0#F*Up1v^7EsHx_WVK?s zhLMM!5?7ik=xIJ-{|TIc<~mr{P2FrYF)Lz!RKpnZkO{$L`M-H^p1>3~9m%hz_Zm^eHa)d#ynbi3=D)1ak=3Tm7{758Xli>(I3be$SE;(KZDwfc~``8)hhU`j`QkX zbi-AHM?>m_SQW>geQ3K#Od_&^rFEm&NtD8c2|FwuIDX2Fa`Y>jNVOtjt)IEDFrVlG=~TkC`aemk9xj?dSo34NC=)&lSMd|^dN(@Z!>91(b!!J zQt!M&EteUo%3=C5zu3>IQIK8S9LpDLH)j^H>@AdZRaPYtv!ZAJGNl@#sb8PJ+l@dT*$TIZ~l9UhIk6l6FkJi zm$_<`QY2^t4KR>qn?(XLDA+nt_tS5i)rtdW$UpqN5lGNf;3fJPEilw0N8>MjT>t2b zv`w1}MbASCo?*Ig;Dcojwra=)LmU2qY+_j*yte0NM;T9SiI~Zc94I>dVJ{Bk&;aTN zn1YPX_F07zmjFlMl=hxRBJU zaGeQl{o=$Z_crY_Za$bOG_Wg)aWy3lkT)}7U^vP6{4*~dm{Jft%;)NvVv-;E8 z6by;dAW7r zt+!bw$^ZGjs`VUy;FcrBCGDZ*fV>B%96U~6E!|quNHNgMLxhApMVNF;(!VEIE)p+B zQDmF)?ZAQqGmgZ$112XnWM**>KoxGh{T7KMMiFv^QO0>w_;0U|u9DYWih7d8W}UCa zr9;N1tU30^`^i1;t!bxWONR)0N$BP$|8jFx5nIhqPTn|`7vi@qL&Se}=V(YEV==@s&;Py-c?XNn0S^B};%I9wzdgeO1AN-{>idwekdcRYoeoQIKe!c7JX@keVaiD z_J&BFA`s}xzRP`DR$~QNw*rvtu|1WtX_(i|P3A1&(?mZsDLd7jKbIZ5`e(vk9_5id zjIyae4L=RwFltfCNH8J%h-noz7kM=LRYvtN<));XkLEAk``an4xNN=XM(r&hPfE72av)vH6nRg#zGYPpWvd9v*KD4eU?Qrez5%oGhtws;US3;02AtDp zg9gXSM(TWBtiA!zT#bAP*_)1#MG-AI*bP~7gE^}O&^mZb<12T!rnd3ACELq-uG6sbbH$_77(!{!(Evz4Pp z-q~0=^N3h=TWtTU`~p9o6&p-ts8fY)v}50r@;b;tanHHL5p&;3G52(6922;u&nqs} zB=Bd9DP)nJ8R*1a>xRFAQEx>e4HK<>M$L@JWO^~ikdM^e2?FV0BtcMt#=8F5G(ux_Xvb?zf9Qy^^Jce7>K8FU8!(0gp#jI|ZF2XPnGD}G78G8^RUbU#`L>iT z6CL=AHZs1|nf{@xVl*&4je!o{XtX=v$@Qcsdoi?WEcp@Fk2nv*lh>?uUfCoh6|3t^ ztQX3{Q3j2nBn@R9*^t~SlAN@SBWRtttEXTZGUlg=GLZj^v3ClO?0KVwCrM9?4kmUc znAo zS$s>q=hRfG_CEUuDhm3n^x4$vy!l@0^7djqjyAqwnS#4TU+>A7vUtsJ#+29@jX9@| z)6044IIlE%R#iBgC&E~?+@Z#ejNgu?RrVS%Op7ecjz%-4hVQa?B#{lR#E{dvq ztQ&Hav}LL3q0`TJUWIGyB#c8`Y(I(c#?tV8Ymz912+n~_5J6csN?JwFeHhbN9r>UE zMC~1g=mc zd;o?usKyE{86?b1BqZ>Z3$hO|a=T9p8DeZ`rwU@RS;{n<-_$Gwi*fb7Z~Fp|DafkZ zgO`+pCAe9iZf!HL_zOyud zRB0FIji5()JKYewr2=oCA0A7XJU1qg<66QrJE=h(wi5BHBtDH#-jX_lT(da)75O)- zM|Pab2Z;RYJYx{nJUFX#XqAkaLAT z3uQ;yN?xtH_OQSFoWVq%$dYYlrN`I9`(gLM4(wmWm?Oz_Aa}FO)o7^&MUc;>)t2I3 zC!c&xI}`FdY)mw@v4%VS-;Xs~^f+xsO0DvnSJp6R43tH*k}1Ly!%flGYD@9t%GI`8 z=;{z{=?qnE&293c$Jv~g<5V{!9h^1&m*-;^8^R3sN0~FCZNa4TG3`272Ey2Gu{Fh6)9P())UA%>SF6NA z)&{o}{1A;|tpDAhAk3)1XeGa~{6svS-tuIrah$onAxO0$vnG50}-|9i}qGyht;3K{f)(M?xb%buYo zwj>mH>eMgpaW5+gNtt`E37F_8c}hL}i8Hmg4(*{b9-M#4_3-(0`oaP`?4|=w&1$ht z``Le@_xIJAqlmpfJ%94xczfrhFBoNTPipAYYL)vsQ4MM6F~b~NEywO<1c1bfWgkf> zk)LdX4k7S^YryH#NTGCY%59{Ml*wu?c!bQqQb0e@LvkAY#@7J~)sRM5p0OoP*P!`u zwCdrK_?Va$-gReW&2VHRQT}U#(o^qszf3W;Z}?|Ic-I}_Xx!+2Wp%<+-qSon=kfC) z2CAMwbyuf_s{BGgaSDQEZwF*Z7L4jxOUJ!!TBooJfJCz>ns)7ej(cquN!~jVvBS(N zGj5^8lPXH4fjMCP3Em=2rNI!vQEqaIyj(lFa2AyD`+NcVph+kIXV*=`g{)S|p4&jL zB`x!(Umv~r1&$o}^XMxAiwVBGA6M=dGvK4B2PQ?&{D+33nqJ0bMM1b@G-`EoJ&!Pn zCZ>A#-4Qd^yyLVqx1}(hs^wu_XX2)_QWL==)S)5Kogj;Va&ngpq6dwVoc&CPe( zJ8W+!aNJ9!(1-$RWpt37dSPIOg83YXdn8=)VAkByLVOpQtoq;{&$PbeNM_qQ)$8;A z_bhw}QyGPX{}Hbj`Sy|BiOU_h8G*?{+sujJ}R? zu`P8UZx}Ac9hAfduZrwoL9<>BF>27J$cA`T5+ucM#=#-( z6>{nr5{)>Tpdq!#ch#)JtC5L$iXwlnLjtydC zWOoA?T7&Y-!SZjb5Nq{qD9Oq>HbRc$v0AXkQkWoYXnXy_9z>6A7$e%UaSfREbJ?d7 z-$-YFXoO)KJHC1FsXz>!&Bcd{B1n2CuD(guU5@mu#Tmu+3XY0_IJ+Fbb@@x7HXHAp z7M>e(Z{-o~CD5vp>`=yIAn><}lw;>EaauKC*0rD5RaQoWtWF8xkrvgE86 zJQP6iAs#=dm9na2-W;^GRzP<9pGvpldP2{+4Jb=Z-&-5cN zf|r9H?m*){SQ7BS_voBc9T6L7WgOS!%v{y|N2vs*ZNY1!b%-FzAt~%suc&9&=^Ar_ zxzZ~Wps?J!fgI z>L|hXSgM*wC9-(H(Eh)kyR27!`eB#{I25yqAbHsU93|LTZKcG)DCpF0-T#3ySq(_*~FvIwEQ##) zFJ^HE-!$Jzc}W}!zS!v8T~GC8L_^LC7$ZPyVT$Mz1K)MPhTIo=!N%eJ)}9hpbLbW?q<5; z&U)yj5MG%qf3bsC)bQ9QB^Eqxp%lATm6_p7fml@S5aCIizQBa*d^c-J&Vdy!5-7o5 z3Yi5rK+@9}u1ewe2zAKwQ~Z)Gg~`r%Iok7~o5<}V!nywrV1tZ15&Mj=3EhCMQOtnC5qQqOS#pLG5 ze^;MldfOjorJH35>ASmn%^+9GXl+hUM2&*!O3b!SoMo|jv@idJ=XL{(Sp-h~tX~!D zK}BcIdjNQd!R1W zwbuODHFiZqS;z3W5XR-@H!H$erl7cC)k14Oh7+-OI1joq*f;Bn(-=Iu)-W~iircom zYyTF__2Ipd1#0%EWS|i4tXmrABKpjGh(rK=iC?(UEEFUrFFR?w|>Qk#>4N_p12!w z8M_@n$?haBJ;@11Ry)QROD&i&?W}*tv$Y!j`k0rpPA`?u!(3Go zc}ue*&+`tnT6#4-_GM^pYysz$3}-X7{UL?m^&!BLU@Oo~w&iuDybzLT!ipOG&ZLK1 zc`JyB()3Rp1BD>A3e#ulj^bs_X54TGcM%Y2QK^QK0aycd{qVLtVg;cOq4KR(ft84TJ?;gN zk%ogFl3?T{4!rJ5^4A=XhXy&Qfd7M_v9P`UYa`I0kE znd&w4&6*h)7x?DQ`+w{_?x2*yxpEX0MCriL^!&ph1f_$ytSn~R`Rtez%a@`q6gHfl42TmPfauhEv<+n^J`@=*h@3w}X>p9OBUn1!X?~ zbsxDTkyDr+3jSd<0bt=8$@yC`PJVEhL3Q2;&*O2D?XJVy_~FzFUQ)a+K%u?)t`Q!L z_mS@MxLRB_%krj;*$jbg-hL)FG$P&5-X7}}btzWxIxeGtN0>EWMHZ+PuB=02&pyNo z=s_r3E7F0{*>W&;q)SB>hp3zZ{mmx8gT}{i)JZn-Lw|Gu;PNsve2qY1w)P(i?eI&_CeaXbxwo0!}EY#`B^T;PytgNn6MQkklv zL6Tl_7_IuT&LJj}Sp?rpm^!*-HEt+1!?wv2$LIGXCL@)=6>y4)(MDYHrzYejxQQ$P8T8zqzeIuqtI>CJTHy=+r3C*{($Il z83+YUWDIxk?n*#L%ZwNJxz=*p#+d{F@I0n0h>wToZR%n-`@+= z^6$Cesbjq2=E{YNrgNfgcc0ue3t?J?dtd_!Q+HYq)xhPYM_+d}RZ=D`sm?9LIiH!qlzC2+-7d-A2WBKERZMh zY#VSWMx~J_37W+u07bH9qvks{f!5e(+ZioRH3bV()m6>dFm0(Yc;0N+IIu?;OTVzC z6eOCGDyx2iTX^;9egFp?*$rzs_Kmp0llX}_&AHw%Vw;`J*dbd0o; zz#4EHT`DtG^(yVd+v7m`3?iR)UJGg+(`cT1U-)>zY={s zEdBksW_SRVhzu`zXO9CHD$)MWB{m%6zZSG3)C?aS?F?O&#^NpBKsuN)BgoqUaa$9)UU(Tx2a*AF$(4o|S+x98epYelOM zg^vo5k8f~@rr5O;hxNDuqxQ%E@25s2%}(%XC{Lh=<%j%e+j*ZLbMUo*8D8|C{Fy&b zpV6^LZ(|U07p`j7hyR|$`bBSDh|v3KOl@VYX5Bdwxd_$c^5@QYzq*piaTP7jQL-i& z4hx4WYef?6b7a0f`um}5HIj@qu^1t35w2z3)kL;NUqz_xN-(C`Z(ZacpV{Uw-cm9q z*n_q%u%sm`^>GFsL2X*E75_H+2WoZ6c!(aMKIvy%KM3s4FEV((S?@C3OsPLR`!>U` ze-lNZNdDQiLAJ=ZMV2-wG~>*)m~_&d^%swl@>Atm!XfvK=0RW#l$lPb7(S`7MWqyB zd-x;Ph?N9Jza{D~-mBAJADbJ6c4hJp-z^YHcxJ3g-)~%*9C0>wwP_JR^}iECXKPPF z+^vK2BCjd6FW#7ru}AOu*Kh50a)Sr-3`%?g9IiQ+ALm_`z8IZpN459!RD*-z&oJiA zVjwGzUH{ud{>M7)^ee~0)0!HiK_~Y-%9hLJcgjvmX}#o{~n?gmeJn>M?6EIdZW1Pt32 zyX-)2ZodgZe^X|mae`?8hv*q`2=~VFm7=Jb2MJrpQVo3swoQ0ai{$th)_JpP zimyX*bq^(COrGczDSd6qQaqA+#*n(t8*;8&!ugOiZ2bN$h#AM)|CJ-~bvm?_vo=CR zs=h{ie;jmD6f0W4$+jI&$FKmQ1SGU=@hkH_MWq{&MBo>n^U{gB8-NRr>n8DdFq3PY z>qtZ_Zr9N3d%yO}RXq%LJv>9BY)rm3P@`DA2}Qr1t0_(I6b_VfVOW)A_sWH+I#bO* z^}>3>CG0y{=VVw)VMS^Si7(eX54FE<*xv}Jsz_c=k6^{09#==b6ob(D2D{YBD)_s! z$u>yL*=B9k>=&dSneczj>c+Onk@=vXdasFQykB~}W_m9hb!<${DPu{Zr%jl@-4>_Y zv4HYiTao-0xxKS;-cAniWHrScM(TLoQkZYF6Q?W=3qm$|0h1jWsc+eW$N2_#-W6YC^PC0|21!8^B43E zHc`@bIri!o`G?CL=xlacc>XiExfOqYnCQqpt)KE~z8(*^i3|+g zKJI}oIP$P4KLCxjO^K6k5<3_Vycx$^t9c;{t)(l63AFoLsN`-ah^APDGW^xayz=9) zZoULLZ;%wRt*_;8mThP8w*H=gt{GF(=lG+!nXtOmWFLaX_vunisOxelrqWukY~y)u z+j*&Cy+o+{cra&m?$fbZz7Ta;S;s)*rCeb8TE2n^vjR#FbHEkl-GA}6%Xn~R@8fF< z5yUfTYAH{sFx-7^p`=ld9yXMgf@JI5D73seSQhj)xnNk)NzSWAnu0etr_LaI#ii6F{LVYJ}HvezoqZHMRA(ub|^r%NFmyUSncduD(9!JKfIp z+}#!;0V$uOH1s1t+wdqLU3`UNmv0ke@rkdu2TjJOT|n!!(WI|#!r;*y&6I};Szkig z_MAHeE7~k!F1$=Wjkd4ho8e169>`(a&}xp58SdhgUPdA~Q|1mf-8PMcT{j&o{@N|L zr>C~3Tz2>U81ZUZRZ<}Y%|D6UR5@R|@We=dfQG%L2eJ7_qB--cR@UMT1J@2)8$fm) zI2z$_A3LnJw9kaT7GpwjZClHVmC8$_{;4moC>d-e;`+$yg#D}eTc|YR^E^SVEEAOm zrdZl3*!JSP8su96mnhMXDGyFKTkySIwOr5$i`G~MWG13_4$=lQ$=%w*dypw!mZcL(%Rar(HZjMmm)HVT5UxPuf%&SloD z_=1G&>odAX$v}vyQu@ z*?Hs1#=d&0NVd5&;`M$qnNbikRZ191%KP~Y=gFu5_zXhehOSfW^MV)2aj7I3sHi(E zqqb3!47Ntn30|knI>ZyO0x2twn;Re7I8fX`=~YsML}<$4wS?Jz-I(O=?&|Akn?cKI z#Rwqj$`^&7s81S=`{D(etG`TWZtvVue~U`Ir|Uxs+q3W#ope{|5qlb$(!9)11L;9!Ny=0$W* z3Q)d5+&Bm&A=-GeFq3~k#L2@gI^1%FCL=2&!q(tVAh1jto&%AHPh_k>i^Pm98UNyr z>6fkoTA;%MkMVJRqDOZFXVjgAFW*}(a`pbr%tP(j3x-hKe1wIl zuyv4|RnN}KW+H)No_FqcvzQL4LPSAZ>qE&_#1keNHG=G=OvNGC+mZb=pq5;Zh@Htd z!5i@+3H?a+*dHL@a^OKqa+39+W4CC)Kg5eSCTi*bz*gy4UOfWMsF8T9aGz zaAGcC92J;MrCu)}AiCqvdU1+kkH$YJpYWL)NhAq5aZmq^M2pKHU^#RZ3{Js4kB$7H z{u*@|`<1H^%HD6o{@-9|Lnie^=yfx1zo*{L*upW2Z$(zyW9K>vs5au>J4`_Xz8$#f z7HHD{g(Ti*+kD>uXQ4~Ym>wY*iL)H5YMF)BQXg;WmXUj^WC4r#cH9x>nommRJe3bi zoH>B^q#R`u;i@ylnzO3T7f~__94LC3w|pTvI*pfVTx5GeChiX#EP~f8Un58PshAUT zkT|$P#vmAaPqokw`b97#>nHen)mMpp{oH1CM2Ee!WMO#(p5y&l*HxI4)4@X7NDw#{ zzF+GrESStPf})s+Z~19o%Y_k1DF&)N{$Lon5l#hrX7&?bHK5k!@788@WENAX zdP44!!LpQ~1`*qzyJg)b3_(Npl&-uWylh%0oN^cb!ZDoy`5lE}SLoREE-gXd1o@xu zUlj&6{rI!x>Z93KAb}Wg;OB_1`2VTz&gS7c2$l8|b8{JvO;sCZXnLTzY!%E6{shgOy> z3=D{B(GC#ZBin}#4LHW0M%nx@a;jCkdb6M(ea-K9lO7|FT|x)UFyvm6wB{5PICBMb zCu;oy(WQ8?b>sekhww*=QCQKy-epS^J+W?dM0Up_?$2#9(CUyk689SiEc33m-=8rw zXI*{QJy^_bvRKTC9jxB#*g&7qH47mZ+aD490EaNp&d*oK1FWZO?<^K@_@*P6#uQKMPj)!;te3G&}Vm7fn3q@?y0escUKnbv^;WV z730hDFy9JYGG)z%^?gSNoA!h8AA|(lb~hx3qfoyj<3=9^qi63Ya*x4qAEs`>D_lgm zgD2x5%I%#CY_wNH%JJ~FgNcNofQLpsOvouDG<%B~irh!klFbeF;8iIQ$_xZ?k+pH> z5NF66{-KD{^mEv84OTZsd&KRK@WiZBP!Sf6h^p39n=08-2nQoW1#N?$Q}i~nCjGxX zrPK}G@$4vw!sV)R6d?|pBq3jVdN@zMFh;hwM@sx+Lv^A1QD6k*^YB@U$e@G@BOXqG zIQXtmW_3h@_eiYAC_*FzO9~R-ktW?|sA)tEI-n@6De_gO&8h;AemGYOuJXS-YuK9- zlyI*q)k?^r-ylO^Kqz0TgfZO*5O6FU)6AH;e81abR@$?sXO{X)afsM67ltUZt-K@W zw;z+3F+|GJ@{U?V9P6VoFyLnmu;|Uwhi`8M*vlLq14O&N8Cew81r^+~1_;_k6Pisg;znP{kpjfSN~l6BqbSp7R-qyn6jl@3{3f80CKqB3pj2G zOYScKD-_iDvRaTTFU|y_P$8hHBx968&sxVjO+f4*9P* z{cucozeedtc92a}z5rUTl70?3oHQ9?M(u0qwAsiDf?#jphi+2kG9iSLZqj87Bo{W# z6r2|3>pjVZf0kQA=JR(AZO5RfjGrvjAw+nktU*4a!asXfE}RUPq2yUK?nce_Em`e^ zyXa&abV1st(j`*YMN;zYmfq(ZZ+?Xr+R+ZPxx`ZU5>+(kd#}oPvm=W~nS26D+EXFs z>bnx{f!tU7NAX}yq)Sqab^0@$7}XLg8n_~f$0fs$NBWW{=iy-QDkX#-7>ySw3wt(( zh&&CP$xrol{Em{1OO|n`1020Fv~uVyVE5=olwI#;Wo?%3LFG7Ls9{S{!B_V{2t1-Q4Gn_~xo8pX z87eO68iK)`kREhWZdm4EgU#JiR%{HUMR+azEx2ivy3(!9PKr_;Ee{k`C^M-*r7NS` z0FZ??rfkt16#gK)YV5ndI6d2Yno#$D&vuy*uLM={cYlSgaYFdMJ*|Hm;cvC1&SgtCQ?ARB#FI0VGvA-#Zczcltv2FNsx3`ygZ?MU4pT< zGDoASOE&`W9S(LPEb5^7#19*QuDB!Lkn@M%z+28EjNmVr z&A-{Qlfa=jSKi!aG5GGn33I9OYA2LP?LGNfWtN^V}4oxtE)iLGYkw4zYBQiD|E%62DJ&HT(7hu@9CTdB@u;VNEYOcN9trDM&Uwh=_J=$1Gs7#krkDSU3&D<4v zy+yWU$6CG)moQ#9h=Qt|oc7g|YP&wwiR-LjNebdfs6=Qq(NrbKH3%TT3*42@g#W32 zIO-wM_~A3UGG+@tYiyM?D;xMHrLKe=i`f)g+#{x`1CMqY*K6?)H<*8(J<}t`tP_a9 z%M?qGtk?S{|EHf|b&WRJcl)EJ!vyi)DPU;Pc;_mpIsQU2T=sSo6E5kXIPpVM8Qxan zH!;8^K7&?~KAE!{Hel=PW~_|Cr5eEPG7p>|9W3DnNX=_Z7rg@nvx5L{W{Wn((JL@_ z9NIB+7krwV*hWWKWS}Rz?CSi_Zvg*9!}}qDAiW~y1U98eVnBs3OUVp{3Lrp_!=Vyd zj611gX&yjPJ4g#F46NZ{f05<(7LHMfJlXK7$Q{#aqX^3Yv+`LL_3)Fq@o>;e93M9-sC@Qrqvn8_2yN*)tlvKhY7J+5XZs^Ek3N*t9xe4{3IQCK}T z*aKR17*DY|fDK-Q%qcznTFcw-T;y6S!AE^@Yvr{L_oAA>X{Fgn@h;9Y`Ak z;SuX0#LauO>x(CTL6_=45wYpBmp*5*DtK67TH7l6_!ZG5Y!eEN&v9tJO;Ult%kGoV zu?f8;x*6cPn&$j7d0Hg)%K*Y=x`weXcQV=VxY(z~^a4v0ux-oNG}DAx9#`|B+H6(+D*QIw6XVZUAc4y@QczZK9dwfBFKh~cWEn{2PR(wH4*=WYqw z&!Cg~NlEP4DnaBqz_Cb#>AxL1i_=uasr;clw#cSh^x)x={4lBpdn+=6qk2jrl-A|E z6W0LO5fHASTuIT9?USZQR|RtJzmdTfEl zSh?AT1COwy(xtx;65AK!u&^&vLrn^}k}lx+ER{0$Pa@KdK987Cn<3_IrRJ#a%IF%) zl7+IXMxA6D$++!_*`Hi)(~yAye2&o*)vc7gY(NC~YW5riC>2(;b4)1u!1jfQn-uMzwyhhTw4^y13O#+pCQr9FJC{Ye?SA5*zhg-=q)J# z<1g8t?ceOz#46q9>ZTn)I>>=k$Y(H;CwBfOPbh#M1fD}IcD6gK$g!;X1}5-K)r;h; zUg#u-UCrgpW3%w9yDY0a7v#xnbz(&X%yE0`pWg4fnMxM$M{girYK=hf^tIeX1Xg4@ z-jilFBsH*rQAEJG=58G_lC@m~_%Nfzc1QS1sx^kz#tAWlUIQBH9R8t)Hv;Q4??b3p zLKFo}%PW9>{Di!3P6SF=qX}uPkCzt=-9Iwr79st!DHKD#Z%+M=T=rHRI)|>H+UB~g zAQ);ImvUO$g?g5-iXief+n5;^Cq} zlgo|+LV5eSSrDBUBp6Tu@pY7R2td)yk84Xx`TJGCrfP=#JFdy_?mfYVPLhrA+HmIO zCen|%l3x0stZfz|a2s7YqOKw$30L3XaHqv{xFWT?emsf}*tA?DUb>>nWbeS=7Uu=Xf0-nI=Gi~%Y+|1H| z06}yjMLN+bzu3pLvFza6?kfnNc#tBlB|W?&%(Mvwvf07;v!RoOA*G55G3kk*kf9)7 zDL|s2yb)erQ`Yt z4$6jEh7U_8z2f4n((dyQ5ui!HLAxb+Tn-V?MAan=#}iYN3@$`Zi5cunh$j5NUHKuC zw&Vw4`}XqZf*>{H!BE`ZsnW#G2z)O-GmtVV&U-MU9vovS1OhQa__CY5eom}*HI5+mG#3mA)!gQLPXT}< zv;!*}V}t@hpxVqQ6RC5Pr5Kk1N!`dZW2kT9MXJ;4Y6n|@_ZB33baJ?_XHBy z8eFavY)d>SNRLnqE^6lLVs_c$Ky8(2NKe+hrW^-*;wHm{=cT-lPnK&?e3gOu*N_M} zY(y@p5Z9D9CJdN|3xu-{NLpDePTD8Ym+VzS9uk$c^|4zOuV>y}eO7*(#hDTqj>^qY zC&y#QVoP59!9~>&VymKTtjksF8d2>^Vr#kY@nod1d_94nND6Y9#h4)C>TN=1 zOkq$nmKwo=&QduCco<*O?xFp+(R{+S6nQ+QJD9J~4hflHmBMDJZz!!p1c?R8Bh8*F ze_U6~ag0VDTO-M^@_^0e&5bXjJeedwKF3%jY&)numWLuyi*uY3Pn`&Jq#|ID#-fsm zz38GtxS;Q{NC_xM?&h8O&KmI)9N|ijsK@)5AQi#xIcGvV>S!$tN8iTbyMqCWDNIE> z%1qSkJJfKrs*E#{*?9waw^$D3f7(qzK6xZy9=J!)z{+u@XFeIcn1s9p7n-HELa_sW zL32SIXu*i=sZ054qU2bvO%0~s{q&Jo7kdco6X5~Sc4N=Q2URz|oyE~Z=|hN^-u-3q zd^KwQFcYjzW;5sBwNe9NZtzZ9ocQj#K_xB_i!8aF0&5uY{ASeQ{~@{JIKYDz?OxIQ?|H(t&u5!mx7umRvF9nX__WPvv!gm znxyz!=CKbS%CNN9%2Bhm~)bVmi#;DH!)}{snAwyMk`*M;3jzB=m;-+ce_o>_3)9Ln0*}ZI(?6`cpYeL$Yc%J9$&puz0>_6$|}|Qa2;Z%LkG$i zVSpw{B72A&O^OI2M$v2D`N?(`$$Oks+#Sr;=nEeEYqenhiWQ)EjDj3a_2VkK^K@Ij#UE(=r7TLs10Uog+2ybpxt~+!0EfFC_g(i)z?N5Rb@2|?i%@jTk_dibW zTvYGr|KbYm$`dAMT9P`(%YF;6kRL{_RawN!GvKz;vtfUV6YC|fa{M9`Q@TpO(b(XK zNPH>lbk!@P6K|t#4N~Vb>Yr!?zh;u9+D;PcYw2^8suy)z1ZKdSq~-_^0pG~rk2_Up zAy}h=3z=ETOB2|D$0MHJj7K}K4ih5HV7vgJ${B=>9P-AhWR}oD?Pi`*p1D0*n$%Z3 zS-7wUQbDl86-ZY&DzC*oLk1fakx?VT7xy^CEIDA$zd}M!zYW&x22&N^r7l74zHRX&qXd@Pq-Al2!1q$|7BXFW(_>6LA^xTBb@yrEs1R4h7nf!te7=7It?EskXwX1CaN`6cOlsKJ4>Q$Lyfp z3B$wcQ29(jS0~!|1?SB`i8a&7>q#&7n2Lfgzg1wcxHIR-XuS^ER4A+*5mJcNZ4~-n z1yvkZ{3;dX^L*|fuPPySkLq$60`Mwd-oPrS9ANglj=~4=xMDrqd=GR53%U~e+r*5e zMVl}F<5w^ypy@QuP}|;-Ha*Fd@h$uiZ_X{PEzq_8$IbpnNY}dyBm_$!eE7Rap^2j-!!C00gxEnE zC3>iL7AFN@m7C*gtuvBy<(`ar2Q|Pl#$Mq?x-HF(1Rf{Sudz{LY&SA%rT|0b8)_B0 zVA)O-aLQWJR9RdjAgcnOh>?TL_%DDz^|kT*tOyc&aC7IQc3N1)enU?*F#yNi9mclu>wf)9>m^btoeu!dU?fI*TTZ`rV- zUUnu~HO9y10@bJaloqu)68TkO;*?;+EQmF6q6tyxj)ZLKSwclQj!qxySPzm3c6Rjl zC3$jE^Cs*~CjkrYK7hCTQpc5;yDtQSNea7-~SHmvf8IN2}{hg}uk`O5G& zMB(Yu*EMa4PM}E49S!h$VMGW+&wS0IRuP5MSZP9RFl%lwXhi-wqIPb71b@j!LDil zc4TB$`4N(kgQ?Ik&gOP{3ku~}6-bo531DAZt=w_uzzhKevM9Twg)~e)8bgu) zyg{5+cB06daP^U}_HQKlzlH&?J~8YUs|BGEU22{}nTEjD$rF?)(-|&i_Tu6k*)1%h?%v^&*Fgq5{qw{Bb&7c4uG2zDLuA+y@l>N3ezB= z80thl|5UagWWZul5|PkZdujB%MwD7E^fM78FQYy6 z_wY*Q$G)pK3Ih7489b`ubnw!-(E|*=DjQR8Im@e}(`fTy1Ood@JC}?R!Kn-Vx`lBV zKLn>r`{+i@+PicWc#A?SoK3S@)sKYexJKRm1DgpZDGc`g?ob?m>BGcII z)47QS&JJLwZ56v#YO`i44|Y$u-#<*_=ZvL6t71p7&F|)^f{FKD zl!vLrWAPBtzq{RNNmWoa^MQ7%5>(4XD6-lANgeir|K#8Lh33qt%rvSjhI+i%;ec~b z+#WixuXlxS$;LKbs(Ri~`O5WoAxgf@n*Nt$XR736Rg;@Fd3A@0<^xSiZrEHyXS`6X z-2Gwh8Il+*dDdMw=364f0p%HDgb26tHaq}{8kxE>o^}9Yfb0MZ{mR$Sc=>1K77vB* z#}QY03ZoN1(Jo((E;U60$rc=c@5=Rd^Eg>?j15Wfl^|jx8;XMNPD|n#A`v@&$4Aiq zC>zU$UN`gKKi;3TpP!!(clcDv`?LRVIh&T|z&V>ZnVH%CudTNenQN8%&5^$^Pk%hP z___W{LPUfvF1;9af&RJ&!7SwmfkvG92qRuk&cGn^>-tcO;Ctj~rP^gQrsb(%SngR! z$>*EN>F54}&)f6m-;d`o={Ohdo+{AuUD1}$TV4`9mt9xe=iA702I70?do~F4afm|n zs_*;0R<5;%8#?CFtFR$n1t4@Adlq@^9_+y?)o{e{_IjP zt(nnsqejtwX4rzLan)Tj|WWJ;GTOwTQ`dYnZc8+ojT-1oH| zjfG4_S;?ucBPg>i{FLmn6p(&pu4NHPrD;qoXsGkTfoo6VtE)3#PVmI>!9Ns6yYYuXKi0D|0 z60T&Au5I{S?bk{sZKPhJZewg((9i%mGj1zumO0U-<5*L98JSO6G!)jBRQwh$WLJk; z%nfU(6w^_qSAEC;f7F#K5cL1o?lt&d<^QWYt6`xbrfee5=Ddr&X0af&VzgnjZjrm8 zbc@^X4+QA%s8%B7gp1kyf8SO+)wIskN-UdL@H6(xTu!JMEf}TWZvj{RGVy}##=h;m zqGw8-j&rK@Fg}@8v*Zch8g`;Jyl|k{_@JMzajMj>wy(ASUmXj!1l_k-PdbaGyq1+L zdHmoGs@Iy*I-M`ov8C6~##=k>FSG%-8`Nl>v1Ub;zg4cvY!1bre6Ctpn_5$8I(2r2 z<5kfFe$vYSkF2+hs^baXgmIUP1b5c}!QCxDaCdiiy|@zy1b26LclY4#?(Xp3-~Zh` zd-m+7>FFNn>8h@Js;0XtM8}rM)cUJ2qVc=9jcQi8jb$DW=$jngCVwW^Lsy4r7dH2$ zwthEN_jpaIJoMg~*Gm@Z5-IL${MsEbn-=G6^u)Z(QgqvY)u{gnPx{=ljrZFoVRtW? zKH1<(20ld`-ahVc4p_+2JeZdNPp7XR6tQj>{X{T*N3Wp{q4>v zJCCo+e9e*z*e610$vFAI?3UtlE=3U#=#cV42JXnbJ?~!AooA-RV-q{^v=*q@g`+** zQdciTHcrAUB*1b(X*?N>8I@HxSXnU#9JGbK2E4Vr=6T(M4L=loEp@gk!D1$KNHnIV zZZB4p&B8%8g?G8ZSjMzb>+d|zQyOy6*p<3PwOttogX7PCU$6dt+7$-A*>W9bNMuXdRWh3;Q z-)d*(IYz=O!Anqlr7>Rpr5B{6Ghw}$#>G~(sP1YQFZQauQf`-%y6XM?o%5UW!jsz< z@5hr>h~&yrLiE_174}>Gw)n+DgzIe~@VG-$<2J&jg~9THh@gV|IfcXLn_GgMLZ-yq ze&(+)P}gE}%i;*Rq#PY=bO#psx<;-4NJF3XhK}|5f2OL0Z=PoPgm?nQb;wUqPOq>N z8L4X4u|^j|RYv}(@V_9~&%sawdD!wyT%&qV*V`S+=H* zU+%N__SNW<`4zg1$Kka#`?{A7Yzy&?k`UTxu=d~MzWEKyg_n!`SWnZynb`;_#93b1 z-mXNRYyWEX#jw=)*HS4bD^m*0#^5TdXEq2kNje?Iclg!cTPtVZTwBqMKkBgvRb^Rw zcA8PfL5{Qx%HDh2dE1NamcB5u<@dvsb_IXt#L%#Hkqz46kbpdp&(ptu)l2e}J*ERo zpi?0VG;mK3lhD>G)xN>GvlZ~AF`!WUa|_G(9rIA4J;#UHCPx2U7 zv(h$-8vR3qTXyje2W%mB_hTmpL`X01GB1&2WA5h;O!8aC^c)S{z}2Llo0Jgn5AsT5 z=o&-=jUvKL0l}rQB{W@g5V_c<8z0&1PC!KA-0052N>`#sjD@BpziE1c6(h!ySu;#q zl{0A7{VNkd&{4^w2!!6>5{tI}24VlFhB?RENv29PsEj+>fjHqQG3jvO`7v|fx9R7F zDgD=KSK{=Hd%VvFfSfP1zGhu*RK3_MWY__vNq=7+rE!%ObK!|406Y^?6<_aZXS+*? zQLDsWM9DRvLYaN)4>X(n!VYEo36W1oGtunB1GN>cli|Wc7jVvKtjcVezbLeYpC=Q~ zWJ|oEZl^s0d5Atq!c*f~3x$goRCpd2$ZcHUSZwH44!c)fq;>7RFVt4A8Kpple9UQ8 z@K`Md&*JNe|8?SzDBx(WDYUnbiQ$eV(N^%CB6+X?!fyH+^li1S5T|?`fSPMmp2GGt zF|E1j(K0>Y7gW+3iB?(!UU}UooS=&!6NPZ6Aw@G-me4J;0iu=UwcZa@;L3xbSAX6q z^4W9UetfSSBvH~DdFm-F7or_r4fF1%E9n%&U`vG;IR=Q+7Ea&()}GKJ+RNB<>iP%_ z62fC~x6SZ;)S<<2?ilu9m3o;%$8Z|%Og3JOYxe<3rl~6YgriK2;Oq^|Ls!z77mM?0 z8HY?9*8YZ3HeFq}JsSwmu`{!>q~MwM4K22-6>fUJA-MHzzW95N;lbV1kd)B z+@KMXYiig98ILr7C z$Qk%=0$%fZ+&G=733^ES%3D2OL$Cy3qtN;1KjGuD5QiJXZMMVTr}*h|g=L+u+!z3l zbSy`21HPeQx?^0KHz~ns&lqiu%_f>C#`y?aDUG(#@=7YJ7#u=MCWgP!l9;HrNQQUf zu46SDTYGasJ(?uO*FVA%D)u0V4X_}xX! zZjz@H7AFFDBBHiR1>LW|xL+meK2nSuUeL;pmb%`KBLrDfGjNYwwJ2kXY=GL|yDMJ> zuaQaiH#-cxQ{BmUHd7P}h2P=x1gWTn1G7E|cIK{T9i_K2O&S^2-cbKvgg6HJ=|s)n zf>#(S5Ff%tGSg#a!EPZGr^wL&A58aE%dFV?{247Q>9LvN(nAK{#O1&|br#IZ7P$fr zyq2C+hpk~@qHC^e5pFJC@B!7bY`yo62ho@Nwaf;wLVw<`H~C@RQFS`Z7okj79TXma zg4j^-h>~J{VR!k^1cKa%fdbOaRTF2%hkZ#Eb$b+Y;vv)zFRhzN1*!trEX&PE={3)2 zY}i_<#4_&Oz;?Y&&#M{Qax|`V-D;I3`F_v*(nyT$5o{TyKIw#*t$8)wFtx*GjHu=7)Hi}mdZ*LyLZ|gd)HtLmV3 z4wH12eeOVp;c*Lgl^%6l-0ly%w%+5vSvA#$#D#Qwoxhc^M8f0K<^>7aHXJOk?#WeA z%<;7+w;&40g#L}Sw%QQ@{$c5y@2~yBH(^tHGvH4a8=({{c6?M2$opj9qVeV=;AkYwZtfWGH!#=ZTb zjyaP~MkUw#i0rW}7}ITgNtYV7?8Yp>K*eig`2dr&Mw)gSl9#T=XM-_0c_3eW49CX$ z--pVb)j;#{1E>2pDA!(t{qi2Q>EARv27LJZ$t)I2-Uwi@YQ~ya8jQeS_xSxTdo668Kvsu#Q|YjApfzaT_fKU&H7NW$Dj&pB^_XalU+g z07-&4HWoo<5#%)NR*w@tRB;OOw4xzV6yy_%Jhe9@Bu@flP*K8xp$B6Pd}MXU9cbvT$xsmOiKo6p~SwlFc;zT7L{U=Y)!Cwp+ zw|C?rq&OL^iBlsZo#rZo@+kSw))CpFH{B?qHx(Xn+;t19V>ZT&Xw%7EN_`?7pl?o% zwMlDaDCGVV4r4o$4CQjG`x4MgFU?`!+$=-;b$<;nmfdw4V9-oiAq#T5=D_ z{#L@k&@9R3Dix#n^bx}xLiDf+Zvp)`L$}sw6a=yUrf_>QU?zn%>)muDQ1H@u!O2D% z2ZF{btbmJZq(4yT9dfF16=fm-#QHqu;)g$oHoIQ3K)-a|V>&cOy*w>ai3y0pJt4<0 zgimH~RJB9-ALT4IuCYA{Egm?7z=69UX834&M?BowH@ul>fX|WEV`*C%g@U=S+K|Xy zX*?Z;^f|{0HiT;VrjlXimo~AsD3?yN(MF3Xvnd*;dR9cRo-oc|rHOI5dI2FyxQcmZ z0s0=%Yb<@q^!#1I_E39j?d>d(uE{)k2lH4>F+CzmbMP%0UH_Hb^9P9mh@_EMktPL$ z@~Bj8f(<}6C5Lq01<}1TpEfP=C(7fIOpDiQ+Vooq#jQ-*wpg>aCRV3>y zD5O36)YCg$_Thv4R7JJ+k&i1|oObVWC^|Ulmo=IW!m>6&iom9C{jp_wZ3WdN|t{T&~^q5a3n7?`>pQ&YE?q*~({R zSUv{XHdnYD%qxrEQTRABye&MC0i8G~p~F=^I-WQUi8vZU-aPwpJN!f_0$vmIl8m#Y zqu-fRAH0@QP4?;fE#cuM1g@T*2;vJcjqbNfEAFaBS5ahMhk(BCzp;^yDw+$I1^&+?9^&D9eRtHl!R*R&IQ@(c_F5dl`vlU$hOV zkMN6T*zQrQO(hXnOd>27E5ah{p|hnhIY><$ zWc#x~H6?Iabyvvohw8b!vOwtmHw~_an136T$xDG`n7|!zB_fF|*`xXy@@xi%6%tS) zJy-&~AA|k=Q>44ik=NIA(5l6>f-|3@Hwf6_Vc^;d=eXw(wai`(Iq;G5aTevO%2DtP zOWA6iJ1PZy44Gr@;QOL^CxUhcLiXC2qm&xUAL~O;wyR{-;wn1m9*~f)lCkDjhdagE zNYOsHB|t<5%mC#Yo!kGU&(G#P!X%ljuvya@s_?1)oi!*vh9$uTiC|c^dS>*F)ew(r zIP_hRBpIVdgoUpKg;2b82XB1Yg~#>)kxHq6)1w(1Rj`=zB;d>`pp4Q&dx!xvS#5P? z;bj8DNPj1GL`-3cFEbz}EH!t=xG7e6VATN;*Du?}o69xT>_R@8wC_Er5!>Bf4)%7f zCJ}Ou|B%O%LpX>SE;{k9=u2AJ;~9jbAip?TiYR#jaHB?I6Z& z8+DJq_4qXN`Bd}<^ZTY+XqLijGqwX>hF_-z1!p*V*;j%#!aX5Ji?gUA51=tE)G1#t}?tWMbJdF}oTAHj?LO%+zJiZH#0 z<`goB018T6uzE?(kU(zaA4i=VWU+Bqea+-JCA?$({&F-K@SU=eVTEt2xkxhDvp&AeE$k!6JdvzaRYwEof6pb|XY3@M=1__$GHazeHDxFuWj+I+a|{&46L z%B8C7N*?cIcBZbgeE20;w?HCD{}4*?>K^OtXc|N_C13`Ox^e+IxW@K#vaUz$Fm__J zm40r6lM*Gd4Wa~zPKU!^$?_I%Z%i`0aUoD8*M`UfC&-JZqu?%-H^cW7 zk&xAB%@qAyc%&&hC*bvez!&Th%+#$CRsryxfxS}Le99%_SSEKX9-`F6$gvO0?o010L353Z$2GP~M zxWynQthw6vLZAQfll&llQI1Rkt42s=-EORZeS!c7mTV&fEPH<+WMo+@X6&2n98Vbw zzmW+DQr-4E$MuzswDk5nrO&Wacnl$9sYS=EL3cd^y&w=F+sunK<+lxbmp!PN(;Jq3 z5=5*}VkNO>-sN?J?Yd(^D6ew+#rIYnuV473`qI*KgqpSbcKH934LH@QxX#S;FzEpG za{Z%}GEU|I@QqBWl#CGlmgq-78rxIE4YNU%7``iQU_KbEOn-a3e??ku9dnMm+N1)v z#vSmZI;}^G2*#z@u$#`&+R4O+sq8vJ4!Vp3uH-|$U0>b0 zWWM~WxC`Jc$5$Q-7#An!+MRiC(6GmABd@gRHX3!!}*4&?Z0{KwogDF(*nHWGVi7 z((5VB@oZtj0b|*`GQv?=@_}kGgt=>EA7` zCly1_xmEpav)B@!+2rd0?XiJaBX&?>zya}oN5KY+i(?>#qAdmvgIxU&k6HxO@e2UM z22u25I79Sd|4E=q`WtArRIjd^?^Gf`W1(y%93mc>>smNQV!ZMpEe8UB5cQ8IGw|W2 z+e0H^S4p?!-TY1BQCvAnvK$xqVP{)f{O@xs_OHr?xxB&Q)HI&4!4V7)N_p>u*+b*D zjJHBMthetn1V6ZK#^ReDJSt>U39HRIqv6gntInfkgb9~TpM_;I7QYHRu3-<%-xX?8 zhvCo=>W!~TfA&rN57sc?hL`PI(yBgYQ*Wqw+c_9N@KwF9g47 zD0p&^=JO~tA5(}_k(L~dX;?@QttUk@k+Mjqw@|U5yT=4_XpN@;&VTfJ- z%x&i%(d6l7bHboMm}j$UxNa3>+P^8TXCN8@zv)KTVGLh%cCs{;ED7Oi&pSBU%vSYy zPv<`JWK8FF)#+>uRHkiX5hdMI5`M?C&k8Ek9_@mSu@2Ps(5P~+v18dhBl0o*>Rj@I zQ$N%SE-CIrx>rF&9cPqnwY%{q*Yv3S;Z9GYurLc%>(`NCWWC}WQesYbLjSN9Q9ow@ zypwaos^+I^sgTN_>W_DyyCRthcB*AYmzoU;F5oim>G!|<3(k*wt)`FV*QVKM>Hyz| zA+Kvei+CzACEbHyebN8(qDM8B(BJ~OU(UeAuoeb|!oaYVFmG-j)p$qrD{0lw8kZhR zX)eTEt_KyQXGbG5vK3rU|ErqE z=l`P@pw5TZD?Rs!Q%e1Ba|567j~;j-`9FtJ^17w3PCqG}{$afv(KfC`;=cYsfg^u* zKR860k2or!qp<559eYr9?N@}KRC)On>W*P+i0l8~{9WiEESQDttod3LxM~c_gN7=z zDHo&)Y9#lQ!p^%D1;IJpgRq)wdeCX)8z~aJhA`-~W)amA0`v$FYv$aEYCIEyTC4uM zxF%u z`OPBY!(|f|ar|M?lNjlZ_{6t?LX+nzDC7W3&5M|T;ZeZrCr9EF%cbKd)uyC;R>3Xk z?pr&&iaP-=oLhl3K;~0#pZ_K3jv#%|sY1vT3y>O|{hgyl^VG{H4mcZM=#e(YJ3B2uls_S%t!BI*XA+G5OB#Y zpR5VLap@~_)4=CSPsPWSDKZS&SLeTDNFk{1zw-mH@($tOAM*Dwd-UFlpbpeb;hPwi za^mQ(L`8mOb(TDj>0yG1I0GuY zytUn=nn$}7wnj7=5Dpd6jplDy^REOK`L4cNckMtMLOH1d`k&kQ>>wH7%~qDm4;!V9 znFiKo@wsvZnI!?u32Ay$%g$Qk);jg{ zfzi(uUdc-MRhq0G>M*E~Y4-37GZO|3I>ib@yzABs}r>h%KNoSczs{DCG?6A)H z6f<{o4tANaS0w*IEmuH4t7#4M@>`+QraGaJiafEQ&{csn)@0uiAK{~UYtE|A$>z_+ z-t_)Gzm?6$337e&m2oe>Y2%Qmx{`>plXG2F$Jb`E>9vhtMia`}JQBp@gO0{Sa z=k-Yt*!IbkrI|GWgI|zqaITDU#z3jX(Y4M@1!JT?hE z&Zj7b(qc#*L?Gku5bzE4)l6w30!FT9jUdjq)y3LPoT_nwT|B!W(u|9!u!E)*7*Vb@ zY($y*cUSO-{xRqc>;nxUYpt3l3lVRSkR)G*Q)hBFT$#B?)i$o&+TzWJXyZ~<0YgRH z90Iq_gV506iL!-oQ3MA8NNwP^Z#}iECH}>@0S@}uS* zMyMaz8k-PoNw+{*+mRhf8Pr`~OfOkra0rx3O6-W8f*A~W~{3QOP@5udsqJ{lWu&`u-J4DoEn|r{IWMUU&)MUUQ z9DQ<3HKHC0J156?PIeMjZqD!QBP~e-*wc<2EhnO$!d51Pw+8>{}X&HIgZJGn?8g?We4Dtub$rm^*YwAMkARmK7jTfaSHtR+|9Z|gS4;-YS zK_83Pucgq>pM!qyJ4{=jua!w+#?67!=IIv>(46LjZsA z;p~m+{(;!<^D#a9KJ11rROIU*Hv8*-(kDJbLFDxrw8SCa?S4A@>uqnVf#YUN(C;(b zUNhAonm;kD^4(pK)j&?MX&{4`1h`5_^093-cz(`N<`h>&{P(WV?~lbnd?owY(qmtq zuf9gNrGQSqjGDVCN4gr;xS~5#x&O53Qk%PN3QlYtkML0+!t%GgO`oL1J?l{d)p77A z6{z;xb<@0iP#R?sb;OQtz_rq1o2;q(!0Fg`*Q-^F&MMR9hEoJ#dx7z>8(<^86+d=v z72nw7MTX5r_1jkOe0OE)^1Lk~vG<6ZH}%|;#Z}5&5>nD9*K0z<Jlai0h zI@)U@p{n2eEag0+-PYOo6v!v{lx?OuXkw>nat3UO{apKd?5+-b--X7-(@GTcCDb|n zW_4Fv$@anh<7;hvWCCmvznqOw`4eMZHsPSC&bWc#Z`2UC=J<4CbEf3plVR~>lhRrC z`s96$I%%1SZFHXALn7{dxYle|WL@ep9sX+Jkcx2bM*;Bc>fz~y2>7kqC6X$_YhK-K zCXeC(`9XK_*4Y&Orh&Z5#`jHg3HAb4=B$4qyW95bv-TtXcz@z^LrV|1=p<=9t{UB8 ztfKQVcVA*OMt6W{o=vllVz%|r7}&)RO8pfP!gu5IWo-TSdEZtn5|mq*9}_jBKCRRLcxdB*kWqM~z0cu$)gjunSm-{|`Fc)R_vqIx z+|~Gmt(gam@02~?Rb&4lADwQ+%C}b{q0W2sGpX@KhnpbX`Y^+WWM%FL>v}p)1t`fXRP9%onSJCbJa_1Bs)=^3wS=swcRLYQsGri2kQ|euP zfF#o&5(85hIU{r_K+a{u`uu6JR}9r}I;)QA2^?48BHgUcH^p(?134=Tyxd{OGn9)N zm+HXApUFL#c?uhzR!}@Wos5cNF*pys;GZPO$Xu4wN%n7x# z_mXfQxm6ZL+lUBlm*Hspq_bA|=%;rqVKGT9c`cYhv^X7ABuJ;%BneCMC%|qdUsN>s zA7dswX8fd0$3#{E6Jg|5qJ6{|)9DG7)qOA!$?L60!_@Vc^t8_|KLo2q8_&z-!?sf{ zz7|8iE)_VMtePXmz&;<(9W;sIk~V&&$RkH)qs&&bJON{ag%5Xm$1t&jgel0N&^3$b z;w15TU3{`g(80;1hKQ@d-vT60@Vw64{7yee*Fw&em8J$~>A@?B`NRS82Leu{7W;v) z0`TDmB4m})=Gfl<0@#{*&)_#GSZ`Vyvs_3Z(rm^?nCH_Fg{BCUv3qK&i8DOUR~BVs zlZ|3sR$!?M9&;9xz2^(>y0~vv5s7(MD1)7VQt&9Q*ztL9{}co%!FQMd*f9vBNwdB} zU{1M)_csST$Ju0h&1vy@(B?@fE%-nHI9k2pkXL=fxL4eGt0!rmsU5h=R3;_V{;ej> zh$#d-$3-uM@EXzIwX5O{!Us#sqBn%j-Q9z~o^5$J<`4fky1;j;h4djn>(`lV_lWlU z$e6_5!6#tS_&*;}LW8$+F5(N^A^WK9YO2yqD&evC;o9zn@NPrux8XBUE(?LCj*w(I zhRkDgiN2-e(>MZ1o)G0gmf8D(+@A^%WH~B7=n^v)7kyy^pUs8J0XN#8zkaXIw&qA$ z>4C#!*C|rJMiN@-LX#}v-@IJ+hpi)ajh)7k59MuCO4veB@L4y`1okY+mJ~Q{LpF0N zs{9O)u-9)6aOJFlX?tJI24Dj5hQ&`)-@r;mYRce+AKDg@6Ix3-MFz~WjN=*#C>iIp zlw_|4GD+{qgK*FJ*&1wpeu~rS8(^Xs^C%os9gU~DhQI#Hy{3g{uT@A6eyFTLScPJs zbtGzQOs8Bk;@P&^vUuxu$Z0^4h?(43k!t?NVdCm(Hyh3 zZiehtGBL0FMBlK~PDJiM0>Z;(Yy286v(eaHBOHn!IxjN~CGObMn{U%cmX#ZkNxy*+ zW5(^JUxg4|g9DeUN4)^9K&1T!JnI&xSJ4O8&p!}}2@PQWjkU9Ua>sFK1&2XM{3%#7 zymwO6?g4NI_>_5xDjV;nS*!=W&z&x6Hjw@yG3j=>eZUFij!f!8zgs16B~d7Y+v=qp z1pgN(H~&`Kb!mD-p@ny%j0);^=gfd5XG7&T|7EAPs%+iI%@JUI5akPBagEpjK0p91 z=z%V{&duwd!7ElJztX8VzB`qg)z$(qUtL4gJ4H0Hj+U`cI6e>(JZ}l(ekTs6!UYge(t z*#!+;Zl;ScBH+GJc+&0}27YAcwjxj!AstWc@n?~>dt1HKke6CX>~6Yl-x9nZeogyb zTSO4T(AldQZG#43?nL#IJf>EHv^nk@UQUOXxUuUGioz&*y#Zng8i+vgd?erDNUi~} zgFMj`t%NJ)BR`k$M>je}vr%p^Gys=*qOo3qJ!~McJ#ZyDoV1MSqjqSvbA7zQ9}*zo zSxH*UGMqbI1_qVj{<(NBR9%fnHSW?32>`Dp*wBwk(&c9vLEQM}bCL!eJSS|_bFaq} zEH+%n2M_f>q%AwYn+Z_{3q)>Wef6Ifx6OSEYxIl>=ZDLVyiW)=WSUbkjH~XD=htcs zy%Z5Q1MdFUp;?&3j#e>Jo+pVv3}1?(G(IIdkZpRO{1_EjoF?Qdf8VPVc|d-Vr+s@* z?2KDK0&yYG)O2CL;p~mj3kQXyx)C|09YM^g|JO!$c-&RIfmKpSDg6!;EQrs}CN3pi z#4tdjJQcfL<^9AqiWgtr)ai+%BMm`DV)p=KcGEfx4;0>hSsbqNjL{Q?g=S(kA@qj} z|HdI|oEnK8^o~B9BF}CYl;nAVBm^Z^!9ttBE<*-Hby93^NlkqI#uW96$rX|7$rt*~ zCU@>ElsQ}ShwsuUYPltMvd%v=O>KJ%U7OcJiDL6T+<X&_*Fv7|;H_707j< zyy<8f0hhwq2_LBtzOikerZdgPFRPaCny z@{s;P>wOuM+b+@q?{29WYB!f!oT=CS7XQtwX{tADilRyh@2hSW8ZhK$cFFrUg2$<+ zx++v<)nd*=Z)FO~np?82E3kqn8Hg>Q@Shy`LXQ$7@hn0G?hyxLE(sGIk`%?3Q=#wI8kG5Twh5a7y|WE5V{iKo=apBrQ?7Q{LR;5R_W}HQv6ChiVzO<`p)a5$hyMROTKstm@zpzY=jR`VHXzNYS# zw3pfGzbY|DogB*`+2m%#M5~!fPYe?f5F$iE_8WO}mS%&pbJ8%PebfKiQbROxsb*HD zekDjYbwkeUmf>WnDDC+RfF0)SY&~~)=0CfO3;Aq*lB&upuoRky(m()&+YSoIW?jp; ztk`SYgflP@@KCCo%&*ZT$%Fsxj3D`)WHD+4E(6-2GRzX4O30}>GN%plnBs;m@a$4N zTK4w|Wxr5<%z}z9Gn%}IjSyg}c2-E_Akp=O$+b}O<==62tedhzL$>LSBP*ZG2Mq?uQ$f3M{quPdPPoRDKE7^iKj}*&BGX+mdh=_xOq>xr*M)Ea1x}? zTZb;KG^*TLVyM(8HUUojt(TxNEpF^_bjen5v^Y)-Qx`0)OCbP|fDh~f#icN9B`KK^ z%>DEE0Ee5xDg2~UnFmX=Bn3njtxoyKDZiaJ0Vq#H?~zl(2b^ZDLp>fav>7^yZ&8dg zPWq@2azsOJX%$)6yI^i9LfZbMIR-al3vUNnl3BuC%tNQM7R;J|boeHY$-sB!9Hs${ zLp(f4Zaxa1cu2r3F(%$AMmlgbg&KkNS?tBbI!IhGI6{0iGH;e+=5aimB0s#7D3(3| zpi@8>v^A^~_C?8fagk0}=bJQ~h%p~hAGHw$jFGO6@jidJkVKo*pgFHOysvMg(2d9! zED~7`lkKTe@GK$A2(M8)|BUr%d_~v_G$jdy(ctShdS76O2#JD=N$5uac8Gh2|9Pf7 zdvXaI)KwDFc5(x$)dgtVry*bn!pollRQSu(NXnC@TThCY0|(b?CK{~hU}ET(WAOXi z>@0bk6V#q*Z#pbVe3pk%iekx12+4a*cM3*FFLw2VGirsl$;uK8iBFySl_Op;!y6t< zFO#qSJ@5y;8C}RA+bl2heq&3Du5F8cV0-Uq;T7JJl@nxEKtRCy*cDRkL!PKjj zA>%j$E7*=a#tjU*T*5UvjPQ2wb?m|gr9aAPVZu3#m{9pEW?Vt72npP<%RLypswb_B zU?2`eWN=vx_j=fXA)+{6vKV+ZgYI6PoCiS*EoVx&pa4U_rwf#>%5UkC#SkEg zehQ6^l}bZ#)Lh;CK1j#;N+Zl^;h`b~E{9F$P!AAX8Z%9_1d7gGWA8#o!LifWyI8xQ z-~)PH{+^=X21gph1sbypPy5`rK_6W)#v^>-*EilM%DsDzt@Hk?dM7I3nnwyGi(RTvL0F`W8lBgGb{Zd+J>?{M zKUw>incC7M?+rMv8;@T@1um^C5$k6v*oA>+#0sO-=5B*4NjH>W)#C$q7>UY~FvvbQ ziB}gv5MgJB=uN{spG8rpJ&P!OpfMGn{K@!-B;3D;y~`Y6HZ(w@Z@IFCx51XnEt9wg z2$t{H#h{bJ1{3bOXDnpbnrlx8?__%e!CJh<{mWT|{(KPt&a(rMie-)xle}(nA4j}F zk18*j!@9Wv9{>slHi>W%{3n%pWJ=d|QrV=Bdyp&zd9vG8)wQBg3uhTW2rgVhL{5O( z*G-5-1Iv^vp8Y<}>^siu)K6@Cq33}z&qI-4)^m$NvYu4>!IT4{x#K@X+Dcx&-wj+~ z@Zm$7{9>0fnU{G2R^S7qCF>FI_9$Ch)ar~cDHCFu>7b;Zi^sGK1grN%b#|UACzdu!s z--Y{YP}15)-lL!hKM&Nc(&$Fd%pnHKnzp4P-3^*UEe=`%8A!jal7{z)K_5hmHoN&xDq9BVMrOJ-+-En>UF{ zqC}7J{!wM%f17C?-j;vHni=)V~iXa^<7aev#OKs~ZODWN)KWH%Egxh{fb++7i%y5a@f!}{{H%yb95r-mm5 zyJs&|`SXwbY+Ft}rh&*@!zvTkF17v+g*L-ymd4TDgz6pV{G4d5)Yt0$1e)bOHlJS?2zyXUGd<(hAktzIz902M1%#KiOq2_2bcn2Z?n8#s~ zz|u(JSyv6b8TbGL)gi$?XA%xdr$muXW*`I$%nrteWpyBVt3f68GzrtcDU`WL9cuVV zBCKh12veOkFcx=>Tcdn2n#du_3FHuAC=C2evc>&m9DP(HcR9>{{m;ZgK5GRE=_DFt zDt~6E0Y-64>_W4Dpdf!NtoUt9g%V#$Jh37Gf!Yp7_Sa@MBWwuIC>9&Y<^?zkI3Vkt z0RX%*qxxn1;a~4eP*3Me|A46#o!oHhj{L3V=i^groB9jMJeV+`m+zapd`IKtLv-)r zVXrx%%d1mB+7+w0O0Vfb$MRGAxWZ8BMcZ+muhm_N(K-EMowdd))-Gx3-?7oYR(R%t zn5^o_H;9}~QyEr#o~Xfs4ivEs3?S?qxGJ~PALpLO-wXaTNslY=XD{bC@ja(Gc~AL? zla*f`?L!X{bpvJ+;AANeu?B=8Tr=F>r+>&kLx*^i>l4Rc&Sx8f?R!oL zY)ydPk3ozHGfLI#uqdev^gf$6Oi{@M{6+m8~Tf4DYhUobSW-do9Vw?wb?cm=gAOwtd z_LoKCcot3=D&udpp(GKk1Tfo$nr1VR`T3e3VPw76y&XNNrOMhIb4bIRVPNS(z6@Oj^xY&rv@$it4Fal@R%-F9}i|n-d(lp zn< zo9L;q!ieR_x96J^#mmxq8)r{!uWScpX8|k`eX><#IN)nwOj!X#^e-r32a44@Lob$d zbb_J2s1oTsOS~7h95Hnj~K+9 z^a!rB_sBy%KQ994@XLY0{>~5z)BG^3RavsoD7@i+J!)N^FZ3|2e>TcGl96zm*wt;U zM*?jUTMA={!NY9`0AD$2Qpjkm%ZCi?_&LyfW~9jR(>IVAqzTx6`zO3Y2?I)Wc2-*) z*Uz-=Ihy@|H{Ed#iALeC8dRH~({-zT+D`%qTkzlofixU|5# z;V5=hpi70vu2gR{*b6~nqzC>Kex`_F1_jO6FBCIo01U|}oP8d0*ze(`cY^Q8OSopl zQX=*PQA7b2Y`@ujSudTPafuCMYU6JbgT62ck1yRX1Z7^1vl3$~Rt@!B;Z^0MmogT! zYC~x*>X~)Mz(VSiQ2*wX9r@3EVCHwU{CGT2fPU}uiOX*`~vc7|e*yWThZ9)7jyiyhQOA5MJjvJVN*x!^l@IUnjVF2e8k-dKF64 z@Y6Ad^#KP$2|CRiJJ@a(u-}*XPTR$^h2=;GzCVZpse8P96U}v%8-w}VO~0VCq2V4h zG^}T`6f7z}lENg*0h#1aoGy|TW4O7FoG@sBsO8^tzbss!gs)u@57Ep^nY7y%VzNGg z+N=E_O!PyI^YwfJUHeQp+JLwyZCnd)92GRhM3#iB^Y2p;1BARedN~-pWQ?2Udr?G% zO7Ut)C=BNz;m9=jwds1(JZuW7K~g7eUL}yqI#-b$>JQY6+3=$HW6ZS}v2|tpl_0mR z{Ga;JyhhDq-XM?$Ntg1N`!@gq*aymxpAl6qDl}Lg^Dsi7f#R^4`slPnK9blZL$)~K zq9thA2R=mdkjn~1f*=esNBMRg^D!S(YfV;#d|5Q&88>y&9(`qQUd#@HXEcc!<)myB z2~@(L3IrYm@;@SR)%Q(Yc#Mjm9f0J}#vrg_Jju9so+i5t^6D_S*F!HV0&(mRK~T;@ z8ePs)ZhS7Nre32@qgBv}>E(RDON3D%N~o2_cA%*5M04wVjd<|Sb#BkAJYvY%WDSYd zx0EI}GZsYtB4#*qayEc`0qLk#3IS4nLpWcjdkKl(p~gQmWEyu5?awV7u5o2u017d$Mk@Vex{(`guEMQt5Mz`HS0?$aihZQ_(^L=!(ub_4rf zdW1xZIcDHQFm4uta+K(P*DQKaD+(L=<)Cn`5U++;ISe3h^f&O=?C?KCN{Bytpf{cv8Tq-an(%9$xBx;}X`lSF~CxF?M0v)bC-KO$GCK}4FBNX&?k@hO8%{mI7r zja*G+BQe+>AS$$02s#9}zZu3s7f^ddef4g>K*cu0Du zN)bXWw2jw99@?Oc&a^@UsxH0SyelBKpTqQ}Qo<{(hK6|2()F}%Jp801t#j^2nETt81dQae~63_0U|j6 zD6@b}1T&jHziN5=cYm#t+DLKEEtP^5j$pnydAo^3Gz=QcX+dWfBpbr@=_`JpRhRuE zAWRAaty^K*TZJ9^g{P1$S{R=*C6x2Rr+)6^`=Mt5}1#^C}G zMm>QC-WC}ICNfv!{@(M03vDlHKNm!=qv%^aXh2qSc$30+{$dID-yftkF8r(pK)u=d z#ZAB*< zdASQs@HpwyP~h`%*dEA(APsebXv+w^_G9|*=l+!7*n7ScJ;gxRwbENvVwz=V;-KV# zng&|C$b7aW?jIwjvDcC|Y_xS}w9~QtbHU@UZol%^qie-)yA2T{MWuE46aTZo;l#Kx zb@nv&L)_~`~)()^|F7gBb|GOi$ZIC>runI z&dS%k8Ox?L22S{I-IwP#;8^rcas%^cm6L9#96ryS*Ms81BJu|*cjD3Th4iL7g;NZs zO!Qb$0vSwV>DpzU(oVy=s#)~PBA=PzGs#fN`FPi6GxrlOtap4-sDBnmY;3bU1MgLy zeVP2CczXs4y(q9V*7wDUBZxcYj!n2c5!tb4$D6zO_FW~Ej#wHOD51|iK`ha)7oxFc z5!%Yd1^S^|5|R3k%a1VsmcwnR#WI456{)ztWE_WG+OoQjpOtP+)CS%bdVl&`ZQ`^t zg;sF~(W(&h>69{s8l=2^*y4Hg*iN%8YOq_wbW}cz3z|?H@08p@32zssHt}yi0`EDW zx((l=q8-ueYs}IL*rzWrE|IXI;|16ksKt-YhvNE&$U+ZNq zbZy6pcDiWnkpd;&}OnvSw+8Ml%yii-oX;_fKM zbm}N#DOZfg--CLq1s$HVA9nZjzg`czyPzU>b}8O3wz}WPK>{RV=u%rPj&smE@wtP zC}X8b@s9EKYrGF7pF5(^0IA{H{S89ks+GjM!R5RP_ZX!w_yOV)6iAkTzXYW z&Ui$3>OQbm;A{e}=vcKiVaJJY;#9uswGq%g3aZ#o6gdR)#{TwAeHW7Kpev~uD74h$ z0*^$Q7&A+f?DHH7-K4Lkqw7oM;cVa0I+ENlge+wbKs&iA$b@F9)Dt%Rmm1Y22M*dS zXL&@dS1Krs3NXn+mw_g$stBAM2F0f$$#`Y$d2Py@aQi0oLm?|gn`DV^IVEt@tlH}p zB>4rpjVD-Du=dO!2JPYitk4c#BKbs)%r~MDc5DIEZeFe`TvcS>zP#CMRUcqBi7^|0 z>g#HtlU`WuoxyP2%@7u#-q0oH}+%6o&^Uarl#}!QrDGh#rNa>@&yJB= zri|uenuZD_2>2{4_4Qum>gQVp%zZ2W<*KGUocW&f*bvgS`<1m7@_y5S3uCI`p3Kr1 z0gJ<~i|4Xoz*a_YT&=g#6}Z^wxrrx@8hxYmVHW5;2(J=>&b;Em%6>cK~s4C?o%C1u%ffpE=V@{nN# zmJzUcUI*u~|2)N@vhkZ7<`*rgniPUjt@QTwzzf+`AEFc76I<*|^roktoNYiOs0>jW z>6`o^$h`!x3YA`DY$I%&64-fB;E7Hn5s`O;=?h|qdR}ZI#`(-P$c5-w0|mtJ#>4l~ zp)hO>2_bo>!iC@=a(!ht&J7JrI4n$V^l)zG;;c^jbIB8H0UBsMWTq)YAgLMSxemTIAGLo>n@fia0SNF^CyW>QY3Y&KoM}9rmuzmAJ*hWq zGKCc^9PBO8wx3*aD$4pH0I1mSa?s+jY!2Zy5YStEEsD`Rw^WNVE;{bw16!w68jE-8 zML(K`xkE}bUs&^0jmz#bJ+^tU^ucl1V6j0&QoM!XshCVjtMn3F1pYqX=iIN zBH~TR;zg4?J%8%Q_14&B$to?=BK=E_{8J;es?ubtX<1w86Puj72cpJDiupJCuUD&Q z*J0=UbF@qt(18>a0ZO)$hMd@U+26L~G-`72yB)Y05c_rJUx68pe$&1fC8CW#_Rd1R zK{~csQuJ%$@NUXVygqO6=E%bmZVtnU7{Aba~{~ zAo)cFcsiYS8Ut~K!LbDL5UstY1-TtO6ervA&eUl|B5JGfS4jTfw>wi?yC_|&kxHq# z9R^ds5-HSOb|v6a-EGCOXh7O6d<`p0&oc?kQIcUqzIe_EwPH!HP38(^b+&?46G-?e z z&1*1LXhW5@Um>j9X@)FJ+VaiV%9bl_#ty4%&&4DqL}Dq-$J&;$l5G9zeL8$+Sux%#xB8 z8=Dt>vlJbDXrSAACyUWl*?+wAo89@~YL`qM&%hF+@=z{D`=ZHuIZF4j+QdmE{d7CD zdtmI|w%tfmo?)Q9A~d(-e6=|NT8bQ9cY+md@PI08DU*cV6j|i_8@lA&s$b%YR$esA zTUIZ=9WJnwgMFs@k=NQdz4RB$>fgV5=?2|v9a1HZAY+S>w6UY~I6#m3-m zzP>I)Xw&*iI8=jS&h+O;tHR3Gbs#_0=k34@1nW`hZ$6snddVVaPYJLdaKzGv#wx{e zqe_5SAOG0Pc8Yo0%&XprG&y+`9OSs& zN9X*MwJ~{Tw1?=dlmXj{XqtOjo3(NZ<2g)d0jSC*Z8<`uNwP@?;QIW|a{SJb^kM00! zEq+<82>yQq{{O<8Y!AZQmzWGj+(^L&>RY)b3aBbY(_B~;9T}OTRS$`wT~$I*xby6# zmq_re#b&tR>lJ1!!2g9i$DuIFp!MRWRB}lC}#C z5pa4l44ifwox{bK3s|_DlkGvVP&52~namZwoyYZKeZ#qw&d;{jD-%$hMhz`LI%P4T z6lSnqh(5&D2x5(4kYDvQD^7;#`3(bxxMVKcZKxox4~)7efG@1K<}JStUJiYOzpQ5` z|6+_#UgB%hwDQ7{uC$p2i+wC-BhZI4)KjY9OP9Y@AjbM%*20u6|Nd?lWs;pF^deI4>bhwWm4 zOi5%R0GqIA2m~nh8P4?>gD8T46Eq_``v##LItsO0&psDy32jw+R0F5`K5kBE0nu|IcLxOeq{H7 zK~ok9l-+P5=-!<0R3+q)=<%KR4n!eA_K)k?tXZY>A0Q3| zb(j6MQPrG>M|~B?LGXZKfh?8~B*ssXPZivBgunzi7e_+HNoPdfD5!X7K(BAS?*oVT zaY+r>;Z}`iVvn^5d%P26>t=RC6}y}wWE-E|AU$c|bdmwzz<|kac(3XI6It6Y+iE_$ z=9Pjvu$@L$w4|XLG-1vm39D^8iIVUsmNMOynnT(mgx--YKLpTge3qY5 z!0rYD${_i3*A~I4p|^rUFSdBzX$~E!;V>gwd7n0{T#<7*4^P)Kt?H+WYk}vF9I2s} zy1}-Mp0;A+@N^7hsujx0G90CetS{G1B9tp??IxxwRID6*M7lW2I&A&D`>rhLTa4ns zhJlFF>hRPB(wBt}5P1z-+u-R77ubCVk*o4>mt_WoHw`d@cLscWU7ygIvMM;=iep|L65xJgB={Ba(Tu?-;~DjVMN+jYlcxwf}NSs4JYe{q}uQqpV- zcF;89d!dhR2iQz`+<7!9ph?%hR5-ZyKz25jXlxJk%J=r&*mUN)5~ITtwuqOO3)YeN z`Ik`Zg&Vmi8+poSfrDZt5$>oJGeeWCXwVMe(9{U3Ldq*#ME3Ol=SQR$;^&+fVl=7= z!jrn)`v)`cdNz+~N`JWcH^9o~D9+T~6q&XiV{pxH1fTm)akT%br8$a~fO^44yp9AC zHx;(5pR}{+lXcRrHAh((yzL}i0%EM1P)utxa`ZXb@7KjA7y#qD+XKtiTmm78)d>MtSe!6rzM-*!&F5xFo3+Vc!t2&8z6B(>SEGNA&dOtlscUmo zHE9Q;|l|8ChTe3)E>L@z7r zGHe?NqqzWIEFAWT*K4}CeWsu=HC$q%ZQ+sEF0&v9hDxZx;DiL=KAk>JeJc1A`$O{X zPq=?w)(Wn2w_OKl{E@-gQoc7k5ePV~N|_g@=Nou{X4iFKN1>^&d8jQ#o`u#$Mj@!^ zUpB^f>^RpI-%UpFG{@DUL5j*5m70zdKe%5NwIo#SP;sz3H{)E;g|@aMkjh7%Mzn@P z$9+g?w$Nz4qx9?v=aCxb-&;}X?9G^LG|YE&n|0IUS8MdrXLs3*YMbcU9hq{y%%tqy zPR9_lMu8y0)anV5bnoBExMhp~N~yk+SL>zwvpxG%PmJs_fRgO#wU=|rAjchjxX*7O8m+8z5TBe+7uNTBul~CU zgN9|d}0m(gf#t3UC{lV}Mq5g19Q zlPLu~b!RoRxjcMr>3@== z|E43DKANm`{IW^kP!$=LZA~M*y+hJ9=$ajcqr=Nt9bS;v6+CAIw8>6V5ClenRWuGWIW@MYfVc z&g$U&_Y{-MFy%x-qn#+YyK$t^GkbZ!>CO?z+D>1Gvcu7Rfb{5QGhswTT>^m}HntU( zTEZqC68Ib>%Jh7049Q8S>sG>@=t68v>AFaNid!}Ff*vYlDoyd=MRn^k3Cs@qxFTq= zc=Yp?A@aDB+u~Z}=!IfGvu{5_Sp5Ua?v8mDo z3e9M`_({WWK)ALoB175z>-m9CY$J?|vDxYXr5=y_K(uLXMr#oQlrl`}2&(gXxVR0E z`vx*yk=E{3a9axfwY9r!R8ua`2WV1#U}3RrEiC58ao2GVN3y)!(%@X+l1R?Zhf-+c zZ=^^G%s*VPG%%Ho-lnEobyLgzqTC_DxNTleoW(l{24je5T7}89@>sJ1{ z<}*W71xIwLPN|VQ*qfAM!Gt8)JAXsYdPfQ=v$h8xL8;j*{>d*j6i4vOwe?+Cl-f$% zE>2x30WwjGv}S1mHi~HPdV#ccPpkw=TKVPsSL3u*LLs*C-fJ|qwa>!NXOB<4iPsUy z!v|gr0OYU(itkWdY2Oe@0;MJ*S@@(OYPj}!Bw5?N7iOZZE?N*X2Nz?a-Ua7o$QK1;y=Do3#`N zlu1a9opqe1VpwD%CwREZeh&!wAJRDPW2{u>`SnSU19G#Vu?tah5-u2`=NcJbgI=vm zX4Niv%3b4xuezPsp-IQs;B7$1$TL(rE3}=4*G-*}t4YnsNqyeVXEmBHW#{&?Kmqh@ zmY`ezq--@6@8Xc_p3N>^x@tQT%Ws^R$_N*;0u6*FirP#q7pY$M;5qb$+9(C)q>w-m z(Qi$sNeT&|4W465bhM4pr9pzh_?~KA@C6UP7*lRsp)m_o90>QzhFygQ3F?X|DFts% z?9D!SuJ8NrV`gm{#?dZKnyUU_z;TAbMT4P%1=ebUl@#1yFM)M>_~lyyD2 zq!5q*+W(r*ku+NJSx&yH8cVJ}eI~k9od(G)z)SS5wyI}qb{m!3kLW~={JxB6AL5>a zJ3po@*Ym^)2DQ{#kuqp+Pyrq@LJy?H_h+H3rBx9*>c zeR`XaL+x*UJ}!{zNIis@OF=%BqAcxg4{IYqKf@om)Kz{GMoNCW zPMxIvzgt1N=n!cEE?ypv|6vB%tUmf>*O^~KyJgwZXq9u5${j2Ak)S+a}yp*XIU6{ekZ;k&ixx}m^Cc~m|_S= zA=eqd!!`f@Ny&$Ozjjx1H=ToBXzL!AeZ5*&-QD#O3_5Lnnz{RLzHpQVE9Q&A$J28O z^O34z5c>G=bho$c+U(!==Un2yl}+J)|J>Ymcbl38u(~eiq&x_}nf7E9*oO0V10s#< zBA&Z+MmN6k<+kO4Vp@e+XM9Wx*gtglDx|w3Od2C*&n)}TsC%o0S?Q!PBL8A?p4?N* zQj*c}qr=Fuy^WT)?%xKqUOTup!bK4r{V0@rME-xhiImA#v4;plWsutl6T*WL%U?Ps!+vXd~n22 zYIeZBKN@>4tQLx7WUh$tAgisD6pd03f+E#R@}?>J&0KzCQ$kY1>fO>$VENiyx3ZqE zq{zZ|?&$r~M4pp^Hx^a}tm$%}iH<9*o>udFQ5zU4{#kaN4Wb_`S1ysdQ<&9Bczuzg$e4k%b9)`4-_3V+ z>4fA+XWaTzUoLEXvlr&i105p`l)a^3-NHK5>?v1bO*&<5P-h8vn|0b z{0U@8Njpa?SiVWA!K|RrgiCK4INlJ81l;#er0@Q$eDnZ-iA9@vni?d9UFc{&7Lt&R zz$;S%FVSm}Ak)uqwfORrHX}<>6bH^2)1RtPExiwxdP7JA^YNv87f!`yXT8{*RiMAg zK!rL5BezCOGjSC6Gj(GiYLGC^Qi9IZt6f-7BJu$$1JPZix!}fiUp!wB7HQDU&Xja; zpd&>3g-#}Lz5fu85mve8%5k~%b=ob&7Su(7n4wMVn=%A&-g6Y!C473;Yb`fPNxLhL zG_Wv{@U5~m?=CY0&$xbqO{Z43a~MibC5~m!XvnL`u3=9UvMT z8IHSDCZUZ~ktg=6un4Ff;pcdTQiaCi zxP(%%{~~XSpLLwOuy!X24PghwFs&1RJoQkDpj$61=hrcPcIPs|R+;4(?}&!%h*a92K$pDBVlMEzHcDNCz7 z>tl{+-t}5BKwcqEEtpH~Nkv`|kYqTzhHaA$-mWxbF>~LBzH{~GE*ub?a?@CT)E4HwEpP{#ZV;DzCP?NpuD5$a|_UWcW`C>u1(16W#~`4g(Y6rx}{;pwJGQz-?up$@@6_7WRe-`v52 ztb-@A(jNlhxEE~R6$@Npu!z?1=DTv8$eVI3VSG5M-wpea?ju^CZFSW4Uvas=(whQD z6OFPacK6X#_jCe{oW*5!Mb-a>$4PHJWbHQ|7`Fu$5m=oz8as8dRXgX>|34HRYfIz2 zqf6`DRA!QYIqURi>dg0Il-lDPJUG@p*b4j66E0%i#qJyKfRY-2+vrH)b#J$EXz@8I z=}Z>ax{7a9srn4uZm*W=Z1}FD*FTA(X1b4cP_PgBqu0iKCt1Afu84`yy0^!YGh90U zT>7*`wgx%L4w{CzWo2OYmM`NR6y>Cl4;B(^uPeN;{(|x|k}F<4VCqhE32Vo}L5H!k z?9XAE?#3Ay2XI_N9dUY4MPT(Q9{tit-J$`P8x83q#JyVl*XtidBW8C_fCFw-bF7Zk zT8@w%F8)EInLxySnwjn@kLD1aO6BV{m10&S8&bKud+Cqb16_2&9sg|#s* zI_0&op`I=EF5>u`-+K8$t`O+cE78%KrrfAE^<61WfbH4jRABtY%+9a9UiX!!)*DR+ z9ARq#yn~J#p0NA0o3KM$ff4nZuTN@Z8cW@|)v|iMvlJz`8XJRiHqfSMzj-0*U4eB! zjx;TZ`k0AC=pxoQGMwb_!*;Qmr`fk(O0j#W(>O8FE3*VFsoRe@1ChILvj^OT(?mEE z@p>!|z#l5i(6oFAY^?MbhIwDf_)FSY9Of_@Z_pBtcv)lyXAj?3QV7o#2GA3!SM^tZZ&1&+mo$ZQMuOM zh5D?G@oeHMx5r#q@N5=kG;tx#g>vWLoAU$NnxUwTO3My+7WlP?MWoe0OP%83#a(aZ z-uhMIhw+8ItX&7*@MKpty0C@e@+AuN!zqb7Z5U_(NGoSZzNhateH6O_tQ7t-qBZscLZz@pdl)fdv#N$(ipPv;q4ml4F zVXEE7m*_}4Ir8Ufc>mM#Jio2puywo!^u`$9(H+uXeY4UWyi`(0E(uxLF|w8^BwAV_ zLvf|Lt3lw>gW~YzpUvASijX+v8ZWz29GnzZtidk&6AtRSJ2s>N+`2j+fR4K`XVm^xyJZmmq+=@ z-;DH#N##7A1Z=|3T=(1-eBnhESew86i1`dn@^<4GBZepLKQE{>MUus4haZMACPm$W z>?aDzcM~jDifRvqC>Vw?0#0C`b>@>TJKlQr>ql1f93^bcCu3B9B9|{zR7MwyumM*p ze{4Jn!Tmp&beE?<=YB(8H|x{MpZ=atg$xoV%0UciqTIxbC6cIJ>MT)|1D5*W`Eexj z6186#G>w7@VZr4s^YJ}P-*z(PLDA?N)P^p{Gvp;ML?Pv-F-xpmJjSR#-GI@csp)(F zvc;8#$zNJlN|n|FNBqzX`q|vf+LB_7($_^W-73=h1Ft;)@iCwjBr`+(i;W{dNg|MW zPW-NEWw?{X`V-lV>_ijrFI^7fZ$>>u#>1#(L3uW-|%76wsKO=8X2dz@Ir7qjsTpDm8tss^t=d^k>Jk1=hB{HJHmD)YC~KAb^1elD&_Q z#e~#uJ_)$L_2h)m-6x0lq=fP$HEPYGnp@a`u;0!)$M%*p zNnqaqnR~)Cgv&=9Q>kl|>Rc?NQ(IZ$htr%XPt@L%#lS#<{VKmQn6_u*LB!+xNeq*O zS~(8r-Lu**4`b&xH>st-o}NsHF!DAlgQzUX?Ikz)OmY)^qO!tUA& zNkH#+RgdiQ^fb1HUA5@gb15t(!E{@dh#5@uu%^D0$ zS$GJ|mC~^Tk#V!{SyR#ZSIkQx)(DZr{8H2a4p<42)|~5&aiUP^HX}IWDJS1&flrU3 zFQl*m*H{i#+xUv;>RrJkPyVE(l01j`YW_ZXD#DA^*>lsKw?AOXaA>tH>)dy3Qb60* zbCTT*tKhbyR$41d`lsY-kVH`Z=OSyEg{*d;VZi;<@mUtVrWo#ZNMdTI%p@b9{v=dD z2GzJ8R~1wR+!YFfr+3`2V7EH`vBwvWH>B~#wl5?J6X|B9)h3=>$A*=NgXzreN=(Jy zkykiDKo{ot6Y@|l<&6pYKIDg1SEp7$ql09c;0Uu%gxOhga{#aYHh!ufY?6#lFIm?x z7|RZkDEtRSn_PL6`n9hx2#hEGnHVF*hcO z>kf7ZH)ElZG(%mfara17*K zqHBWc@0qARNVTiy32O|M2r%JGW?-3<8ln0tv8~RY2U+N%Lgt)g!^ULvX@mPnKp`F}<&L9U%n8;~Mgq28~!AsuvvqfC^Agkz2W1mlb8bASiaDfP;g0>%t zVIqkWoHr|xb#X~PbakfylI~{k#U(q(`%MKvIUM9m9!XlJnb3|^@j&v_8bYk} znudkDMZ=HSO9F022~=2G_&Bhy28!H9JL9EW*v%ykdCB%DZv52kpSdZ1#EbZBz5<#mkPFqBw0DtoVf!9CP9Tu7PBt*fIe%*fFVWP9@)ZAW-e3#CilRiu80t6+}aEWXzol|(t-F6W&fO4C zY3EZyleg8+zYA!n)iD(&TNheb?0SA%8D^zW&JT6W1|mYes5X0 zg-vC*hx%@votcLfzV+FLdlAun{h$9@R|UNhsA*<`Ky!+!Pcgu7FR5?Kbg!0O&n#(H zgJAxMhWV|+9DTLM1zMejJ@J;s{dWha7}ot)@y`}B^n*h|fC-7Jg7IM8(H5t^~FkK81x#J3<>I!tK2Z*=_Sor`BXbN7YoG)tXEXZx(n6U*bKGLj|M zbE(O#&cg1XA?L^LUzO=!Y_*S-`Hjz5LX1a$mYyo5?c&DC{~Xp2QH8n>dD;$KdRLB} zJ}WT%DWzZelhUquNw*vIK5r%EshUd${#5DR!LEQvDKYuFmDxygX~@j$nVlh#Fm zrtGx<{e|XB)GYfxfy_i)d(n&fs#yeHpys)XMvvv~^WpD0X{1Z1SiB!60_A#?d{amH zgY7|;#D_gxhR0v9({o%)@ey7Lt*x5*YueS8Z8eksG}&aVG;vv;?c)H9arF6H=Cy&^c<3)81N(|I9Hlq&)%GW<(;7)xB zS;j$88Da}jmcotp_enCEvldi%1S3q;`1rZcLy|)*o!j9};I+3umUSG!^?evMwO2x# zpV?=o@o(MGZ3ia>vN(Scj54S3mx$Cuf_q>9QE!18(aK~b(wfvMy5#d;UNlvEl6%P~ z6GCxl7(rI?2hG^FxkD@x=sJfw(`=N;$IZP_UGZq#ZOLf8IVe*SDrwP)Mc0-=0$M?0 zm)1M?iCL0k;~2@}VUw7lKA|H=yKPOu1qVC(VSPC#hI&^k?8F!QhHlt*OPcxzCU`&+ zuM8BrVt_re1#MgmO@aYg5^u+rrao%7Fn?ssj|bBV6vze=eLA*~1ygju1;I6=-P1gN z;+|iCV9%p-0Z(Rt_jUvaeH;EOo@Ep_&+l;DUtxzAHj{|P>Tz=-&g!H3sbD*(?551> zgq;F~`|KBHVQiQHP!>3S?wxJq0qw**o z78xjRCyNf3$1L(SG!B{g3Hw!;q>hKm0L(`)35Il7h|0ijxscVv#4vYjUhCAVYKcTc zb$NmuPewpE=N^l`xB3&>>v6}|+Rr(!1Y`)W-b#jZK1w^2BgTPQkqqZGGH@H3?$}!A z!f8yW*7I{JS=S$NCRmrFA_ez=FL&IEp@csqRgPv9v#~4*Sa_TN05k9$&oLvHrJ!CdI)n`t45sWW+{5= zn2Yl%&!lS6MGGoGTtIkkpwc_$ejtIx2ErvpYSrMg=MgIV_niP|TEIYk)&%v{2HR&; zmSgO20+ExIRUD?Sm`uyO6fWH2HjT>bdQo7`6Jqj&>14D~qtQXtWzPym-IY*wr zf~yZHBOuUzQFwiEYG)9bwf;~gCfIdlBQTLe32>|At;&}+Z(34woLD z8QqGTl?Ee8(aF)SC5vzlSexjSWFW=te!k)5EwPD?if=UA=kzY6apTSQ8?8OT-`BH- z%x+fES^QD>&j*ANsVAJ=f{V0n|Ly5~ z1#~^ZAAEZSuyEY^l8n)@`&>WQj-#cAGG;Z8R0vC^?Yn){X&V!`>9l3OPi01Tbmb3z z;k<(K<$@x{y%Q*nvzQX|acQJpoqk5l+f3;tdM0VlU8#x7=V=y0p!^@@*fNZ_L>v@D z^uBn=9NNM{nU&SQ|AI+v7L}x0EBxQ>b~=jx>~0X zyB+w-`f!`QQ69<+7Z`kz$lN20Tuf1uh16cu2rlsffvuO0jSr@*ET*Jvk}vJkUlhEL zu+T(8$Sc`zlZz2+dsdeP?;uPzrF_AEK^r7K8BJ`o8`(!0Yp2 ztnh+-JLMDN-=E7MOWka)H8@?*$aJ?)_*kDX@UeVmkUY1mT$B6vmXdMJ#*XXIit+CS zbztRGW()|j8=IdqmW$YX-1p;cUq46x z9;=+Hnizm)3YMv(-zb!BIx*Er_X(8WmAlcD`E$!Op8wgO?YbF) zNqtqj3s%b=4b(OD$3e94^W|)zHvG2D>KC11v4mW=)p7y`JmBQ)i$uM%DQ|0C^NZM1 zv9DIU>TY#qeUur9l?C(Pm8Ohwr+_#p*4MX=@d)QU%e)#Bw861>GaC@^MA*&DhIcbd zHeC zW3mG$ix*(h`Sp$9TPfc^5;r*3UO6#2yK|uPfoOljY;t^b!bjdhJ4;Z~mnSmHg7te6 z@eJur^C?`eE%wC$shj`l*(uA+Dq)Iw%z7WD!6sgA{hQgG^*t|9DqV%!;iYu^kWX-~ zgCrjWy2sA=^NSW;LUnF18E;Bkl<<5)=D}x2EufK-GBl#%V0AB7N|>gJb654ZE`>@mL0~Iv)-jPk zSRu70rEAH(&N!rJkPH>fDfcWt*4Y)R>8szOo&TEE`hl+W!$ljUXeug{wj-?D z#RfEuPJS!v?8-Th!DFWrwe%$i)6?rx+FqR0U5HtU$73-qW~4DuNYm?501NP`za2nT z&FA2;d5N0(g8kRkTNC27jL-#4Jn%G4gK7V(b^XjjfMt62lRynZ4MbFUX;bA9`I8F0 zE`2!5Xi%c44xv<9WKK)psGxl?Jupg3uN&;Sfv7>mG{I6W@MWQiRs3}2>~Y4>BcGN@ zEfcbMB^tsmx41RpZz&_w{dV(U@DtJM9O@H#e# zpX)VXdb2{FsYPl<C4FlSfN3XiY>zepe)IHj z24vSgCX=|D8S6QMyJj;-8O<(UrC)?5OMt8W9$AEj%drZDhF0^u@bD#u^L^}Pne^AN zhvUU3-!=S{lS-&-cHLQ7y9eQV&obe?DaFhpO&z}lV;Hgk?fv-zef~(*&_+l@=;MOn z(=2XiK6}d&upR3YFw%rTxA}>|u<~kf#Pd)x%7m-c zDVhdf?OMh01UkX!W5Sbpa9HCg`Cwy=V8Ckpk2KU;^{5>ZQ0cP(3m_HkT%DYBKsc_e zLOfmJ!jyi4*))PXwQfVM7y6~n{3CMtH;s!N7LlPI>})5W+LC4Z?294hA4z%VbEi0FNO7~Ppdi}xnLl~t45DIv$;WT@dFznyad+fd`EfDfC z$O#=js&!0kQ}!a3nSC%p>1(wADA^ZWU*jX4j75C%QdwmeC&hHt#|KMMnK~eulR~kV zmYiXF>Ub7Zs1Bhsx{m3|zL`)1gEK!N9|$BKD|_<80w$12MPcOiBhME;O~eUQNS;+n z-hM^VcWZMDNux%`VmN*qwTd8Jq1lwoJ2x-6Xt6=!KsQu(bUn86gH}HIKtkT>UL9Z` zqQP+0jXhH%uY=$s&b6&9B zWvR``??mi)xd5u+!1i`^fR>cZlGYId)BAYB13*J9D~uhKy+hz=H;lYecfTS6R2wcZNJG-Rz{g48O**VZHo(aT=j5 zQdE8LE3(r^_c((`Q#iE+iDI{wnrsG3Q}4sqN;1r4YP zWAW1$u`|zjH?yYCMLY@B%>QI8rb?|P#a3OE;gM$Ws3(J-M%cDMLc-{ zkjzd{0*jQ|BOIeK7aDK&3Ou785^hO1Z@P4a>0Wx0u`MaCHi3+uU|G<81i+W=PRT^s zV&x6@EEcl_>!Fn&tYaBYx&I20{#Cw6Q2X5R&|t?B^_i1x3f>-ZW+$9y5uX5(8(QXi zEu#EV4#AYciLAazNp9Qq^*g^mt18EPOnTQ^tcHhRfPHe_KRX%=FiE7@o~$a;bffWZc&oe z0(=dNl)@Al&s0^F40;r;21eS)t*g4|%Za(prfW&8Ac-=QtTcM00k4tD!4|?X59T)r|m6fBC z{f5CR+2>WrK(nPF&g%iY1Aj7PWXX^miylla^iG_V>i(sr__!!)nyN7+;R%#lHe#ni zP7Z<#V7#EAx(|#Ga>tj`YdJ762{nh;$*3O<4pSu)w5Qh*A?qoQPMCg`6-k97rP-pz z#1mluj+bWD<+WnXMy+JTWeJTCN~QG80VOAOk?x!^gVzRC^Hqm1>;idepz~I0+z-|8 zcNzvHoVjIB0A`NYS~z6)6(A|#Lb)s*Fi64^T9Cu@i5<8D>k|2<&90GviQ}-}@#Aak z$M#I*?M|6HhUB{`h`%7PbgW<&l;++Uc92E4B-t)TX0&3@gqcluADuxP37BJWpsx~A zr@={rh6a^;piwv~dBcq?%NCzOW{>ZdoSSt9{#l-)k=93NHKBR+I}u!PIr@Vd;Cu*QF=h=zHh>{m=imgx?*lW>VkNfk?eFdUn^G7^ zGf|@>mA#)PW+X@C7eqN=`Ohzf3nDLT6+x`Xp4}2hl zBLOr8YUc81*bjo#TY@})q;QY6IB0fL7>KhZBPwRH-U^MqwO_V52&tbff(o5KnU8cs zm$v1Q!d-SIdKj}N+#Kq0VDDp~gu3L9{;HZxX_@k^&MPw7loHaVf+#iGq}xk;%}x&G zSJ{*j!(9B?%bwlj?@`wXX6w4UkXKO3gaqWIs(}h>v8{}ipZ%OdsA8;0WLd-^ppV=& zKZU<&p?v6xQT%i+VVoGUcc1koCM$#J9FQR*JmJ4;Y%rUT-eL8JbJNHfnBwkolSNN2 z>}jPvZm}|@W{>9zaNoM%ICM$RBw$d@&B+kEbj3R(bUM#I>$6C#|H&B8%xhz-0}xcT zc#J2g6h-yH7n?-4iz?lqRCG&sLPI+v!V;kH{qx8M&8$+YE_DvHQ>O35OYPM zY3_M1S-t<_XC5}pgJGvwHVo87Cd+=@**1HiOXla~^;*1nxAp60tIPafg#Be$9nTXr zisEh?cXxN!;0cxx+=IKj3?2yX?tvYGdvJGmcMA@|{p{cW+%NCF&pqc8GqZ=D9_i}p zwW?Ni2%?Ul3@W4ak7LM(9ImeKderV)e5dI?g*T@Q1+G9Ixs=3X@jy(R(=}YeR;2VN z@S2(8WeNh%O`zxP++Bs1=D7T&h`@zXU0UIL3v-5@OC5kcGaG~rL2PQ7d z46bd2Mbv1HWuWP?$ELyv;L{l|g|CZVHs|Rr7eu@F@GS=pQ&hW#V_`S4iu?P}f5{kP9Fv5mRPoY6uF?lR*&3|SRCi~`hg4J zylhyOYJ=L+(5f!Dcq)R%b7fx7pOBL+ogD)>>wm9FE;ozZD`=l@GA4|aOjhW$Pk!Fm5ekarGfHQVF zv*q}++BEkr^r0>(%)C+cb2@b_ea{7evcW^BRSeYH%_|JuMtA>L~J7ulsp!`6hHsa3UkN8IIE~Z~G z8KfBuA6U{ja)Nxr6oft)@Wx7eVN&W z*VRtFaEI~ms3*ZbWvv_E~2nZh$hFY<5OH}>EiYRo_Ie>48a%nBW`cH9F? z?T79o+M8H@sY8&6MD(>}fhO4@gCyt%AIDXDYWL(BwmbiKBaj?8Nh_u;i4D35wwq#S z*^b4R4W&TaVd2`^m0QTr<2Q!9>Aw8kS_w4zojnD!i#mG&u97<)(=GWBFkydP3V}S8 zYQ!JYhlqfM$k+O%`8t)?rSY%pdoX!^m7yLef>%mfrW65O0{D=jt8(G+)mSH~ouE>I zkve!0Ql2ga$ZaQ*p)AFGLDX{{=%Z_8MGr}kd9b%C@0Jmr;Uts|)#MPW{M8+BC5rV) z+mCfMa#A8u2F~U?^k3sg)@(vX>b>1hdl;|HJpI^53$SLqpbnP{F-bY>=4RqGxt52~ zN1#$#RYMkLA6c-vQAgC-r`L!>>t+<@OGCte_fd%@ zB6Y3Z2IkKAqTj|<7GKslh*a}lDr=_mp?gx z+#lRss=EeRmKjaD2KBSfg++=&Gz!H^Aq?j;o!y44tr+M7deYLrsYjh4Yvo%3S7ln1?G(PMVw9@i`2Qnxa- z<^34+2#@ax_6#H3@|@_(RJWR!CGEerDwJY7oUn8+t?*teMj#_Muu;NTaM1%Cuqjd( z_vk}^)2^EbY#e_kD9ye5#X_JLx3Yl0Vj+RD?};-fa=*^ov79AC1ycv2NB|#B|9EAb3I0;Mi4MLu?T%5kh!HFdA zLzz!!X!T0R0-}wil79|;Y+QS`#6xVlQ4$-6g|F!|UK1)XdA6tvY>uBT;xI>7J;7Jx$eS;X?8h7&TtSdTBUPY?2KV*1@dgVS)`8_WncN(&go8WnCYWDGlD1-ijO1>(jrzZ^)G+H7Xp9ej zqszyUN;)@EJB48EW9P41tkH4=I~9udka?SMB3Pm*j3AAX*mI_b`yW#6Ui4PBuf3yt z3p6Nbz*M(Z2>AC&axdXUKSmhMwW^TQkxN-7pOx@HJl7FGjnJq2uwVTb@8%6RbePDR z+Rxk@{u2z4w^NZjkMmgE6rxvwpuV5s7k8TrNe;kQ-*5IkiOEG0LFSQ&MDiX_Z%cpq zbPX+_VfO2O$DS7%BsFUB@B;{NXw3g_T5~S;5Vl5$hl~IJU~BdbAi1%v zF&!6R?ZqHLaSCI?zvnp<9E zElH&JN{eMr7eN~8$m^rwi-&ZE6LQ8v$kF1z=8D^I2(Dh`h_f8^u6lU=H%VT<5PoEQ zA`p%{xKzM=$O5$f|6eC?){gQ2@t(Bw_*@cYSxVkIYoO7|Z1L@KES678!rC)&6~Pho zVM5x>-8N^iFV8qHS=*aP_Q-Z<4;RK;7n|FvnC}NquBgEM5n$6lWnc~tJecw+?a54( zC?3}lV=YrYn7^ful6p*iZ0Z7(EP6V_@-zWY(wtbPps4It% zHC#RzBVk)f<%cYSXovg40@I9Ywr_BFj}c2P0+he}Zk_tW))n8VM=8wy@IcoVW4C2}DIsS6nVP8ho;w8zb`&yTp- zE<4*_tA~gG2iSRm^?740hvJQSIi$5O#Jq~hP9fz(eL1Dip*$4OH0eDN`6KR6+U3(5 z**PIarXWjYk?#7K{viup#Jezw10uVty?VPb$oU>iE!&*4wOkinq&$TnWa6bsp?_#Z z#BJ=pfic`VB(gk}h>q+(9qHW+8TPu~oi?WBHKH`rBNlq=~cz z8>%MJ+e2*S;U7oz(1VkQcz#=7jtH-HJ6RD8u0u0c=S|GHS0<)q%R?X{%xJ{RNg5Q= zzbQhyF!jZfK;+@d%$ECO2m%gs2xV=q$YoQDh>r2dH|@h`VXp7;EbRgfIYdSKae%|< zw0nnvO_XomR0$dH=BkWWv!abEKo4%fmD@l3|XRm+u9a=R}TQdLPyR8lm~N7M7wqxuf#prY%88C#wv<5i!j z1sem3UE!BAuM$%yvahVe+^VA3ZQ?CGRh zg{vH&a6Yjr{=(9IAT%JH(vQ0;8|I<-jZA%YN1ty&gRY+Kt-8wHa;R)ir-=}x>!SR7 zPt}JZCaB00TSETAJ?+XJxKb+Hn_7!wqC2Sk7_4=0gQ0>lDScp5*k#9241#erVh1oS zhA^W(umgyO8-pa!-{C&S53h$1xwN9ihNE&fi&Q(>2I!5NOzS%Keao!cAJ?uzB|3Az z9M>c#FR$EFcboHnA_>^XuT8wHCb?2Cx4L{{?D>q)!jkLF_<747AgDWOUuC>fP~eny z0Mn5p!&~T3#UK&J4KIz=cR>z%IPJ4gSkdNeqTxg9)LfS75KCaa!V*I~iQovd0lt^LWthtZi#b@~y8Fw^>-x_dF%};CrGt zPl|zZSJ3VJKMN<|Kh{v5L*W-qH<)Dkg23oyaK}KKj-0DJ9%hjN!d?nT4zLuVE;1B% ztvaMe$OliHZ^1HH_;y{lAKm%(pFTZP7+(`{sd zaIJqvJ13-^1O)#=s5Y(!bpFp9GpBEhW*4r;Ql`LJ?c+%lQwpQNY-sKjw z9n&6CpR)rIszxbz*|E=EVX#kCxoX_mStn;my9v2>KT#f~-*26)51vHZ-+zmK#mGlF zK%c~=0cy}rOf9yyOuCapf+t7?xu`K9=KBuj6s#{}sf4*fKD(Tn5ME|% zfC$IF5jn;J{9Pzid=E7LvGL@*MQvf#R9rs2b^AG` zxIDr5+Zk1EGS$aL-r;Ax9{@5{f{Fn82FI$jl;(Zllib&0cD+48blg`fgf z+d=SWtfu9&X9(v{-5#J}WR-?xLdm6$H$IZiki%+!+2g(bn2u0&V#1P)B?j4qd!FDo zU*?9UZ%|3~mQ@NN^0@?%MavmQbbKz?KLzD*S_D~~&ssy4G>C?^x`Rqrid%o^u9?Yd(`=54sZFTkMbOt89ZDu;8`FU(ws*yM^6o?Z%N&l%i!mPMxad zIHS7lo-17Y7e};mtk8E=cdL47)SWp!mC;YJc#mhee+<>@FK>ajKB|}xEu%S0TUF0@ zOWz%Fb`%A~J>vXT9bUdQgL9(CVi>wlLRj5)nK)Nt97D|7NxJC-I?nVleg4$|e>qk&EPoG_%Zj3AEauXB z`NxZOq?x3NQ*{Gl@Mo}CLzy~OkqA6{1NYpgmWH(2d-DR{h(vaU4Uvp4Ga%%-Sj z5|2=23viCcqykHCUdAXUs712n`66O1vkL$)B7 z9~Jo4udmKIxY35HO3>QJn;XT`iF~Ee`P*UHG*&9lM1T%eWN{>_mw72k#X2KRTF3q4 zXp9RZua|jjD#^Z@0_Q3do4`l`WM%)t4NivPSgqcd6T*c|^m+%$U$*GL^=pjZKZHOY zRW|Si@~l3h7Lk5j|3iMG_(=9YZS&+E@ z=VF91GV&;ebRO+nT8Jb>$e>*dp`u$1k#~C|k{Hz6-fc||TAYvu(t&tZ2mhn%qrzyu zpP8y{on?FEd3?%&&AVdSBv{XKCa4C2xfh9O^G}4ke{dl?8k@fwcFzxLUyu>twBBGq znrw%!F(ycX_-~yr7ju4+wjnEzB-OPhBvm!*AVt zN0}4?lsJQqB3N;`(FEmNSynW77|XEj`Yux259XTgU|;@ia}^Y0+O?fcY6D+GCLL1S zsS0P5+u@m^DNe^Kppa9x7{fki+O2x7oc=KVp+MU7{Pc`bj};>!%6|oy&w+ApSiP6R zWS!|jM@3EeD>)^GZsN`Y8r0|#vJqhXpJaiXpI%xi=v@ju8C>$gAUwSU?gy%M5ZkAO zV~pS?-P$dtCC+g&(9{-YGjK~3-ml#20z12jd~2ruS<=tu_G1K6a#oFa zbe5qIQiPf>W~ub`a^+~L$A}3s>86`G%9OX5-e4)dd?%`%L4TU94&62YC+^oAt`?UkYA`eqmQ2xd1?wOwzMkGZR)zj}7ml;%*>P>0_!-=6#d(dPhe&j+hn!9d zJpnS9qLTCgqOY$mP2XWpn79~2Rg>jx4h5@;J72t)p5suTZ&GeUNFDqnIdq@gahz;)uwxfv^nAZ<{I-CX{(m%Ub@ckz{VdVThr zs!YCY-q#=Ax+#*9p}9YTnFvtEQYoW9sqw=7{y`br35+Vp@430%yv;xTYmz|v;5bl- z_~OyF+^TTa^ff=HJp{yke;c>SOw1y0W)D^krj>cPMsUrZNX-jPij8OT z$9Fo316+y>=_}U?3^w~;oT_h~aDT{7=R6q36n0Z+vnHG;-8FgC=SDa=uc7|tw=hmk zu`7W$fuK|^Y>M4}Ir#k`EGl;e#N-DCgL;+q)#fVPho@df?ChESg|*YjDHGm5 z7CHQ7uGMtvF%ivV@X>ejA|X+OU6D_=Z+juGfJ)z7A+4+|c)k9uA_B$Iho70VJE_q@ zmq71BSS)XRhW;L=AcMLoqf8shry2XG5^6QBTqh>*(I_@D9(UqgC#t`yxDH-J!p7Hl z8Mxz*pJgASrVM{ZOpQ=GmJI)*=4(j%b`TOotX7zAb4M;;uwah&Eg`d=7W6iyi+SCf z1z4l|L4$+~pA-z;Pxu|Gh%U~SA;=ZmK&X)Oefagq-94{AR}~Y>>IDbFpyj_Od~KGs z#uj0z16+#Kekmd`8F)=4XDKp_p>GO2KR!m#xVruFsxW4}+)ZH8IlARil;Om!eyO{k zt%^m7Pz!2lnB9Iq6~8^0-r~b2n!aaE0-!-})jm0Rf6aASWFy5erHuXylk{1BEabz8@`ZOpK9cjQzeaM%zOopGnxS9qvUw=4T5EDF!Eq2aB>*z}r zAE1gvLV)cwGtRkjNTaU(^DhmEIE;=X{b`+Cj9ORKj;M!RSwk+QA&0gg$33lG&|}S< zU9(xbmEwnQiIntpV!=*?cw4UGC)x;5Pg2s(Ovb>!zU<7t4K@E(_N zFcaKY4PWeCgM<8kzh@eS>vv@0PrbCNfp+b|01{$uy%~a{Onz@VfJe&w#WIfiLrI^1 zQSwktjc!%*7C7kq>;m!?(BXrl8)g{7X%ig3Yxw#cNYNV27DN3K{0BjL`M( zBRlux`gLLcxVjBLP>1b&^5Dx!_9Y#k8Fy-H(mbzrWI+)pn2EYF_Vk5qT<7d1N8GCF z$HFXe6gIUVTX1py$J*JJcNpq5x`~fTwmHH|t4=e6hqRy|46+h?IGQ$#pApqG2erDg zs((tTdUKOTZ>}#PG*QhENaD!b)!bd?JbX#hXC20O$13as7`a@_}57s#tPpkHJX*nwXm@<4R|qFS1Ls|f$Oe@P0Vr&gm5z`&M? zmt|9+9>l!@5^CRMRiP#gHho~dE{J%5A6?t1pJ$^)yS+kX!ypBp0qTuS%RTUpu$72d3k>=93Z_qYI?PwB_gh+(okzHfzHmQY&vtWt*2hgf0!LmRf_WYqQv4hTk0M1AecIKV z(gUddF_dvYjH5bqK#L-_j_#NY#^pD*TyHMCR19wXOqHHh_sj@mUdSeU536zF5Jx7$ zl25-D4iSA1+XAA@!^b`?9Ljdi7gg+S@Fn0+qXOeX16m-qU_vZUgPSuqWKo8ssZ#|h zGqAoYO?y!bd4Y3yv!OnxyGr4JteCg;hXv9!xEj|)_7EZbcy|<`6Osc_ zff#7U*hsL6FnqqERx9RlYpZLzU~T09LFT~}bP1cWwZD;xCzddKSRDI^xo6zw4cLq% zG6f&TCN%%wZcxnDpH|woCfdlCEK*CbKF6DLxY0lMjdeXZSn3y(AM{)5557?lbJuC| z6DMXUQ!g6PMMRpNk)ZBUT9+3T6kzaqO}NgA!zx3A+JG+lgsZbiPC+%h+=nYEsQ*)C)svW;Y+06bjY%z-Z~u zEI|p^?Vq3y4Hv`}D|j-07%OeOJ5L4lT zxV1kXP$gVQ4aqa_)lmrtyhL;wm^VIj8_?XkFcH5%hayAe*7D*c(AEMsM6?U5iHIoo zVwXQ_kxwseQI|iCQzRk*FQiJwB!0L9_6pRSNOUd|j!fFbdXL$JI~CI3AikeIYaT4n z+Aw}6qj~Jl;Xm-@vY9HNN8()r`gQ2r5g#i<_9nsegNoB=Da?$VLm9PwNHqqEa;OBz zpYH}8d9{x#yx^hmh z|B9XA$1qovZQ{Se8KYnV2AK@|H~DUb-teUHRY8HqY{WbozvED#fQ*!#Jt&_-o1w?= zWmnbctxdp3!YXu=cS?UXao&Ig0p5nB`kRWqWVNk`iM)UM-aS8#hm$Q_us==rxFrc= zA%AhLv@K42E5QG`TwhzICfa?TZ^tnc^Y2l9m#dyR(W=}?OJhz=kvQ|B-m03`qTG+H z$wpkwuP+oRyD%+tNa0jLLo!*`BOG zay3kZEW{Qx79%>n4SEh6N4OhflHKh^Oy&K*RyH*jR05STxB_W((aNy)2AK+)m8{RA z3mTh$U8}m(^-PIYgz(^yn+a@C;ZMXz_aFVt?XM&n=7)-s@ZJJ1OFKRW^ZuNVJyf&l*8 ztfXEVePW8%>cw_mX9zWJx`MdH3+(l9&-eAeFWXuaKuBKMc;E~Lq&DShXy)^-QRmBn z=hH67yPwXN#=88eBS{)13h5~;?4CSw1A5+ciB1XyQ?Ty$}vXnukZukd-8VEPwPUg zMyG`;sl(jwa#WbAZPs=~cVZ<%JG`gD~}9xcmM3O zHzO#-!_DA0_}D|@M~=hoNB^u;Wk7}9RvU7>(gXFaCYdttL^m~E3rFcf~@_P4w_J`lxc?6*lsBZ zV8`x?!gMKqu1DBV-++~+aZxtDF9+5IYyd}qy_q{D5~(D7xHmc|iD~C{wgd@M4V$Sp zNuOW#_gBm;Y7qi?^}Xt0id~K+4*|oCmO8Fqykx`cqNN`sEOJj@QOA=IjQCZV?^QDy zL=fe#LrJUd^`vROBLJx6wdp)X9`n(8oTrY$}aIRS7Q)V7Er+#RlePFCc z4c{twKK$fJX2xp3>5n(k z#a;h}7TOs*dNx}Kpt&T`hfz&~s~W|~{v>LEa%#-Hgs*8v3VxVpt`2Q}Lx8}Y7eD%9 zOS@}XY5LAF1{U`0tGILp4VWMp;8lTEOf==U@eAnjCXn_=#pAtpXXNxHD5spu*+J^4J2du&m>@3Od$v_rtK(VLnCbKQ+;)^6>4W$*+6zXzcS$M z<@=^lyJ6DdHZta)4p$Z3ixImBMFT!$`4cX<=zFh_?{p>!L90aqckM_85M+Xkj?!5G zOEnspB<(H#cnBZ;Fpl1MFJ;^$_)Bcf`Yuw5$FQ0(t2fO8+X7+Boy{&|)wrG0UIqK5 zVz}d*KOeOUE;J-@X*q`x=3|gR+4WYK1A%Sj>+9c~f&T1>mFYVTPmkZM=!T1!0hf{l zG%L6wb`Njft5uy<#aZX|#ku!QF2(2A%Ld5`)W#5|3I&cwcq2e=83ULKcM7t7 zR^MtMS?(7pT~X{xW?S;gVBkSETvYBFjEy`?_-uT)Zbk$55y3N(gaDG1@p#2z*Ts4L zx47$deUF>Lc{StENM$E*(Or$>c4>nW-eP@}kGgvLG7kyDvYdLA4F*ul1W$U_mh%Pb zq=u8EQRSmO@`UrdCP32k907r#j#j)ZP*Bc?AT6V)PM-`h|E&fWm%}WRScannJ!Hh^v5Q1S%dk`B|^S>yG`Q+Rj$)M5``-Jgla)>YpTz4@( za>sLhBWOSu>IGMT7~-f@#L|iM$G}yISF9uFw~t{kiT;#)OXdyuvEj^n*tzR{Zpk!9^Xkc*LOr z1bnAJ!3#{g&xI{?pYwDzPB%>%BDwBlj-S4kQ%CiGtFdy(e0!Xj>ikmE)cN-BF0Sc` zmRLmW;nvX+c$_`ExcOSl`Reg@;mME4^SZHiEb$Ip@7lkOR!MaFzZZ49zNiK}>tuP2 z-VFZ5Vp&kVEX~c8IV{Yjc+Ggzx&D@n&SAzNDqemvdDuBMDG}iR{1(+gRP~MVrql2F zX*SC{B2rDi#s77m&07Bb{^Wh*?Gw&9u-Wmpsi#R#XsR_Sp)?6Rj0FBKz^Nm|swwa$ z1}F=?=`YnV2a(w&^Nlp0_lDO?Qm|jW$-bLE6>1HeU#x|s7=sB0evvA(zD<9**v<;w z_;WYFWM8K;EpEkKh)i)Ppxgh~y?*=3LJsx!5>`7)904J#l4BzGiciyw-t(KZBRH{6 zxQvehGfZr;W!Rd*@7a7l&FwgJv(u_p0`N-Uk4{I8Cj4YiC1XiG&UJb~S|BLSG4VTH zVca?*jl38+x<6`>c@`5fG-iVYiS5Ji> zSsjLUZYiA_Q4X#?q@@UfluY@(_bXydznn_JeNobR+$kd2HN&hWI%e`Ps7%`#U`!kA zLXC&g#pz8A=J{MaPD&Nu1C3-vF#*irl4g@}8;M196+1ODQoBiu?Lx^=;>a(gzg$pB zuY{B%-uP(L=f*UOVdy{=O}6d?jSmfO-cfY9VtN_G5xZE&F@*f3c=Kf(R7o&qzobuS zRTzx|wUY*3`bL1^)z}R&AHRwrrLwDS(#5%=<6=#rlBrM(vnR-e(`P~C)_}}JdZX!M zs-&3^NvdGz*g*thbF2D)DWJa$OtbG~pl(PniMq`)X+IDjURINg+6 zy>5f_HN5;6vpOF8)jq5OV->0LjSHA9g;Hn^V>jlmK-4FM!AgMzz}76wXWwG;N5LEp zuH1V|(G+f~L3Hgrid;9eWcW!#*Y|wC0=_akdQmA55-ToV;kYb6!8cqh^1MDMoiR(W zlCy`>GUW4$HX|KIK(ncbz1nu~P1bb(S+r-K1ck7T8ueCG$Re$K!dX4v#;y9PNrk{c z|MSK%s~&|hR*+pgKvQOXot`QZ&nc29H`{k|ru*)7?p^!SxPdv*zktZ2eDsDA=8+z} z^ULd=a7vT<0>1x?vBC|k4|MhyfvN3Rm6L*FF zhF6(X@wh)n`WHk76%@RDL|5dV7?$_ncB{w*mj#1A?LderA-(puIp(Nb_eA9b7KL!*3=f>WtD zWf9oh)hf}A{;KGilUBUQXZk?(5VXwx6rx!#458E~a=`u|FidCs36tbSC~jEW++D>w zCF#27g$C%u1qwZx%4DRytQ^FkKsTXw!#dg=ImDEB@<0pRsvJ16EALvg4l8AvK6WB9o_mLX{fk zKk0bSVU?Mw%8O`VKoG-_0z57JId={#gX-MyKzUqv51&Dy686g-V7+( zvTrN2qVg-6_7_c*d8MjbC(73A&V_IV8Q_1F^2mX| zikt}=Co1rNGp0a09_tIugv7PNSnx3{@t-V<*aXd+SoJ}sr`C%5`W;$t^haE=h+9cj zwV*p3ED>9_jRz{N$;HsT0=Zkr%v1sqV(CG_!|Efti}%N7-r@Z{pcyjUGpj-v%CVtF zr&iBP8zI>-zM!!?0AIXbvX_w$C_;?aA2Xxq2~(8-%zt`+;CXeePIV;)Ae!`8-`sdT z+DU3}5Gfg5n9#&tQN7_$F8M?WUVPn9zAZ5KXNQ;Uz+we}D-z~e+0Y|68yWN$$WREd z1N9J$mR@Mdl7|&j6HY!5aD+iq5SDF?!Ee)DeTnWl!ujuS#J_S~G#X&!@hA4ClnoXJ zbWi9kLkg)5_qc5Tx1T%^Syrni{14GHFNlH8rNrxZ@C?=h^^DZFAv-@&36Xlz3L5H- zBcw8?!zAA>pOGs}YD#|NnFx`hQBSG=c1QxH_6AXQR=Le)d;+(l4Et<vhN(Vo2)z7ZanxI4N)d4}3=yL{avT_lt@A2txt zB^X|0Rjm2~rwiX5LVU=O7gRjPEc>SwX=+Hj{q0$RwAh?9y$NFf%z|him>4`?$jVMmEYN zaBkZeQAJQ19kB%!T7_n5Ewo*%1BV4S?BQQ&qqmoPF$f4r=un$5lR(T%!YRrt=-^Bm zixl{lY;8DIR9Zl3VlIS6jirgkhs#^iAcnBUj<)q^iS;MwJ8iQ_Rxrj{jE1n@_A&}u z&tif=0^HVjR=4k0$}T+k7HyghYBN*i{!r9d72rHtkw&OvsU>c|Zhul#9;TVEr(wP( zgff(?Nsm?#h^ZERTozYvgZgs38*}q zs{+dQ#6_?_E>M4Y)vYsc`$L88ud*C-3#F2Wh}5=Q3w)TL0YO{!1DD*ketuKFV3l17 z1@ak@9B8QDeE$Q+=Rb*oj9JZZD{|8*1NNc9uf5*f6LI~0!}2O7WJ^#%wmawVR9KPh3_ICt^Bs4z8HSK2CRw4^Mr`3 zU!a1Kc=2kPH<06SB;!Gz4=d}r(im5tgM4G>*1krHASZp~LNWp-7F^cN!CoJ#jsK7iGkRQy!?fA%jX^4>0*``_mYi)%rH7<$gKjWu>m`6 z_>~isNVwE!l#;z$3Bn8Bv)=xzRL>DR#ScUD7vT~!`X!Y_#VI2YMc)1XnM@i?mzkhT zzNj{}>x^-gb{d*}Qx1Bpq`p$B<*A<*4xMihb(VdTF+|K04#&Q~H>^7AV%Ng=5og=@ z&bOl?x6@iS`}-I*Vr$fu0p390)w{iA#Yp> zk+JHvmksh?79IcnLbZ4JW{0gJ39~8|GIp9#V(7zKb#C&yZy1qf8FR$86KU2oCvRl! z=Lk}zMSWaGc1A^lN6l!Kc;U;Y1`PU}Uj5TY#l$~%IF3zFD9CybWM9@#^tt_g0#BCk)%zb~acsMTzp5T*!Mcd;| ztPpJTc4~y6;uAhX(g2Y2ielYh)1tR^XC$U7XkY3o+XGDF;+YD!(`HKh88juB$x^Ts z8qVWrkr>_zzn1cR)g3N5^2toDx_{Pgt(1_c8i$lDDDhaIO=3t>#5`SP@?Q3DMx7*& zZ>-O9pDdqw^TM_7-xE@_z*X>*U5WWaI2;`u(G)Oap0Azub4&7O<@;@Yi*nUnj7vZ> z&MGB`NDXkYR0%dLzo-qL*s|e+a?5qw?e8#63SVDBpm8;&x=N91!irkcmKpOfC5a!4 z3G0i#8-?upEyvhHaSPyM^Q^GBnu4zA1R6n*;|gO|bz?EIecuE;5ZX=$9L5(%UzP^? zH{x>as=MNHwnH~)X*(*{m`qYiV5ilNBaM!M!Nxd+Hbu#icvK-d#Y2}=r%B3=)4>TS zMUubDCOZn}Pk{`r@lm2WN`6uYs5L`LVSW0ljnD>nX8t}Ej<`8TYfHk>`s%yjyZ2SK z<0zqT3h%5=&0aMZb0rO^daLTKW>#-1_KRlx-zsvSF2m?~Ob!}XRTtOp?t~7l%mIC% z-sNPwL)~@p{OsH7)94S*=3=Sju`s6dZV4g0s$IZdie5wCY5e?WoAwxJ882#jsI~-o zh^vB^7Go5v^&1ZsYJ^v2PH%rkVUTvaks`O?-$)|+s$1ZPNPB0n zl;6Fs5>J)AP>UCfKR!Exs_c=le}o`#5=q28tm%DbzHXu_BD8-e>|c6w2-d@hh%@a` zZ#x*ZnQ^uM@_#Y*meFzaK)Ybf%*=KSF*7qWQ_RfFY>(M7Gcz;9%$S%NW5*bCOp};- zJMVYTo;~;Op0mGZN~%`ZsMS)bYVDk|x&Um9&pDNs4f=B~ml(N(Z4 z3S^EjX|vyg*i@T8z)dvcU~wF%l_G!l$)@2q%ZM-%pX55c?+v8~#_!#^?c<)Zy#d>o zTB)468&C9RY7o5;-ABUDpzaDe|wL z{rtqmSqjxHvyGVr0hNZuq@k{I_3PS4Vd7aFN(pscbedX?xplPx=Vrg>ZIk9F1Vl=A zZ~}W;U4q(MYTa9*#qBYPHKQ&`7#MC?r0cNs-opzT zRI1%FzzwFNlJfeqoQM?+o|-Q5596&=$MsVG(WndK_*)EmvD|V%#djL_mb{6Ps5E#B zQrOW3gfGC&53ERa<6J5eD0cNwkE_(@ydS|0dIq^sG;sh|7kh7QErjhJ3jA<`F?9WR z0bDG@&Nl;EYAC?IvtyQ}@V2bN&%z__ z5ehqme1d3ZC}jx$SGmk%pJ7*%i=K_AeeZHx7&+twp30ent*)Si zw5oD3F~FTIsfRGMj#yifNOIQLur;l;ib^AAL;&2aMQS2*vy`V)_yaxLN>4%CvdPo- z4tD zB6-dl;4zKjl{77i6C!&0?5A>?!iU0_rSvve;1~M`i$372xuRXVr59dH6!dZF`K(~V z?!~U9SUb1itZqh;L(0q2_sjy;|`F1`Wvz|a}W+4z>fO1#eie=meQfWj}wxOFQJ z9m{1g1fJc0;aA+%kgs(#2~%$euwgGdD=C4XpUIU16iWhCu%96=i5NEKJ5|JV9Y?9= zP2n|@W18i9-M@$yIM9COtve>UeGCag_#&#^>gP%qzYcl;A`OId_W`_la0(f+XfyC6 z(8fVStLvq*_dn3TEYy~VBGj^*nQY)8uc;=^Tky0W2?8<1ucXBYrgd0%s3qs;?r?*W1 zn?>pI0W^$f)+&7{D*Oxm6N#)sZsFp*gx*DIow4NcXY9Qfm|8WpwGpuG_%vBC{5O3D zJ3W@(D$>y2187|+6}j~xS=mI2B-5IelHj76b@w=jJALH`PC-TK z{*>Gn8k-5eK!;R!+$vWm8=RZEvxRo11EpF{UQi zZ%)wLn1SlTVJq87X$$L!-V-XS(9MY}`KyZ-P;sGCuA*2jhrha+zCZoyPP<8;q3mp% z5osQQcj4yK#ruu;)cUajApE$uU81MnbBqAy0E1DBwt$SyoDY+n#ve{miJPl>Zerlt zVnGQ(YQ(S12ZziJcdTh)Q8xYu{y{B72WQ+*p8kmm)CwrKsPZUzOqJ?I@# z&_6_=Hw6pQ53QFGRyz{4I$tTjO%_->CRnbBELY&|9_gBA7my&-`nQ)0JxK3&3k#%a z-J`p-;E@aQC#}9=m>s@37)tO;H~t-l)f!9b4VOWbJ$mM8j)o;Yp88|#@-F8^dQSZCm+u-2x+{ypG~sw^6?OvQh;8&~wX|?aiTnoT6Wq6RfP*;ssyuc^HI` z88u?$n@{xHtnG%XF`R>)?tbBwbqX+@ie~?TRWdeY+KIfd-M57 zeTRH}iHSKfn63BA_g?QGkTU~47{5iW$L78D8yLCoHMhaq3pKb6{G~nS?gK5C=MAuU z(GfjzWx83tM+jR!KTTF{{yrFncS7f@~+(=P=I4<$kA@Vt0W5eNbXh6Pwy_SC<}u% zw;jo65&*dua*YHb*IJY~_qT-eCRfjby!UChtV$B=oI<&srox}Semq{+FEt{?le-ia_A5_Rh-mVq?B?i6!I_JKu zks-HL(CVAbvVf>JP^eqnacs=Cd+8}XS~Qru-(r~$V(JD~BdD3ezako}W!4o~C|5Eg zoklpatMX1H{E#A|8KY?N3hqJ2o)!O=qoPYNpgkR&QGCfbtmr$T=d9T7)p2))e>PB0 zaWkDqdy84u+Kj&cybi> zUDmaJsolFsc2rJ^_vWt20;t)&&r;7;e`b-k3!R2t^b?(Lxt%YhGnPuBdWS8Sx9)F{vd5IVHsN?MhAwv)0o#Q1zum=NTzvtYf-@0(HqYvK zZ^009W9(;y00N9Za!3#SXg==PKPi~TA1fU_QawITmh#E%*Y5Z=?-$6X7g{+~U z!+Ae@(I+qG$k%pGwJmFdXP_CH?O-{6C5QcWQi0$_DQpT|p|CqK;lp1LZ2Pbzlt{RU zrV(djm^0+by{Qc^(J@GKXpYT<%8{|xwS@R&o5Cd+(y_2JQT?9oBo*v**5=@86io02 zcLM5Qt&KkVMerieMa~#m44={L(4yN#u6U$!jx(3<$aU6{GflDABi*Ba;v(I%>a5$n8Xvv@1y$ zJC*U;8S#>HZWr%dygzVLHvAAW?^A4d#%Ab=|wn@;@~kY=Qz& zU+JIbJpax}4*#X)!zt`rPt84#6InXbG?y5`>UKkTX^cI&zaTT_SX z;8X^mrq_l`6;Y*mHg0IZ8s3SBc2nG`ThE5==pp22g;2k0cj(aW!ENzXw)SkxV9}l~ z?S1SdJ?#qlrhD~*hj*3U`vWazgaUayCDVH1& zjehH|9}~Sgi+4#kOn5-ryD!}qiWeadHvaMT&-^oaZFffrOB%Q^#anJY@1?$ylVNC7 z@oM2ZYp*dg>8kdiu|ttc9-1vqOe|5hLpwwlf&c2|yvQ}=Ffx(Ld9kFgG0 zmT1Di^)=?iqseue)MZj{>#MD`G5g!A#cDqgm@{A5zL=((i6El#tq5O+(uwFj;5c70 zFPhTXuYttk(I`{`L2J1=l* zyWlIXcz(0P!M;2`<$F1F)fblP@kJE_q>Z(CLpqQ4tXa|Cj!(-TAbc7s-EE&@DfGRh z;B!m=M|RZ`7_wHC-etmzin4(AVMlX=X!3;hD)g5R4QkrMgF48ukmwb;n ze8+K6A1bZ6cpGW95tt16677k&*XPqdt2+U5kIcmAWJR5!TH74_sj~FazAh1AL{4D^Ft1v4+Z>YuyF|zbCP&)7Sjj2I`JZfUSKAxYr^4R}8 zxJkV9p?Jja7s2R7Tq4%<@80byWQ*Q&8HdrJMHwsAU9X!SZ=`l65gJ;wu&?JF# zPwY;=69_VSgBM>x<9&*yjwCjtByyTJuQlZFnB5ic2||j!b0u5n!|Zx%n?D0ia-O$3 z3)eUtm91l==jH_JlbqS%ul1f4Pa3^8t2(@|I~O8wXVrOIH~F2y?R`^x`<`63pyh*d zcJR8JBnd0GK{l%+LLy6JbJLfq_K(jH4|^n|k1229y4V^Yknim0lJFgZdLH@Qtndl0 z3Q2UMI7^stCD#O9WP!6|8EWGKrwm$*a3QJmRNMknvGiR{9RE*IPGx_5*=N7sQ(E8S z;=&bux_pqBfvJ~ASe!x8M0n5cLAT3c3ZP4%-xJY$1N}WMs$5sShri4cX25`EgL-Vb z`u-US1R(v`~<3p_tMtv$g*P(-(?3vEY@XWTx2ef7<_Hpf@od0zL{ZTv2kE?l5 z@Fh~Mvmd9^S|+#~&AE^+3>1ISp3#Ik;DGAnyuSUfMrkO_X83~1^(4=Lg`6)N`D~b9 zJGJTUh%Z=1m!oS^dx(EZ8Cd*}G}_}ge2tf*Nq6cr1UC z_%z{;sXq4OM$PDJA-YUtJs5<eBJtfsy;jpj|E=OJkYgDSVstjWAf z`z@XoQ%^m)VTt4XKU?qL;yVcadT4#M9dO<5S-fAdXET6tksl{!SwcX~0@vHZt+8Xy zR*paS6ToylVFmiEzt!^<-wmstRA}>D|8es^_&Ua|?OrOZY%_`yl$)m=YQBF5i3FLI>P0j}}qD0luTb7LVrKCV#;M zg-^MNjVL}tM%=2bmd*GkC)+uF4kjjS`R9lr!|+Rd!Bp+ie@{$}EpzJ13V&BWyqO^) z=uDlt`4dMN!PjwCSrhGjElH^%Gx2q7*!@{+ij!5w!5dy^C|mLA>6i)HEG4?0lAJmV zr#>g*Y4DEyp%Q(`0&keJ+GGPKgo@JWlo=b)POy_>tBY06P^jh0WH-D9nW)t03`oaM z^P^(GEeGO)B3oF8kyur(2=;^96L;RiL%5|6NgliKq~9JgZlCPsq?`It$}8va#k4ld zo!lsiM?j7%TDs=wR-a#*8yZn(T5b}R=ZeMT)|P*YyEj%@p8sHVUXMSR_LP)+lYGlC zBFWV;3uI2BBRcDV;vUoMIkZfpECU^DI!%F(RcP< z+<&#c2qI}}ay(6SG6Wq+i5!;=Dbt-p<<_TOJSOkbZ=g@xZfm(M6n$NX4IC~m_i9gD zIe1G~sGpXcZH{#>w@_rqZX-DTJ!mr>SxnOS%m+($YXq>TyQZrcsx9(CDasJRgvx<`hPcO3sKD(w92L^~(u0;pMiqq2U}^2X2bTiF`SWbFKn3b)jU zx&eZ3=$07rZtNzC>DxE1r<2p%2~g3d^^QpH%;Xj<~pFZHo|8*%HHVeCaKl1`a!mi zup#f!bPXIz;@C+|6Gun|x>CPHVJmL+&1L>r2z%hY4{2ONFp~cX^2PQ@X zZT!>ns9a45nIZ^(|2};+zN^^$C=U4H_!T8FuEU_o>?+Iv?ZMC~+N2Hr`0mx#0lp(# z`3JE&GM4VApz{K1YidxYl*qb<;trF=cMifsx33-ihk!FWG2DGxieXe7N-tK(NN9K- zlx8f=H*fMSv)GPl4D|eYkhToWZ)nfzHP;t=0a6>Git2GfYSGa%5S9GPae5pK`4;6Ps5j zY4rWPaY+|ywYfiY18t-ta~*9;&I4_L0N>!?uh^=7b#u9QDmd7vZPB2*B;DVdz-qb+ z!G3jnM%>;i6Rmk$KAovAHyrM!CjCerr+!mliq%|MNs_!&;flueb*5!XM%Uglm8nkv zDG@Lvmm$~Ya9b{t(A^2L`MKP?g|&PAFs!aa-4am$_k+v3)TJ2iXW6GgS?*Y~jeWTh z;M~+HI9=!R$$w@;`K`#im&a&d{!ee*gnHKP7ajk;meF;VV$m7nNBz%^m;&1|cH}I! zDZL5OzolTc8wohOvl)X*%B=?(MZKSki8+sSiJh8cJET_$%6)kXzpJl@`(9uB;`6R& zp)P;*T+d!4f!td_%g;WGP#r(fd;=XjcweRY!nU=X$k2`Q#jZ$ZosQ=U&s>L8gf4IB z!q4E&I%E!?L&gMA*O&TLNN1L@YTs(eRj+)vrr>&vI7ByZ`SUh!bD-w#`m9F!uUr|_ zP;l019lMNO_DqItTkw7$^)pEgnXYq9toqcZGi+*jgLtz@qn^y@bT6v~u+NXL44L)4 zl}}Hych-NIMDE;P@1_V{<ASI0iMY43N}kmT12!htS&}sO##bZK2O5d?!JWye()yXe_q~s9tKnN7L z*0vdIL7hnT;ZS<)kDqt5V zuqKo&mnl^@2p{pJ4-uskZVQc<=YSymnQ!?QA>Rnh#43wvbi@_}h!s!Ep@?Cmu2jLX z@ffkPXi{=JU=S?Fi^^N%J66`TWOpbsVx4(^!Qj8%%IirIbhamjArdb>hhTmSXir%9 zi){6Pyub5(Fn}&JG*CppQ^>vXGt5XMHb2o$Z~CRLW?^rEQdu|3v*d4S5Yt03>Z(GJ zrysE*sI{RXb1{T7tTB_mS!>WRZAzGp?gP+4BmR_~`ZzG|uc%2xqbJ!2u!vRWh#*)RY6}uZg>m3fTLV{xd`Hlw>kUV? zYOrqk>NKdauJifR)Tk=!YZqb*8*+dEk$p_WIzG@R5?S%4CJj5y4#@vTfu%Wq)=PIK zLz1QWzcIo{G%|SLQ1|~76D`b@x>$)MhHkRPo7tclCP%xOb-5!!p#&JfMfeX34s~4O zv!kJbH_Kl6MnUr;R^CTTXZ$$r0#iP6dd`chdZuYq_5Lpg1>DG;*_9|a9#2E_M>p4&LWbXmQs1;*FYeZiR%~Gte6_pkuLyKUl z|2?0he zt7v#|<)`bUBwpVyO8yP}Zh!9FCl|gg7(}Yw+%bH){2hiMYyS$y`6ekluB@Z-LRj+n zhY`<~MsQTBo1XwrY$(l@XYeC)XvnK24|RivQdi?zVANSHJFkhKVsGQ~Z1N+55F$vr zV{wYpgQb2_%2w9gLVLzUTJSe@3I7zKusPrHL{CCdsfjxd+>%h^*oVj5TG|J#xVZ~$ zo5o744{>UXUI<+~E5K&c;Wx9X$uSE4gQw-~nuelJDOFBc^I<>i;LweaqPQYMrD$~4a&trb!Mm} z=dxVtEADMf2%i|R6JsQwSWz?H?*8_{`6psu4XgcBIUO{%OS7hApF2dw7{&5Wl~B48 z-sxROwx>}-G}gE@?}SG_W?*0#DNKIH<3z_ep!884x;)2?*?B%tOO9iG1(BR6#fn zgLyb(p1CO7j>lH%`12=b0hGOqHCb{WSsF3zXqbFyZ7gOS*MJM(SQK@%U2N**?F1X? z19?~d9Y4J^+7e{y14O%eEL6Wop4@-RdAhiT_^W<4wHFA!!!kyr7^3}Y7-zMh-OXNa zCWwpL+l2hRi2I)5oMHnvNZkto(MfM0-EJ@5bj-m|!{_m!o#*276}nL4v(j*5R*ldb z2x9rydqrmJ?Ejy$WEzOU`t(d%)ni`d+q>)fE&YvJP#4I;ZJBS1|wT2WF(rp_G}S}tDI%uKNz;gPY!{2(#gEZR>3 zeb<|#p3(KZrN3~~P^_e!Nic)32}lQm=&xE$o5YuH_< z)FQYHxu~23c|5wiH{Qi_XR5GE`Cn&je^dn=$-jEOEvkxjl?&&aq$_YYR)Z?3F*r3t zxn@TQJG4^;CZu#9-EG~B5$ciBY)pMowNJ|t+9ZZQ1C(eurU=In!2@vUtOe_5Nhog8#M_Oz8ojD7ublELau%VP9sXI(|+>e6&{lpXag zkv@;|<4jmbiv_Kx>_h#5CTKg9!>f9rmCB*MM>b7k3Tgpmd`IMV%eB$8TDW#b?{JM@ zOyT1R^tvOMET|rflZsh`aw2m;7Qw-Or=z%$qs$EHaHuK91cjx#1F*9ZZiK!fDbs2= z<6x#nOiy{qe1eqhgEyle8Pi^dvGo1=o5Hc>o5N9cs<9|@1D=W(Xp)(VL5gYVo9b%L z)-Z(9ab2&z?H($^KqHJj_k5!<(9I*Oa_s(C=M!uqKQrB9nL#_SZ+@|)9eAH5fnVE= zvRgyY(!Rf%qAHZ%E>QTh8KEga5+>hCt}Fxi8-tFp*`j@qI}?J?fXnNw{#t&u@-hZv ztE9hxIVJ$uaJK{MeB&LPxwZ`BD2=kpZ=$flRW77u?0gDkZ<}}hq#Lw2Dy?##KTyTdq2k5Kh zy09(^+JR+Rrs(%WonV~h`Rr@RKlM9=t%VQiEE*rKhIrd7B0XfGH{wmEf_W9fzEV@< zJ0>s~j1PebRQco@A(N;e4MRAJ7Qp(o6ZzrGIBnIQ1u_lSkf+qC!tjqMG67-RcF&{Q zRqn1+(qrYbYZQAt_1At=>!Z~EHPqSc7}ngy>xSVD!f#G^Z40kR`cvCgGeZ_%m$!iz z#@~OR8!bjxPg4)m?fQM@4##}TQ}AoMvDKaEsu9Ri4eCLMwUh}ZKSN@^g3f7_psiK4 zl`2!fE3-?Zs3wmGuNU_+A(<+`62_7TO=Cs9wvFm4uB@>2tA367uvNahLRh!N$N7c` zKE!VrPCFV@1%xl(OlUH*ubVMOPFWu8ec&-jzBa8U>tTj0mP*Sg`n|{{gL`h`R@->I zKU9Kp)P@%KpLmi!$(prb1pJ9Cp@cm-q$l^4NpcUQ$k;N(_t=)CY()mf1rI%=jWIr6 zvkM`G?#a)LJjV@jXQ+oD3I!IG1z@(}gV{Egm+Sm2+B{F>o#$RHezjjQ)SXPK_^%Qs z%e+L(o}`Y#x3Xc@7)WpW^8dLM=9NJMNk1~}Cx4G2<)?bVWn=wA7tq$EnHqWEW?b&h zleO?s!zqjtha}ic$zDm=$nd$%NbUD1B%Vwh4WSAY=1!-7&2rYmhC4EV(T49IlAUS9Mlbv@~Rwj~Ya2f7_fHNopN}j4W3O>I3VC zSwg-WV*AiBXlY-#T+rW!UIdmd>v>As8`u6b2X&>&s`t)AUh7cXa#`c^XQe$gmy7>T zQ|jT&)MWHKJ~q?e)A!8UT-f1&)@kS4T2M1?(^k^Dyu`aQ()IqUNC(x-7=|g|{g42hX=GX^6cq;olgz}gs(Ih42_J&zNI>;s-M@VIccdJKSp(<+b|8-=WLnkr1p-{CUS2dm@bCPEk=O}ha4%_ZLKEr(XLt4_ z1n4^q!J9*;=I;$ujm5K^vPqHij=|(vu(|dL!V`J zemnB^G{k@nba)-sJUkZ*n;^Ju z9nz#bMy~j{7>29y`nGNsBNf-D@GHceprY8@F|~{{vKQpaRuH48qNh?0i+6@V(z-L* z>F%zrS__o!FP{U|$E?{Wcx-j^CJTL%n6%80F}} zQVZ2uybinAw}#BgS%&g-$I8e7C%A+PL+tu^%%4m3<0rfE0QX;-u_H0~w>jK&6418d zVes+oE^zGBd0UBnu<`4Yf z5uoFeXHN`q36EkTb@L%#Wx5%`GerR1I0fFS*- zO~c+XXAAB{&4YxZvN^irLpUNP(Zn?mKy_kMFJfq3% z_&SleCJ7%zxL5<}5d(6A$Bbt`So!~BpK|}k!P3qn6KcA*Fg}z-GUxxjx#J%k$~Hqr z9|V$g?`Kq5NN<@a=((xOp&yCbuHGKBVBw9e#qu>;sPEVv^~-`oa@E%1H{6195jRiE?jqax@<>AT*U0J zvZ2-$35d7^vDi8mjHDLg=E=}=XQDQY>L#m;YO)ri9|341W)57srXMHJzIA zaW)N2KPDY86WW!O6YH#lWr#AtT-G?D@Q$c(@4*{OxE?!GI8jp3pTXmX@8r#WEl%{u zr#vqQChwX0s`=svr-$UP!NUFmdC_nP!C)HHSG<~V7rqH`;z>rfA>uPG zvNtvWm@LA-NI&L#S0@Z3YQy!uVyBW>t^W!pNZG&ml;37!XgBoSM$Y4%+?)jM$es0B zGFBosKU2_#rLzGbr&us%T+SA1kq=KKB)%8I1rXS;igu(g{TVS|+_)DvBjV&+KbfC{ zKAi|S=zJ3u0DbGt{pE0$j(Q()F9Q0q&p90KF7Xb^8y&dkjW3^B{l&RR75611-GW+~ z@;e(|o2POYRcKteB6m?ye(#PrSPu6fj|QW4=?#}nTKAh%$~Uf`aaVHS5}y>Buu?gI zIoxkbEC)G(s`&c5y6-6IIHstGgmYw7CI>wUvqUezqDZNfBAA@sl%$WtO|l5? zl@lLcOOHU9=QYK4iZQ3ZIMqzKjy}96jJfT4b1=PB*o~f8teK|*K&ZM{kTe!Cur)7P zniJizyk=-h3Q|OlmDb4>u@qCm`jF1o_UYlL6mluv8JW@k z)=)fESJ_^tV!$$CM;2arz6YP)4<4$$5rua3sPG-q?Lpal>8zizR1}`yjiY+qeL4kt zOQ|U^P9~{0n+)AA^-`v2rWHXcYq3$0u1tlMD6pmv-c2TxOaFU_4ox?JV=SW}Zs8l(Q)c8@&T-?bSswlo6X{ zKCOCb&{X5+983$fi+)X~*fTAA*qvqje$^2bIcygoVR2EV;tKk6AM^^Fh-*tIRcHR| zouysZmj^O`V{qr&kGSD&>sgC859ZVHtDZ*U6}{~9T`_1&IJN_R( zuWZdtlD`ZyVdjLh=?=&a!>-y*vm-@XW#=@p*jeac-?reZ(a;I?!ZMm+&@Sq;Dk3w| zD|p)Ko=_z_K;46e7^fY_TRWNwdchYZ^Zw;>4~~}D(zeqhS$mL}v*n5Mkg%DF@+Ttm zRFL_>-*NIVDtM{oWCh{^RpR=?W%#!9@(bvLqarq7DSr+FFVaPb3WO#*yMF-{22~RE z-A5~$hp|Qx?5+d_l2{EnU|cHV2AP@S>JSbxA@niK{Q#9#oj39NJW972OZ z%a+ZA+IZeVS0Ip-D?bqUb)ge)`NvpltIK|>rgH9i2o|Rgn4x}=V(%U`t_(euM7RMn z34B~V0D5Ig7*P5Q#-*7&h@?ZJqIzlAWl~HNJ}6gSPZ4yD?MU$#bXFfhZ^Hz}j^LZ* zF?DV?^`m{AqOjR!0eSC&XexZ#7djGmfFL=Q3UdEcF!N-ob{cNxxoG<5;4CI)|3(<1 zejFW((jyZB-)wX&)uq4!VVV-yirTvRgNlI$2$Ph2i7Ir|g`hAE*;orncKk7v7;<@f zNjNdUI6o=s>$NSULH!OfdHj6E`a^;g%6%;l-m3>Ud1X#hfXbEWXM^TuZsI1^?xoo8 zBVc&B2fZY#;(Oz+d!Z9<4B5rKv&hxsHJMojYZ=jKvN)Y?0xyH^adDqnNwa zI=*1WsvOP^8}3w5y`9Q(_2lY&Qip`+V^~R;@!(aFGa>$)|4W@n#;`@8{+EGevRM+# zg{q2ai_cTRqJ>DwU+H>F{Edg0V%4n_K`>+y0{eYQb#t}I884;qqp`v`6kGqZi<^J$ z*|0-`!qxFq+bgfrB$(>nutQ`y+5Rlw_qDFJz9Ok+uJ&9N72EU1lcl7_t+ClN(6KE7 zJS82G*{p8KcxG2i*IVRoOm{ol+|ZsQUL(wdBd#W6eE+eAzOmVzQ~LOov>PNKjE%wa z#O-o#=Cvlzm%O!7b3v`HjTW1>tW_rTjJZ7|^5&2B66#4$P-9m$YL7i>>&nI%;`tiO zpP3b>wFx)EoC|;Dj(Xnn9Q*RF>x12s^d_YgC-(Y3V+UD&>&h#{mNvnZQJXsRuXU zg1C-f>tbVaF1f$EzAnpzKQI^gfjp;;R!^3m%x}WfbnQvbAK4?G6n~!Rj;!rbG{#R` z3~>7N%l$b&!(Gexa|k<4+>h$cBJJcL2{5-1seBlu_!SXGHIx^=21=)rxNWhPrUrP$ z);S7-kkKZOz7|?d-rNs`U|XOU4PB@B$M3b*gGYGIF{J$7e!>=F>r&^m3z$SM(;%j} zrI;xG3jEfb% z?J>PzbG>ml(zFZP05$rlMYwImLi!fC7f+5M;7yK}_GK7WYL=|4(1>qX1}r+uEAjd# z?`Yas1Ysc*5G27cUgy%X{&c37WFLrz<~YcFRKoVz0Lyc=4}5d}2*5~M24TSz{LMww zIpRqM$dLdo$k^8k3*R7(I5YvJa>!4W)il`I>>m*~OA%^7+0iaG-~fTkf{goVNnWZf zKC9x1BFZ0o67Z=1h*$OaP$dxA2N|ualc=hMJ3AFek^!zYI28uF5ziSq)+s}NS;3>& zeWDpEA0w}uwg+jBkbJMqMe9izG7AQGU{6IDSU-(|r4lN2sZIe!sS$$RoZ&o#OyZ*` zTvAuH)&bg;A*s-8hAeaR@lZ3U$O9*i^;U#i&Q(Cxrd?@-kSH%vESLvryuPeEKSi$( zP9C%N{8r>{qQ3|u)vONTq|k{NP=eR4uaXEglhsw+zsp0%)39S_(1~ELOb6Ufao-^- z-5~&y^-6&nA*BxBhNbXNvVfr+%BwR;r;=+91^q)d1YFTLXpv-`x+MQk6Nu7b$DY6P z$ru2j~C-+e7@Q73klQ=3Vu=yz|37l?&!}!G{jTxmekgL^6o#ovhii9pX+< zgBdl@5dmR<0YGUmsn+?O#xy~Bx>31bkShv6~GE3b#4O-c0o%ebe4%3^E<)QvocyfX*QM9ijS3;CBN z`CPQkV&+5}h2o`ramP#NXlKjav^91j$2o9cODSn1}|xA%POv$L8z zyrYb!30i#lUiwshb9vWtcMAWxNuf49=n~SSI&9$>C-CjJTEu=&?A{7xui-6SXf)b( z0ljC_n_+C9NO-NLoLgZotP1ga-(bq~Ce;sb{}T_#ypwG@6d?37!V@%#vX8(%*g%pz z()hEpdN-17{2$<}GVq>H3;56swcI~4Kp5$RRQK`ifCM5io^w_u7lV7!7H{c zV){oP0Xk~DHSwb4VE@_#0H1l46+ew+8_q0PH`bowD?aTIihH#i5Nu$QmdCHmvHGw0 z4{RO#es&}buwB0t`Y~jh#RH0isMy@i{@I((If9*m%y9_^(4>9rL4jRhU4noL5G2Zd z<1g^6I%u&u_a3}5-_n@fBfZ zB4-)N;Q6(J>-zNhgV5499F%?W?|)v6P&d+b3ZAd$pFE;5f-Bgs_MokL;}+}Yx(Q^c znVqDu(#`a6%|C6$f1GT2llF)o7`iIq_8C%uBoy2c8&VbO&N`p+W-awkushVm?By*R zx_)x;59Ym$mB0+>{RI-9nVQ)W$eA|9h8){Ep#YYK-LQ4e{=mTxEdfanh$s^vL%A@5 zX1Fon)0A(IpI&BoQozbX0$9ieO)sJdrjNh20HwnF4K8NVJY_@3)$VCNeAo{wzn*oh zZy$v;%?@B!N`|iaMK#nJoK%@G9Y8R>QpQ+7qE{?cHxEQJGL=w3WS;^M&ILbGwH!U= zVf&bF-_tp55M34!Ay}P|*Upp=Zn>8ZhWd)oRt0?-2}lCMujddfs|-Q`{}*F#6%|(# zv%iuwSyL$-k!QI{6T@u{wpZEK&{j0o_ zEO84bIKzA!vg`R~x|Np5y)-xV(IAV8JbCvgui0qzH+G(&x}jAAC_1lTH(5li$Eppt z4v?%aep@mBDAQILnynGMATEHQRLtYQ7=0gGl+8!Z@x#sT_(Rn#>QhA02CUnQ#{Dxz zk~hsYu0PG`5G>U>aq9@#V&)+sy6Hc9<^TNc7W{L-X8~Q{clB8)E^!)(MBw47=27S; zqec?-Ff)4qRBhN?BpEL1Nz?)V`^fU&VG&r4f0LQh9`zLI=O#^BM{3xY@N?v0ma&g|NPN6fp z3Q+Hx-jaQZks$95yQLfXJ`+eJ815m)BQ+ho5h(pO2yWcOH51*;tGOm#(h%GOk)X3Y zsGS%1m|ch;(j(W;eNru#xMvaddxpS92hgLYl$`&+6-1<6K#$Y%b8_+jpA`|6bVC0N zBQ6(AnwbzRv*OK@VI#wG34;cr3_xh>VC(m^L_4xqCC7RTA>WsqrX4wrfk0N{B>CRoxkbV`hL%rrNWrBnbC9w$$5YM zyZRObd3hYI@+;eXdr=LBHN|eD#o36u%QJcnx1HBlbYwkhKX!k};bN1~eFq7>?e@03 z_`D;(y+9Am`rRh@apeY1K8PLvUCrr8#pDR6S?TnBK27;W_SU)icK&w}dYo3wVe{>Z zmT@<_ro^qO;r)OFe!j}R4wVN<05QRweZD;eo(-IHv$msQy%|0dCNrAeAV+pffDj)H~__?Kl`6>LL zm#3h0PZ?PK7sW=WP^%AUL+8CQO;}_jb32Bp{-q*&=GdK<~iz7AIZ9-wF-&g(r?k`?+ghX@E8y$$|4@b zJHsqgp_B(v0SR>w>2zA@s_~0PXqhY$1gf~yW4#R1KkH_h%;6;9`Q^XC^tDxeh^5U# z;3vv-QG~MwBbX+|D=e^aLY#Yl{l-p|fyaCO;dYxmo;xp-cjd0=QVQQgfVc7`By=%^ zN97-=u-Z~O7VME-fPHmW9^7nrSR!mqBsdL8ILKdJ@4dr!sEs9p+z(=V=DDqGGUtFd}BP!4W(@GZU+sBbS(*0-5A6CF@0jo1-9N=}a&OuIS@iv?h| z$o$yNc07&WCnWI|qP`H99pTwC-*JRZ^_$Z1GYl1HM5iv63UaWRlK%?rb85=LcU0#~ z`H5b$2hz|&+bJ8QW_YStt@@GXx?Y;?LRd<3X_aF})hXU-1{FgQugmF{`n?!e@dx#L zLFP<7C;9g#kVU(r?s(c{UW39ezSHpPu|L4fJZMIj?WZ0*#5v7zAV(s37iIAYu}?;# z+VFzBA!m_;)wKZ;3m}qvSI5h`yoO(>A~nO3dxIG1`aQB9y}D3e2n0u&uV3gANV~og z7%M?z!RlV7_%H3T085E=n^i}zoecP9iE!HJu^2yL2bR-)mHT7TcOF1ocxlkW<&jt= zTgfr&z~|Emp);!pjI_a;!3Z;|=lT`aaT$+q31&5>BM7Ue_$xQ*(?E*(?L6v2ig9f+ z_~G)ts<%{#4=pb{Cl?t=nohmUKgE#A=#-0Kp810&GmB=#-1w_R2Wcm>Pv-u^UeMHK zz8V4?vxR_)cj;BJ+MP$D^gRy|za2?-B=V|KUr-4zWPVXKc2Lbeg^{@ANDXln<>Q?m z%_NcBhpW}lVNEi+iA1n2bLO4B)xdZ0hlE9>FC_~)dCeu_45psEr;F^YkH}OvJrTp9 z+CKUP8nuN>f*_w#p#n7{1Fs{MfG?lHy!Xu$J3zbepv2?@X=Eu7b3M%`%@JaHci@$# zj8VrlWS_Mgqn)lCDls1cv`dujx)K4g8$u09`EBky_gyG(nsf>MIS&oG(?$TA>`ywp zl>$^OLtOOmcp?PPmAfm2mf(jTxUc^@mMuT?TY-<1H`d%tBV5;JT1c;mPg$V-ZFrdg zR?3u(APvz)^MaSPH{>>r4P6}^dsHf5Wy}YNMXWxKJ^Yp2P;=mq^7!Z(M1ZvouTpiQMjFhSLhX_H4x#*rIo_i6=~3R`k+dj9 zSq>QBqw$&2tn^eOU}`q51w$6w@$7O!#q%9;1Hi){(w$=0d~jaDrC6{QIK^hqPtq3g zuUugRP{A5P2~0v|qMl0sMGU-5h`nTKj)XmY5KL0N!N?q+kp)0|t)5}wLbf(+l+Vxs z?a_Org__^j@b~wOhvVJE5qcz8esFzQz*mHqu+J0dUeuh76#hp!h4^K=8onnbX;wF& zx5jXH4?{w=JONmxMzoU}Aq-!LSx_2HbALB=-${FuBxb;v*IYNFFF_M#bYK>Fhf&xR z%n+MKPm`rVi*aZKm+yb`9TJMLJqj%UybxM#W~3LJ7IatY_I7|#f@eQEmae)8i#4=R zkdW7ZScN;pW#M>?=g5ceI)ohw6)c@;#)R3OY97!Y;#f_@H>d0%g(KdNrFj?t!%zd8 zOlCbVB*_4uO_#AJtu?7U_dms0|JjTk){*Xf8C&pB0k3L3gjNaiVyY5cw*2+Zy@>Jt zYvCxpTvL$ucA#a``JB@3YJl_dYOb;23OZEzxR{p0^cdyf7jOZu@%}z+a_Gp9I=UdY z7&Kav6ntl>Zn+r>esHp)YyzpKZ(_f=bI{fGnLwrd^KzPGvZz76_z-nN&3@`<`wJ4@ zglQc-GXCXdWXRF;@*p)w;|H618;OA^W5QhaZ+)n=OkI;U%X@`t9S&DXyREdh8hv(I zwzrs{5aK@~O9RW^oUP#wgl zL2&Z@g)rWXk$$nDO`ZcsAD$AC-6QN%7Jy-xihfd-{wxj4kkZ)p)6gC>hvYknODeG} zl>b^%H?-~3u-lUiQ@JMC9eV}rhvtxMlXsBiIxr4 zKtb=VWv-ZQmyqYGR#wl^QZDK+%XsIYf+hQBkP=T}M6rKG`z8GZ6-}6E3&*$YN2)#uQ$!D6O#Cz@} zU#TtdA9c}5LSqAT;$XI~7SPtnC^^INphMX?mvC6b(`Fi8MKCEk6_o8adgk;>B&x=- ze3^rni9boiI+TV^EQf8A6{RPWvKv8gaTd|LNHh9wxI?xG5F|1uygv+UJ=|KX!+i*e zCREW(V!8;g$TJHN4R^~EjQrOi>UQ|n$p_xu^5?h*_)o`1Un`1#pKgpQ`|M>s$0-Uw z&PYr8X03@WN!7R>4?imSqf*eMoP8!JcWI<1nb65zTFATxeQojZx;b`BBdl9D5D~F! zaeKW%$sKu`>uDmhAC9AHMo%n1ih(^W$)Zr6!Tu{Y zJD$yx&zZ=#zgqD*Tz6CsS2JKqO5Br}gf1gG1@Qd^cj)q|2LUpV%{J01`@}namNt`A z3<(Vc_8xM;Zn=JSF$H2aYW9akF)P!zaPa=ke7@f7RxoY1C9q?T<*kp94L#%&=zC?c z>Iaa^0uC9Z9(2#CNQ5(42tQbmwH(?=%)5}eNUdC6URoMHg4IHU+yvc^?eE#h$dh7MeXtEjC$d?;Bz>EQA z*K=mNmV)t>AP-PV-r+I9SsOEOvbG4z;^=x>>c)xbX4Pnx#O#J89`-_5eOCf^-B| zo1Wrl-kSQN-soGW-a}J`t|M_sUM_Zsq5VD2qnM~-u0fn($h)F&aBC8RIX_C_A%cB8 zG7vvFG3I*(>nN$+*gh_2u`qD16F_g)7S2kK+v|xK$;{^u?YEmH{7RSD;TFo!w#i1j zK4W*h;^_u2(gSmG zpRy?w+k-GT3aTi>+Ji#fD7FPHAR-R+iV=sYKkjb@`p{7Ju5MP*HQ?F9d|j`bh#XpM z-20S=VT-dU4i**GU za6U{TH@4<>3vqbqxe;FUNfdtQgve&{@45tdu3Xcl)`(p+Zv`8ZBV%wt3ho7x;PvTe zL|866u1Y$|ziVREkBR*QPTmXQ(qoEvPy5(}zhVwXRPjO#o{>}LtEIZQX$$WCe+xB# zBS>%`;7udb1Q~gPDA_+(aTLgU~iRGLB_MaEh&r9|`T8fi z!FSh%Dyd_p;ExKj*pti{Zi$t&rcCn2iT_b+;TBO_@`-II{hMTxk%(ev&FP0udt30G zGbx>s5iqjAMaZZW52(CjuO+|ZDPWr?;_xF)i?FZ!=nJ9~t>n~0Hx^V5@3B`#(``5z zOx(U#!a+g`yOxYAIiXVVPFw$DEuvA9<#KSqJv&I;1niI9qm9FTehCFkNd6M{mMO^^#SD#g5yv>uwN}SiMW5#Gzk{a{(eQCC=}?p zdK7Z?^SD=0#3yye?pc&5Xie+~yEVU~?3c>#Jm;17LGA6qdjnMIwPq#0oE65TJh= za!#qxxQu)0l)u@bSpddflVn1}&@++Q)R1c0MBg-E4>Mfo)tuLpEc-E^TKh}r58I%O z8s==ebJ(Hz4s3Kj`9gA5$-0}ea=v={26FhJ5;m9D-?~1R;;>Pke}8XIOA@+W=b6T< zqQ*tWvYU&FEDwungnpa}@#0>7%h6~*h9s!IXNx%h>H^| z#i8dX7qaMK(>)~a*mj(Cqgy+v!woSYCn8xT0rAw-$E_5)mT+)=ZOy&5?{R*gAYuBw zJ%Jb9z88vfPT_)lF|TZl6!oGZ#LL6rj`O;skya<&ebPZ|)!-fvYVX|Kn2O8Ip1FPQ z5o#1ROb)hN z4!R53I~P(86}32278NyEvUoTB)56lND`s(?qhMzyce(3^Zp#IFTeM z&=VnzJJ4@I$#fE?K}Jq-DL&u)wNc*N&ARn~dW?i7qB!c1l7l+4jb#4R zMXQQ3XjF5w51L%zNmvY2N;@qj{gv5*okaE`TMF#pF3?Bou3;s*JtdTuIy z9IRaKm7nuuM*!!|>o~{jqXm3#|9o_Xs^}L7+HCkXcsU;?LmQw8jwsuBZZrI-_4>#JY9sY1WW}>?V&mDH64n4$xZBa56_{ zYq*f#(JEWmGUUoaZuOzwffR#rN83?JBPeIie#epU`zH>C>(E({kM8z{Zjq`A1_CID zg#IH{*6EqdKp99UJDX6UYn~km=TPIJ<#Ubw9&((XZ?&1hnG6ko$ zUo;q50IgdynoJAVqn>vM?ae&bR!yIJ%cjxSC}p^n)tx!3Wd|Z3C>bT9GP#G7Tr{l3 zMq1w=OVL?pul{VSq>e{Vk^91Z2~1(X*Qa;8E@5=zp;a+OlDsa- zT#SfFPJDf+)wobtcPJB0AP_tL(}yAKN@2c*pQ&r2$O64kQWt?x)ZKh$^%b-xb>mtq zww~QOMChy$^XF&Ee6(IA7iR-f5niUe)8sr9+Fgv{yr#qSf*=f?2J(;WSI=5I($(bj^7aD_v^D1l z!yNL0hQozsLz9}XUsx}694opl0?2-k?vB;QPV{eW$_pf{6NPDXe*O&j8_s2unt>vm z9*RL~(t803VX|w}h*U?M;Jz*Qo zy+;0A;ylgf!AUZn*D+k3}S+$;QX-2j6fniwsoCo`?;R${Yb-5h zKeWSXK`+}dkUB|4x2`&W_bz#PS|9NlH9gpe{}RA$a;XkyL#$Ea{B z57%1Y3+ch6cS$_zx8cqcsB9knEumPV8y=lP{Ht;M z8EdI|x9FDl(@x*baE?7Ti4W7e<&4M=GE&!@x%$gWvBQ95Hh2#4tyZN z)c@sh2~c#Kc7O@eEiy}LhJH%a|HpZhL&U*T5cpsGNG7JgPMZ8Fxmb_` zGgx$i^m*{*KvbdcJQ~SDSz=bl&uSx6R4c!;AxTKpTVHfOvkC8F!>#DAuPO6eN7MG= z1nnVT7c>ewC}5$WXvWXl+_G1uVRlb$|2O*E?xqDV<(wCV5W*^Mdm{HgA(F*%dPn(+ z%!@g7m*Rhb>|QwA7TUv2_D5=mAJQtz|3$B|Il#3w z*nM=c6ER+2v4@h|emS@Ms=H1sZ(j+wmM%Ec!aH5Qri)R@R@R6GSqA(Ustq(|SEo0k z+MSamK~85DlC)-_;OPV)Ue`ibhkPB+hOD}<=Nlu>&dj?-Bh2J`A&|xBbJAO3VYWhr zug_be9H|1;jQUYQ;cphax1ag+=OqTkk9*s0 z@qHaaw1>@?n4f>rNnag7G8 zVFKjCT5dPP{EOQ-;^{&9kK)6&%gTWeze_qBdW!E1h95J@6bw*?;7yq2ds$!wKyN;m zzQ8(spBUR(guTc)89$UESZD~wzuHU-l3!_bI~GoU|LEkiE-@$YyvMrJ-|I~;?j|A#@r zhDhy4NiBP;lsLZ}q`Tr$k>#fHM#9`fH0IPnbeoV&-g5nz?E11K*pW(dty9eQ?-^qW zh)+K!b?kdz8;eYoSCf4wL~Xt>VOs27F*OU%iBL~N0-5QV;s_!r zfRmU^{8bXXZ6=M}HA7RMtFhJQ{T}v0B*$XG?7tt*lq40gdhazBH;6c0R{Bq5o^yxC zn>m_oidqa~6N*|C-LtuyZcoKjYyR!JZ*qa^v8}e$wV{g6{ zp9q;TBQGrHtod3?WLKL2321y#Ux&&n;VEh#v0v#wD38w*?`s1xA0II z@BW{kFcVKiyL=hz$5`e?K-nqbY)Q#!MJ@6x!%$K$`2QuXQdH2gFSSqisL{MfU9xb4 z-X>E<8$A}aSnc$yuOmB7WgGtX78hoV$;D~agz(8TS7XrnqPA+@`=?I3+!!oF2~F}f z?_-11PlOTToGh(~MA+ni-~5?l3`*5yctONRxMBWjY(`Hf0EKj zwk2LuW8mH_`t*mz!K>qy&*l~il(M5S4>>HK9~{#k(G!75gMjbhbcgkngOu76GZY|C z(j8hw*0-Xu)O$zTj9qbd$>yEpP~$tSTXC^#koY+bsq{2xP(H3asc4KCx&f&kU!@aU z)SM4KLU7-MKWmmy*YK6-9Qeba$ioeTCASEFGEgo(S!xC3#8kimKamRCrump#F(ZNC zbo1VN$*vq@7-1fp6mlL-xCT{oeo)IncRZ1AK$J^7SxbR0r?Z7sW_zBus4sS=-j|i{ z6!}daN-28q=;SGA>_8Maeu0$fegFfs>Gw1S8a*5@M~V{-0RR8m^xF#&9W7-|n}ig? z!OqUj_y4a|@Lm1M+T`@_)hnVI!zld_z8XthFW%=bI;^Mv*-{r0DQMyup7Cuw``G^K z)ELj(cCeAajK!(AgRV?&A)r6sbN1$tFZ7KK@A>W=@^ojoX|2e8H-B;X{&45;esz~K z_gmfL_21q3CO=MHC8X0~<0R+(xwYvp8{}=bY4c5`^YyY5WkCP*R-gBB{6A1&3Zv5n z?5s#Hn=-=L+O43Dzb8QcHXAf|0+DF@p*1aX)EL zz$A1^6XXnDtV-d3uq|km5m?0X@}<4Gl(wvom_D`a9aQCYBP?*{u6e+ec{DT-yJTuU z%NoToqP*_jy6>gy%8fvuZoLA-b(%o1(Qsl0B+_9ZS6N~zy;#4a!H8nnkvXc2=VKn< zX!dP+MS2?{`vn>u3NzCyF#{<-x#*n^COZ}(4TWOL;=e0K%) zg_Zv0#h{D*J?=E={=+{r3FLcyWxrmL>-w>B>?FHi)FQA}P5Qs>Wof-#9&l-~e$S-2K1n)i!dmKM}!od|aYyr;DWj zcBO(3+2euPo+PcR8@YjaR?uq$8EE@f`_7wPT*oO6q6!a1!u)^yEOv-mD8JqN07tOw zv}1zk1l{2$hzy-mMiXFN#)snNbitQq?0x@|?j;iT9^QPYOhnyy-TUN5WA~5KzEvPH zWqP{mp>1H4TnaRws#(jy#%m)EH@ZmHbg8k;|r&%r?W*elYXxz_lTuq^4mPh#6_fFV<$zQ6-d ziPzv4Dy6~$*25V4L3$Ua<6K1DZPQPgiZ7hTakuceu%`v|uq|657`#$7>6qQ?yMtJT{$85QT*5wI=_ z&1NK5DlZG+Q7+JqFMZ3jIpMyVka<$l4i^3OhN8U!tgMM+=TZ>~?Jew4c=cR9QU3ru zGPd=7h-<1EP|{<1C@O`Ty$g2TeFeSKA-rAOe8n0e_+bTHnV%@VU^jDOib~3KRgn6T4xE?-0 zIN0Lzi`_Vhy1iNP2UTSdASZldCb=+DcV*EF_*O%jIV0xJ12bWK8He!n{bAxzPif?+ zJR|@KKox7qIbufKr>-gp#Dvs7R;PYSBz^~tE)eb7rdCzMd5#Vg@q|Fd5|vj6y6;e& zJoZSA@Bv>Q9wB`De3N3T5;V%iFQ67jsGU+pFm1g1NC}g6;@OzucHfE8&Xq%Q2T7c+cShL z)ty$%z;|0Ht&*3Q^VoaEt*GoaV}u}sRn1ShACdf<8zJy<$O)Iki~BbX#RzdL5(AuD zzuX5#g=-Sv&~T#&giIbRnqNSWTFcpD8sWrW{+y%#J`9R)y`RI5+hDT6|zQoZ;-ZvD&26#fj;!BLQ%L$T|O9qL91 zHyodZ=Nwy13j#jBcHIVyj-QzDGA&b$(*=OwzU}AM8gP+81fyoD_&0p`D`ELmDuf2R zaukEx?;W01ZBzzqtYJ?Jqg>48|Dr?JLDy_FMY5529q-tx_M+(y1$?>O<@)+)G;su_ zr~p4{;tV*#cO&`UQp9qN@$yFSD1G1SA+W0jeImJiam~Z0< zWd48$k|9fos^aPdUSMaD3#KF-0M{40ZU2Jy$P1aLLcjuQS%L#A-9L@asGqSfW#DS# z9@?ZCtg2cB7-i&lFq}kl!vdl3xKh@=Eq}iC+=0Gubo+$QVvbQ>pqW-e5j+YXIxDV! z&N-K&^y9Kb4NCyu>cgj*H1Kc5F$2$&^!x}Cv^O9gb-3~*{(#h^+A9Ip2q+lXijLQ_ z^)OR{F>86e+S_N7-R*`2pFqn;zvmvob%?k@7V9TGLK6YWMf=;_!j*UnX2wPXKJxpx% zQy2mlaJh#}&&Zj5(eJ85(|>VKmoZ$1(vSMp89)Uz{>da**C>AnDk0lI*&RTKqW?<7 z8K^+nXAp;ypQZbE7!RSO3M}cj6XuYp-A;JP!lHAED?Ww9sp9fm3<1>|vbKwWli9g1R83Kl=vp zm<2;kn9VJN)^qfoJV@oS5SUpJK7b!)eg=${sQ1M4ECm7TZ!H?xY&5xFO}@{NC;_Fq zHq&|b0&kFT;2u}1@9*Xdhh=^xeVcx803ThaRNoJ?<|q!EBHI{OlCP-nhr8R!4S1S! zy~f*Cb%2ePs@xOHzYKv1k$WKw8uy#Bm#m-9ZHxs?f~WYK!B~!*GuD&cw9DB6YL0SP zGBw+32s7a?Xj&e*eTJ9|xJAnNf;3RDGD*d^GFH9RICL<1x%H%@@cqAsT6EWcE1kd!#v z#FRWfcmnQ_b|2|f*;R}s0f5o zUF8zl{>sp$4FnJ#m)(9#vxM=ewmz|=kST0LXF@W>@ebDd-7B`n<+lloh{3#>Gsx+z zCl>dVTeo_Fq`J@$beG-4?gP*bQ^tPyxZy?H^1*Af~y^$Jw89x_LnP|p2f!iX9IdW{D)zcPd)|J=HtSXB6{f~r_x1Pq|5Efv+!TY2*W zg6-L~t(@#BLVD|b>NisGyI_JR@18yyj;N%5M*>4SuIxHr3vP8q35o(R0aRPYzR9Yn zo2W8`h9rH~6zI2^3uz5jQ2Ey(j8>pLg5CyHGv_(amOO;mB65jXUe#2jWV46^J5sHU zm{S;hI1vM1O!t4E+d^F*XQkA{i&|tXxmDgTMFI=DEZ9P{6$OAEPS$Zny7tPxNY zf>VGo;$dvg7YuvP==g5=kK+JmvYGje`C7uAw=dVHeWb1LKgVrOk4Qz)@GSuJ(5$NS z3`dq^?dLwi?EZz2_H@I!H-J8s>RujpMpP)ysgvuBEnhcD!>K1joR1+>zP><8OYT_y zniUk`e|siJ*3pTI^CVijHvE8e+Gh!Yd@GCPIVlRILBI-Y=dYD1;HHFv1<&^`TdwL$ zYh9YNp%;LGqII_OKCa?6BF%xq>ZcyEd|=wE=8!vL1T6N^#FijbR30#}n;b^+nCnhJ z=?+o5cfwv%TG=~FJP9f97nVhU z%aM;;KQ@UT62co6(n$}42f{k|s+Wq^H!UPE%RQhV82rHm$kW;Xw)m#vv5E&(kc`tb z-3uF>CipbLrmvT;#R`w;633()ZU1_Z*+eM(K|YM_Of@SEK3(L2MkN>7t>u-^UZ0DK zwy~irxCv-cLEm^;5dcRW4q@jUQntiRT^7}Hr&7eJfST9Sw6*YGA+#-&0PmoHl*ycy zg^xpczB?;Q-ZEp0QiW6>`NF{uR~Q}m58O6LwwPB%CEkAvhJORwtHlYBpx)m6irzGv z-Mt8a@8ZL1vyJUYVLA$ynBVqpc!M_TaB}T0Z6wf(CyuGQ*=@Nede%(iTFfT6j$^rhq<*qCjJr$H{e6X!pdpv2j8V8f)Bp z=5}tr(lSLHAE?!7=2Pi63AuLz0SxQqR1WC<+)2~OcO$P^WuMxmkTAz*`L6H&3wM7k zq*nYRIdzyhKdE5RU2m9IMAz5%ELmS++G_Z#B=i(2Zx3;x_HwZ;_y0ep|BT^jnQoDI>b^9@;+vYVFem3EQ_uF<)C+DPiN{`!k_b4fNSR)geM zza0uU&j?cxR?(=0j-3l%orcOPYu*l$0uCE1MjN1m*{r6y-9%R`Ry9&qRYw2fBS2ax zhHYY1u4Z0jO@I~H)7q5lT;@nwT0x_MBnsQS zo5Q=jm%Fe z1;dX|*2MvasQ7xj=NPH{eOZPf;T2ky+53?lYgj+F>odm-NoHW z8iT`hEua|UsGw4RglsEv^vEsJ`Ftl0WX6r&_{R+=~+e=f(oP`M}Kth zLpDARE^ca&oW;z-*YU=YvHQ*5m`OJVh*--svdWD^hN68|qHL)>7Jl0L^3S`8ey}jv zw+Cj2s+BOfV21Q@c@L;4A;~p}n;CXsKR*w9tl}7+&egcP$c=3U#EeW&jLzkRrP^ks zkRRh{a>&ggVE@5Kr}-AuzA(#W7DZLU!6qRdV)8khLv`15lACx1OUK&P`w#7WvJ#U7Q=DU3+? z;xpFYzhsg~mqvB%uU>#cZ&g;h-BXeO_?(JAH1!|%KBnD=x16`(*n!}o6M^F@2Ki>6 zi;UG-pI~z!rO{FKdL~4D(-?qElGJq1Hsca@=!yN&E^1mj?(HOe`JXBLZvur!SaG>A zLP$ks)p-s)RO}?G*YQ510hQa+dtKK+(7|d3SZw5prcFOIH+!rKDp0vlWM%ENYE(}(jJW&{sva{ITxR}XNtq=7fTH8 zL-R8$;C%mtjRiqar^`A-(u{z6dfgLU^lrl($Vs?W^_~*it4D4}KL*o#op*PK`{ksG z`5p+n4~DzvRBx0?m2D4DSYh1o4$=D_wWFeneh-R$oJ#dD`P+_j{dpbYZ@chgLta{x zo9KD(O7O^jwHI z&2*~F3rGSLI)>C<>Q#*p3{bn?iq22i(_XWUU_OzF$E_Qi%$VN`3qg4EEnt8aGflQ` zv=E02*`3+!?}oS$O=hTcYZdCjR>(E*mRrp~rPoecFD!&;jkk0Ic%alNMW5=Zb}r6} z_YA8FA^(c;o-NZqjodle&45Z8hM~$iFMkUAiM|mL&)|J82=a#c+=BbZZk66{%q9HD zZYt&^c_9REy%r2`MTHJs03F)!Xt>x_kvi!ZAIkVLxh5FBID0Fd*%tGRx=E&#g&zgZ z%Lzq0e>YqP_0FwjAST6uraPW_UIdyS4;n>rgLDclNp!}K=I{5dp*3~nQW}v-R>k?! zeQ&3Yr`iw`EPfba>#q(kE=+t)EnKomHW?*;L?g*b*N={Fauiz`DYDV}Kdy6I);s+) zo9u;}0Gnb9m&`v^-9?1dkaQTwXg&3 zEr{17Mq(C)1>OcVM#=d$)k2~1MQgHtG%;$ z;(&jml)a3R*i-gaVktxpxf*+Y|1-5&9|HFPOr-BhAM1!)4XnyK5JZs@b4@%VBH;# z^{jAjEjHZIoQ!y{GM=Q3CxkOgL++g>`wIrhobP@)k*M)bO3&Vr=SCnrQlFR{UZ