From 4a81213b3b8a9ee58db53d2f02f9e06f4984f26a Mon Sep 17 00:00:00 2001 From: Mikko Mononen Date: Sat, 29 Jan 2011 15:28:28 +0000 Subject: [PATCH] Refactored and cleaned up CrowdManager and moved it to DetourCrowd. Update tool UI layout, context sensitive help is now rendered as overlay. --- Detour/Include/DetourNavMeshQuery.h | 5 +- Detour/Include/DetourObstacleAvoidance.h | 16 +- Detour/Source/DetourNavMeshQuery.cpp | 11 +- Detour/Source/DetourObstacleAvoidance.cpp | 24 +- DetourCrowd/Include/DetourCrowd.h | 185 ++ DetourCrowd/Include/DetourLocalBoundary.h | 55 + DetourCrowd/Include/DetourPathCorridor.h | 74 + DetourCrowd/Include/DetourPathQueue.h | 75 + DetourCrowd/Include/DetourProximityGrid.h | 70 + DetourCrowd/Source/DetourCrowd.cpp | 944 ++++++++++ DetourCrowd/Source/DetourLocalBoundary.cpp | 121 ++ DetourCrowd/Source/DetourPathCorridor.cpp | 342 ++++ DetourCrowd/Source/DetourPathQueue.cpp | 197 ++ DetourCrowd/Source/DetourProximityGrid.cpp | 194 ++ .../Bin/Recast.app/Contents/MacOS/Recast | Bin 1122452 -> 1124716 bytes .../Xcode/Recast.xcodeproj/project.pbxproj | 64 +- RecastDemo/Include/CrowdManager.h | 335 ---- RecastDemo/Include/CrowdTool.h | 30 +- RecastDemo/Source/ConvexVolumeTool.cpp | 24 +- RecastDemo/Source/CrowdManager.cpp | 1593 ----------------- RecastDemo/Source/CrowdTool.cpp | 472 +++-- RecastDemo/Source/NavMeshTesterTool.cpp | 6 +- RecastDemo/Source/OffMeshConnectionTool.cpp | 20 +- RecastDemo/Source/Sample_SoloMeshTiled.cpp | 4 +- RecastDemo/Source/Sample_TileMesh.cpp | 5 +- RecastDemo/Source/main.cpp | 43 +- 26 files changed, 2701 insertions(+), 2208 deletions(-) create mode 100644 DetourCrowd/Include/DetourCrowd.h create mode 100644 DetourCrowd/Include/DetourLocalBoundary.h create mode 100644 DetourCrowd/Include/DetourPathCorridor.h create mode 100644 DetourCrowd/Include/DetourPathQueue.h create mode 100644 DetourCrowd/Include/DetourProximityGrid.h create mode 100644 DetourCrowd/Source/DetourCrowd.cpp create mode 100644 DetourCrowd/Source/DetourLocalBoundary.cpp create mode 100644 DetourCrowd/Source/DetourPathCorridor.cpp create mode 100644 DetourCrowd/Source/DetourPathQueue.cpp create mode 100644 DetourCrowd/Source/DetourProximityGrid.cpp delete mode 100644 RecastDemo/Include/CrowdManager.h delete mode 100644 RecastDemo/Source/CrowdManager.cpp diff --git a/Detour/Include/DetourNavMeshQuery.h b/Detour/Include/DetourNavMeshQuery.h index 105e493..7a91888 100644 --- a/Detour/Include/DetourNavMeshQuery.h +++ b/Detour/Include/DetourNavMeshQuery.h @@ -167,9 +167,10 @@ public: // Updates sliced path find query. // Params: - // maxIter - (in) max number of iterations to update. + // maxIter - (in) Max number of iterations to update. + // doneIters - (out,opt) Number of iterations done during the update. // Returns: Path query state. - dtStatus updateSlicedFindPath(const int maxIter); + dtStatus updateSlicedFindPath(const int maxIter, int* doneIters); // Finalizes sliced path find query and returns found path. // path - (out) array holding the search result. diff --git a/Detour/Include/DetourObstacleAvoidance.h b/Detour/Include/DetourObstacleAvoidance.h index 4a7187a..4e17064 100644 --- a/Detour/Include/DetourObstacleAvoidance.h +++ b/Detour/Include/DetourObstacleAvoidance.h @@ -97,15 +97,15 @@ public: inline void setCollisionTimeWeight(float w) { m_weightToi = w; } inline void setTimeHorizon(float t) { m_horizTime = t; } - void sampleVelocityGrid(const float* pos, const float rad, const float vmax, - const float* vel, const float* dvel, float* nvel, - const int gsize, - dtObstacleAvoidanceDebugData* debug = 0); + int sampleVelocityGrid(const float* pos, const float rad, const float vmax, + const float* vel, const float* dvel, float* nvel, + const int gsize, + dtObstacleAvoidanceDebugData* debug = 0); - void sampleVelocityAdaptive(const float* pos, const float rad, const float vmax, - const float* vel, const float* dvel, float* nvel, - const int ndivs, const int nrings, const int depth, - dtObstacleAvoidanceDebugData* debug = 0); + int sampleVelocityAdaptive(const float* pos, const float rad, const float vmax, + const float* vel, const float* dvel, float* nvel, + const int ndivs, const int nrings, const int depth, + dtObstacleAvoidanceDebugData* debug = 0); inline int getObstacleCircleCount() const { return m_ncircles; } const dtObstacleCircle* getObstacleCircle(const int i) { return &m_circles[i]; } diff --git a/Detour/Source/DetourNavMeshQuery.cpp b/Detour/Source/DetourNavMeshQuery.cpp index 2a2ebfd..545773b 100644 --- a/Detour/Source/DetourNavMeshQuery.cpp +++ b/Detour/Source/DetourNavMeshQuery.cpp @@ -813,7 +813,7 @@ dtStatus dtNavMeshQuery::initSlicedFindPath(dtPolyRef startRef, dtPolyRef endRef return m_query.status; } -dtStatus dtNavMeshQuery::updateSlicedFindPath(const int maxIter) +dtStatus dtNavMeshQuery::updateSlicedFindPath(const int maxIter, int* doneIters) { if (!dtStatusInProgress(m_query.status)) return m_query.status; @@ -841,6 +841,8 @@ dtStatus dtNavMeshQuery::updateSlicedFindPath(const int maxIter) m_query.lastBestNode = bestNode; const dtStatus details = m_query.status & DT_STATUS_DETAIL_MASK; m_query.status = DT_SUCCESS | details; + if (doneIters) + *doneIters = iter; return m_query.status; } @@ -853,6 +855,8 @@ dtStatus dtNavMeshQuery::updateSlicedFindPath(const int maxIter) { // The polygon has disappeared during the sliced query, fail. m_query.status = DT_FAILURE; + if (doneIters) + *doneIters = iter; return m_query.status; } @@ -868,6 +872,8 @@ dtStatus dtNavMeshQuery::updateSlicedFindPath(const int maxIter) { // The polygon has disappeared during the sliced query, fail. m_query.status = DT_FAILURE; + if (doneIters) + *doneIters = iter; return m_query.status; } } @@ -979,6 +985,9 @@ dtStatus dtNavMeshQuery::updateSlicedFindPath(const int maxIter) m_query.status = DT_SUCCESS | details; } + if (doneIters) + *doneIters = iter; + return m_query.status; } diff --git a/Detour/Source/DetourObstacleAvoidance.cpp b/Detour/Source/DetourObstacleAvoidance.cpp index a255c9b..ac6e0d1 100644 --- a/Detour/Source/DetourObstacleAvoidance.cpp +++ b/Detour/Source/DetourObstacleAvoidance.cpp @@ -410,10 +410,10 @@ float dtObstacleAvoidanceQuery::processSample(const float* vcand, const float cs return penalty; } -void dtObstacleAvoidanceQuery::sampleVelocityGrid(const float* pos, const float rad, const float vmax, - const float* vel, const float* dvel, - float* nvel, const int gsize, - dtObstacleAvoidanceDebugData* debug) +int dtObstacleAvoidanceQuery::sampleVelocityGrid(const float* pos, const float rad, const float vmax, + const float* vel, const float* dvel, + float* nvel, const int gsize, + dtObstacleAvoidanceDebugData* debug) { prepare(pos, dvel); @@ -428,6 +428,7 @@ void dtObstacleAvoidanceQuery::sampleVelocityGrid(const float* pos, const float const float half = (gsize-1)*cs*0.5f; float minPenalty = FLT_MAX; + int ns = 0; for (int y = 0; y < gsize; ++y) { @@ -441,6 +442,7 @@ void dtObstacleAvoidanceQuery::sampleVelocityGrid(const float* pos, const float if (dtSqr(vcand[0])+dtSqr(vcand[2]) > dtSqr(vmax+cs/2)) continue; const float penalty = processSample(vcand, cs, pos,rad,vmax,vel,dvel, debug); + ns++; if (penalty < minPenalty) { minPenalty = penalty; @@ -448,15 +450,17 @@ void dtObstacleAvoidanceQuery::sampleVelocityGrid(const float* pos, const float } } } + + return ns; } static const float DT_PI = 3.14159265f; -void dtObstacleAvoidanceQuery::sampleVelocityAdaptive(const float* pos, const float rad, const float vmax, - const float* vel, const float* dvel, float* nvel, - const int ndivs, const int nrings, const int depth, - dtObstacleAvoidanceDebugData* debug) +int dtObstacleAvoidanceQuery::sampleVelocityAdaptive(const float* pos, const float rad, const float vmax, + const float* vel, const float* dvel, float* nvel, + const int ndivs, const int nrings, const int depth, + dtObstacleAvoidanceDebugData* debug) { prepare(pos, dvel); @@ -498,6 +502,7 @@ void dtObstacleAvoidanceQuery::sampleVelocityAdaptive(const float* pos, const fl float cr = vmax * (1.0f-m_velBias); float res[3]; dtVset(res, dvel[0] * m_velBias, 0, dvel[2] * m_velBias); + int ns = 0; for (int k = 0; k < depth; ++k) { @@ -515,6 +520,7 @@ void dtObstacleAvoidanceQuery::sampleVelocityAdaptive(const float* pos, const fl if (dtSqr(vcand[0])+dtSqr(vcand[2]) > dtSqr(vmax+0.001f)) continue; const float penalty = processSample(vcand,cr/10, pos,rad,vmax,vel,dvel, debug); + ns++; if (penalty < minPenalty) { minPenalty = penalty; @@ -528,5 +534,7 @@ void dtObstacleAvoidanceQuery::sampleVelocityAdaptive(const float* pos, const fl } dtVcopy(nvel, res); + + return ns; } diff --git a/DetourCrowd/Include/DetourCrowd.h b/DetourCrowd/Include/DetourCrowd.h new file mode 100644 index 0000000..b17957d --- /dev/null +++ b/DetourCrowd/Include/DetourCrowd.h @@ -0,0 +1,185 @@ +// +// Copyright (c) 2009-2010 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// + +#ifndef DETOURCROWD_H +#define DETOURCROWD_H + +#include "DetourNavMeshQuery.h" +#include "DetourObstacleAvoidance.h" +#include "DetourLocalBoundary.h" +#include "DetourPathCorridor.h" +#include "DetourProximityGrid.h" +#include "DetourPathQueue.h" + + +static const int DT_CROWDAGENT_MAX_NEIGHBOURS = 6; +static const int DT_CROWDAGENT_MAX_CORNERS = 4; + +struct dtCrowdNeighbour +{ + int idx; + float dist; +}; + +struct dtCrowdAgent +{ + unsigned char active; + + dtPathCorridor corridor; + dtLocalBoundary boundary; + + float t; + float var; + + float topologyOptTime; + + dtCrowdNeighbour neis[DT_CROWDAGENT_MAX_NEIGHBOURS]; + int nneis; + + float radius, height; + float maxAcceleration; + float maxSpeed; + float collisionQueryRange; + float pathOptimizationRange; + + float desiredSpeed; + + float npos[3]; + float disp[3]; + float dvel[3]; + float nvel[3]; + float vel[3]; + + float cornerVerts[DT_CROWDAGENT_MAX_CORNERS*3]; + unsigned char cornerFlags[DT_CROWDAGENT_MAX_CORNERS]; + dtPolyRef cornerPolys[DT_CROWDAGENT_MAX_CORNERS]; + int ncorners; +}; + + +enum UpdateFlags +{ + DT_CROWD_ANTICIPATE_TURNS = 1, + DT_CROWD_USE_VO = 2, +// DT_CROWD_DRUNK = 4, + DT_CROWD_OPTIMIZE_VIS = 8, + DT_CROWD_OPTIMIZE_TOPO = 16, +}; + +struct dtCrowdAgentParams +{ + float radius; + float height; + float maxAcceleration; + float maxSpeed; + float collisionQueryRange; + float pathOptimizationRange; +}; + +struct dtCrowdAgentDebugInfo +{ + int idx; + float optStart[3], optEnd[3]; + dtObstacleAvoidanceDebugData* vod; +}; + +class dtCrowd +{ + int m_maxAgents; + dtCrowdAgent* m_agents; + dtCrowdAgent** m_activeAgents; + + dtPathQueue m_pathq; + + dtObstacleAvoidanceQuery* m_obstacleQuery; + dtProximityGrid* m_grid; + + dtPolyRef* m_pathResult; + int m_maxPathResult; + + float m_ext[3]; + dtQueryFilter m_filter; + + float m_maxAgentRadius; + + int m_velocitySampleCount; + + enum MoveRequestState + { + MR_TARGET_FAILED, + MR_TARGET_VALID, + MR_TARGET_REQUESTING, + MR_TARGET_WAITING_FOR_PATH, + MR_TARGET_ADJUST, + }; + + static const int MAX_TEMP_PATH = 32; + + struct MoveRequest + { + unsigned char state; // State of the request + int idx; // Agent index + dtPolyRef ref; // Goal ref + float pos[3]; // Goal position + dtPathQueueRef pathqRef; // Path find query ref + dtPolyRef aref; // Goal adjustment ref + float apos[3]; // Goal adjustment pos + dtPolyRef temp[MAX_TEMP_PATH]; // Adjusted path to the goal + int ntemp; + }; + MoveRequest* m_moveRequests; + int m_moveRequestCount; + + dtNavMeshQuery* m_navquery; + + int getNeighbours(const float* pos, const float height, const float range, + const dtCrowdAgent* skip, dtCrowdNeighbour* result, const int maxResult); + void updateTopologyOptimization(dtCrowdAgent** agents, const int nagents, const float dt); + void updateMoveRequest(const float dt); + + void purge(); + +public: + dtCrowd(); + ~dtCrowd(); + + bool init(const int maxAgents, const float maxAgentRadius, dtNavMesh* nav); + + const dtCrowdAgent* getAgent(const int idx); + const int getAgentCount() const; + + int addAgent(const float* pos, const dtCrowdAgentParams* params); + void removeAgent(const int idx); + + bool requestMoveTarget(const int idx, dtPolyRef ref, const float* pos); + bool adjustMoveTarget(const int idx, dtPolyRef ref, const float* pos); + + int getActiveAgents(dtCrowdAgent** agents, const int maxAgents); + void update(const float dt, unsigned int flags, dtCrowdAgentDebugInfo* debug); + + const dtQueryFilter* getFilter() const { return &m_filter; } + const float* getQueryExtents() const { return m_ext; } + + inline int getVelocitySampleCount() const { return m_velocitySampleCount; } + + const dtProximityGrid* getGrid() const { return m_grid; } + const dtPathQueue* getPathQueue() const { return &m_pathq; } +}; + + +#endif // CROWDMANAGER_H \ No newline at end of file diff --git a/DetourCrowd/Include/DetourLocalBoundary.h b/DetourCrowd/Include/DetourLocalBoundary.h new file mode 100644 index 0000000..149659e --- /dev/null +++ b/DetourCrowd/Include/DetourLocalBoundary.h @@ -0,0 +1,55 @@ +// +// Copyright (c) 2009-2010 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// + +#ifndef DETOURLOCALBOUNDARY_H +#define DETOURLOCALBOUNDARY_H + +#include "DetourNavMeshQuery.h" + + +class dtLocalBoundary +{ + static const int MAX_SEGS = 8; + + struct Segment + { + float s[6]; // Segment start/end + float d; // Distance for pruning. + }; + + float m_center[3]; + Segment m_segs[MAX_SEGS]; + int m_nsegs; + + void addSegment(const float dist, const float* seg); + +public: + dtLocalBoundary(); + ~dtLocalBoundary(); + + void reset(); + + void update(dtPolyRef ref, const float* pos, const float collisionQueryRange, + dtNavMeshQuery* navquery, const dtQueryFilter* filter); + + inline const float* getCenter() const { return m_center; } + inline int getSegmentCount() const { return m_nsegs; } + inline const float* getSegment(int i) const { return m_segs[i].s; } +}; + +#endif // DETOURLOCALBOUNDARY_H \ No newline at end of file diff --git a/DetourCrowd/Include/DetourPathCorridor.h b/DetourCrowd/Include/DetourPathCorridor.h new file mode 100644 index 0000000..bbf1d5e --- /dev/null +++ b/DetourCrowd/Include/DetourPathCorridor.h @@ -0,0 +1,74 @@ +// +// Copyright (c) 2009-2010 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// + +#ifndef DETOUTPATHCORRIDOR_H +#define DETOUTPATHCORRIDOR_H + +#include "DetourNavMeshQuery.h" + + +class dtPathCorridor +{ + float m_pos[3]; + float m_target[3]; + + dtPolyRef* m_path; + int m_npath; + int m_maxPath; + +public: + dtPathCorridor(); + ~dtPathCorridor(); + + bool init(const int maxPath); + + void reset(dtPolyRef ref, const float* pos); + + int findCorners(float* cornerVerts, unsigned char* cornerFlags, + dtPolyRef* cornerPolys, const int maxCorners, + dtNavMeshQuery* navquery, const dtQueryFilter* filter); + + void optimizePathVisibility(const float* next, const float pathOptimizationRange, + dtNavMeshQuery* navquery, const dtQueryFilter* filter); + + bool optimizePathTopology(dtNavMeshQuery* navquery, const dtQueryFilter* filter); + + void movePosition(const float* npos, dtNavMeshQuery* navquery, const dtQueryFilter* filter); + void moveTargetPosition(const float* npos, dtNavMeshQuery* navquery, const dtQueryFilter* filter); + + void setCorridor(const float* target, const dtPolyRef* polys, const int npolys); + + inline const float* getPos() const { return m_pos; } + inline const float* getTarget() const { return m_target; } + + inline dtPolyRef getFirstPoly() const { return m_npath ? m_path[0] : 0; } + + inline const dtPolyRef* getPath() const { return m_path; } + inline int getPathCount() const { return m_npath; } +}; + +int dtMergeCorridorStartMoved(dtPolyRef* path, const int npath, const int maxPath, + const dtPolyRef* visited, const int nvisited); + +int dtMergeCorridorEndMoved(dtPolyRef* path, const int npath, const int maxPath, + const dtPolyRef* visited, const int nvisited); + +int dtMergeCorridorStartShortcut(dtPolyRef* path, const int npath, const int maxPath, + const dtPolyRef* visited, const int nvisited); + +#endif // DETOUTPATHCORRIDOR_H diff --git a/DetourCrowd/Include/DetourPathQueue.h b/DetourCrowd/Include/DetourPathQueue.h new file mode 100644 index 0000000..cc144cb --- /dev/null +++ b/DetourCrowd/Include/DetourPathQueue.h @@ -0,0 +1,75 @@ +// +// Copyright (c) 2009-2010 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// + +#ifndef DETOURPATHQUEUE_H +#define DETOURPATHQUEUE_H + +#include "DetourNavMesh.h" +#include "DetourNavMeshQuery.h" + +static const unsigned int DT_PATHQ_INVALID = 0; + +typedef unsigned int dtPathQueueRef; + +class dtPathQueue +{ + struct PathQuery + { + dtPathQueueRef ref; + // Path find start and end location. + float startPos[3], endPos[3]; + dtPolyRef startRef, endRef; + // Result. + dtPolyRef* path; + int npath; + // State. + dtStatus status; + int keepAlive; + const dtQueryFilter* filter; // TODO: This is potentially dangerous! + }; + + static const int MAX_QUEUE = 8; + PathQuery m_queue[MAX_QUEUE]; + dtPathQueueRef m_nextHandle; + int m_maxPathSize; + int m_queueHead; + dtNavMeshQuery* m_navquery; + + void purge(); + +public: + dtPathQueue(); + ~dtPathQueue(); + + bool init(const int maxPathSize, const int maxSearchNodeCount, dtNavMesh* nav); + + void update(const int maxIters); + + dtPathQueueRef request(dtPolyRef startRef, dtPolyRef endRef, + const float* startPos, const float* endPos, + const dtQueryFilter* filter); + + dtStatus getRequestStatus(dtPathQueueRef ref) const; + + dtStatus getPathResult(dtPathQueueRef ref, dtPolyRef* path, int* pathSize, const int maxPath); + + inline const dtNavMeshQuery* getNavQuery() const { return m_navquery; } + +}; + +#endif // DETOURPATHQUEUE_H diff --git a/DetourCrowd/Include/DetourProximityGrid.h b/DetourCrowd/Include/DetourProximityGrid.h new file mode 100644 index 0000000..b098261 --- /dev/null +++ b/DetourCrowd/Include/DetourProximityGrid.h @@ -0,0 +1,70 @@ +// +// Copyright (c) 2009-2010 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// + +#ifndef DETOURPROXIMITYGRID_H +#define DETOURPROXIMITYGRID_H + +class dtProximityGrid +{ + int m_maxItems; + float m_cellSize; + float m_invCellSize; + + struct Item + { + unsigned short id; + short x,y; + unsigned short next; + }; + Item* m_pool; + int m_poolHead; + int m_poolSize; + + unsigned short* m_buckets; + int m_bucketsSize; + + int m_bounds[4]; + +public: + dtProximityGrid(); + ~dtProximityGrid(); + + bool init(const int maxItems, const float cellSize); + + void clear(); + + void addItem(const unsigned short id, + const float minx, const float miny, + const float maxx, const float maxy); + + int queryItems(const float minx, const float miny, + const float maxx, const float maxy, + unsigned short* ids, const int maxIds) const; + + int getItemCountAt(const int x, const int y) const; + + inline const int* getBounds() const { return m_bounds; } + inline const float getCellSize() const { return m_cellSize; } +}; + +dtProximityGrid* dtAllocProximityGrid(); +void dtFreeProximityGrid(dtProximityGrid* ptr); + + +#endif // DETOURPROXIMITYGRID_H + diff --git a/DetourCrowd/Source/DetourCrowd.cpp b/DetourCrowd/Source/DetourCrowd.cpp new file mode 100644 index 0000000..f90e8e6 --- /dev/null +++ b/DetourCrowd/Source/DetourCrowd.cpp @@ -0,0 +1,944 @@ +// +// Copyright (c) 2009-2010 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// + +#define _USE_MATH_DEFINES +#include +#include +#include +#include +#include "DetourCrowd.h" +#include "DetourNavMesh.h" +#include "DetourNavMeshQuery.h" +#include "DetourObstacleAvoidance.h" +#include "DetourCommon.h" +#include "DetourAssert.h" +#include "DetourAlloc.h" + +static const int VO_ADAPTIVE_DIVS = 7; +static const int VO_ADAPTIVE_RINGS = 2; +static const int VO_ADAPTIVE_DEPTH = 5; + +static const int VO_GRID_SIZE = 33; + +static const int MAX_ITERS_PER_UPDATE = 10; + +static const int MAX_PATHQUEUE_NODES = 4096; +static const int MAX_COMMON_NODES = 512; + + +static void integrate(dtCrowdAgent* ag, const float dt) +{ + // Fake dynamic constraint. + const float maxDelta = ag->maxAcceleration * dt; + float dv[3]; + dtVsub(dv, ag->nvel, ag->vel); + float ds = dtVlen(dv); + if (ds > maxDelta) + dtVscale(dv, dv, maxDelta/ds); + dtVadd(ag->vel, ag->vel, dv); + + // Integrate + if (dtVlen(ag->vel) > 0.0001f) + dtVmad(ag->npos, ag->npos, ag->vel, dt); + else + dtVset(ag->vel,0,0,0); +} + +static float getDistanceToGoal(const dtCrowdAgent* ag, const float range) +{ + if (!ag->ncorners) + return range; + + const bool endOfPath = (ag->cornerFlags[ag->ncorners-1] & DT_STRAIGHTPATH_END) ? true : false; + const bool offMeshConnection = (ag->cornerFlags[ag->ncorners-1] & DT_STRAIGHTPATH_OFFMESH_CONNECTION) ? true : false; + if (endOfPath || offMeshConnection) + return dtMin(dtVdist2D(ag->npos, &ag->cornerVerts[(ag->ncorners-1)*3]), range); + + return range; +} + +static void calcSmoothSteerDirection(const dtCrowdAgent* ag, float* dir) +{ + if (!ag->ncorners) + { + dtVset(dir, 0,0,0); + return; + } + + const int ip0 = 0; + const int ip1 = dtMin(1, ag->ncorners-1); + const float* p0 = &ag->cornerVerts[ip0*3]; + const float* p1 = &ag->cornerVerts[ip1*3]; + + float dir0[3], dir1[3]; + dtVsub(dir0, p0, ag->npos); + dtVsub(dir1, p1, ag->npos); + dir0[1] = 0; + dir1[1] = 0; + + float len0 = dtVlen(dir0); + float len1 = dtVlen(dir1); + if (len1 > 0.001f) + dtVscale(dir1,dir1,1.0f/len1); + + dir[0] = dir0[0] - dir1[0]*len0*0.5f; + dir[1] = 0; + dir[2] = dir0[2] - dir1[2]*len0*0.5f; + + dtVnormalize(dir); +} + +static void calcStraightSteerDirection(const dtCrowdAgent* ag, float* dir) +{ + if (!ag->ncorners) + { + dtVset(dir, 0,0,0); + return; + } + dtVsub(dir, &ag->cornerVerts[0], ag->npos); + dir[1] = 0; + dtVnormalize(dir); +} + +static int addNeighbour(const int idx, const float dist, + dtCrowdNeighbour* neis, const int nneis, const int maxNeis) +{ + // Insert neighbour based on the distance. + dtCrowdNeighbour* nei = 0; + if (!nneis) + { + nei = &neis[nneis]; + } + else if (dist >= neis[nneis-1].dist) + { + if (nneis >= maxNeis) + return nneis; + nei = &neis[nneis]; + } + else + { + int i; + for (i = 0; i < nneis; ++i) + if (dist <= neis[i].dist) + break; + + const int tgt = i+1; + const int n = dtMin(nneis-i, maxNeis-tgt); + + dtAssert(tgt+n <= maxNeis); + + if (n > 0) + memmove(&neis[tgt], &neis[i], sizeof(dtCrowdNeighbour)*n); + nei = &neis[i]; + } + + memset(nei, 0, sizeof(dtCrowdNeighbour)); + + nei->idx = idx; + nei->dist = dist; + + return dtMin(nneis+1, maxNeis); +} + + + +dtCrowd::dtCrowd() : + m_maxAgents(0), + m_agents(0), + m_activeAgents(0), + m_obstacleQuery(0), + m_grid(0), + m_pathResult(0), + m_maxPathResult(0), + m_maxAgentRadius(0), + m_velocitySampleCount(0), + m_moveRequests(0), + m_moveRequestCount(0), + m_navquery(0) +{ +} + +dtCrowd::~dtCrowd() +{ + purge(); +} + +void dtCrowd::purge() +{ + for (int i = 0; i < m_maxAgents; ++i) + m_agents[i].~dtCrowdAgent(); + dtFree(m_agents); + m_agents = 0; + m_maxAgents = 0; + + dtFree(m_activeAgents); + m_activeAgents = 0; + + dtFree(m_pathResult); + m_pathResult = 0; + + dtFree(m_moveRequests); + m_moveRequests = 0; + + dtFreeProximityGrid(m_grid); + m_grid = 0; + + dtFreeObstacleAvoidanceQuery(m_obstacleQuery); + m_obstacleQuery = 0; + + dtFreeNavMeshQuery(m_navquery); + m_navquery = 0; +} + +bool dtCrowd::init(const int maxAgents, const float maxAgentRadius, dtNavMesh* nav) +{ + m_maxAgents = maxAgents; + m_maxAgentRadius = maxAgentRadius; + + dtVset(m_ext, m_maxAgentRadius*2.0f,m_maxAgentRadius*1.5f,m_maxAgentRadius*2.0f); + + m_grid = dtAllocProximityGrid(); + if (!m_grid) + return false; + if (!m_grid->init(m_maxAgents*4, maxAgentRadius*3)) + return false; + + m_obstacleQuery = dtAllocObstacleAvoidanceQuery(); + if (!m_obstacleQuery) + return false; + m_obstacleQuery->init(6, 8); + + m_obstacleQuery->setDesiredVelocityWeight(2.0f); + m_obstacleQuery->setCurrentVelocityWeight(0.75f); + m_obstacleQuery->setPreferredSideWeight(0.75f); + m_obstacleQuery->setCollisionTimeWeight(2.5f); + m_obstacleQuery->setTimeHorizon(2.5f); + m_obstacleQuery->setVelocitySelectionBias(0.4f); + + // Allocate temp buffer for merging paths. + m_maxPathResult = 256; + m_pathResult = (dtPolyRef*)dtAlloc(sizeof(dtPolyRef)*m_maxPathResult, DT_ALLOC_PERM); + if (!m_pathResult) + return false; + + m_moveRequests = (MoveRequest*)dtAlloc(sizeof(MoveRequest)*m_maxAgents, DT_ALLOC_PERM); + if (!m_moveRequests) + return false; + m_moveRequestCount = 0; + + if (!m_pathq.init(m_maxPathResult, MAX_PATHQUEUE_NODES, nav)) + return false; + + m_agents = (dtCrowdAgent*)dtAlloc(sizeof(dtCrowdAgent)*m_maxAgents, DT_ALLOC_PERM); + if (!m_agents) + return false; + + m_activeAgents = (dtCrowdAgent**)dtAlloc(sizeof(dtCrowdAgent*)*m_maxAgents, DT_ALLOC_PERM); + if (!m_activeAgents) + return false; + + for (int i = 0; i < m_maxAgents; ++i) + { + new(&m_agents[i]) dtCrowdAgent(); + m_agents[i].active = 0; + if (!m_agents[i].corridor.init(m_maxPathResult)) + return false; + } + + // The navquery is mostly used for local searches, no need for large node pool. + m_navquery = dtAllocNavMeshQuery(); + if (!m_navquery) + return false; + if (dtStatusFailed(m_navquery->init(nav, MAX_COMMON_NODES))) + return false; + + return true; +} + +const int dtCrowd::getAgentCount() const +{ + return m_maxAgents; +} + +const dtCrowdAgent* dtCrowd::getAgent(const int idx) +{ + return &m_agents[idx]; +} + +int dtCrowd::addAgent(const float* pos, const dtCrowdAgentParams* params) +{ + // Find empty slot. + int idx = -1; + for (int i = 0; i < m_maxAgents; ++i) + { + if (!m_agents[i].active) + { + idx = i; + break; + } + } + if (idx == -1) + return -1; + + dtCrowdAgent* ag = &m_agents[idx]; + + // Find nearest position on navmesh and place the agent there. + float nearest[3]; + dtPolyRef ref; + m_navquery->findNearestPoly(pos, m_ext, &m_filter, &ref, nearest); + if (!ref) + { + // Could not find a location on navmesh. + return -1; + } + + ag->corridor.reset(ref, nearest); + ag->boundary.reset(); + + ag->radius = params->radius; + ag->height = params->height; + ag->maxAcceleration = params->maxAcceleration; + ag->maxSpeed = params->maxSpeed; + ag->collisionQueryRange = params->collisionQueryRange; + ag->pathOptimizationRange = params->pathOptimizationRange; + + ag->topologyOptTime = 0; + ag->nneis = 0; + + dtVset(ag->dvel, 0,0,0); + dtVset(ag->nvel, 0,0,0); + dtVset(ag->vel, 0,0,0); + dtVcopy(ag->npos, nearest); + + ag->desiredSpeed = 0; + ag->t = 0; + ag->var = (rand() % 10) / 9.0f; + + ag->active = 1; + + return idx; +} + +void dtCrowd::removeAgent(const int idx) +{ + if (idx >= 0 && idx < m_maxAgents) + { + m_agents[idx].active = 0; + } +} + +bool dtCrowd::requestMoveTarget(const int idx, dtPolyRef ref, const float* pos) +{ + if (idx < 0 || idx > m_maxAgents) + return false; + if (!ref) + return false; + + MoveRequest* req = 0; + // Check if there is existing request and update that instead. + for (int i = 0; i < m_moveRequestCount; ++i) + { + if (m_moveRequests[i].idx == idx) + { + req = &m_moveRequests[i]; + break; + } + } + if (!req) + { + if (m_moveRequestCount >= m_maxAgents) + return false; + req = &m_moveRequests[m_moveRequestCount++]; + memset(req, 0, sizeof(MoveRequest)); + } + + // Initialize request. + req->idx = idx; + req->ref = ref; + dtVcopy(req->pos, pos); + req->pathqRef = DT_PATHQ_INVALID; + req->state = MR_TARGET_REQUESTING; + + req->temp[0] = ref; + req->ntemp = 1; + + return true; +} + +bool dtCrowd::adjustMoveTarget(const int idx, dtPolyRef ref, const float* pos) +{ + if (idx < 0 || idx > m_maxAgents) + return false; + if (!ref) + return false; + + MoveRequest* req = 0; + // Check if there is existing request and update that instead. + for (int i = 0; i < m_moveRequestCount; ++i) + { + if (m_moveRequests[i].idx == idx) + { + req = &m_moveRequests[i]; + break; + } + } + if (!req) + { + if (m_moveRequestCount >= m_maxAgents) + return false; + req = &m_moveRequests[m_moveRequestCount++]; + memset(req, 0, sizeof(MoveRequest)); + + // New adjust request + req->state = MR_TARGET_ADJUST; + req->idx = idx; + } + + // Set adjustment request. + req->aref = ref; + dtVcopy(req->apos, pos); + + return true; +} + +int dtCrowd::getActiveAgents(dtCrowdAgent** agents, const int maxAgents) +{ + int n = 0; + for (int i = 0; i < m_maxAgents; ++i) + { + if (!m_agents[i].active) continue; + if (n < maxAgents) + agents[n++] = &m_agents[i]; + } + return n; +} + + + +int dtCrowd::getNeighbours(const float* pos, const float height, const float range, + const dtCrowdAgent* skip, dtCrowdNeighbour* result, const int maxResult) +{ + int n = 0; + + static const int MAX_NEIS = 32; + unsigned short ids[MAX_NEIS]; + int nids = m_grid->queryItems(pos[0]-range, pos[2]-range, + pos[0]+range, pos[2]+range, + ids, MAX_NEIS); + + for (int i = 0; i < nids; ++i) + { + dtCrowdAgent* ag = &m_agents[ids[i]]; + + if (ag == skip) continue; + + // Check for overlap. + float diff[3]; + dtVsub(diff, pos, ag->npos); + if (fabsf(diff[1]) >= (height+ag->height)/2.0f) + continue; + diff[1] = 0; + const float distSqr = dtVlenSqr(diff); + if (distSqr > dtSqr(range)) + continue; + + n = addNeighbour(ids[i], distSqr, result, n, maxResult); + } + return n; +} + +void dtCrowd::updateMoveRequest(const float dt) +{ + // Fire off new requests. + for (int i = 0; i < m_moveRequestCount; ++i) + { + MoveRequest* req = &m_moveRequests[i]; + dtCrowdAgent* ag = &m_agents[req->idx]; + + // Agent not active anymore, kill request. + if (!ag->active) + req->state = MR_TARGET_FAILED; + + // Adjust target + if (req->aref) + { + if (req->state == MR_TARGET_ADJUST) + { + // Adjust existing path. + ag->corridor.moveTargetPosition(req->apos, m_navquery, &m_filter); + req->state = MR_TARGET_VALID; + } + else + { + // Adjust on the flight request. + float result[3]; + static const int MAX_VISITED = 16; + dtPolyRef visited[MAX_VISITED]; + int nvisited = 0; + m_navquery->moveAlongSurface(req->temp[req->ntemp-1], req->pos, req->apos, &m_filter, + result, visited, &nvisited, MAX_VISITED); + req->ntemp = dtMergeCorridorEndMoved(req->temp, req->ntemp, MAX_TEMP_PATH, visited, nvisited); + dtVcopy(req->pos, result); + + // Reset adjustment. + dtVset(req->apos, 0,0,0); + req->aref = 0; + } + } + + + if (req->state == MR_TARGET_REQUESTING) + { + // Calculate request position. + // If there is a lot of latency between requests, it is possible to + // project the current position ahead and use raycast to find the actual + // location and path. + const dtPolyRef* path = ag->corridor.getPath(); + const int npath = ag->corridor.getPathCount(); + dtAssert(npath); + + // Here we take the simple approach and set the path to be just the current location. + float reqPos[3]; + dtVcopy(reqPos, ag->corridor.getPos()); // The location of the request + dtPolyRef reqPath[8]; // The path to the request location + reqPath[0] = path[0]; + int reqPathCount = 1; + + req->pathqRef = m_pathq.request(reqPath[reqPathCount-1], req->ref, reqPos, req->pos, &m_filter); + if (req->pathqRef != DT_PATHQ_INVALID) + { + ag->corridor.setCorridor(reqPos, reqPath, reqPathCount); + req->state = MR_TARGET_WAITING_FOR_PATH; + } + } + } + + + // Update requests. + m_pathq.update(MAX_ITERS_PER_UPDATE); + + // Process path results. + for (int i = 0; i < m_moveRequestCount; ++i) + { + MoveRequest* req = &m_moveRequests[i]; + dtCrowdAgent* ag = &m_agents[req->idx]; + + if (req->state == MR_TARGET_WAITING_FOR_PATH) + { + // Poll path queue. + dtStatus status = m_pathq.getRequestStatus(req->pathqRef); + if (dtStatusFailed(status)) + { + req->pathqRef = DT_PATHQ_INVALID; + req->state = MR_TARGET_FAILED; + } + else if (dtStatusSucceed(status)) + { + const dtPolyRef* path = ag->corridor.getPath(); + const int npath = ag->corridor.getPathCount(); + dtAssert(npath); + + // Apply results. + float targetPos[3]; + dtVcopy(targetPos, req->pos); + + dtPolyRef* res = m_pathResult; + bool valid = true; + int nres = 0; + dtStatus status = m_pathq.getPathResult(req->pathqRef, res, &nres, m_maxPathResult); + if (dtStatusFailed(status) || !nres) + valid = false; + + // Merge with any target adjustment that happened during the search. + if (req->ntemp > 1) + { + nres = dtMergeCorridorEndMoved(res, nres, m_maxPathResult, req->temp, req->ntemp); + } + + // Merge result and existing path. + // The agent might have moved whilst the request is + // being processed, so the path may have changed. + // We assume that the end of the path is at the same location + // where the request was issued. + + // The last ref in the old path should be the same as + // the location where the request was issued.. + if (valid && path[npath-1] != res[0]) + valid = false; + + if (valid) + { + // Put the old path infront of the old path. + if (npath > 1) + { + // Make space for the old path. + if ((npath-1)+nres > m_maxPathResult) + nres = m_maxPathResult - (npath-1); + memmove(res+npath-1, res, sizeof(dtPolyRef)*nres); + // Copy old path in the beginning. + memcpy(res, path, sizeof(dtPolyRef)*(npath-1)); + nres += npath-1; + } + + // Check for partial path. + if (res[nres-1] != req->ref) + { + // Partial path, constrain target position inside the last polygon. + float nearest[3]; + if (m_navquery->closestPointOnPoly(res[nres-1], targetPos, nearest) == DT_SUCCESS) + dtVcopy(targetPos, nearest); + else + valid = false; + } + } + + if (valid) + { + ag->corridor.setCorridor(targetPos, res, nres); + req->state = MR_TARGET_VALID; + } + else + { + // Something went wrong. + req->state = MR_TARGET_FAILED; + } + } + } + + // Remove request when done with it. + if (req->state == MR_TARGET_VALID || req->state == MR_TARGET_FAILED) + { + m_moveRequestCount--; + if (i != m_moveRequestCount) + memcpy(&m_moveRequests[i], &m_moveRequests[m_moveRequestCount], sizeof(MoveRequest)); + --i; + } + } + +} + + + +static int addToOptQueue(dtCrowdAgent* newag, dtCrowdAgent** agents, const int nagents, const int maxAgents) +{ + // Insert neighbour based on greatest time. + int slot = 0; + if (!nagents) + { + slot = nagents; + } + else if (newag->topologyOptTime <= agents[nagents-1]->topologyOptTime) + { + if (nagents >= maxAgents) + return nagents; + slot = nagents; + } + else + { + int i; + for (i = 0; i < nagents; ++i) + if (newag->topologyOptTime >= agents[i]->topologyOptTime) + break; + + const int tgt = i+1; + const int n = dtMin(nagents-i, maxAgents-tgt); + + dtAssert(tgt+n <= maxAgents); + + if (n > 0) + memmove(&agents[tgt], &agents[i], sizeof(dtCrowdAgent*)*n); + slot = i; + } + + agents[slot] = newag; + + return dtMin(nagents+1, maxAgents); +} + +void dtCrowd::updateTopologyOptimization(dtCrowdAgent** agents, const int nagents, const float dt) +{ + if (!nagents) + return; + + const float OPT_TIME_THR = 0.5f; // seconds + const int OPT_MAX_AGENTS = 1; + dtCrowdAgent* queue[OPT_MAX_AGENTS]; + int nqueue = 0; + + for (int i = 0; i < nagents; ++i) + { + dtCrowdAgent* ag = agents[i]; + ag->topologyOptTime += dt; + if (ag->topologyOptTime >= OPT_TIME_THR) + nqueue = addToOptQueue(ag, queue, nqueue, OPT_MAX_AGENTS); + } + + for (int i = 0; i < nqueue; ++i) + { + dtCrowdAgent* ag = queue[i]; + ag->corridor.optimizePathTopology(m_navquery, &m_filter); + ag->topologyOptTime = 0; + } + +} + +void dtCrowd::update(const float dt, unsigned int flags, dtCrowdAgentDebugInfo* debug) +{ + m_velocitySampleCount = 0; + + const int debugIdx = debug ? debug->idx : -1; + + dtCrowdAgent** agents = m_activeAgents; + int nagents = getActiveAgents(agents, m_maxAgents); + + // Update async move request and path finder. + updateMoveRequest(dt); + + // Optimize path topology. + if (flags & DT_CROWD_OPTIMIZE_TOPO) + updateTopologyOptimization(agents, nagents, dt); + + // Register agents to proximity grid. + m_grid->clear(); + for (int i = 0; i < nagents; ++i) + { + dtCrowdAgent* ag = agents[i]; + const float* p = ag->npos; + const float r = ag->radius; + m_grid->addItem((unsigned short)i, p[0]-r, p[2]-r, p[0]+r, p[2]+r); + } + + // Get nearby navmesh segments and agents to collide with. + for (int i = 0; i < nagents; ++i) + { + dtCrowdAgent* ag = agents[i]; + // Only update the collision boundary after certain distance has been passed. + if (dtVdist2DSqr(ag->npos, ag->boundary.getCenter()) > dtSqr(ag->collisionQueryRange*0.25f)) + ag->boundary.update(ag->corridor.getFirstPoly(), ag->npos, ag->collisionQueryRange, m_navquery, &m_filter); + // Query neighbour agents + ag->nneis = getNeighbours(ag->npos, ag->height, ag->collisionQueryRange, ag, ag->neis, DT_CROWDAGENT_MAX_NEIGHBOURS); + } + + // Find next corner to steer to. + for (int i = 0; i < nagents; ++i) + { + dtCrowdAgent* ag = agents[i]; + + // Find corners for steering + ag->ncorners = ag->corridor.findCorners(ag->cornerVerts, ag->cornerFlags, ag->cornerPolys, + DT_CROWDAGENT_MAX_CORNERS, m_navquery, &m_filter); + + // Check to see if the corner after the next corner is directly visible, + // and short cut to there. + if ((flags & DT_CROWD_OPTIMIZE_VIS) && ag->ncorners > 0) + { + const float* target = &ag->cornerVerts[dtMin(1,ag->ncorners-1)*3]; + ag->corridor.optimizePathVisibility(target, ag->pathOptimizationRange, m_navquery, &m_filter); + + // Copy data for debug purposes. + if (debugIdx == i) + { + dtVcopy(debug->optStart, ag->corridor.getPos()); + dtVcopy(debug->optEnd, target); + } + + } + else + { + // Copy data for debug purposes. + if (debugIdx == i) + { + dtVset(debug->optStart, 0,0,0); + dtVset(debug->optEnd, 0,0,0); + } + } + } + + // Calculate steering. + for (int i = 0; i < nagents; ++i) + { + dtCrowdAgent* ag = agents[i]; + + float dvel[3] = {0,0,0}; + + // Calculate steering direction. + if (flags & DT_CROWD_ANTICIPATE_TURNS) + calcSmoothSteerDirection(ag, dvel); + else + calcStraightSteerDirection(ag, dvel); + + // Calculate speed scale, which tells the agent to slowdown at the end of the path. + const float slowDownRadius = ag->radius*2; // TODO: make less hacky. + const float speedScale = getDistanceToGoal(ag, slowDownRadius) / slowDownRadius; + + // Apply style. + // TODO: find way to express custom movement styles. +/* if (flags & DT_CROWD_DRUNK) + { + // Drunken steering + + // Pulsating speed. + ag->t += dt * (1.0f - ag->var*0.25f); + ag->desiredSpeed = ag->maxSpeed * (1 + dtSqr(cosf(ag->t*2.0f))*0.3f); + + dtVscale(dvel, dvel, ag->desiredSpeed * speedScale); + + // Slightly wandering steering. + const float amp = cosf(ag->var*13.69f+ag->t*3.123f) * 0.2f; + const float nx = -dvel[2]; + const float nz = dvel[0]; + dvel[0] += nx*amp; + dvel[2] += nz*amp; + } + else*/ + { + // Normal steering. + ag->desiredSpeed = ag->maxSpeed; + dtVscale(dvel, dvel, ag->desiredSpeed * speedScale); + } + + // Set the desired velocity. + dtVcopy(ag->dvel, dvel); + } + + // Velocity planning. + for (int i = 0; i < nagents; ++i) + { + dtCrowdAgent* ag = agents[i]; + + if (flags & DT_CROWD_USE_VO) + { + m_obstacleQuery->reset(); + + // Add neighbours as obstacles. + for (int j = 0; j < ag->nneis; ++j) + { + const dtCrowdAgent* nei = &m_agents[ag->neis[j].idx]; + m_obstacleQuery->addCircle(nei->npos, nei->radius, nei->vel, nei->dvel); + } + + // Append neighbour segments as obstacles. + for (int j = 0; j < ag->boundary.getSegmentCount(); ++j) + { + const float* s = ag->boundary.getSegment(j); + if (dtTriArea2D(ag->npos, s, s+3) < 0.0f) + continue; + m_obstacleQuery->addSegment(s, s+3); + } + + dtObstacleAvoidanceDebugData* vod = 0; + if (debugIdx == i) + vod = debug->vod; + + // Sample new safe velocity. + bool adaptive = true; + int ns = 0; + + if (adaptive) + { + ns = m_obstacleQuery->sampleVelocityAdaptive(ag->npos, ag->radius, ag->desiredSpeed, + ag->vel, ag->dvel, ag->nvel, + VO_ADAPTIVE_DIVS, VO_ADAPTIVE_RINGS, VO_ADAPTIVE_DEPTH, + vod); + } + else + { + ns = m_obstacleQuery->sampleVelocityGrid(ag->npos, ag->radius, ag->desiredSpeed, + ag->vel, ag->dvel, ag->nvel, + VO_GRID_SIZE, vod); + } + m_velocitySampleCount += ns; + } + else + { + // If not using velocity planning, new velocity is directly the desired velocity. + dtVcopy(ag->nvel, ag->dvel); + } + } + + // Integrate. + for (int i = 0; i < nagents; ++i) + { + dtCrowdAgent* ag = agents[i]; + integrate(ag, dt); + } + + // Handle collisions. + static const float COLLISION_RESOLVE_FACTOR = 0.7f; + + for (int iter = 0; iter < 4; ++iter) + { + for (int i = 0; i < nagents; ++i) + { + dtCrowdAgent* ag = agents[i]; + + dtVset(ag->disp, 0,0,0); + + float w = 0; + + for (int j = 0; j < ag->nneis; ++j) + { + const dtCrowdAgent* nei = &m_agents[ag->neis[j].idx]; + + float diff[3]; + dtVsub(diff, ag->npos, nei->npos); + + if (fabsf(diff[1]) >= (ag->height+ nei->height)/2.0f) + continue; + + diff[1] = 0; + + float dist = dtVlenSqr(diff); + if (dist > dtSqr(ag->radius + nei->radius)) + continue; + dist = sqrtf(dist); + float pen = (ag->radius + nei->radius) - dist; + if (dist > 0.0001f) + pen = (1.0f/dist) * (pen*0.5f) * COLLISION_RESOLVE_FACTOR; + + dtVmad(ag->disp, ag->disp, diff, pen); + + w += 1.0f; + } + + if (w > 0.0001f) + { + const float iw = 1.0f / w; + dtVscale(ag->disp, ag->disp, iw); + } + } + + for (int i = 0; i < nagents; ++i) + { + dtCrowdAgent* ag = agents[i]; + dtVadd(ag->npos, ag->npos, ag->disp); + } + } + + for (int i = 0; i < nagents; ++i) + { + dtCrowdAgent* ag = agents[i]; + // Move along navmesh. + ag->corridor.movePosition(ag->npos, m_navquery, &m_filter); + // Get valid constrained position back. + dtVcopy(ag->npos, ag->corridor.getPos()); + } + +} + + diff --git a/DetourCrowd/Source/DetourLocalBoundary.cpp b/DetourCrowd/Source/DetourLocalBoundary.cpp new file mode 100644 index 0000000..e3fdbcc --- /dev/null +++ b/DetourCrowd/Source/DetourLocalBoundary.cpp @@ -0,0 +1,121 @@ +// +// Copyright (c) 2009-2010 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// + +#include +#include +#include "DetourLocalBoundary.h" +#include "DetourNavMeshQuery.h" +#include "DetourCommon.h" +#include "DetourAssert.h" + + +dtLocalBoundary::dtLocalBoundary() : + m_nsegs(0) +{ + dtVset(m_center, FLT_MAX,FLT_MAX,FLT_MAX); +} + +dtLocalBoundary::~dtLocalBoundary() +{ +} + +void dtLocalBoundary::reset() +{ + dtVset(m_center, FLT_MAX,FLT_MAX,FLT_MAX); + m_nsegs = 0; +} + +void dtLocalBoundary::addSegment(const float dist, const float* s) +{ + // Insert neighbour based on the distance. + Segment* seg = 0; + if (!m_nsegs) + { + // First, trivial accept. + seg = &m_segs[0]; + } + else if (dist >= m_segs[m_nsegs-1].d) + { + // Further than the last segment, skip. + if (m_nsegs >= MAX_SEGS) + return; + // Last, trivial accept. + seg = &m_segs[m_nsegs]; + } + else + { + // Insert inbetween. + int i; + for (i = 0; i < m_nsegs; ++i) + if (dist <= m_segs[i].d) + break; + const int tgt = i+1; + const int n = dtMin(m_nsegs-i, MAX_SEGS-tgt); + dtAssert(tgt+n <= MAX_SEGS); + if (n > 0) + memmove(&m_segs[tgt], &m_segs[i], sizeof(Segment)*n); + seg = &m_segs[i]; + } + + seg->d = dist; + memcpy(seg->s, s, sizeof(float)*6); + + if (m_nsegs < MAX_SEGS) + m_nsegs++; +} + +void dtLocalBoundary::update(dtPolyRef ref, const float* pos, const float collisionQueryRange, + dtNavMeshQuery* navquery, const dtQueryFilter* filter) +{ + static const int MAX_LOCAL_POLYS = 16; + static const int MAX_SEGS_PER_POLY = DT_VERTS_PER_POLYGON*3; + + if (!ref) + { + dtVset(m_center, FLT_MAX,FLT_MAX,FLT_MAX); + m_nsegs = 0; + return; + } + + dtVcopy(m_center, pos); + + // First query non-overlapping polygons. + dtPolyRef locals[MAX_LOCAL_POLYS]; + int nlocals = 0; + navquery->findLocalNeighbourhood(ref, pos, collisionQueryRange, + filter, locals, 0, &nlocals, MAX_LOCAL_POLYS); + + // Secondly, store all polygon edges. + m_nsegs = 0; + float segs[MAX_SEGS_PER_POLY*6]; + int nsegs = 0; + for (int j = 0; j < nlocals; ++j) + { + navquery->getPolyWallSegments(locals[j], filter, segs, &nsegs, MAX_SEGS_PER_POLY); + for (int k = 0; k < nsegs; ++k) + { + const float* s = &segs[k*6]; + // Skip too distant segments. + float tseg; + const float distSqr = dtDistancePtSegSqr2D(pos, s, s+3, tseg); + if (distSqr > dtSqr(collisionQueryRange)) + continue; + addSegment(distSqr, s); + } + } +} diff --git a/DetourCrowd/Source/DetourPathCorridor.cpp b/DetourCrowd/Source/DetourPathCorridor.cpp new file mode 100644 index 0000000..28641fb --- /dev/null +++ b/DetourCrowd/Source/DetourPathCorridor.cpp @@ -0,0 +1,342 @@ +// +// Copyright (c) 2009-2010 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// + +#include +#include "DetourPathCorridor.h" +#include "DetourNavMeshQuery.h" +#include "DetourCommon.h" +#include "DetourAssert.h" +#include "DetourAlloc.h" + + +int dtMergeCorridorStartMoved(dtPolyRef* path, const int npath, const int maxPath, + const dtPolyRef* visited, const int nvisited) +{ + int furthestPath = -1; + int furthestVisited = -1; + + // Find furthest common polygon. + for (int i = npath-1; i >= 0; --i) + { + bool found = false; + for (int j = nvisited-1; j >= 0; --j) + { + if (path[i] == visited[j]) + { + furthestPath = i; + furthestVisited = j; + found = true; + } + } + if (found) + break; + } + + // If no intersection found just return current path. + if (furthestPath == -1 || furthestVisited == -1) + return npath; + + // Concatenate paths. + + // Adjust beginning of the buffer to include the visited. + const int req = nvisited - furthestVisited; + const int orig = dtMin(furthestPath+1, npath); + int size = dtMax(0, npath-orig); + if (req+size > maxPath) + size = maxPath-req; + if (size) + memmove(path+req, path+orig, size*sizeof(dtPolyRef)); + + // Store visited + for (int i = 0; i < req; ++i) + path[i] = visited[(nvisited-1)-i]; + + return req+size; +} + +int dtMergeCorridorEndMoved(dtPolyRef* path, const int npath, const int maxPath, + const dtPolyRef* visited, const int nvisited) +{ + int furthestPath = -1; + int furthestVisited = -1; + + // Find furthest common polygon. + for (int i = 0; i < npath; ++i) + { + bool found = false; + for (int j = nvisited-1; j >= 0; --j) + { + if (path[i] == visited[j]) + { + furthestPath = i; + furthestVisited = j; + found = true; + } + } + if (found) + break; + } + + // If no intersection found just return current path. + if (furthestPath == -1 || furthestVisited == -1) + return npath; + + // Concatenate paths. + const int ppos = furthestPath+1; + const int vpos = furthestVisited+1; + const int count = dtMin(nvisited-vpos, maxPath-ppos); + dtAssert(ppos+count <= maxPath); + if (count) + memcpy(path+ppos, visited+vpos, sizeof(dtPolyRef)*count); + + return ppos+count; +} + +int dtMergeCorridorStartShortcut(dtPolyRef* path, const int npath, const int maxPath, + const dtPolyRef* visited, const int nvisited) +{ + int furthestPath = -1; + int furthestVisited = -1; + + // Find furthest common polygon. + for (int i = npath-1; i >= 0; --i) + { + bool found = false; + for (int j = nvisited-1; j >= 0; --j) + { + if (path[i] == visited[j]) + { + furthestPath = i; + furthestVisited = j; + found = true; + } + } + if (found) + break; + } + + // If no intersection found just return current path. + if (furthestPath == -1 || furthestVisited == -1) + return npath; + + // Concatenate paths. + + // Adjust beginning of the buffer to include the visited. + const int req = furthestVisited; + if (req <= 0) + return npath; + + const int orig = furthestPath; + int size = dtMax(0, npath-orig); + if (req+size > maxPath) + size = maxPath-req; + if (size) + memmove(path+req, path+orig, size*sizeof(dtPolyRef)); + + // Store visited + for (int i = 0; i < req; ++i) + path[i] = visited[i]; + + return req+size; +} + +dtPathCorridor::dtPathCorridor() : + m_path(0), + m_npath(0), + m_maxPath(0) +{ +} + +dtPathCorridor::~dtPathCorridor() +{ + dtFree(m_path); +} + +bool dtPathCorridor::init(const int maxPath) +{ + dtAssert(!m_path); + m_path = (dtPolyRef*)dtAlloc(sizeof(dtPolyRef)*maxPath, DT_ALLOC_PERM); + if (!m_path) + return false; + m_npath = 0; + m_maxPath = maxPath; + return true; +} + +void dtPathCorridor::reset(dtPolyRef ref, const float* pos) +{ + dtAssert(m_path); + dtVcopy(m_pos, pos); + dtVcopy(m_target, pos); + m_path[0] = ref; + m_npath = 1; +} + +int dtPathCorridor::findCorners(float* cornerVerts, unsigned char* cornerFlags, + dtPolyRef* cornerPolys, const int maxCorners, + dtNavMeshQuery* navquery, const dtQueryFilter* filter) +{ + dtAssert(m_path); + dtAssert(m_npath); + + static const float MIN_TARGET_DIST = 0.01f; + + int ncorners = 0; + navquery->findStraightPath(m_pos, m_target, m_path, m_npath, + cornerVerts, cornerFlags, cornerPolys, &ncorners, maxCorners); + + // Prune points in the beginning of the path which are too close. + while (ncorners) + { + if ((cornerFlags[0] & DT_STRAIGHTPATH_OFFMESH_CONNECTION) || + dtVdist2DSqr(&cornerVerts[0], m_pos) > dtSqr(MIN_TARGET_DIST)) + break; + ncorners--; + if (ncorners) + { + memmove(cornerFlags, cornerFlags+1, sizeof(unsigned char)*ncorners); + memmove(cornerPolys, cornerPolys+1, sizeof(dtPolyRef)*ncorners); + memmove(cornerVerts, cornerVerts+3, sizeof(float)*3*ncorners); + } + } + + // Prune points after an off-mesh connection. + for (int i = 0; i < ncorners; ++i) + { + if (cornerFlags[i] & DT_STRAIGHTPATH_OFFMESH_CONNECTION) + { + ncorners = i+1; + break; + } + } + + return ncorners; +} + +void dtPathCorridor::optimizePathVisibility(const float* next, const float pathOptimizationRange, + dtNavMeshQuery* navquery, const dtQueryFilter* filter) +{ + dtAssert(m_path); + + // Clamp the ray to max distance. + float goal[3]; + dtVcopy(goal, next); + float dist = dtVdist2D(m_pos, goal); + + // If too close to the goal, do not try to optimize. + if (dist < 0.01f) + return; + + // Overshoot a little. This helps to optimize open fields in tiled meshes. + dist = dtMin(dist+0.01f, pathOptimizationRange); + + // Adjust ray length. + float delta[3]; + dtVsub(delta, goal, m_pos); + dtVmad(goal, m_pos, delta, pathOptimizationRange/dist); + + static const int MAX_RES = 32; + dtPolyRef res[MAX_RES]; + float t, norm[3]; + int nres = 0; + navquery->raycast(m_path[0], m_pos, goal, filter, &t, norm, res, &nres, MAX_RES); + if (nres > 1 && t > 0.99f) + { + m_npath = dtMergeCorridorStartShortcut(m_path, m_npath, m_maxPath, res, nres); + } +} + +bool dtPathCorridor::optimizePathTopology(dtNavMeshQuery* navquery, const dtQueryFilter* filter) +{ + dtAssert(m_path); + + if (m_npath < 3) + return false; + + static const int MAX_ITER = 32; + static const int MAX_RES = 32; + + dtPolyRef res[MAX_RES]; + int nres = 0; + navquery->initSlicedFindPath(m_path[0], m_path[m_npath-1], m_pos, m_target, filter); + navquery->updateSlicedFindPath(MAX_ITER, 0); + dtStatus status = navquery->finalizeSlicedFindPathPartial(m_path, m_npath, res, &nres, MAX_RES); + + if (status == DT_SUCCESS && nres > 0) + { + m_npath = dtMergeCorridorStartShortcut(m_path, m_npath, m_maxPath, res, nres); + return true; + } + + return false; +} + +void dtPathCorridor::movePosition(const float* npos, dtNavMeshQuery* navquery, const dtQueryFilter* filter) +{ + dtAssert(m_path); + dtAssert(m_npath); + + // Move along navmesh and update new position. + float result[3]; + static const int MAX_VISITED = 16; + dtPolyRef visited[MAX_VISITED]; + int nvisited = 0; + navquery->moveAlongSurface(m_path[0], m_pos, npos, filter, + result, visited, &nvisited, MAX_VISITED); + m_npath = dtMergeCorridorStartMoved(m_path, m_npath, m_maxPath, visited, nvisited); + + // Adjust the position to stay on top of the navmesh. + float h = m_pos[1]; + navquery->getPolyHeight(m_path[0], result, &h); + result[1] = h; + dtVcopy(m_pos, result); +} + +void dtPathCorridor::moveTargetPosition(const float* npos, dtNavMeshQuery* navquery, const dtQueryFilter* filter) +{ + dtAssert(m_path); + dtAssert(m_npath); + + // Move along navmesh and update new position. + float result[3]; + static const int MAX_VISITED = 16; + dtPolyRef visited[MAX_VISITED]; + int nvisited = 0; + navquery->moveAlongSurface(m_path[m_npath-1], m_target, npos, filter, + result, visited, &nvisited, MAX_VISITED); + m_npath = dtMergeCorridorEndMoved(m_path, m_npath, m_maxPath, visited, nvisited); + + // TODO: should we do that? + // Adjust the position to stay on top of the navmesh. + /* float h = m_target[1]; + navquery->getPolyHeight(m_path[m_npath-1], result, &h); + result[1] = h;*/ + + dtVcopy(m_target, result); +} + +void dtPathCorridor::setCorridor(const float* target, const dtPolyRef* path, const int npath) +{ + dtAssert(m_path); + dtAssert(npath > 0); + dtAssert(npath < m_maxPath); + + dtVcopy(m_target, target); + memcpy(m_path, path, sizeof(dtPolyRef)*npath); + m_npath = npath; +} diff --git a/DetourCrowd/Source/DetourPathQueue.cpp b/DetourCrowd/Source/DetourPathQueue.cpp new file mode 100644 index 0000000..f7c4c48 --- /dev/null +++ b/DetourCrowd/Source/DetourPathQueue.cpp @@ -0,0 +1,197 @@ +// +// Copyright (c) 2009-2010 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// + +#include +#include "DetourPathQueue.h" +#include "DetourNavMesh.h" +#include "DetourNavMeshQuery.h" +#include "DetourAlloc.h" +#include "DetourCommon.h" + + +dtPathQueue::dtPathQueue() : + m_nextHandle(1), + m_maxPathSize(0), + m_queueHead(0), + m_navquery(0) +{ +} + +dtPathQueue::~dtPathQueue() +{ + purge(); +} + +void dtPathQueue::purge() +{ + dtFreeNavMeshQuery(m_navquery); + m_navquery = 0; + for (int i = 0; i < MAX_QUEUE; ++i) + { + dtFree(m_queue[i].path); + m_queue[i].path = 0; + } +} + +bool dtPathQueue::init(const int maxPathSize, const int maxSearchNodeCount, dtNavMesh* nav) +{ + purge(); + + m_navquery = dtAllocNavMeshQuery(); + if (!m_navquery) + return false; + if (dtStatusFailed(m_navquery->init(nav, maxSearchNodeCount))) + return false; + + m_maxPathSize = maxPathSize; + for (int i = 0; i < MAX_QUEUE; ++i) + { + m_queue[i].ref = DT_PATHQ_INVALID; + m_queue[i].path = (dtPolyRef*)dtAlloc(sizeof(dtPolyRef)*m_maxPathSize, DT_ALLOC_PERM); + if (!m_queue[i].path) + return false; + } + + m_queueHead = 0; + + return true; +} + +void dtPathQueue::update(const int maxIters) +{ + static const int MAX_KEEP_ALIVE = 2; // in update ticks. + + // Update path request until there is nothing to update + // or upto maxIters pathfinder iterations has been consumed. + int iterCount = maxIters; + + for (int i = 0; i < MAX_QUEUE; ++i) + { + PathQuery& q = m_queue[m_queueHead % MAX_QUEUE]; + + // Skip inactive requests. + if (q.ref == DT_PATHQ_INVALID) + { + m_queueHead++; + continue; + } + + // Handle completed request. + if (dtStatusSucceed(q.status) || dtStatusFailed(q.status)) + { + // If the path result has not been read in few frames, free the slot. + q.keepAlive++; + if (q.keepAlive > MAX_KEEP_ALIVE) + { + q.ref = DT_PATHQ_INVALID; + q.status = 0; + } + + m_queueHead++; + continue; + } + + // Handle query start. + if (q.status == 0) + { + q.status = m_navquery->initSlicedFindPath(q.startRef, q.endRef, q.startPos, q.endPos, q.filter); + } + // Handle query in progress. + if (dtStatusInProgress(q.status)) + { + int iters = 0; + q.status = m_navquery->updateSlicedFindPath(iterCount, &iters); + iterCount -= iters; + } + if (dtStatusSucceed(q.status)) + { + q.status = m_navquery->finalizeSlicedFindPath(q.path, &q.npath, m_maxPathSize); + } + + if (iterCount <= 0) + break; + + m_queueHead++; + } +} + +dtPathQueueRef dtPathQueue::request(dtPolyRef startRef, dtPolyRef endRef, + const float* startPos, const float* endPos, + const dtQueryFilter* filter) +{ + // Find empty slot + int slot = -1; + for (int i = 0; i < MAX_QUEUE; ++i) + { + if (m_queue[i].ref == DT_PATHQ_INVALID) + { + slot = i; + break; + } + } + // Could not find slot. + if (slot == -1) + return DT_PATHQ_INVALID; + + dtPathQueueRef ref = m_nextHandle++; + if (m_nextHandle == DT_PATHQ_INVALID) m_nextHandle++; + + PathQuery& q = m_queue[slot]; + q.ref = ref; + dtVcopy(q.startPos, startPos); + q.startRef = startRef; + dtVcopy(q.endPos, endPos); + q.endRef = endRef; + + q.status = 0; + q.npath = 0; + q.filter = filter; + q.keepAlive = 0; + + return ref; +} + +dtStatus dtPathQueue::getRequestStatus(dtPathQueueRef ref) const +{ + for (int i = 0; i < MAX_QUEUE; ++i) + { + if (m_queue[i].ref == ref) + return m_queue[i].status; + } + return DT_FAILURE; +} + +dtStatus dtPathQueue::getPathResult(dtPathQueueRef ref, dtPolyRef* path, int* pathSize, const int maxPath) +{ + for (int i = 0; i < MAX_QUEUE; ++i) + { + if (m_queue[i].ref == ref) + { + PathQuery& q = m_queue[i]; + // Free request for reuse. + q.ref = DT_PATHQ_INVALID; + q.status = 0; + // Copy path + int n = dtMin(q.npath, maxPath); + memcpy(path, q.path, sizeof(dtPolyRef)*n); + *pathSize = n; + return DT_SUCCESS; + } + } + return DT_FAILURE; +} diff --git a/DetourCrowd/Source/DetourProximityGrid.cpp b/DetourCrowd/Source/DetourProximityGrid.cpp new file mode 100644 index 0000000..d8226a4 --- /dev/null +++ b/DetourCrowd/Source/DetourProximityGrid.cpp @@ -0,0 +1,194 @@ +// +// Copyright (c) 2009-2010 Mikko Mononen memon@inside.org +// +// This software is provided 'as-is', without any express or implied +// warranty. In no event will the authors be held liable for any damages +// arising from the use of this software. +// Permission is granted to anyone to use this software for any purpose, +// including commercial applications, and to alter it and redistribute it +// freely, subject to the following restrictions: +// 1. The origin of this software must not be misrepresented; you must not +// claim that you wrote the original software. If you use this software +// in a product, an acknowledgment in the product documentation would be +// appreciated but is not required. +// 2. Altered source versions must be plainly marked as such, and must not be +// misrepresented as being the original software. +// 3. This notice may not be removed or altered from any source distribution. +// + +#include +#include +#include +#include "DetourProximityGrid.h" +#include "DetourCommon.h" +#include "DetourAlloc.h" +#include "DetourAssert.h" + + +dtProximityGrid* dtAllocProximityGrid() +{ + void* mem = dtAlloc(sizeof(dtProximityGrid), DT_ALLOC_PERM); + if (!mem) return 0; + return new(mem) dtProximityGrid; +} + +void dtFreeProximityGrid(dtProximityGrid* ptr) +{ + if (!ptr) return; + ptr->~dtProximityGrid(); + dtFree(ptr); +} + + +inline int hashPos2(int x, int y, int n) +{ + return ((x*73856093) ^ (y*19349663)) & (n-1); +} + + +dtProximityGrid::dtProximityGrid() : + m_maxItems(0), + m_cellSize(0), + m_pool(0), + m_poolHead(0), + m_poolSize(0), + m_buckets(0), + m_bucketsSize(0) +{ +} + +dtProximityGrid::~dtProximityGrid() +{ + dtFree(m_buckets); + dtFree(m_pool); +} + +bool dtProximityGrid::init(const int poolSize, const float cellSize) +{ + dtAssert(poolSize > 0); + dtAssert(cellSize > 0.0f); + + m_cellSize = cellSize; + m_invCellSize = 1.0f / m_cellSize; + + // Allocate hashs buckets + m_bucketsSize = dtNextPow2(poolSize); + m_buckets = (unsigned short*)dtAlloc(sizeof(unsigned short)*m_bucketsSize, DT_ALLOC_PERM); + if (!m_buckets) + return false; + + // Allocate pool of items. + m_poolSize = poolSize; + m_poolHead = 0; + m_pool = (Item*)dtAlloc(sizeof(Item)*m_poolSize, DT_ALLOC_PERM); + if (!m_pool) + return false; + + clear(); + + return true; +} + +void dtProximityGrid::clear() +{ + memset(m_buckets, 0xff, sizeof(unsigned short)*m_bucketsSize); + m_poolHead = 0; + m_bounds[0] = 0xffff; + m_bounds[1] = 0xffff; + m_bounds[2] = -0xffff; + m_bounds[3] = -0xffff; +} + +void dtProximityGrid::addItem(const unsigned short id, + const float minx, const float miny, + const float maxx, const float maxy) +{ + const int iminx = (int)floorf(minx * m_invCellSize); + const int iminy = (int)floorf(miny * m_invCellSize); + const int imaxx = (int)floorf(maxx * m_invCellSize); + const int imaxy = (int)floorf(maxy * m_invCellSize); + + m_bounds[0] = dtMin(m_bounds[0], iminx); + m_bounds[1] = dtMin(m_bounds[1], iminy); + m_bounds[2] = dtMax(m_bounds[2], imaxx); + m_bounds[3] = dtMax(m_bounds[3], imaxy); + + for (int y = iminy; y <= imaxy; ++y) + { + for (int x = iminx; x <= imaxx; ++x) + { + if (m_poolHead < m_poolSize) + { + const int h = hashPos2(x, y, m_bucketsSize); + const unsigned short idx = (unsigned short)m_poolHead; + m_poolHead++; + Item& item = m_pool[idx]; + item.x = (short)x; + item.y = (short)y; + item.id = id; + item.next = m_buckets[h]; + m_buckets[h] = idx; + } + } + } +} + +int dtProximityGrid::queryItems(const float minx, const float miny, + const float maxx, const float maxy, + unsigned short* ids, const int maxIds) const +{ + const int iminx = (int)floorf(minx * m_invCellSize); + const int iminy = (int)floorf(miny * m_invCellSize); + const int imaxx = (int)floorf(maxx * m_invCellSize); + const int imaxy = (int)floorf(maxy * m_invCellSize); + + int n = 0; + + for (int y = iminy; y <= imaxy; ++y) + { + for (int x = iminx; x <= imaxx; ++x) + { + const int h = hashPos2(x, y, m_bucketsSize); + unsigned short idx = m_buckets[h]; + while (idx != 0xffff) + { + Item& item = m_pool[idx]; + if ((int)item.x == x && (int)item.y == y) + { + // Check if the id exists already. + const unsigned short* end = ids + n; + unsigned short* i = ids; + while (i != end && *i != item.id) + ++i; + // Item not found, add it. + if (i == end) + { + if (n >= maxIds) + return n; + ids[n++] = item.id; + } + } + idx = item.next; + } + } + } + + return n; +} + +int dtProximityGrid::getItemCountAt(const int x, const int y) const +{ + int n = 0; + + const int h = hashPos2(x, y, m_bucketsSize); + unsigned short idx = m_buckets[h]; + while (idx != 0xffff) + { + Item& item = m_pool[idx]; + if ((int)item.x == x && (int)item.y == y) + n++; + idx = item.next; + } + + return n; +} diff --git a/RecastDemo/Bin/Recast.app/Contents/MacOS/Recast b/RecastDemo/Bin/Recast.app/Contents/MacOS/Recast index 9271ed04e550b542ab41191f11e793e3a89db0b2..331eb7ee2cdcc4d8c19ea9317d1cf36d2659ee22 100755 GIT binary patch delta 274879 zcmbq+30#%M_xGLQBFJ_@_C*#!L`4O~eFItC6%iCvT*^{Q%M#Q|1A|-A^_KNWqvl$u zxRe&^bxl-4G%a!|*R-;_gq4|D=(w0)H+#=cPKG^NN`S`yl=^gVJDl&t+X3oo>T5y>6YqvfHzl z%OGb*-MoQ1-JmZDB8xgZ>TX+!Uv|R|(-B9V zsj!R1QP*%yg_#N?EfsS+D2!K*RJL~-pbYOcSxxTZiSf$gaj|?^T*b1uVG<#+hhN2= z_}wzSqf2=sjc>&V3D4S5dUtc+D62^9F@W)^krl-~Ipvkby{ieF-eRV6kqODgDy419R1BO;mB_W zPj}R`wy(ePW12#h77ScO0`fs2tbMj0bXDZWbUI^Yo^y#l%9Pmc~tp2`u9*wUwUNRJaB-Y>M{w}TrLQ9+bDqceaLh5{wO^C9NqNg$DenW$?GT%T5 zD}0pHp^+|Yr~uiSKFYI0zwjIhotcf_0gqY{=c{B7TgNL~D1Qz6m|MJ*!@~pkX0M7% z!_mj+hPETe^Vk;3%OiX8pA5?3k)ixKgYxyr4k2H8fGZfBpl5XnI^mc;iVVwI>!Gwu zZ#DKq6cktH#g+6y)dok>TNL`rEnDp~=Um`Y-_54HJ}TA?qsaq!)RrfRDMWq*&-F3a zpu?=|T|Dy~t*!>;-Sjm7k)9|&M%90SlzBEIqE?=7j*9RY4FDA2LgZIHluo03`8ZD{ zZBzzdXHZs-isXSF%ArxwfupIa)XVFa>~PYN^rox;(sv(&@?caDf8eGBWpw3r9?GbU z&U}}LV$A5tpZ8EIGg|qLA>odivd))ef-Lnci4pCl+{uVG9HzFU*67i+dxs7?D;-8h z^Hc6h*65!6O?PGK=&rryxT7(?2~;VliF67eC8@QhzGVQKy2epa9*Us0G!&V0uTfLn zU6qE>?ZYp+IO-lp^8yKWLCd(=@Nc>)Lo!3V)k2jI*YOb`Xr%M{Sgo~0zL_+h4IU)L z5Eo@lW>mpkLQFl|sFmSoOWdNYlK@7o?bk2X=+`f!1n5#xV)8AfoYtN$DhpHBLIR>C zroPK5h4uuX2wm>H>_;M6(1hrLE9$K_DM?uY{Hm)mJ}bJD1)%ja35R;ecNL}3LF)(; zJWTG>2{H_tLf^mYs_e+}<#Sw>V_D&Rl&eyg70F{=6^}6iyoIY0GbS?aC$!Y$D;Yvk zle=Vyww)slkZvSD)J6O%2|4R5+T>iaK$`Y#$ZXy0qP#ICJm?iFb(if!{ieQ>725Z- zi}J~sn4nbRcoa>Cki%?3LRTGJ6!)RIV;h`3w@P2df^e3YADO#hcx!)7GZz4e; z2Z?qT5Sd07)=;Tk(d(t2!RrHnNzXp@D1J!KqPb%LDcUaldMP_-UTm%$7~8II25~?7 zPX+gCQfo(~*UQ#F)HD9gmB{Rvf}b!3)Yh+;jVFyl)Gq)w`Nq*$<|g++P1JIL2uL5k zvIjIX+DQ2B65mT|rAHI3ln{xgkA=20DtX4)abQ!0loJgaH;$M+H0o&Pz#z6&K>Z)n zq=L52idT+*OV1{}^;+7ru$FB3cPAw^CzjtBsm#eaz#}#(@#9iLE^TxGS5ke7=H2j+ z61>|?d1G7zTccEriwl`$M;r7XXk7^{q*(&M);J|%e1`%L;F^-9r*M!-Ig8xcfQoXp zDW@J8Ir$vTD*0}7(G4F{uCwt{Ub4x7+I|Y98iOM;DH&K~(v1+d$)qPG*CT0Xy9}8k z<<$77f+q>X!ITmwNpq1KSXAxP`vv`i%W54%Y;+;xCr&zE*PAG-Wcp!|dYY1ZP(4A! zFu4yU4KkTXNxe*_Q1WhB6G7Mw<(Ua#?k54OcQ*x4d8M*?fhmcdGIeP-5H_ zmq&uQM?*#QBi}Q(%V?r$_$miCzVv-_?Y7 zRk}T1$KsXnX}+ma;3OJ^wyLSpAMWaP=8)e>emfY0?B^9|GiJ*HebDA;v{JSi;y*tv zHf9NE?8s=_Njb0%}QY{se5RKLK~zw+uW5&GY@jV+e+xHfWUjd>1ismx6YJ$k{bBk zZxthFb)j|6TT^*!W%E<**h1y(Qycxhc>_`}yk63~WDXVv*G!zSPbo{E?rs-pELQ&1 z&?qPshT({1hjr^O%6CsMXJ?cbXUBwYSqh`FDK){-!fR7B=Qu@-k= z0wo8_KxxV^b4V~crz<)6FZrl^|1=q?gxz$|uf8)<`6Yj*8{wOB%N#-obK2a6ZYt(g zkfPq3b33pW1Tp2h8MZq(q?Sv0luq-r*?nd4{1A3c*)TsWxN-SyNW6Y53BTVI+adlQ={+ z7UnN0$$Pl4nX#g9!79114SlhUA9+dXzG!HLp&**Gkrmw*IdC>q=~eVJ+oWtMn%FXP zA?m^44#c?jG_4*4UE0iRkB8E__z8AcSz7GJZ+a-@#clZ5%gX1)t%7nFpx=*_Bs;?# z+nAEwY<(VXP~453_>Y$=`Wg2+@N|Q6cX2vjVo-*bES^|0556rR{!+c;ewaF1Cp&o# zK@FIuQZG}VPnB6MGnO(zC_6|dMl(_>Af$m&=k&VxOD1W0MAl)R68~xsUS&|8d^N{z zzaiSF4uIjpes_@lzJIpjn^(P<9cSgkI131;;7o1N}|FF%9=AVL+jEha9dzxx6}> zjZhrcMDV3vO7xm&u76Y+u_h?6$_uW(v(4kdVN+*7>9xwDHNpIjm$GI}7Vm#V`F%~q zjF2Ok0J3~c1DyZU({d^q?qf=VnMn@+;fcRFOrCfbR4x4gnF#fC-4trj4z)p1Hfgb4 zD_9$sPy`y1i;$rcT_TngW=Swp5*UmXfs&n@4%=s7I!|b!e7iO|pq)h8Y2&KRX-iuu z{no{?ZE( z=SvPKtIAA#n0H0n4Y`b+P+r+Mh%fN2_IbqtG zw#{4Nn>&SuNgOv7r=7{1N3-NGwXe>5Dk z9os94KlqIEGuxD`olE)fZORWjU*L(p%G6zb3-%AiFb{5Y4CZU7nH=XkRNzD7|2jc1 zXqHL{jeH4#5x!`{DYX&~#@S38j#)y$XB4K42?3vBHXJhzTjJBphI3Ftz$a#e4M{o! zV&rE-Dkb+o0_h1t6NY)4#^}~SG&Cg2`e1{cFb+yM*j-eL_V%|=0&B2siaAAr%8IL%%pHuY1mHNOX*i{ z`YChv$Ip5V^_%s94$hpo8yN5Rf!Yo$nOo=7Au7+h1`z*xR?cB)tw&`$QBIpiDRz!{2{b zdHGEi5dNp(9K@3#Qf`Y zTF^;m(d(&|)XH#MX;vlKgcoILkPN>@mc@~!c6qFo29bY_IQ&#GyRw#X&;Atyjtq5l zNyMa1N2NF$6vvWydb)D)*id(Z8pa++fg=h!*Q8Rxb2ZEO4{s@km_wH-Yfeeb>7SglV|YbJ(aA!;=<<%&j4gvSX@0&&un`Lv%1n9t91N&1a}TsUi>#`1MTUM(S^Rwz+fnh}_xD)eiU3rk zE~(3rtdAlzxx!vSSx#BG!hRK58USz2#d=Hy%~QU&_Otgo)10B!>vx0D>m%l(*Q1oj z>!Jdx{Xw5vC_6jNzT3+TQr@ZS%E!-BE&yjV;TY4=Khke#tBb`!6}~@Ka<*Oh;zkK? z?W0WjDTMEuQ&I3!M~9KyJt3u!wlk1|u9gtUZ6-!Ec1;q3alcDKFmRtENHTC17Si1%A8;4vbU8Ve~nqS7?gi&J}-PqDZdrMA9+ft zzO~g;wXM`Lhtw+778m{2WDg)7*2<5hm8(xcD}&h>H-1mk`(!v#KdHM(Gd7p-Q2mv(zgqDSC*_I1BG_GJ$zKoD z5wJRe%v`or9RX|qUTqrzwAM2j34unyK@8l?dz)Iwfs<9NY7Bc4j2id*3)x?a>3$fy zsBFdWzKT!o|IP|lu_o%4X7VaQ8aHAu$gE}{PfzVGD!LI+l6$8l|DGw|*_0;Fz8>gM zp)dM1O&;I%?t68_TH`$iAnz2L7Z7Hn=lI0oU2rhd6j<$22rp zBcmD`;C6F@#S#~gPYM>5F04I&JXrkX0yeXPMTjfw;60Dr^6T*+7#%4I76pq5uB;

r)+cnEwUx?JdNwrR8cSa|H-TA?wvtQ^2a6lv?o>+% zhvLK=F3eYSbz=eiTCf=DhI)UYk_mCBH(Vuo5G-DIL%l8`;*c9_+cGEw2sb+cVP`}` z!$Wsmn=^!?J1b$);&peH;y0rUla7t%;zrp zsH&PQ&!WIs;1-Gc&vaFR-=>S#Jy>}71W|p1j5PAi^}@0V&eSB0hzJ>bsJ_gaznqf>u+V`ltnzUbdR z+xk`Vxx=vAab3D-@5Ng82#Myp^|b^xLg@|b&&njmU&H$IGD*t}gT?VOGLM%SVebu~ z{wiH8_F}CP--P7?n-bUt}-{u1W!HD#6+TW;RYG?%)9E;{**N zOnsCCdc^wUaGCZb_)Rq(PU-7N|7K`sOw5HAe=~R)J>|2VnYt5svyXgEJp7wsT;(m4 z2OxjUI0(P0w$tsYOnWL@rV<7mGfq%bN5u2qET-U?G0%=O+n$=QrN}>*jiObzSLp)4 zju{K>IK}qVVtZ7wseq-x$f!h<^&m>YPAabfMuL=SP@U zlc*Fl@hw0mGv!PSBd#GmpsrS8#RE&ijmHhe2MMcGVsRK^K|^{--4=<~Grz5=lr&&G zZ78-aboN0mlbN72h%cUFy1E4tJI-L70<$tnoxwMSs44Qq9_JaVkTkIL>><+bVya+k zl*Zs8Zor#)mgx%W9qV4h>71QU3ONp{)ohew1=ifiYu>jEF2P`I4aGJ}wf0NYXXjcs z81=ygsQqUyrQvMbLRS-Cv*e4`yfDK-=Un$^m{f=ekHgd!?8iKVr9vz7!keh6A$=Gv zLGOq(KQ^7a9T7YHSepWM=bHT+*{zz+`QkT2b}iX2SvS)6P}Wi_yNdjIl&z*Qfb@HA z^6BZWm7fBvhDO|c3D0q)m>uMeG#0?ev0RRg94+rvppJCu6Ee|iLfQ5(ii#mUL}#g& zY_QVlnhwmm7U;&l-k1jRy&Jt%uK`?FcL%_}KKL;hf5NZ1RQfXXX*!i&6zBYzXTfsf zXfPfD0t7Hp1tc?#T;$C({;5qgeoaR56}T#*bSZg@l2RJO>iEUjl;gK<9$59!=f@Ww zl)Up?8_ar`Ox+}{ilrby92556P)}dfMS!{iMCE8O_QJD~(kLmTRZ48-Nuk+hm4lag zsaPMtd~Hqm5#zn^pp?O2yn>9~uehRmtos0}JBgnMH3lQh*;b9gXhFuBpQhK9I~YnU zOO90=B}Ls@zzvqt6mrX@)OLf#n1&2a0g-8YxWr6KC@4HA{a0RI`%+R(NlkkrsRdrS z5-N1xq4p_EBipR1)yu4^x!q}$w_K-|Uqtz8QZv-On$&LCjw7hktQL;r#XwcLtlm@g zW31juYn|EXLN190wLvVBg^QzjIFaM6Hd@6`K`esp6oz2d29NG|c&kj* zakK!8OvXFnnP3(bOOlaW%zPmrPP-8rNhMGV65S^smSOF zAjvlfxR3|^KxaQ>Nx7I5kGQ8}P2gzAMB3Ar(uS-PhB0y=6GePOedaNvGg7Bc4(nUg zpf8BE`Ru#^n~NbuQ!zYpLwa1j3la2HDZo`uwy=1~g|tC@2iin3badYd3z+w|I{9G! zcQchHiq#>^pBJQv-61TjU<=xdSw@!x^)FY`-_YcLfYPYjfzEjJQ5+BJvugR*?nu9- zrk^3)rD~e_BVCEKbr*iHD3I<53xkxX0I;F}MPi8{&YS&jL2Ch!wJnN=;S>`RsHJ+H zZg8UYoXSy09G@nRQZ zLjY$|7I{}2Ku>_#b^vUgB@53`<}-Zr04$hF6OX|t5QhWFHc}fEf|@g7HxzFL=sN^0 z0`wM^NHkb!1r#oy?aVZykvGSPXF}O{UNAs>8p>V@Qj19(YJZH1g!$&%B=JNT>oxjV zf9b1BRlCaZ-J`Zd+En5EdAfXRh9g-LMgXio+c+6KsNdD6-TG{K^JMW}I15N_T3k4P z&c864sxeZZjf}Lsd8*2&X>sBFDgVM~y2eO-HZs!k=IN4AY}4Yx`BNWegaMviI#V(t z2IALn7CM3Q*4%#NO7mQx2j2tGPCaSFw^G%UStXfZR+;CVfR@bK7&WSrPtY_&+RL$x z-wjK}lMyVqEt$hD!?@DP=zGn@l#Wb!nhl7$N1Y(YdH_vMw{fjzmU~HH z_~3TL6IgD4scy>|G4W6v>A3^lcmRc*#Ccl0Ujkuqsn&Dyn1dB}-4Hen8V67o);|5@cy4*Jn zfbVWsNUP7^3=ZATvKSkv3wT;*0o7*X(xlZkpa^Yf<4BG8P-I8576nEaR*>&+ZR-RIva)5u~eZkEhv~3|QRHd`JLfGO?i$(+OO=2HMkJ=5?OlE0FtyyedE^6E0 zJTK2({Md#C%}nd1*A*RgUi5d=w~o5}W5z%7(o6^M0NL2^A1+O=?W9Jen^x17j`pC# z@E(Y%nYLlWyo$rPhV+=at^}65NNhn%E7kTGPm9?x%-@TcYdcojWR>0#%VXFiw*(R} z<})mN%n2eco`oR-Rg8*feg))_;e~%T#GKRox9X5p@IfL39F+fcH>K^Oa*l=!@DW#Ap>>J_u@)h7NvH}NwpvTrCSD5w@h$q z(k;?ksBS~_ZHG4NT*bt8tXu4-sINNp-Ns?kWWODKwCR3(c2`l^jKbGUzaqN2@N4 zrje(vko`%%aBI8csiB%93)1b^!;i%OVd|}Mz|w;5=r(l`Ydd1J|fo(xRYFm{TfF@#$Sx- z#Ju~SgO+UL=Hs}gzZi+paGe;cqaof+JGhezFOeI^TBbZayF3C4j2M@aTg5oG zn@(LQPxr9W41ee}Q1z`)9AbQZ#EOqkxu_@#Pp;QlL(Z5 z8!>iQkf64d+Jjl9k9t5C))@yn(iWl4W!IR_nh6J6cyJFy#(Gm=aE4ItX|i3lE3mIcmxHT)DQedq_8~Nkw3*k<+6v;(ZrKMwxtVrD&g`k?Fc%=F?O46w z56t#^jrMPFXw(WksMiDqnM;?G(Be!N*0T?t)X1{|Pn;B(>F8WN3P7%u4$YB+&sg4p zE{6=ofvSFWx^;=xfDU3%0&7*UE>@05^oGtl7wPy*SQp}NV#_LR->kj>k%M;|vny$r z>?8S(GnYdQ!g%= z{HTj>sC(@?>Zln9)jb2ECVdb0QrQ&;Lr&PRG`gr!Kx(|BazfM`MUXU}nE#I3Z3-f3 z?ENY2=?>IvKN%iH`2eDkTL7r(4aVh7Ze3eikxM9g;srqCE9(kQLtL9!Sd_zYs%!Cf z*KnlU96u)M?2Uh*P`%1wjn_2sf7Cs=3R7!3AJl#QD~N2DB275ny$z1%@nhSe6UPF% zAA6YPDZv%Q^gd7Z<$C8H=Vbs-o*%dq~7+L_i=E zNlfU@ig{cs@lAKumwhI}d$3S8PW11={^WZ;5)nNxD~;^Qn&H%HOi#AAeGLuok6|K) z-KjU=3Y_CBi}s&|&YBsPRU%JISh-~@a}~XMvGz{2MDVPum`R!Qlu2|IYbXVA; zs70okl}auP)|rflM<`%6udK zCi(zM?`SSM_5oH~%DmWIOr}gv$_#5R-lWVh$^y%D)-i>roRowWA z$Lmi2F20K4i3tx5jOtM9S8pw z2uQ$j=A#5nh_a5Pr&ih48u2SC>l{mLPQfpuz0qKEnb@?qv-$2fu;KM(HnJ%-4I=cM zKA>O#(G{t5)V$edOoLyC+p6z<5@Xb{ZY(X7v>JWj<*YB=hU@w8mj?}|F~hKYaMmVP zAMFLVx-BT8a2^CJ6y2CflMcPRZAz8FIk$;@^|92QI-NMvpSAX_1z^#_J(;Pahv#=G zT6lovcd-5}+!I-d@9*2_<)Nb2 z065H7LiM^dBAdGjEUFDl=0S}nHTbD5%8IHcG!An04MkJ(WNchyw9xvNaQDfR(GbKB zO(k1d`P z_|3y|!4|Az&;Z!GeB%Ak1Gmgn7SmjT)%B#hFC<-k+jfG8@8AdyBcrtXKG7Kqo^^1fDso zjE-e?1!JBXUPkA$x}QXCGFzKIAEb6H_2}%6AYiEkNjETJUZJsxn&fiv<)-*5t7^hm zNxg1}Ln$np2X1ja$JUUiubMqktr7_TtS!tS7%VN}L+RQuxhL!h0|q z#Geijxr12`-&lxBVub_UoK;2YUKt>^3`V%viXX(q!K{ORnx9^$eEx>F2pz&6VXuir zL)b93S$sN#1sY~-ljr3i)>%9G>BZv9`Vsnlf578hysYoYS9*x~L)kPoUR)c>vRSq0 zIgE8-d&R6_EGWgV71I@cL{o-7zlBMLtm@5hCQ#NTL};l+4pc<%vDu1Z5Iv0^p^mZU z_=r!2v6d`M)D2_dEMK?`hkH0A+74&I<9_tU@+xg=6H)`hv_UEl_p8-Xc!4fzMb7y& zW681||Db%YUnAubZ?Oi|@W;Kynpu~)M^mWPF?HZnTJ#__Le6NLfPjzhs5TQYz$uzW?|{f zzzVi#rb%5*b~%yGT?Z~eot~zF^YM@)+bu~oU^x{HOegE<3PkKk5L`;9)O2U3olg4z zYK+3b`$vgnRoSFM)4-OJ*N?84hCAZW9&hCgoQiNccj~{(VPe}THYo9V9K++}MZ)yq z2m@?O=L@AVsKPYBlVs`WfdM-ZvrT@G$t>YXo;K0@go}g>mc`%ME=(D0Ccp0??q;xV zT<<30N3*`X^m#FRGy+RkyNT7KSp;9xT~v-{QBI%tBt=XWpN(d|ex@D}(1?Xi$-wD0 z@n(k$zf9J_V4n~8B_ z**qTUVmULG4P~uY;l-QyOYz4cdq3*=!hh2A)r;gDbenaQcp-<4=zJy-8@REvO#|rd zEl<+`Iv|ktwN9gLVyYz$=*qDosTYspxKN20$6|TBRg4_RQu$;j@zyxjhrjPA&W^)E zY_Fqepl7zDXg8j1;5SBz&&RVaVs|d{)DLnt9v3HaSug(4eM_^6%$xBUw?yzH1WQj} zDR(XISNJ^1JC_w_+y{v_t@v34`9{ho8CWyj@r#fnMHM6yIrW}U-oAacE& zr0z9sc(NQD`yYsTlUYVLr`IF{7t&8$BnV8DqFIerJ7h$76B+f+I?Jgd*;kVzMZ;v) z+sXPC`gYb^B54W>wKR-po{W3{BD`{05cd^QZWndMv~G({=;>&0w~URALchKa`&qmy zO5ejl#nh!cAcjema!V+E5Mr1*7fzT0g-yb~z_lEQpomvLUbp^%IQ|H0#TPyhKRv=m zx4r#9#(}~n60Ln2WLi!(9|3Mkrok(N0j`e{rUwqK9ELVHh#e0cVjRMexb(mwir;-8 zu0G0IJDh&tAlf!K#PCfIMEq3Nw(kOPur}NW%T(y5uzyii6h7J%0H{n+)bXMl%gNj2 z-Y&_%Q?l?LKBi&Hax)G0H06uUQ&`95c~Rjw`wb}>Caz6ko%o;kh1Vl2p?&HZm=WG3 zBYR7wU8l6S+1M$PGQz>qoLfcf2G0j#_9Lu)L5ovzeM7gel|XSDq`E$cg-%OzE3(Fb z32j~F4ea%kSYxDK@8X1=^SQsFhTPkx{5z(F_vD)c+E+h-EVp7|pFOm6T8W;pZagiQ zP6ku5Uaq@)!5aMGBuP3_E@(FpUV)0|qvADw*y{DuxKO1}Tpe91o}bEk`RmbOGrnnn zolcfBl$i2YLjy`J!yjYISW4AOuG8LfFsYsVp$5@pRlgjv8bED5{-#Xo?O)P*X{BgA z4YB>_BSp?M78V;4iKr?J@s z(>2@sW3yy65)DLRZZ&clN<~m`5uk3^q$Mku(1R$xma??`Yc_hq+Z*5 z%m$c3fHcp&CvAXq3Gmtbxed@?0s{7aVFPrOfRMeHqQqnK*$93u%Cc)d`^15-8zo*^ zz}on$!K4!qOzN2m@w2fo$#KNhY2^Zz?4m`QB3f0rFJ$8lT0Zw0umQBpTZlE0iyGYK z**Y;pd|AL|YgC?n(=)`VLN+8I51~nO?_Zin5bcernFlC)I>%GaAk^s;aWE+9H=xE_v_>2)eM+^$+8BPfL`w|R% zFUqQ{=K`O2KESi6+PUO!90AnkuQ2C3oh5MgRk3Cf^9!#fG%%_mw4=_HJcwjk@BG?l zFI&^DinEJYJde!~PA{=kubVJCoJi}VaKf8aW9|8s$bAWO8nm_GB{t9}6UIR$u*Y_! zTTcX(iZ5ScJ>Bet*5|K?kRpVzHA2#_h_oVB73{qA0d~n&S9%zipc^rWz1%P%)m;{? zi`k%V*^+(E8Q7dutl^N1fxwwIoo%b}u7GjWPNSk80a z3FfAu_m%?@H{+g;8sl2Sq2y+Op|f-FH=#8V0Y-rqh)d4F--MPLj4HVU82%_e*`gTP zXhy@+`Z8vM>LkTjvbUO7*h;Eq>S8v_Lz5evD27^GUCahkS-TRJPtWxwh;YPnUkQ7( zK*i10YVb1FKnI3HNz@J!%3Uj$vDSc-9!NS(Hxwx_L2HDU850m_+5bRF>S{u&HtI1o z+F*hf%k5>ZZLGfua-)3os_g%D9X9aL{Q}gb#Ger1ntV@CS87ZWZJ~e>K(G-YmrjHXKheI4!wS2=m6*5(p%g+U&96sgD zX-RM1p_b!*nwq>*%|%67KT*pyIc)q@DZszLs;CGXGy${~K!T;2Np&I{(8=%qa3!<#vS_KccK+^y!aMdc%7-$-@x4?SlbG4f_`hPUw6O<1$ z>~^9n?FaX;0n7vd&Wr4&UevyhS0&qiF6v)rZ9GSyq@G?=laB31t!T9rdx*oeV)#-P z8@{L(bdF?k^iMA5j@R`73D%;=>w;^=ilyvPexg=9Sc)A<~X=KGUk zx5B>Tqgz{6FJpK?I2-km7;f0!H4(!p8e+^iVL4UG-eH9Oj9{^hw>>V_F2}qB=XH8H z&c{Bg5g{vBYno`1SFj!(mTKJUA8ynMYSij#C~<%cv!*H5?U&CN@ne$8txnx2iCAfJom8ZzZOUHj)%pRwb;UZT`7!fStP$zY1y)t1u(8Z zY^hquzH>l3#nv*MnJ>Wlp$yH!^FbL42wecx79GST=58vss57 z`!MU{jmi9Wrqt!w1GwTrtt#G24ZKcQ%|}r?fu7kbk~cxdsr$qen^;&_GDuDN%W5yA4 zzJ7tli0^l>2EL}X_~8Q<8d|P3V<-Ynni%aaYKHgwBJxA_Ys*4)IA~uPlo#xBd6atI zI`BOaU%`A@UBVY4E`(f}`lb`zY=`IXCSK~*kURnC{hpXsft&nJ@2P9C4)m<1(E?Fr z#q^}5nLCwW_2vzZC3vG#{kZMnZEz~Ra8*U0f0f%2+Qm_Se2x;LTZ<t8m!G?$KCgyKP&S88B(`D>+y2w-B!6;jPP%rdt;=dN=FgHhHub z=I&THT8P~kZ`c$CS=b5IA_Pu^R7xjD)as|o#2*S_^Vacy-5Wf3aj~3w|gn+(<>eGGlXfbI&8^!Vba6kO@q%v`3KgQG0 zGV$kr_Okt(5U*4gG%>EYl4uGUQTKFAg5iy5SuuB~1jBc=h zVdi?1W|*>^$+bAH6O#_2!lzQis|Q&K4{2j5KZxxtFCHzvI>b`F7fT6q4jVew&dY-; z-It8EbgN_+I1lbGypFQZ`JjH{`cd|+Z+071NfakS-?Ihx#mmLzDoiBJ`-;eq*)ZQ3 zt7NaD5kSceA;T%}BZ@y}W!#z}+EwFh|64Jr8Uv%MH}>kI_4pF#!gVDJmfph&K_V@Z zBuQ^kT#a+obs3gR)hvklcI^dZeBUii!-4&_>LpxiSWwGmR5V79h*N3J5VTxW9%m~9=L_=LgxNs{Taf|-dvA9!=LE}WPBp33e0qXy=g1yRp-P)=zf0L1!vueo> z@5YFsU*jb3@e9n`XL?LiJC&p03t_$h<6jgbwqC%znj0fNyMVjX#29gdo{=%4`9;Ko ztTYOK34^7lQFNeZicw_K^V?!kbcwYNdI=G05Ym|P3oU)KjeX=(?){HkVpBN$O6$w) zG@m_M+`WuL81L31@CuGZ)iyn7W>D=I#56?+go2V7&feQt;ULq%VUAz!l>+diU}cv2LTt&?_W z3X?XHD|hg7Ua!z6pg+E?}&>;i?74n;CJE0!x z@?Z&}h(t1cV$s}&vr9q}@R5pOP{~iN$d@s!GHX)rh%ed8_K>hAwKADGWG}0tvK_%g ziH}MB8qmA;!dfa^rV+}_E0m$nsi@!knU5?vwBqN`C>8Wrux0J{>?zKdjkXx-*nP%V z_z91C7UT1@9|llziafGZKYg6*Cx+DH&@wb%yjYJBdnZqn)w7}KWy`Pi>@bV`!5jPs zrqIge9ZbKZQW_MdfeAD~AzZb$IQJ7Mug(#F{{#a(GRG3|GplYEx>)T2XQ9nE2Pm(P z3Ztl+iAUjxM*=QQH?Yb28@# zo`q1>pE`GIJs+rH*vwI}xvybK^Y8d|O6>$((3P0O3U zqb#R9`Lt&Iu^&Y@fBq7`Gg|EP=c{>aCOwlas{*)#1N%#?3+DdpXR#+37dH1&#aF@n z7>TzjgkN>wX-Q&nI8Wmb5=Ct||B(A%vlK^gKLpnG6RTSBSiY*SIMIqvkuv1*vu7U3TQUNTHHCQDGmt$Vjk0Fd!`wY@LgY1dErEV5>vqg#m?F$w;ujyU`MoOf+>B zwz#~0kS$Is{wp!EEe|Z1L8drbC9?;3ePAcs@Rj_2j12I4ouKIS7wD;lTYY&&-df1$ z7DVthG>P7mF<*Cs?E=Y|ud#N{Ud<`y%e^t^%Y5a54EoBJL0{WdLVM7cyPa^_*D|JU zEKcQZQY1nO>-){|^OgR84Ep*)Ol`-*+i$ztD6wI8awaV++Lp~9vZ_eFGj%H+cb;bOZGpd|URi@tV(hM8ZN4nBZX*MGCKNI_BbQNIpD62yF5*NiAIyL2 zB78gWoxx8YmwOKxE7Bd*&^k59+PaH_c*C6y5YZj^EIy~RDDB8+_jK2<1KmnIB_M8hqQFJ*NhHD_#T$) z)UR zi{}Z56A^F6^VirXqFrZvW%)m&MQ)3yJHzN73J*z>*Vdo3dw>N~JNX&Be*}Wa5RpL` zlK&`?>(hrqL{xSQz|LA315-Itk~SGDpH?)#TvjhsJ>(YAq+*V4C%n4wexVK>$d}~H z`*MmJsb6a}h5K^Jx?QoJ7V=3Nmd*o6<^aqUH27e3g3*NO)X zg)bt`!OxUtAC>3Yi@^yzf_)*LOyI5iHqXI`P9xKEHoaViKBTVGggH7EVjql#*lANC zv^xnsn=0*&b5`Jail-8ItEjgyU~O?5%c=Mt{_`GLFXFP~xOa^a-d%Zw#|K|GMq(hM zWI$Iwl^qtFy7H7(RTb#Ybdws4rPZIdvXL<&O5D5gxHeyZ)CiLiCGXSO=8sV%m zh$xxbjdyLcw`U`A9)*cy5b`LAY!5#{Oi5)o9@)M6)~qN*pK>ibZ5h-xuyB1PX`JchzC zruE{Bd0n*lwHNQhySEmddh@n?Kx;9Mo?k}^V{a^iZj7@0)|*GT@Ty?pm&SMS37O)j zG#<%wwdX|bIVsc9eIR$!^Y45_>QEjYIn9s8J@#U1RBX8q2I3sOSuejkOD%oJM=T!7 zTY9yTh&V=25vTiz-9x!C;%jfBw}Ve3YyZzYK0#)w2p`6S{WjRq8ZY+|S!f=H<z~4&-qw}59ga%mj(Y5WsUVQFO~9L zl@garbZC6Hg=jkxGX$>FhL6NYqk{@n4meZx^evX@iFDV66{+RJ4340h#hI34qj@Id zH6umKENtkR z4NF08c)1!DOj52x01=NCC&yv!jOd`cal9ul%d|v|=llMPa`spk;$tIF>$P`O7r9R3I?CqI|>ZN{hG6FVQ}Lm(Ue%Zf#`&@P(F9XZEs{Hu?nP5KPW=EwO_2mfu5 z>R9T@LS12DJsl-`P|M3REk#f8i!4AbtwLd8J>67}aMp_RXY$b$a9}y{6!7>{yDS@L zb5|Cz1MK$d;u6D6SvwKsV!d@s-qg~ZM3g%-#p!4GbNpC^82&8(gH)9|2TON6ug}3^ zyL^;L$>Wpov~0-ZWt`6R@6F>a#mM>GMLatX<4T1j(6jS=xuO?;&*y#lo>8LLb9`m^ z9!P)<8TRmcC?`8*4=#*yv`e=f$91DDx1Zy6%}}G|Y9a5*sA?oyi~cY1Qd`FI_e;Ej z(Vk{UG5^~~-s;BSntoEPA%<+s_x5PZAtNt#@%iU}BNI_8#xCU@RXK*k?6dWINshfz z4t4h=<=C*4KjDBnEMCiaYnkXFc#uPzhr%E|F(b>_thl|pBBYf7Eros*&#mNdYpw24vmb}#?nkxitu0pZ!(r|wvsD}!zwnOg`l-{pHt?C^aad3$R)SyB!yEOdP zQi>QvV0tSB$i;RR9b(1Ow;|#HDy9FG5vAGo(j0<%tIz><=yZbmsL)tDbPhp%Rj8jG zT0~Gk6{@pC6@ud9I#k<_m`ODe-ytx)k^=Bq0!zVn$BM*N5b-FLI;y4R_R_Ni#WexZ zylIDCBPiYG0lL5r{e_?iY#`|4cBrlcpg}4$-3|>PDDDvnw--SRq%iFX9IS$)G-Mda ze?-_yvq}LftVTw5$z4X}eME01AU+GXiu9&RIDJqy*Ufk-zd06m*+8%NMo3l&-Wheq zV#6E2VgRkXtLT+9k+GV42OWS>N(@hv1DPaQ6;)E1X(?FEe`g^(RW{AA!fj-8p4j9a z5lh!{|DY;jL8YFiW=&btWLgfd<+&_G*RhEtZji(alEeaNJy9uot>+`XCJ;t>(ZZWN zk3=u-Xj!?Qk7pqaUqUN6T$0uU3kfX9^oH%tXsrd5Z5@TzySyLYG*OItmk03c9mSLH z@?IgMCK3e{QIeJjB2O&<9uy&+#Nl`0Med2e-{pZ$nVnGom4hOg1uVCoS031`LY>!%n1XXdH7q4s+#NegokqI~S#%^#RiW^?#e878irS z`pSOs%tpS7kKZp0n@~gKUJ;LH<^kg7M?sD1JHod9zClFG;7M>b)J8j-Y8h{TSqKr& zGFY$^fwJ7_KrdPY^@D+;>&X0p%qmxFRWng#DVIj{01!#j?tSjW5Lf%Oo@$EO!jrjWmzcGM59NO6#J(+nZ_5<^Td`QHKO>A=d3(3KGjgp+CsI{n z#8w_*7zhZt08g4_GBd=DtvraxoVW4tf_tZ%6splXUa4mxpk$y%+)^ZzBh9mzBq*2& zF%mS%rk+LKL1yJ%^aHT65mGTild_Y62=ssBfFYU^C9ZA5oIn4xcz+w(3ZXvT#{IkY z2PfKEdZ`@Mp^yCM$lEq~mk?V=?!d7Er;sT7LjKdpHFc#oIxT`!A8 z@AK&{H>LQVUCXeheV+@)2Yn!x?BFl($VH<02hisig<{MHyxystI&H^xG3Z17IDhl7 z*zqCn%71uY{O}>xP0u_pyeoKnp7Oj%tl&@b2^r$O3jTfoDX!$N;?sG7Xt)+4BtLmI zXD46E8&(R(T|AS!mWlDZct$WqRn2+)`KgAODjdBZF=RTDbhzn*&^5dGE3^a}wVMYt zw}UOu?&cF2U$)+I+QNG?r;{Y)^>X2}mrv#=_lddm+&x#E-^;VP{sqx_AOA!}y1h~8 z_w!-=?Asz^KmXq8CQ`L9HNSJWKi39XuSLHf|brmW;-3s$98u!@@|LTh-- z&OwA%_z<3)et|cJ@P5U73#ZtH(8fG@zrngs%&Ngh<&y}|d7)TZ!{eK!QRXjktOok{ zushO+-#X5_bR99zdEGMk2XMAN25x`g2kb`?=J+Q7I3%VYx3TZO zK$wo(*f)qH;Hk2&7Jnn1BKezNu=8(W^ko0_?!u{pX zL$QY9wc@E0nAJ-1gy{rN8+Q3E3h~eDrFoUhc)ER*AeRHO&+z%ZRO>C=UU_CwTxV=0 zO)_|<-lRQdDs)x2fAfEG?)3>zD~S6S&Qs88n>GA*&MQbwaFLiZDoLj48YSBBFY)eA z0=uXx-FEs}bR)Z@SCf$ZB58KqV5Euak0O8khUZ0)AjA$&>Hf5r9u~eM*h$`lM?Nd? zmha~naf)m!V_L+!o~NX)jT4P#u}zwb;-MC=g3(c_`a1w$@@#I(D(RP|K&N ze(c%jXaAcY%le$Jij;xWMa$44!>g~+@4q-apVRy!#I2k;&A0PyMp1l*KhK*jdFw0> z@V{lkmnZrf-wY=6+^CRPcf#AhIedAflKXf{Nk= zH(Ws>!7Ve*H3fGC1ys6Xn&L5+($ccBvNF+9!zIwN#IoFXQ;;&Z)NUvhI&*3Bvr@upU&H`IY*p{3HeD*uE^DHY)66g%4-+P;$p4GZT;n(e))+J!U zs}&V7Fdv9q6Nnw%-0yfyC>rV%fAluJeGYx~;@kA|ISod33H0O~upHk+e&;duBOG}i z;nz3Ou=83YpB|fZZ5s60(Uqw5TZ0=m(T4NjA7m*&7H@Ze#$*-a&WvN^8$sCI%-v<_ zxL-EX{qtD&8lsR3tRP9C?H5tV3Rt{cz?egL`2}rO{l6CftIy|dB;Si#TgihC2as9= znsQNdkRv9+vCPPN(!=jP+;c?5SOP1A&}m+{6by!`%_2qV1^K*1KV8I5;QX6Z?~>N7 z{zr@cRZy$9=;cdLSJnnTc1N*l4Qwav%+ZdycS`3S%RjK7yRnw8URAm~s&P$A zs{hWyf7QL|I!e2SE`Pk1-nynW@ELO$_05@p-GOS!fx z0RRIu*9}W`0KWDy=Q_C1E|K26juYXzL}@p)EbZZH`s)S;=)u+0q7*B^%GH!wss+^V zwfbK~tU%HtLcYQ9OVGz(^4(G%hu8VYQ+%bF89GLTz#4w27NZmMoXsSAp|v^ z${j4!jcGy?%e0=(gBL!lIGuW5UuEcEnRZyKJ%jRYYJ+{hMlN%rOP(C4oA=;(RdrFD zWqX=VhH@>b?GCK7mi?MTI>df{u*{hK1JfP6)Rp&`%6xDq!39-&HQA2C7`-xgFmt)nO$yLC4`N@+>F+tA2cT4evdHV_dnG7aiH!a3^=Tci1aqJpb3w(K<{e<^sOQ` zoV-=E?B%&5Zw;btkF+$y0Sfp_8|$pwkh*X`{W6AD|D`pm_3ap)3Wvu~KuzK4y_Lhr z>B7G`d$3uCdcc|Klr)AO{Dsqr;g%dNkmGNyS*_{)bZW1Ekp}*)?b94yq`Hr>7`--{ zk{@g9UFM?kc{#rV6PJ7MMY4aQede-`WAjxk7V+>GsrZRj?9vY}rRU{bv%o$-n%;bh zp@g24LnYJ}dzZ&D3a|l-u;cW?Pd;C#wcw2u6rTFc$pxWz1^vg3W4^T_j zsLze5{868BDw(d5Ka}cfjZ$-08S9eh|xh#sQ&+Cd3opHurpV5ZfPBLxzrwLl(0>HQUsAl4H3)iIlPAO)V}OWvucPY zKA|w2vyQqF2Yu4|8?Rt9pB2(qHN+LoG=$!A6z-Z|G8H(A@CG)HaAFwpAm03iJJh<` z$~(Q>YqjSnuw>gII@8v-Ae%RsnU+&SMw&-q{MJH;D#u<4)r8~x8#ZD~# zrP!AysJ%XT1R6*lDz%Wm3doY4#K0KkR-j+2Vfr6Hg#h9;KrbTMMAMywOGiDV5V|;9 zlHxC6iPL?*WAUrX!G|ZYtcpUt#wJjqlW5fE?Lk~Wz9z34fy1EcjZpK9pQ@h~sIq0A;V~yi|AbAHRLSq=ubbnh?cR{&Un-kv)&eQKEwgVg|GJqC*!(2Pb`~lAb2oM z?@v8kg}-48jdK;g|KZzt+dneYV`RuUGJsEnLSmx-`$*u+e`Gt?PtO)&$=3Zpv-NU3 z{EvKFEcx#FL)Ed*`)Ng-d1w!e>zut9OrMn8C##8^gVv670KIq7} zHara#$93Qzb6lwPDEsF=bg{1Rs^8WKNjJ`aOs?siIW7=C7fOGfM0M(kHXhN55J2*G zu>mOz2YDt%UySpmC_NA--_*HFy$js3!unph;9%Pr%N15?!h% zp0BYUrv{~;O{A`FBETbiqQTB^DmO0LJfs7^_j4GvE1f-&X1R$MYTWVzq{~FQ3djam zCg_me&2czyNDHwTZ@$xueCi7yk03PC9M=jdt@32FC2?{u8c<*OH@E}SRC7iTc&N!~ z3)aT$at0(W#fyBe*2lC`jfWiBat9El4Dk&zatBBKtEU)5v;)Z77Lb4Q0E2ilNQMRE z-~G)XZ5i9J{j+@tVZ9&AyJGt+NpU}RFl6b@j(z9*=OhiIxb?nUt)qR2f3{cQXsr#tcr zWhaD(C;KE81bd2i?F~n$#7DeRSq1imY*U3`uENBw1;c$st^qSZ!A(Em!5<_7#F)xl zt*hti%(+aR3l;~6Z>rw6zfrw)eHds|6usP7bZ&kP&*9{nmj0t@mu#D6TEgtvEP{S& zEE;LEI?=<%;yb54%)|3Gim05FMEW66BsuG?owr7~ebFb8o@*j5*6bgtuXgjPVN)z} zZ$!|5rlNOc?LVttdv~r_-H3uOn~K(|&9|C~@doy@QAZoljwT0-K@M{nCW#IQi-69# z{2g8oL-e)>U)xIG$3lU9fyvKps4QUVp4%;|z zk>-bprWs0q`ni`9plTGyIdU(TdIN1~h>lw+dcZ6NoT-tM0(2{0ycux(SG@R?{s9BX zP~|lQaup6O1I;Eka}u14IGQsV7L;evyi&$F1at_GQA)tPm{aAkwyB;Ssw5yJS_C;I z0Bx|ZuA3ZP4fK#L=v07avDc7;6xm#?cM5+{oD&Tuv&_du{Roo_OAyN#oz!)YDz*=b#{nS!))wcE}_g11Ai(Oq>iH4eIUrK2u zynKF%SDQ_4Q8XH(YshrHOY^?8vXvO4&5EaC;Sg`@g^LDSY&`7`$GYdPBEz+-eP{)T zKgaVu{F~K>?u3iL!1jHx4XttpRp*>8|95DCZK$qwczm`XqP6H`@aYo-;>09z150Z* z16)iJ2(L`%Ue<`8M&xw{9&Ol_2P2v&p9`L|u zjz3NKvF;G>-Jo%=~I;&2Fxs6zb>ZEGU}4ZqRxHlk6Bm>ELpkS)kPIL(RPBe&HIb3NVz&~t%nq-9_h}`W$~o~H{906tEPH}tVf3V-XN6I9vA{M!GMHy zgEH41luZkwYaPTOZ;Q7E6U*lItI92p^0IJ>jpv{U@t$Ly*YWlM%#@YBqE(0pUkuyNN|wT_3vLO?YV!yvZpBQ~rO*NU zqL4fHFrRBi(fgK!!mGV7x2bjFDmXXR%*K8JE5$)U60yDij%ngRQ>Qb<&uW&N>_OSq!R|l#Y4WQjd z`mUeotfh3M+Wm#UR^~!2`ilsswMIynRvJw0FL1*nv4HxcBPy>a*TKYOQ?F@U=0{F+ zav-EbM`!wbAQ*gJM`|%h1lIMagZ@4MYSpPk`obX5Tbt=j+XrE`O?9U428m9-D=bxA zQoX9D827N+)HFe)Xzz9`$W9RN8MK{1K3Me8KB`4?28+qQA+>mf96~8x>_7^fEo<7e z!f}Wgz$R-$hlr3?pCjdb>UKEcPTUU8OkD%>1SmI?)Ju!TA=ivySEkz=gHDutGv6ZD z7ehpwW^A1X)PQwcUIkoe3_HNUCFOw@V3#D}#zi$v64Bb)8ZPQ>b>XHs8B+i-jZ7A8wU-@eO|tk!+iXu$o)@j^OtshS#_WIWSUxXr ziZs*w=S8C$-4KT;%6MJ`)bO$m+?7=+A>Sg9d%IjYaI)SvKMmV7n+_e%M6WAp>QE79 zadxXNriDl<8Y+skMS_;4hz{Df9qDk2SjfM9Qqkx5%}5okwUHWqo{HKBY4lsFh!t-d zG-^9c_KQ*1~sM(%ZafSd12af6})4$D#q(O2W3Mw&2I^mp(6(159@x{jsf0sS~ue53_D zpatX56GI7IlR5Buox=j*M+ORv6ISFO9yhEQ% z663W4x5;}lIB3~z>OUFb0k`SmCeeU?nGB_v*KN8rSq#@+`-A#TL52JOK})8fS>b=s zM^i+oCjOwaQ-JJ;TU6^6H2Wr);uWyvpOIAb3S8PfjildR5uG%*C~7_xYjLwE8aNem zyvrZ7eyRx8Vxp*cD)Kjvq6bs4mb`k48ch@Zw0C}|Y170#ZF)J4O%oAXWI4T)hTeL3 zlWwGmmo@WE+M6yyXkNN#>XnLj$-*Ce#gcznKkyJ7Uf1KLG(Z7$_0o`T&e;W{e4eK6 zmq8R#Jk}$MJg1{lCvQ@h=_q_!8I7MVQZ=_S`gXb)rtK)DkQri+=2c3iGtlV#8{|Aw zEYZeB5zQ0{o@r4S7H+w>OP#^KJ<{BDtaGDC%tF)7T&J*E!bf{GisEO95U)2GdI_Kx z{0X0QkA#(NcSO;OS*S(->$Ho1gRj#?{PxnWL%0%#ST5iW{MhFnWPzZP*TK_gSr2I1 zWBkNah?&^3Uq6j(xu(O_meszq(eHDArKPhmDOX&hi?c;{ZTB_iOkawbgUN2RC9r0W z$kqz4>M2ok#T|>{Ud=^2uTaN%!1VkTnmG?O?Q(_Qng_boyF%a1LyNyfC(aXou0Nus zWk2$wqR4z9iki+B3EK52nmb=i*X~3W+@CK-8GQc&9M2GwaBazE>RHG$gv&)r%M{1m zk6lD_a%Q6Ms7Bx z&=P(w*zu~Euh|m#(;ulz9!5vcA1OBvQfZqX>4Q9sCc}?(K2N-_Ejq3b%}vWNH2WQ= zJD=ia{twGUtp;t5gG|L=jb$Ed7XBk#p44Zt`gdIRT!xBWDxsj)M3ZJVo;+5UAjiS* z2hft#2xh_LVGi)a_OZw>HC zpBAeV=2<6tkdJP>_bmmlMw1*n)9}?IMjLj7Hm??EwfrLm3kWl|)~txmz5&Vl&mwBJ zR*cYQeM7lx#h$vyzTv*AR?Luf;tg+?Lzvj|m<+kefmVw8b8kL4NKWg;Snc(LG=07J zLQ6kDEj9>GTV{Ln0PLg1c-MMx=&PSC)Z(3+JU~Be5QDYS{nYeL(aqt_{V4l3`Q0~o z(ULboR+rAS<4v)m=~smqIx&HmbfIihg}$$1{Ph^+ev%4l{99tVZLzR3bA%2_TlzJ{ zZWQ6JFMf?SRI$O}uj%WJ;OY$b*Sz-7lg(hf@-N9}3wmqUm(+g?M)x~k(X=fhN4vILN8=wqvJ*R~)`w!C`-==7po3fCChSmf%Rdy8vg0+l*8PCfUPYST=dR4G4xiDfkHA@hTFW`)X$z_X$QE=7=vo5x;5E zw$nS?!AWgCp&zzmxMNRxV>`s};UCi{pJIFA@i9-j5j+S&Kf`n}_#;~KnJ{TLJJYex zM4-2ZwX5teHoe)47dYT-n`b9?Zsf6TWc(b=vSJ&>e=a6#b-K{L&mkUob)oa0V?z1r zLu$N3#CS~q5aYonv!c+*4{6>GFmlr_1)uB?2c*wCFg?r7Dus7ekk%a%LQF0+Ce|(F zvfU!RV?rdZ$+pXSros7o-0c(&1!euErF&;RGvN9}-0f8yRi6Pk)G-Pns6B6&L{XtOvMNECcO5H%|2QX)E z*gzj05F~AxaiF| z&5Jyl#pEKTlEI`sW<7a-gPlEq+J7UOdJ337nHSl#TGjp2wUmz3HWrhjcsANl&Mmnd zYa}0!=CMahL|Pp-@|OJAH=;?a9&14v83@tNuGAOb40BY$@>wZTcwvvC`jC|pOv(NOaR!vYesrDv5p7J|Umj`2f=-_n&H>KN0j0!XFuXp0*ulv6`dpd- zL&1roIJ4IrUMH^~uz9n4ojU&@+&g8zZm<&@TCuFQAqxM^Uxe~El#IM~k3lMorVMv; zl{Q};HGaWh%!NH)rxid^BOE}bU#_5!fw#_t6^fFWA>r+A1ziAu+cm@~wPn7_ijCBd zE6DMf2y6Z}r+`-G%9Q1ZsmMt{5hC3wYcGG;r|&MUv4Tb(1Nz;|6?#nfxM#GSRvZ&A zMV&xgOl($88enC_I?ZluDUS{H^X8pn&Gkc|;f!My0_A$?wc`*U#4`HyILt;aFQfb)MX=#l`ua!F zxX$xQ@FfL1THYa8mFZA@cv%{E*d`Ws_1l%|{$4Lk<1 z!l|jAv+@bG>}=Y2P6P+P-yFwL9!XCsO5+AS`Cku_bwLshyCD4Q)D1(+EU!MT970Pk zh~OIPp{L-HwC4h3w7&Dm@uFzgsMpPG}Tom((dba=Nh!0iJDcx+1LD=%s)usoQQ@iDg_C_6FA;sIy?UH~*g!?%AS z58yo(e&Cy_)erW9Zs%3P#owdAUd9Ib3y&*BR0Oz|*SO!HTGb4WjxM zLGxUI1)85?oBX+5;- z0E0T7`T`eFEP8~N`~-_SEtX1t5}`qS&h%+5b$5E#CMKpG>{ZP1tIP|=V&Fi^?S%>3 z?Lln{JRw5e8G83j&`8g)gEPGUJB>LZI@dplK;`7F_uth8wEG0iC~o$r%O^y;8lPk^ zjhE7+i`d;Y$)xa0*pcr3m~tUbE^eGZf|Y#)J%N1;;}3Tn071Ec%Ik z!=KUVbJCYqUKXxSZ_eN@WUH;NN#uH7y3wJ_IL=5(rn*-|OE348&nmL^@pPx98!cCA znHJN{H1vw_ZnzQY*7^PTJgiqBzM8Ld3hDJLI4bY+F15NL-09*~QIqOi1?s_@Y+~kc z%)oalW8CD#x%|Y@RpCa*$h6+p6$sS+nS;>&R377DxJO4zsBL4FDZo zTLsj4*-V>4jmDf6Hib^*w3rdt(bU2#(<^y3EFZ?JPG0&o9yQ1ENtR+u`)WQTY!IUs z+uvu{AatpY@HnT%u$P+uMmTE)ZDE9MRw#t<#|8H3gG_Y$l4u~t*;kOu1=%19G0N&- z-Zf^4tAYApcAkzq2D(v038KoqtK1G@|Zflz}!OGw4|v zq={i=qe6?mn)PoJ*(AZC)8J$3L+0B8S5doW??#$FU~OL#V|W*er;3bW0v zXC6qyZ(#@X_EegE3xqj0h1TD~sYH*i1tqsc6NB4WS5Q6Y6j1X;fLuswrFW?2ZJaS= zccqrMMHfSBntU5a346Ly$yL03_iQ}vxD7R5lPM(bhzLV4b-E+s44+cY9nlW2S?#$a z8X0QR#XF**!@)N&$?si#S2S|A>xLctC^U=POJCm+eufTGJPo|$UQ z1fJ53Hr~bY z9uC}((u?ER&jSnqm0USW#o*|UW0bYxpDz|1`;#Tj1!L8St7Hu0Cz|E#VcJ--e~8W- z+nt&{gl?ntSc-j!cC7DCvmc7yZn>ktPjDC9jmLO>rXSoaoqi~qyVHJjfE|)^)o@j5 zc&W?lk!bEa{vbAQd56*Stl9T?38im1${{SMHD96^9*K}9ZC^kGVpxL1fOlg7>?n{G z$MEF{#CUSdEc)z`IHqlRsUYhw(bv$kq4IT??#cD2_BvO*W7!sXiYe{*H(2ff#tpm` zpu(QmW-^|ekdisieRlPv!4{Ifek$Fm)ng$Wl-79${+!j=0=nG-3hzzvk71WRrado} zvzl;rcyD6X!7G{T9*ZHq=QgktJx6o@5&!l67r8tUZZ(&VP-~cZK;^q%gPw?0)UpQV z=NnH%i=K^ssHm`gTFJ8K{cRWzc-4!G)Tg=!(s($>Dq=NIv7VK$7#*h6r%>z_jiilF zMGND&??G)WN9s=R@{x4zsR(pwhe(Ux|6|xA!B5jO(JlDeNb5ozT^fpEWL+~qMm$#m z4aXA9K4reew+RoXaRW^9-A~vXNw{!0&;P6jXtD8cBoj+i3!_m;NyV_-tRm zazt#FvTB3$wBWZT=L=x?#vp!1albL>Fefu0!zHYKg5sejNj?rxM5L$)I3~h7GhshXuW1ZAXbd_7 zO^PwB-gK@syMZzo!w#wd`&4z5@j6M&A(lG-bO$IG9r?fCA z?o`x?;=7gIq?w06#lQ}{f)Lt^Y0$VcIVks3)?qDkR&zU}=@frsZVa}5yJXG^;cqwx z0COQd@f@(*C$Ri&I)Tru!dAS3vV9dQ$4?2lWy<4HNp73Z#Doq9HpvtELk7}|^n zl*Yq|9%kOkvH6E5kajS$gI!u*^P&XwM|AFi{eS!Izv*Qt$-2}fxFlD_!XA6v$^Gad z!vU0;*JpVG3d>4E8&F>Nx z?Eo4CTv)I(6R>?UXO7J?(6c(yBLgtG3lL)5*$c+zBGGh-&Dk(`Swmw^JY|kQhZA;K zg~?KTw2rZ^7!AM$2b90(e+h68s_;$e+4hMhBC=~#TE37gEcgNH07>@G$qkTH@0^o$iqL>yy!H>LAUwi4EF#%P# ztFr$64Xa*hVHdUa!&BobmDwJx0UVUXSzmFSp(@AUoMTzF91Qu-99mTl2NQCn=sD_G z3c>jV?C@JqGY9G8Q;z{QL|OKq)0!DF=QOi3X0K(KG#cq3-5nY-$X%M}AblNL^7jw4 z3E%Cz^7jXwtyzN%)_UM#S9A0Ut1bsJ%%Vz|<^~}0sv&(dk~!h~NNZ+qlA3j8Ftcn zuG2>Te!VhtfT8qRQ&kfurZQ^M2pE*LB7(ev6mW*q9j&D`LL(ZX5pQuLw(D7~jc9Bs z`~YVOt1P3jO$BL~qpVru2L`Csi6%KpABXcCxK1k^rEh~${ytFIQ%w!}vKQQx4m-+b z85S9O;!@o$a9$RV4<1i0c^p#}wo~EUqP#3-afZ01@>GQ{aM+U})N}%fC8sfTvD2A3 z7+Z_V*r^=L%dgAOVHgi%kw_(u($89#Bj$hBWrC$7Yu!>RYiq4buYc5~14c6>j zmlKJVb-`@MbvROX7-@;Qt?<&%P+t16`s#}iWTj%^ScGRBtq68CBZ~(P<@Tw(X zk>lPzX$hls*VroY5*Lu2U|GVy!6dYtqHD{RvY#iOQ=L{@roJ#Abc0%?nn#mI;4N+f z^Ev#ESe%(8nKs&bG}+3yZv;N6$joRAF2BpQKbu#;JW}>E0#;Sv%A?fENk$BZ9sx78 z<)vaQ|IcUgT7cgrDfqpMOLce$4~1gI$kbO1tI6Y5GyqlX2aIZ4W>vfUqm(?;4z9=3 z1Ul>_!@Qp~eo_&`q}lZy7LtR;r42#K%#5a}U`?v)EL+zagdRZKT%a)O>ny$7aF}Q4 zbW40irX34XPWG`?G{{@5`W>CgkoC-T*ja|v`VN8|V|q|~bsg!I@x3KDV#J6{M&M*Y zfJ)lsEmo{zL6DDbGnX6&{T}v0#wvaP>BXju>SW=~TvW@OxgOllt zNyih!D_zv+Nk&ChIoqpOqL|Al>SsOD(t~WHfA}9Lx;LsWKwh(f%ZvHVGGD3E8UWOC z{|qvu24$lhV92o1J}aNve4dJTUHO66h`|!pJAcb@B;@h>)emH!C&OfSzlf=aOOE$=A=ZGr_8C%x;KrXK}%X z8&<~b+8l;-wNR(FF$cEHFc`rDW7)2tV6ka4NY9E^JcgrgnVPnSKge6FxcLCew<;oU z9me+o2tvl}4-kzEOOg~DXSgh9KCa^46uu;C+GAF1o@**Z3SP@(2tDNxN9c^M?vpC# zWv}aF!Zne7V7{t@yT+em{SAgjp6<{;PYG>#@q2Rr#+~QV3wL;Y*~+5P zr&IS-i|Bqjm0RRo2n{N*#~;clHX-MTXs*N_$jOH}7Prom?W2{L?rJK*w7cLSQ#4OK zDw~)GncsevfP;fNwY?-f&BnNnueyJn`72Nfwxl^JT3%O`l+h?#n~E*v;0?9 zj^4qLGv-`Es9I}TFwZ)Gw|IA;7H%rwi7yv?EjZAJRqzQJEN~(etwNAMxpA184*OwV z2<695`fH20gb zZm6l1dL#Ax8UKaALf|YQh+|BljG!0@G}TnNc>0T*YH}=&<~64p|8EEXt16d$0~l*< z?;~L0e|7m=}LS z=l^Ta@Mjmsr8Q#KyJq44`Uu2tXa2`aY>v58TJaFruBaG{Ch!nw&O_kPTqV+5WP=62 z?V%5i(kCNzsoH^5%}=J~Jc|s3!V>5*XEw1*Yhca{MPFmyGV<85xEvWh3JQ1xK^v>q zb?|t_O_{U(?9%#~yS2)CRFM|PSr!~n9N`vNntMp+fmY_3-sUO(;TdPk8v%%B*f{Dhj8(Ibex|o)t)mRcNZ?q!@8Vw$= zN!_pj^I~i6rd*m>u+DA+mfnXc0L zrCsCnVfbYm&>0!xly+bZE-mMp)|d4{eatibu~RdxM`AqR)?h4od=8HYzP^!k8WE}4 zWpx?Ww4Ujx7&$7i^zl8`aT&88*wIs0*|?rHdweF^1nRhKm`m;I$^hr>W5Mxylqs7o z)s=38Q!{}UEw_*@6A;K?;sQ;ago~+qhWKoR`Y1O^soXfV`$iM3Ib*AE=gg(^b*0Cc z)Fst$*8@asSkkP#JMsjosVW?p>EW_{JsyC=M2T;fLLv&+q& z!px9ZVqVDeWmaKy@S}gI0I>Ntf5A|OBGe`?WqW`0%|)~(73+_SPY=a6$sDl6Watc# zR2h|Q-$wz37Vf{q4iQ|y@z7KxIqO^tN;)F5ngNuG^XeF#CG}j%CZMj&s{43B?n<7w zc>cs%;%M&v8Qv4gs2sKHfCzO4aKiQk{O|2(?(GzZ57XwXiY~?+2eis^bF&vfD@+>~ zm`c)w&i$Fb4W<^|^EoNEIICFX?f8o0F-^E+vO6!lEQOhd+qxB`W;L9e82AW9TG~AR zMH~3ojA|K_&kHp_9W`g0_i#0;`1?6ztT1iMop%%qc;rfMiE-&juCVT)>G#o!?wK=v z(OR61+9`@)h_bfZt1>Ws`YWzxD%Ue6)KbrwAe)LtwuJALs@$38tg(89 zaDr5s|G%>9d%TIyJ*%M9Uo?;YJ5aIQ3*i-In69{U#jd4Unl-tD-bnl(T{&kg>-el9F005p@+&t*&Tu9tv|gBhN4@}Z@|j5h$O)%IOg%?5 zfY$_Ru*;}ilHLa(Gk{&D?$51T6e_01ip8-=H%rOpZfz8K_3jG#XEtt6wQPEOu&hMe zWV4x$qp>tV$OA8^(^qH&P`G}TjXSl zD_t()trgVpx)I1=T{HOJWYS6tZPqbufH??4K^Oc6cC;&0yIcS7j~?v|@zp{!<&IO~ z_f#(hBxS+Sj;o3(K&M~UQkv{7y#w`LUfSXRDw96*mcfBp+pH+8IJa6OtT;DQg|}>! zQGxehVyi@$^4%aYgu_8Ri?a(ip2dyXO|UWHW>*pVC;%1n;DRY{7BXl1W6(WCDdyRI zKoW}%!_~9{fh9UgT;q3vK1$z#=5fHK)*79oTvPW@7cc42?&IMgnyC;RiJ!y#Q-&QA z%q$Lz;f^>5H76D#n_LbArb9UMM1bvHmwHLRx^FSy5T0?=LTZjLq`h9UL55<|BGjLu zd3UC~V5gWcOM%EdfK8|icQAjV!t6xbnrxL--WsNOts07?|5qq@oz*AUl>hHItVLK+ zH24n`)~f!GmSp@B$1kb8EEQ&%4l_9;J&a4IRY_ATkqB|>J5xSl8x1szO5)|>nl%c+KA+WIsr0T`AX^ENDkHfV(6nrGTb*X zPFFR3h9bG-P!7w$&w4<^`&mT6lSZJS{5vGD+_n1UiH5@@2u9Ua6f0Y#n9hU&)!d?LS$wg zpH9lBg)8{Y8Luba4w0I2*MWB&gUCBnPSc7y(TY%MuB_d=JRquwQ@(RY1*`J+_m|Ds|oX0-LzA+T;3*S@MRib2`l=Fvk zT(j1UJc>W>9Hp>u*&ys&_)S&nv))#fLotA0)VV5mSkx}yiU!uma@FpF)|4JD6Dk`u zRaR@%2yRqyNWqP8*+g^k2Ab0wCSa{WFWE0iAn!Jk3<w>}-Hpz}l_=m0%zF@Y|v#zp(7P6T-bd$@qkWl)zo7}6New%V*WC=z+9qTUL`FC1( z`MhoTMt8Z*Z3=cg=A0BoWmom|YwkvR&m`AYb`l>G+BCR`OYi4S!(-)VV7m9}#YsaY zY`>b-U@tRq=D9JKw%6vqLofG``?L-lD5R$xt4-Qau&O6|sE+PnAmj`VJbmsDDyZls zn;Eo+pHfgCjP!3mrJj9cLPu-Yq}c!Ou1Q6jO-=i8O-~x>WFP6@tl=ge@y6^t(9%2) zE19CWkB6lL^x(U0bNDG6&;_yl zs5m9`m9w?iiAwsyUFASe3hO7&Xi2N7R)0BJTfCa)^p|gFZuQB10J`Q6BmF!;KBxJ+ z71SCiKQY8w+lFVN?8-gN^E>2J=sdT}!gIXUvuW58ZrDB?kC^*Lao-@IC9rXr%mLQvH1B`SwL3(N5JJG`g`BL4KdKhM`9Z=6#B-<~= z`+$Q?H%D(6RQll67$OWKqq>uV|b zc=}7W(8_AkjUC)K7s&&x~Np;zh6 zp)wVZh0)WYGG3c$PkmD4Chhy$^hb&;)Q(B|G*yn)8Z04?VKUhFCY(em(JZPs8gl_A zOCG^p)r>nv(6C`LK|3mF$1oWiZ*6QD?gF7_)%!KoT6z-+Ha+XaRGs$}T{kQW(`qjAG!N4_StWw;E+OT1JvT)qU~$rLd{zN*#M=$jF;vzD4e_9H?6 zda%nIiRSIdrjJL;?e43TM=oPFybCk;nvUvz71Kt^#-e$}6Iwe;cI={Gb5dF{zS^Ti zMbkFkRI*0hCbgI3WQcSwrtMY9RPP1ZS4*}pc;N*(%OKu<`h+fymR*Ds@CUpodsot> z|No-Pfa-J!V7kJVN_a`G64B3|Q29%kt#|%Kb;im_9_+oxN^kxhH&*)a?~<{yueet6q~P>eIn$uE zctnFhUsuz;H}EZ2br60BU~>wH*t245kH`FgnKF3FQ6E6{2KO|SgUL> z2VkiJ=L48lEG`U9t6;eTJ*_!)m07~VZ6oU@w<6sfzdquyF?$28nkEBMbd{cJ0j2EAyPNf*c9nAcq4BU_&k}n+Pd1^oX?H|S((Tu(A#(L&S+yqKR08JQc$H{%1zx4 zhm1JFF(+;YC$e3a1Adt|Q~EN44y5^M(!Wp3$4?+pjMgOz^$RNsKiChM-V4mB zCAq1)6fWL2#RV#aDM0AbF9^sKw+{)$*Ffq&Q+m*)bm>61CrXEa!oO{BZ{ad3aRXH{ zE(>@}lD>gl*+NwS&a?in%9=X;Z-f|bK!|P97~XN9maM@{!JbL4Wp8e>s^y@{TGpt` zH?&HB{tLBa1(plu`GQ-MB%G+^+@*(;Wy=OlpcR2_T}1qvd6UfjqRayv!B#I-nAT92 zDbiP)c$bDxk^T`4U>IBGgnvbGHKMV?uy|`uT*GUP3r@Un3mSR5vcKjF<(F)(xGtxy zQ>0%X>x|eM(~m{Og1}sT`hTwaPGB7m{x`~*7qKC>8UIx871^|PY7jdfUXFELsUo0V zRd20-JXc=`XK=z?Fds52uVeXhY5Xf#erMjLjjv!Ky#EL7c?Ijij0Y4x6&BH00OO`& z0lf7G&7UgUX%4q(=Tr#TvD3(L8ia#eQ)$FBOenci>6>YoKR*7Qv@|)$FpmbOVZL#^ zPaD%PAHQ{vGSj6e1*Bv04N`##&R^bT`tx+j>+E0Y@}4%oyx`V!*}~wNbqxcC-_^0- z3Y$jE2;scRn|7_>xtS7goOilPy=Tc0+OaG2(JUEb@TWVou$g*vg<8*+jlFFAF>k(t z7ORVHb&6vgHTrZm>~3>r%eoeiNy@Bs)D_x1TSm9g0BpT~bE~=T`g!4HAb=6W1rDcI zx^$m$nOx_{#u=X>*_!1|OP1E0r3!R0qIvUqr0f&09e?o?*QIq(7!*XAUASehgoW>HlkyUWi`*thEHrjU%IuM>ThHNQpA&XtN6LZ_Wj*1K%0nI0 zqy&>iRn8dH0-NMo$X$A0;V!|aT{)~OOU#Khe=ay{X)>*yi>=J2%d~&4^z>Q`xC+yW zIOEPZ1H9G0Yt29TGToaCR_Jw!O6SSt4Yqv?snkjt!v#C#7x75h?xnP1J{a`!d3tZY zY^^0;ptJMkzFNA)fQxhYWO^qI`S_SPMSjFb4gq-mXEQ;6jE>H)zG9DRF^p zRxgEb;Nq;F%|&Bc;o9fMWO{7@RzUoIyg)`eH^0W*%A%n?9^iVg0Nnlc9Ex5j1N_dO zMdwWmERG4~RwD@`@k6QlROrvEPyb4E-_NGbS+bSZzb8$}k{+?&U~i5ZIg+Jj zNgS4ek9o`f=P9t&02iwW`Mm{{m*n!F%mdu42|x9u?}4k~84Cb!ipw{d2Y6cnuJoh| z0BB`B$unDSXn)%RIHh`__PtPOG3=r+AgxrgEVjsKmPI>T+NSj<5WXS9MPLZ>FSG$o z_;*pRjNsq>xw4bC^}^~`WiKt|0`+-Sh8iuWX3F%0%Ut}b+?BB%D~H+SUmUF%hF>4g z*~U?c{>9ytG;N;ODyJf?rrFf07^DPmcPe}u9g`y2ah;Iv%zzc^>9 z748AUafr*vdM1tizTi+U{wK3GAw;1BCGhSrZ|sI0#)9g6UwtPX!6q+nIl#>(Z-5}# zHD@k@`0fGyq-$QL3P4+lW!4qvn%gk&Pj6U79!sU~^J|cZLXj&()qr!eTPCv#HP7L6 zq@loJc^uCO*Q<0+$+~3F6O*lu22@S3(&w$B*Op2zk8o93ca_s6NB>RESx<#aW&Pft z9Os(+D^V{dM)HAT-dGh%Qh4!RlVijeOu~#;D^%6Y>VHJeQu5D}Zew)vC`0r_H_olM zT|ejEp)e&|h~ug}hXE!PfJr`<9rIcCpt})(OcVH-fMZ%rNZ*3oOV6LM)MOW}$&-Eo zIy#u!BN2VTo9(2-#<1^C~E zi`t_Ohmv(;h{C*BX225UQayDR9~MgpwYfV5&V(k09Z$MoqetgnlU_ZnHfe{#an<{< zs!OpRB{ zWbOX9G=C*D+;$u2>`Ixf)#^nfS3!Gv;RwxLg=ua78alj6cJw}^W<~w9f{g)CK~$1w zf=R2%Hy`t4?_!F~#|F4Cxxkz+gACfqRrJMbnWMe+21St^*Q`*Xu-Kw1o6=fXCwLZ* z2Icb7H?#D$tcZ>h6gI2!=}(e@0h96{SD1a&dloQz6fk>CK4b^0$8*S{jED+O9g{r_ z^&bUVghXc)c$Y9{_#-kPh;=PQTa;q~GoD_;ZTw$B8&=P71Jho5La&?? zo*v(Ek*oErmDlm_e@#v&WU#5hOI6nXXnBRr>z8)DkuOru=ZhkFxhj3*YYbVt9yf8D z9o@&}oE-DS#)rXQn3Yh)N*@M80IyfE_e-c^UEMcNTaHEE0RFYqcOKs@1pRsG^Ha%_Jq8_a>J{>Zdr%CneoczB8g>utH~|5WCPRDVQiVbT~TZT z>Yp2%R779=EL+t11t>wiH5#brvX5^63}xY4duik^(j#cm-hWc_(C8s@kpU;+N@NWdDzY~pV`(z zFWPPoJvt3VBE0oBJ_CK}(FB@#Mz;Kq%!h0<>x~TgihejFgFVAgA#>s?bGMl}h4V*Y z?dUcadc{iv$aq$|*S}<&Q7?7hm(=mB46b(ojo4&;q{jtq_;?phKZ`b;xIwqi%HHyi zlBX4PyqCef^(TFwRq#0{df6O1f~ifI>MCPKbIhkrz(5uUO9OV%;&ZZ}c5V%wI*0wi zp6yiYJQTT^uhW$CvZdDXC~Z0~-M!Wxg4h4~V`X|>i$?>?Vd|)_={VAjpTWinIC&hF zUfqdHCA|zDnlO)NmvWpFFrM;s64k2suez1H&9r>qC4PcL7QwFYjF`>!&BEM<(SUd8~MGE9~-!nuqp z%|Y1nRCGm#Ylj=rUsvSE!6zG`maO+t=aiFU;Vk983ESiSpk!_jN1Pm}Yr;<&>DSr& zeni)=%6<_WqLd!A7Ehq98sjEHFn`&B7V1=wO~@o0pQ3;4viP$6tcDCQqA^XnCKq`o z_0dPRV4~)ouw1GR+E(E7t88Gbt2B8Z2kdf6kBgU6%vu)cc5M zpLB&2LaWaW*+|>Hjk?~DUY=3@Hn?*XZq#D``!wx_Ow>I3(ziDt&CLCX!b-8X%KU)F zmC9&Qr@<52R*GR7`3s#ag;+5D)ao+nLTz=I&^A|yuMU*PS@zC^cwDX*MOEuX&&Hse#;`LpJoSsW(;&~5H^g{`H0_$W!x;1=CabVR zWa@U~(&N}ul-DqZJ(+Q-{ANMnA9A!Iu*{1!fW~FBB)D#vQ>pu#U@vtFVCAnV{?y}+ z3~4yv9rSvtOL0ygl)xh&%+`k)aE(9Z-H}n+$+7g^9oeSN0UT5!O^t)Y{^WdDhJ++E z=PQCb!~O7eir+aq$4i$h$JO&EiiLGbKna47$V8>tAELq3DsD&%KeicnKP*cU#%lH1L7!<+K8TX37Mj+~mu-$WVmnj%TGFO1B1h46Oo>D1lB2yA3u;!{^BV3^ zcxA)$8QI)36ZcW!L+R_(ZC^!2r&5$>d@Ye~K7=lB)F^862nU);Fy^=N!(q;S9{gv? z{n=hU_u{>kx!2N`N3yl=R$RTa=2Be5hfJ1S9rRq`&Q-a9*DmX8u8}b2d<;sIp2r>| zckxoh*f3o8zhrdin;-mx;kKI+U1u3$EKP&!{jeXzyrHXEfKaJ=>3+ms$QmES>_^J~1&nQ?&ZEwtBjbLVm zV&Gb;0QO32?HDj{{@=2VuQSeytwah0bq5xo!xV~!m) zdMrCv=Xw3%v#;|h{jqFgSVA8>hK%#c8wHOa%kGAjE#p;*A^&E5rCdG18!E*Z+|sh+ zH0i1I74Bhb=JwV$b>#`WrGJ0eM`5nU-4$i%{%U(@D=Kr9hVN3OY2vWULYfR8^Wsd^ zeB*1+K`B%29EEF4i(mm8EEfp@HUMS%qxht{8AU)Ea@IaXl}W4+kCaUy0OHEQ2T$U6H5G^H^wcT5ZRU zDLnJ**?WdNzR1#jNG#6mlI{O34$ri~zPtdd{H#&YAmHjdlAt+PtRp*L~Cms=+~Ot=TWs-g}*PYW5Sf zQ41+h*f(=iJJsGmi9PTo6nLcU=?gSm*qefbR#@fS=+Y_rw~|lqE(e{eIS~0?*f-KL zR?r<`AFL&;Aa7~kL~F5vV))l#1-&d0e|9+WG{UV|C9`k=NJbpr{mK8Ij?uW zV}NIiotjOT-sp-0L_ovo;Vn*r;w4_|kNNRB-~X^T;4 z3o>(E5w``BS?LaR5q8KPKnS-k*k3xEqitl`(j}?LBLiI^l9g^7sc6v#->lU+Qnn5e zD2Iyd?b~V3@^sndMjkbEun*Nf&!e6W_Ws(6JR0v{AFCzi(dQ2KA=>xL=%NGq1P3ZC z>x8|HTiwiDkXTmmo+_44FV$MGP^ECQvh*w6L&7R(X$|`r!`Xt88us(0_RC`G?_}Ro zGcTrfPWB@+unlGzUq7K5XL5SPjGO2vx=D3r#nPtP+?~y}N`yS_Cdjl9IX~hKpf{I)avaQzTrJ!F0@Dq5k~3p1PR5PE`ApYanc>im2{%;?n%JTA(?)b=b{JEfr&VQa<9F{c0#rH1Iq&E&5uk?wh(J8BLYVRn&6DL)qj@G&*z zE?%KQUEQKwpc?Gnu<597j{yISh}H1#ml1uHPP;oZ5|JG`^Dg7@$Oxn3syOLR_iLQt zjx=$<+2zH`VyH+)5}MU5d@bZ<9e1tQUDcb4Klh_dBG zq=I92J0t4}(Ww+JUEUo0*K;XwzN0%Q>!~3aqI^q*3-c55=ZsiEv0SW2ebGA})>934 zx5LY)h$a*#Wk4pJA_-D*(r3)UA^7y@1xuLMtHUKdBZ(WD0(JDB_m0-@GD6NMAR3)m^q5kJ5r9CCH^JDB{Vz zF(RQ)l3c}!c82=ItxMEr#0F8Hx9*Qa%f4@IJx7wHT*L>Ndue9%3>|l> zg)F#b=(J3)XXqEH271imb2sWuno;K~G~!x#b0*V4p&`B*)J`{m?1`OB@5(5ZA98^O z%Pr~s`1!qhGY3^>9toL_#V4O33-W#IgUO-L3osDEG#i&Ev0W802jSRV8pwMc=rLqV z!Z#%Rs0l4f4~h2knzI}(2o(ggF-bU4x^#QveR<==n@(m8UN{YIUj534VwMiKDiQDz zGkY*V8g@}Xf;-fcyYUbA>2^oNrm6L?cZ|~F=KCCo4fL5m2@!H-eV9A=0O=8P#I{{G z)GX@z#jC{6A8hbPmxBvTKjLSJu4=fYk9u2I5nalx<5Y@}*HZH7?mp1bH8JoNhxAxZ z8EOld`iX%-PvL;6AdvagM9Fs>0tF{=5+%ZG37j~ITNRwYr~#VxeBva2&5Eb?9*T!J ziBm_2cpUjhp)7Oe6H9;A^83qg>rx}eo3Ex=m4r%02108i0t|1<&cMeeE&cpVPd&Im zQqJ5xfDj}zFJ9@TM`|b;>yetAFo!5^#$*plA=?g@G*=#Tuyaj*38UJO6sZIH%Yg2Y zHQ~_#1xPDWC7zSUtfJ(kxoRgTjam}@<)pa^>KyXanOtFWd)Kq6hBbpSmVZsyCg^7~Ml4(wcOUCjZ-=kVH{IG=HJ1QKUqu z3aMwpp)?^HJ|99xg)ey`B2+Smpu#$&M`0KsWFpFg2*@9BduVzTF33sTR}wjluC(Q( zi3*n~VHS*(Fzg1A|DHePg+2`B#kZ7?1Wl+l$VjsAL!W{C6j12rpF$qQa)@yT^M=Ta zl!VqnuZ6%*Ys!)%f1-Glc!K8o>eVP}I*{fy=e<%MWZfZjVKs8cn{V_xOUYgCPfah- z!sy8sxShqSxV)p%$1xo#hv}#E;8Gb7UM-dSs~`45MK6r`M2jvVAt?v)zf7Q_lO$nG zFBXJo%IS>u6}=7;m=bB4$MS1J2JXwp@mwQnAx-TdP0n)2*`@mx92gsT?bj>M%BF%L z39l|~E~ebWBp3tAUVt(%#-bsQ=uEvWsYe%(kw!8{iVBa>P`db04P=Olx4b*PfAlR8 z2fZ8P29F6pQ~b&wGCI-8i4pL?fcy_o!VH|GLddEWs2JYZi%W}vcV{O(J#DZc+|tvA z3&JBkZImFq)5S$(dWRux91v{BiE(sJT0d}D-n#Rp-uTt@v@PH;T%<4q!`AWs`umc~?&g>DcC2N`9M&TQmD4 zTqRI?2u(*QG!0i5O|1)#Lf?J(4&_Eqe^>lmd|!WjcGOpxohmCVfEKC40uLg`?7w~b zQW?fN`HKv%BZe~UHD?)-lxfHRHP@}4=Q`mZx&H5&{`WLw-pVlqM&#H-C*IuIQd~QlG2bh%F?z&LO_o7!v7V;J$?hMQ^yJ zM{c99RU;>Y>RFbpUV1KiP4t$yb(&P6&5)g#z9#Q<&e)c&AL#5zPu|&4whI~!xuwwY z5%J0+^~;df7(5d6B*NP}3BwBSNQ_447P2#9r)(7BaUCR0L#tGr(V)cVQIA4FS3}`ys0AZdi1nWXUUC-q>5*MZ}tlf-1n723oJco0bxx1W zyqilElDy67e*{s41!62>JrwEPJs6DZO7WU_nMkD#VlS1>#n6!!I-*3+CJnrlv4@5? z^mD6@jwrh`lbSYu+^0JxO-Tl3kxuMi(c3AcaWJ~U^=c0phDL^zU#mg)@euOhM_ofk zS^y%2qc65tpzSFW;Lr_F69*-R)2JruiYMYcO*&dKgrG~v4D2n`$9ENP{>a&H1ReZO zyXlr5z2a^q1jlK2r~eljlXbkzM5APk0$H#MOQ(PL1u8KNJgWHZF04xq$b zAqBtAnx00zCiZ^kI-tMO5Dq)Qj*KW%$Rc!F&ukoc#IO?=5Ks%^Nv?T9{fY9BI--a% zM97lSkD#@oNMCxm6H~{InDcm~cf>S&gLBUEofJVwddzE3 zdPiTHiFWk6-<(1QOBs|j^5J3N;`3)ImxQKiTNX~NO-6Hs@%Oo zJq2zR`0rf4>p>+4J%T~=dZ#Ecwf}5zFP9Y34#0e( z&jXNeWdNZcwpo;BIiH3zJxb$EcmD@EvhcQ$lsa$mvX#a7h@rZe%I4?Kq+1BIm4Z+% zTR6!PPj;y&5V1>&Wfbeg6@iZ_3UNdoznK|?ZD%nsM;s0rDS4WLJuTO%v7zF*Ey^Ih zAm&5=iAGYXpE&9k6DwG+QRfV z5C1Pe^1#h;zc*5L)vN1eSMh*v+Fn_wuIB>8Grq2xv?`t+^A&Mn%0n-+<~J-XrkYwV zHA>7SSJFvud+lH0_cLOAlC35iX*czxVHx3}#SVC$^HTCJzL%vlO6!NxAE(=lQXfa` zcOf?Uae{KEYT^rdJE_M;oj9qJ#aTR@sT&CS@s7sf#eun)GWkUF?Pqj<$MQw+Kr1=o zxdJD~9O5AZEQ>({)WS3IHP)x0;up8Im zWbu6J5$^{$WmIVtwNun-dfHk+ub_z2HsF6VVlVovHW4vZz z^?3uu@Qd2Q2_VbK9W8q~<&O$Zk%C`CgDt86iWvMy+h8vrGNGoUl*}L!(JEno9D|0J z|L$~ZommJMndKD}NeKuEf^B*979OY217wu`Q0kd*>z&wDWo}fnPu%<HL@Uxuq1b@Qjy>SnPr;gWk$FJ{DE})*gqj5yHl8%->WgsOeN-ql<<7%C* zZdE#3DY;syWm_R-axt#fDr}rd`BHq^FDYpHm+<4D#a~GIF!}^IV(c}58gVOHL%4es zo=9i=u13BOrONytnq%1uq&?$cvom+;LTkdDvjMQ4!pOl5;@L`~0(-S(Z%mPVre!aj z)>r_8#j6@#{Vu@o?7;$xp=VAI_W8<%S6VJVa30I(G16T;hhiOM#VG@?`Pg58|K9i* zgHPwojlw6!YI6tZT~ViYM7@$gd`J3*u2bQ3fVzCJSTY%iC&pslx5_DOFM0@wbVkf< ztJt%}+eQGPY-1K$bzs@vB2nPt366+^9YYrOLtecW9YN(H`A8hyEiWYziN$-T%5M>qY86KCokF5_rfln+R-(-;UwT)eN3$Ot_tRxZj?IOamhXjllH#&< z84Alm7O>$Ua2jq15v37_5J!@{ls%C(~bwys!J?mBc30va=Jr^ z0S+9CWaPSr*eH9k?vm`5(OJy!q97Y`5l0N6ds`uEA|$PYzgWb14KA5H@qk{3N3PL5 z_^|bQVvWJpDq;j;p*c|^@p`~@T19*-f&Y8GUPrw(mRI;d@5?76s6OjK50$5Wq%T*$ z?ZPW<((4SkM!m?~Jp7M1*xmIqCSOcEG1bi@U7NA;0bE5-5b2N6ottwdd3T1dTr2v5 zNIx3V`}U>rD0-EC8Ef}Fz*h4ny;>E2oIn14-7WaW_n%8P&hB3;=EpYal^RU}i$|tx zAv5w)J~2fWWXvJax9~U)TEwgqJuo`MT%Gq_qu1w;-q&B_+6MjO8V{^;kCD06^`4^K z6|rQK-*7ZPwLz~n@&hT;Zl& zA$ePIn&oi(?+FzF#t)G2DO>f<>d?0Q$X49a!%Z7=t6rt;#?h3pYe^he#Y8RPnj1Q! zdD6|g9VCXt=gFC*Y3yho^_d%A>UPrJ?{cZe{3SP#OBfp^`3R+>K@p zg_^E&G|F4a55H41a;55ZFgb&-I`_*^Vaakw`l2z-QS^4MI6lJ(LylY^R7&M^oPBx3=g_I^5{s+5>2gvS2boufOBvEHwNuJ4nnPXweu` z330JZhaO4~^FN5B#WKM1Z_F+8gk1Snb)yRq=%ynuGpe3@neD>4bC1!n#`+fZbr+hA<0&S{{RLR?&-uw zj`YpwH>(Ic!Hr8-{S4%336&rNPjjNu=~=YtFEPY zaVxcdBI|Y5gFJj)(v?s^-SLvU)Q7GwdhhR_{x%hE!w@l~QZWj^z8+TJBJ!d2ySagn ze1NeJ*69a#2RAT_Pd}uTr6F+sl!TY3OBfc>oz>|!ui1~02*w41$GJ<|HuA0m^OlbP zA`v;gbmu)8QF=#H0(c_Pdk8!Y#V{DJ^a8=ySlnF7LmuJ)h?_=t!Hm!U!y%@yF^|9{ zKgfwFKw>1#0e09K;uMTMV;_yj@r|&dPpiJTw@k-k@Wp65)?2Otd*GAM2CeIh2|b_O zk-k^~?Z-B!%sfW1qA-@55qH)MfvYfL*nmculbQu_!atUi zdV(xLoqkT8wqo9zBpR%>Ut*7&|>Xj*pbw5M*# z_eh7O;MbZy(vW21HxdC`_j-RQEOD6W$QEMr zf03=PbLP3e>GQtIQg_In7#Q?G2SAC?L%iac4t^LvHs)0)TftD`4R`=v~S<8Pg7 z?QGd*?vrHCj801WeDZSlCUTL{vW>HI<4-|3Lh&@mQ|6U{Ti!V05geM{8SfCH3#NB0 zb7+B*<#ZNb^X?|$qa}%cMmQd*B-zK{lxE+Zr7G$yRndIcCz_85O?v0XZ~f6a!@vEL zu%`B;#@6`;*=SG%ha49@5Aw?x68*-|a}6SL5hN5F_4BF9D4mS(*8*XqolyhQozFvM zyk>>U#UQ|Lih|<$ecFu6ZeDYLLAQUuoY!31e!tre|D~M}XYoXf{xHT|xrhI@UV9rJsV|{PA`Aq(|w_-a2jI z^>$0g?j5#$qWo#N02goJ;wxOR@aml&h1<}gGIK%$scM~(75vk?w#1w0#HAOAw$9tG z)~E1pdvG+rO$;BiN3Z^R)fim&rL};@VnHC{G?W+}$0FrfGJxE0DYG#iD;H0PN@pBv zC+D9B@MC-Qt9;)^9Q6u_;a4{5O`EuyuN)Wc{tq7GrZXux`bH=1HiDN8;TviQeCujG zj{EG_>#4=jyv=^(=Xx}y3BB5w{*#NA5mtiP!j1BZy9yCP3Dbm@u2@rkK8ohc_v?8) zZK+A5)==0n^%={#yF2Ksc5)3E{5gXdQ~2f_QxDgio69C^U= zH%}a5z|a^Y5HvTpa71?h70hY#u%16v3_7-2P7#z2B&Z$ndcYwXvn=XM{fv)zQsw#N z*8mdc#`C_@>xE6k^yP`4jZ;)3kNKlM*J3Ddn%RedM@=k#FJuiId~(NfWK?Oq?W=Pn?)AAt^{?S!ULi zKo#Va@+UmlV?m8hn2>;M<|ENsG z1KI72Ic4~yaHFng*Mu?g<6x5PBsF~4Z{-`;6Cdn_1H>_ixg=|RTvPIh)Ok#};m<1u z8dW%cS<3ssX#A&p^uC!Z{N-6Qd1(xLpa2Hj6Hl(>{Qk_e&SSn*u+T_ z;wJH<-HZ-Avm4^lx*I_bHhwbeH!&%89AkZB$0tIP!zLzANTTwJd{L#vQtW?k9h2h5 zPn?3v7A`KolOdo2h8&KGdnrWhsIkeD(a@w5#orN#L&_d%ZsOF*^pQr!$4(dnp+j9u zug}HZo-hH`KN0O>lJGJ$At`=ha*{nUHYpz8YgF8%AerUKvQD1ojrEP{7#4x{o;;yx zRBSRtdUC?}cYCJ20fX@rTM!d|lp$fBmd{ z_cB&f=Od$xvAo%D8SL%s6r8{Ith}A?>19OK8&tKUHEMIWeny|Fc^#@8_~u|2Ew#hc^NpH= zrqQ$bJCNAVn4>s;{6%5cVQ#|QfVmBm5Ay)#KFn-gWpiQDVHUtFf>{Ey9A+6z{W2y>r)DW8-1IglXSJV_{u2wjHKY4~?~k83@y?=ikjt3tI;}tA`fy4-eHN zHP#P?0^a*C5iEt^)dl|nh0mw(I+z*m_ zF=hvu@so%@O#Htc0+>ZW76CsAK9l$p#D6XL4aA=&{wu-nApSh@p9_8)CHO$pfZz`i zUqF0@;Cn;j<5v(rL-1pXUroGYya479u$F)!g5N;o^)t`R_)SDzCMwZ@pMI2R8{y{! zWg?e&`iaoY_@9WsO#CZ?A5Q+Gh<6wKM$GTxGl~DJnEdZ2-m!v!y8<{vz-r>Z7yK4V zdJrYOji@N1)=)-w61z|M*-89f;y)JrU@G}l;#UeD!i`K3KUeUf#OD&9EOsS$FY!slM+lw~pGbTw!B@gA zQG6gJP*?Ex>AR03_ez4lOnf}?hTyY^A4UA1g{C`7yp@3A{L7I>RfmJ<7;-#`#l_6{ z=ER2+zfbUkDEINAw1Urveu<9}r4{@M;`OK>VN2D8bi> zFChN5;O$hvP~yJ@@5qezAfO!qCxwTnq-=%R1QEi+a*8m3_*Q~<5N{{GuHX}h z_b0xR;0F@#$JfN+a~dQY0TlV|zo_(2C~iCP-wOT?@&3f06#PBPTqAX@OD#Agy8A^7$r zKjFl;68xLQcO|~A;4u?m@jZyIB=|7;T3soAL-3gV!=3m)pNh{}odSeXfZG5v<7rht zK8pBn1rHXVoA{H0Po^3eNBlm)FCjjW_>Tp@nfN5)R|SBOs`K0@#xQH=%OI52LEaaDI@!d3iX?88ttcC{}43j~9E z4QxL#oxlu$mfS?lM)<)$_9^}MFZ}m|ujR78s&x4ZHhYZ!zC}0@<`U|Nynj!1Rkj9W zbSYQ3v}#>bI<%)E~kAFx+j5 z;S2G@Pmn8`4-c4P1UP7SeK3&Q7iG%C+Y#O^8jEA|G4X<3?PILY4=`B6Q;dBDd&XtN z7h|voKQs0&?1T3i`vCZ=r;so3=l;S`8`$NZF;)i$#=FDr3EK(#9oXk!Z-QN}5C=vs zf=CU-Z#ZLX#4|`?-ftRgH0%)AS+GaLKG9NPOJQH$udp4kcVi?!7QYZMw6e;6fxQ{F zf?owFfL#;zwkj$c1>3JDrXjEg;|A>KWbaVfIoMZ@s2EupY~xjj%E}BiSl34?YYw|% zHH}5VPOPc139v80UIhD9yT-P{-dsy#zroJ#uCelX5B%W?jWvQj7Gva1uy@1GhFt_Z z4|d8qjny4)uv>p1Uf2sBYit4RAdGplVCOnYG-kx2Bv6cXVCRm}*=*Pip~W}Ao(}s6 z?B)w}b`AEpg*tl%d(k4DO&(#enagyx9`^OsIy(%z&wD!i0rq*=PhoHST4(b{8te(| zO|W-f(Ah=Uee!hnI&8-Z5b+?OFqjAXQhAC7O@F-unPS7T)cKZ7^M92o?L)Af8Nu`m z5lk)DnU!hRnW^u<-U_=@7pAQ1!qj_Rm=@fXDcN0d66Ou2#CL-%b!XbX?o9b&Ak!-k zVhUu-<~fBa&!#iBZ4PrN`SY+EJD=IAeavjeHU#{fDK)YG5VxNxe|`ZK@Fi0qcs2-~ zZSOUvKxo`G~RYe=xNF@l1M>seb--0CPAgwZy%p`rvgQB(+|0bw-uLl7a1MnO}B zJ!`5c5J=nXwu;j74MmOVrYL25DEjOkidqt>DE)gWsvkDCvwJJ*quvTDf<2{=!uIx2 zw95SyR(6b{ERBa?k5!Z{j&b<)?g@$#@UEiweOF;|?<&f2{DgYOLPZH*rD)SvDXha9 zMY)EHMYBFql&YH)7W|2#pe5K+zfsukZ}HnG=rZPAQIxi5|BtUL$}OB{-Ik~5wQneD zj~fcxen(M8peL_TpeSqqRMc)y6lL*KMSK4*9M~%P3%ajJVdE54dE%+EKrdCD>7{CD zVz%a$RP9tHRYfy1(8P>8XkKVywvA|BXktcte^q(hT-6dxb+9EpRs8|l>8xI=(r+Xp8Ko*$ z=BQfFxvKi>d{t|-5WG{>$}drs0JLMYWxUj_vf8UvWyt#~o4!U>u5AatLv@S7^ke@{ zReN=pss`*+wXFRJdqlNOzpUzWF01O}%UCJ6qAESEs@m$Ss%ZZ<&mUA}Yo5x~o2qi* zp{laqRF?Xis+=!S)rP;TT0Q6n=m+B&?ACv%dZ$0IrtycWjDDiBO;1!MRngQvil%t` zYV5GDrUX>h)Pt2Z1-itRRb68x)ivF%hQ@xVp{dX-26T$i82SV{#kSS~g#x8w%&D!h zv2`?MEap4?n`qkFCYl-%gk^;wO)G|7(o|FCw9&M?Z8UXiTU@+puQB}4f>MYH)WQf& z(Yt7RU>8j}{)VPGx@jsDl+hfk2q8T*t$(DZyxC9F@nXN~7Og4gqcyc}e@#0wKvNvI z2WncaH#KGUo0`58_NtMZu8q=I_$W;Y#!P%&yr!A)no@n5rf;04Y2NQ>>X~;m{lPn$ zvU9q|zL>6QMbkB9{{l_zm#*mx(>0}Jp{Bp()U>ainrhF`^so#~S(Blu^%rYOhZUN> zZH1ns9T%cw}>NO)7R!}>dkyjYkXHzhu_uoWw1T( zYs%{nH1_m?rX>AaV;dhjG-Y^!#!?D26*}60el`N2o1vd=!=K=jJkgZEXPUP7nWp5H zXtvoNx)NAk*PEBuS)RA9`}*ig)yg_rg{};$rmHdjIve4yt55xP1uEU9+I3}MTV0*q zRxgv=R#)zf)=9;?`N!+5Uc9bvcEsx{biDyRZ)8K)pHI-$M+v&VcC5~}jn$QDZ|T~R zw{-RTTRPh~PS?+l)71jlHOA|#!FXLA3VZZKU74P!YgOOY)zG(f)(!S%*gN0WHQQue zwI}K9L6WZQb?ExLsk(Y0RcC&)b>-4LojLBz*L6EO7j!U2<^o+q2V+C$Vr1yTAb*1Y*UC-R7tC#la zO3)#k@H(WcI}hth%2&EJ{fMqUIij;6Cv*iJlkwnd-9bH*u^GJ*dM4YmTwR%WNoVS1 zT|p0JpmQ>=qJz?J=t|j}I%{}SR}TK7vx>KLW!xQ|CH|@_j(nZHe^=K$@1YR)P;>Wm z&Hg}F>it{S_CM6w?%#B+LIJ9~K-Ufx=!)$TYW6WQ_!vFxlh(TaoxB@nnB=I)_q=01bh$TVv3tdEQezKj3i#XpBHb{O?+ zJ>Y${pc~qJPd_tjmkL(pVXP}=ij_>8@1B_v+-H$djoVWV-53P^b*`K@YT9U?Gx0mV zJ{3#0iR3ozg&VE@WeB%=#wx%aWe^Vx`*wWCAEp}hjO&2kzlU&eQ38#T*Q-tyq()4R{iA-vf8f+7EXgHgvl7-Pq|FWA9gSN!nITq$BLOV4E$gI#a%BcGudnX?VuHZkv+`HlqK zp@Z4s+t18@^Nt&k(QEUKit6p5y!T4jhw`~+nh{if1+wt4Dr5TOUvLzyRwk;7zCo4I zLtT~W`b@9tg=SN}biPsFXoIPLLmoR9MGIbrEWc(eG?$l3UNN@!nGzW=P!_q-N zOn&sEH)SFF=0OWcT4xiq3k6iOXY-i^ zZ5EJn6wt!i`~pF4?-rWjyyIn~I={Zcu;J-?!_8<9f3NV~N2$pmn-x-c&vd*56e#R^ zd_y|wwQCCAZsJN7B;z{BS+ZoQYfv|Kh+yZ`LX+x9pM|5g{Owr~vA~58!4C%rDJj=z z7CsBP_sSEM?9~rUhzrDTJ5bGgk-&6!fe{wC7vP&NFw_EX0es5^hFBnWZ`iv4AJ;=d zujcWipBTYvY=2Q@TEk0)eAp4AuHkX1(DdZZ78rH3N8c3k9fak6Q)n7|7Gc|gnS?D8 z7{sKGG4qo`^APWyZoI$GtJw(_n}2TJIZm@bjUJ zJp&tq8r1*zNml#PQ%>&wgq$?n4ZW8Sxc}}#voqiI6;kul z85_3`uT;tU*glKu6F5Avq=FiG4%48cv$!d+Ogh`;{9+XnyYsv8hwq! zg=U}!ud&vs$3p=al}{I%3wg6SXhx}M-#n4P#IuEF9e(T>LJfyHb#IB7Mx#O}iXysW zj>y`bD>Qe@`p5)39j?83t?Ne32LJ4?wxZawy9z-0?Jz-*k*2aoz_g5oUg8s$qV?ng zj-}>UiEm$O`1@9P9?+#guixRLIJuzhM(C*h32c2Se-I1c|wu-xr~I= z>Y#~5q^_xFkDreo+xEuGWjZyf$W%of%PrxMM z)8-eM(R}IWMtybTe7^WS^xm7DMWzG!(4#L~?a{UqKA$Y&58=iT+Nke!meLZwuE?BEildRSW_=OHbH`4)WMs?6BJ&*o{V-Gy^$cMj6`8-6k`8@y zk$ITUf*#~iBrTbr6q)Cx_i&`&cuSF)EH%=F48x1G^xK~np=bO3Cq#&K0>-wIT$8F? zwGQFE!7eN%x4{IC1^BTD!iN)|2fja7el!9|nIHbF$ZSt()OTM5_UtwhKV|qZ*pSbQ z%)dm2-5-F}cUr}%Q=UGJKU&sr$BLk=X?)@y4tDCUBJ%?oAPMZ9Jw>J$KPIvZ_T*lQ zPE^Nbu#5KumU=z@grmZBo8d4Ms!T)RRS~-QXpwpeNrtTV#%)MpWPS z;khESo{cY_Yt&QMe8V5Yt8wLG-eZ0J|gtxM0;E=GLz)E zbj7zt=04tgH9QxrLJ6yXPt{90PYm3a{X~_&bUCR&6lK%Ty!}QbdE*9hCv%;-5lMdg z3w>o#3Xz4MZ7jC=Cr`Gg2&feCBb$)v0VR}anuPG-d(dTie~bW| z0FD(AxTm0iH%&B8S>UX;z@ zLK-sXy&0fAwAf4(O@>FE03WLto8v?qEK3dSkgeDpQIT)|-l*q8w@b!VEjFox(=VMy z+`H0^YPL~;->=3mY=*A6SB;l!##ATtee~>EaM)I}*j)3x&3d{Q0Q18o?%pKVfz;yK z)-EAySdQ)g6n??xn`c-rEhg@<#x^g$(FbbF7MS&x7A*ohXkY2iLb?gm|P|F-AVr zv$==D_njWa<{s_?jaxPm?AYGL=23%tt}$Avk*#IThrcOm-WWB2QWXQa6hxegJmK;S z)RFrZu)D$HR~Gi8#a;!wVPLV;va?PiH)7bGxE=jOx7S<}NJ_;HvnamUY+?0IV5bZ! zHb=@npJZ^~=e;{Wf^JfNP91DJg5B)~uDRhljIe zJw=wY*a$6l}1pNCM}V>m%F`F zh#6tZ1*a98v4}&jn=L!BR4^j|4kWOm1bwLcTLo}5zL&00%%T&^1AJu;ibQ@Z6a1pq zYqxm0PI}^*UskG_ecxP)-@_%vST}G@!^*n%qu4Tw&7NY&Zc7DQFO#?5fqFUuxYu*9 zHlDcyO7Hs8Vsk^OUa8;`YPRPxes+g}+tF)^%{cx$CKK+|6So1o*lL|S@lDr&zb|?W zo=SZGwZ&%rQiHCY1fKq&*!+*|M)QcTvANisPHnJ`SPS9ay8y<2Qfvl@j!Fz1M}5NE z??MB<_$i-2_M2Pz`duhN<P=A39+B(PDHDy)PJc11E73 zkMf@T;oA5(pSd5dZI6>H4KQrpZj8NgoL?a4caQTDvJ)=xpabxhcBvRkE5chAysf{) zXC8p_wM%^a0n}&0zlt#llfx8u#zujSkpqz=u#3Qsdm*9jn}B@-EUc6$Cql!Qy$pw2 za5z+6^bqd!F6o3D#pZgx>j3quVDoP9hX;|Nhk)Obk{kL3DyzZGV$+>E0aVTxs2uf| zVsz@ws9bpn=KTv_{{@281Uy2t2VOwIdV}vPXOFoD(8r9zlFT&Rv9=1c2<&9AC=3m< z4uf3-c9E3e4TlgzA$UL1_Vsx#@xR=ogcYi855|7K$4d@jxWn#Ky*A`gU&2fC`^A|3 zzmVKi0;}LhPxjMrOtdP)4T0A^dj4(f7{+gV#IJveO3#19Jr5f}+Om>j-r+D-Cw7z+ zV+KyOUnUp+z6QSJu+c>GF^l<85NdUWKST(1k-}?y1v^{eJ;{Em@R?+f()f0=7ufi9 zvb(u+&m$Ou52+*daE}l^^ayG%D5S(%E>V3$_;!LGwJot$OVr%9yo8|b0-~ySr&X9m z&skeLuw&cuo=1(^?$pgsgHvZwm+qNhmw|mlDl6*iH@KCU2_!ak+#i7b3G8+0*$*0i z2@c_{d_MKl-Ma#N>{Wu54x#O)5sPzuErsZ~ZvtBcHc*I!`+19X7qwRQG1$`xI|<9n zSZ(kL!05Sbr4p0Q1L*DX%dEWChxndAXSU%-jv4jbQ$a7NTw-n%deLhq*k@Hrjrrh>Sy0DGxZ38nyILFok8;hjq` z&L&;#{ut~kupPy;#VY`xZA-Tja~FhOzr0P3>dsUXGHb*SrjNh$V=QHnnRFutIt)dt-<{Zk8W>3SfG>LJb zdnhC&FQvr%PDJRQNWwL<1cOqH66lU973cXF?3~xq@xyqo+Rm9!lQ_;uLMcReiV=g{|1opa94?0 zS2ROzKMzfp58j7h6_lx z03cQ`2+Y2Kp4+y)1T#)$DSr2$Jx(ymMj3!a>@W>@^^0(L=Hqgp)XAYXkG+W0%km6Z z#?0MRi?o;Jz5$N&zz&vU_|srdfbCC%%Sta+p?PpF^73#`2^RE)OV3=a&28JqhvuTo zW`|15K4Lg8*QDy<9h)b#MkTkaHsBi+94*0mm{^%C%0=A=XO&=7MB8gdKAbW5`UZ`k z`c1~sH~1BT-d@%M&#e-7M;yt%MGPUHiiGEwIyHuq1pjFIW=3S6{HSbLablodfm}F47uOxo!iS3wDwekyYOt z6|@SsO7K&3MiV0+Kcd?I#R%C};cki9%uTBG#y{XI>^@#%w&lIg8+IGS@IgTdANB(V z0Y4PDa$bfyo-E)y2;VMnY9VEUp%7L8H-Es=@mAms#Bkbu5%5iqNXtH#WB0?regJmr z1?Ket*!1iY6I+E$ueMe+A$NbQsE7VRWfQAh_=N;E4Suf4j!bNcgkD3o@4!z@QGTCI z@Kc0R)I>e#v(}*1EycEmJDscE4qqo}JXXhtVN9EKvc#-{ir3eZFR?@z40!h`UUCg8 z+v5xm`UxwRwa=B91r%8u@-_=&FB^Q_{JMlM`3d8os~1Z6Q6dgqEaATq@$`=pUh_I? zf#GuL7+Kqi*CEI4z@L*v7Hb+C2t0qW#2hb29y$iU+u&!u=#YF`g1rt`y4$JmdC$tD z*C@cXb4%pR=EL`7MXdn12|<%(&=X+W!B0HKl=?6Vdh9b)!ehXP;46hPQL~aiBBnp= zr}q#W>SflnvdL!C`&o(ky&PoIl<^tZ?Jqu-TtuH%SYl?$K4vfcxG~fGQ3kmMb}!f% z(dF}O@dUrdD-@LkM-jHk$u=!vOp$Oflfz7UA znoDGgTMuKY>fll=*DQm>-%Dw$WtzjSNRVt#uq%kIZ|n!zog%OnOL2nlrOst|T@$?q z&L~t9+3pGtjq96GFr>xZ$AKLR*4nCA0d_dpx-w7Hc9*uO&Xqi)nwlKAv{_|GYChU1 z{^CdB$S2HG9DH8caM) z4ACfEAUw2&2|&V+5m`L27?`dwt;rq659TQ{oey&r<}}g3uELy#ISA7d;lpA2!AygD zJWLEsSD4l?fe!rV1`~`#LSdp{hQlPnq{8S3=nLZwx&S3}Lk9g|0%2OibR{0)H^40) z^i`PC$oN4jAsM(G1hxewkB5nY=?de9%+cS{SAB=Ay@|uLIu1o@3d>X#whCq~OjYpx zVG?0hVX1c`uq`kP!LNWB>#ndVFtcG6!@Li(873cbrNTe-9&6-pENxbspS)>=IL_gX ztHsrE<{9<}u)D+F0s9=nd;y#OQhqVm{`Ly#4K$iA4J|Wr?Ja}d!J5EOnC5j=w!4nXW}-7JU4`4~tL#Y)oaO}H zzA-L#{x7R=P$O5a8{9%N!*OEt9)8KCY6Q+;4nTCUSAZW1n{qe_-Wk8~i&1gaZA>!G z52W()fZK*$%k3x1zWTPoY+G<{^%EQwy@lhUSt`4R*i(}s|wl<^8?KPRM$apkAb21Tefl4^~jW84fg0N&O5@K zzM`>**nms9h-eYLt5u}@h(ng&BN_Z$gxl@^IhoR};!?OPnYLGv%!0o())*%Esm9vE zbcN{&Ga6Ag9SYZW;hJx)NLTY{wr!Rz|h$(+zt(_4pSB<+i`k+1Jl`J(7B#E z8*9_qDqtzVhQm;V4)B>qJu#*i*66v z8*$JdxuxRPL+L+q^PYjT{m8*am@P2dVfMltg3+>4kd5ji55r&fr$~Pb+}G)B-1|Dq zT&@4@L(SZ%v(_7MIud@)!|xrAnt|H+f2pt882nlq!|$HKW}ig#Fo*Z+>=evpn4q(` zUI4o%?CBSfUC``+&TKGLtRDvAm)4Aij-d$G6~+U2Wtae%uIF{;3)2pCCzysX!7#7F zP*?>QK(bI>^miIdy{Fs^+(?jr#6KzbqRNQB40jBZ#UJrMg13A)LfARN? zUCp9(K762|J1QVRQXFera#OKm^CnaVUEL`DQC1`--5USlMnMB7z39bJz%Q9+((2L zVFto@?<&K-6FfgufDYjq==<*cUV%}s9O2T<;60am))j#CAb>^@*pY&tSunr$z^g~F zKZLP^rox_tiKe9z{84RELC9}=U|nHT`fO(zeq^a<6$smtatE&bZuEIYUC@j-EN5F5 zRPren>_uqCdTqtwDa4|!>l8_G;noJ*P#;Umzyk!$@0GLF_Dl}M-4F{)4&+rmY_+}a z0jvF)^aq-odu_Emk2k<62MavjfKMlndBA#E7-;@;q^*|MJ%9`Pj?IJ7R1+ALSQGbp%w<3o0$lF z6yVzycr-|);+fo(v4s|v+*IbUMlh{n$&_mZ^KM>9q+W9zB(bo1&G~e~2DHQ;iiHhm z$+r^LyEPUfEv$EI{sUn)oIlV%m+{%!^RnK+7Kbuc)4~>q^0wZ#s*aZ6>v?0wecxam zEn0s7>9J@#=QCe zo`D}_wXyD)4^xJXQf-Xd>N()l#@cu1*%k1Ws7>cvSaf&(2$&bO`LZ}lMgBnZUt1s- zq!b!iAZUJ(Q3XTa!+IMF@vAJMDe2SZcV7+P#I z(U6O9e1=07-4*mPi|zsXG%v1bs}uAcAXgzB zyJTVB(R?Oh>A*bpNPp>g#GkMWzydAoLNvclSh@bFEDI~wpL?S1dA0-A-@@AUm;T-X zHpRl;vHWcXw#34=_80Be^FFY{7Iwcszd-SI!t-!HSy-n5yo9iIz*H=!P&w8O;6asv z-2?WTh20y#hY}VX13h42!7+R>VcEduT3B`rKLX6>J77yKjOd;G_sX_Lo+EGsq1-;1 z%!q-!VHE_w4XmSu-L|lJoET5Cu=qiIA^D>Vs7ox&{w6;}*gjxiTiCug`8~q=#v=ax zGL62mys96t^P_Rj%)-u(=G}mKeUX5x5EcfS_v&wZ<@MtLNKC#fkDm8{q<;q;Z_#d^ z20KMGdhYXhBko@oeGPOT|HjW&r)eP|m&gn~_)n3kJQf?mz^ST1^QQZ3wJO-(LT`_Y zjiM2N?)?St|B9`4?OnhqKZZ9t;zKgsr%0=UMY~1uBmPhxHNm?Qodud2V`(|{oX42$ zOBp|Y<@F}w_I!Ol^t^?=KA%^pYO6hB%mQ@A7DhDkD4G+Ul_Hv&6VX}lL-|TUzRDez z^cv9JEqW*DHAJJH{Gu@Xw&*}Bzx%+u@>}UEnO|F}cJ*u_&L;t<`gpdGUq{|Nvz?6X zv9N3>_pAo&;3Bj&3p==owW#jI(G~EbqQZjSlwley>djRQFj@? zK-jhwXnz*AZ3QnOEPoZQHdt8xDjwtyEQh20Sy&F|LkX(}LEK|u)%Nkl_%4<6!BaiW z@WYD5QAscHliw^6ysHkr2mP`FHBd)!Su%gdVQ#CAG)ABdDHb;3EB-2Bn-KN`3)^&* zk0z|$N$d<+Si6&a6=5|`F;?lAjIZV?*`DKognjHL>SU|ha1+ zci=}M9{LN$XL`Bz3X%4H;8ZfuyhSbK*j~igMGFMYM-tctV7>){=3lM>_!B^Hd}#^} znja^h6N;fGED$vRgTRkUaP!*&LGv-KY}I*aZJX}75CuMKxh!P7Pi+hpOz^I3_r?dN zY+o-I{(Lyz18Zuzz$sn)4ngNIR6ec4J+d&+{NgTrC1BnV2J(kBI&NB6BMZZt9pAA8 z*`tNJZWahyg0yls*#bfHi$maZKfv`C2%3kC#Xy5rIF4ChRgJ3w$PcY}+_W&zd?Ka- zUbNCuVu7F~NUMW>5Kqb_XgSuR^_LbF2wM82^~PQn2%1mag*XcU4zobe5~S71i53W2 z#@P;_!vaC``l}H9I>03s2wM82rI!yZ5H$aQie3WnOA7?e|FaSxEnEIQVQ9m7c{Rq&{oTbRuxVG3_$UTzRAC;XKUm|3k@y4mM~~BpYfuF(?|;h zEkRmI9cO`{B}hxF3oQ_|1Zk~xiv@xfVE^3!Pg)?+$cAW(ufQgn+9J_E!Vk4MEYPxi zqRV5`4-3J6S~M*Rs~04mbyKM9rj@|E1UU{g3G#oMy%1zt$h`@i$_|?EplM(^tnwCG zAZQ8F(r@{T(kEyMIsw+OK+qCA2e73Df)?O_a^)1(-2#br6_T!oxe7^iH2hG(7*=~n z5shJQKMZdj799h6okb7EOysCP^!gV7T&48Q{bwl|4!EoZPNf9Rd-|HQ!HxhqhJNNDBka*SwFw zNANP%TnjuB!Yem|$6&02@3An@ylE^dotDP`Wr3jio6v8bw5INM$x6CCze1r$1FLOe zpn0$T2u%y{?JN+qXhfb_0Q*~DR(n3WF+vw$g+9^3KueFbY`@R~pLO7!k&GuT*YCEl z&@g@qfjwy%|F(sl29aDWDJIk^&bU1R!P*8n@*iG@nRnfENF?%Q8jKQen_;fZYN?OI=CZ1K}13T546= z9~fbQpe0Bf1`8|@v;=7fVVeblmLP3ET(UsWQZv!M!~+WiEmI!~(Dtp&Cur$231Bq~ z1TB5i)4BmR36TOH3LK$R`1$Vz0& z2!%DaFwj!CQUP|dK+s|_slr}>Z(1PHZ(rrlnnUm_kAi?$IA|Gz9bmo%f~MB}N-h0+ z`6)gPz}(HE_kr$Av=^3H`K%4LYC*AJU6pzqG*zlwsY;!RxV!!!OEz;9ztaLOH6l)7 z<1H*Aj#q98>@u)L7Iry~cP1+dTVKRK+!5tt<>Q=hac_qmvZY#{!Q|;*jaz@ulv427vb%Y+kV@MVPM%tVW_u$-AZo3H>U_G2w9 zz{wv`B7K3qVPT+o&Hn#~y>|h#sr>)H*Phukv&LcX!H`poLkKxc(l`&HaZE^&!#IY7 zgdB#wNqs449C9P4geYk$H7YSmrL%OBq=`uqa;lJc-tTq4H(THD_xWG{>-t^K^*sOU znai?X>%H!EuY28Vt$W>j@B8y!IA6UX_K^to#K2&Pqa+S~%uH{L9H&3-bDowq{c-a$ zwas&U&JJmt=a>V~f_GvV$6je*uVWfm4Dk<%i|65uPuTc0w4(X;P)^S?W2oI~e9j%x zZZ&2VwfT!thtlRRHoK`kz65<*X^$`AWmBc-Q|N9;D*lv7ZHi<+tnxW8N&8`y89?om zXME01X`eh}=22_48dtKkR;$h1)V8hhIp?HpTVt=x*0Ag=@uMv=*o?yWjloF}YfA*1 zQT+Tj{#l>XMk3h!b~jGwafrPo9)H%n+zi$AH?;etfo=WAufyRfyaQhsa47D}xT<`3TQXZ~_Od9$uK>R1&XToZ#GG+3(~nw!OwW zjiE$Zpq1c%wyXPI^f}iT*ec%lqIskR4)gw((4&xc|4ZgIYRNC7-zP2kWpjwyv{z7V z(x$y)N~NPZ%5L&GE2V+WB{rdBU&TXB;@DTscq9xw_L|Q*B<-=+%vx&oa?$De$rh$w zuKAkU+Sh%~Ez;J$ZsJ=)TlyC67imlJeG9cUBMS@Dkq-F8Z@Q6)SNnhKLV?9}u4fhs7z~@QWWArz`#G1n1?S@e3mt zGM-ikeh=0T!e05;Nlv{(8rGD}`xe~$l6IKt1 z2PA^6xDaBoU+vz(=A(PC`O6SnNd$Yv50*NFrcEMPJrsyTC8j`p|6OeU2*f!O!Dbsj zsqFgM=X@d&Y+9g|2{b-}>q%ncBc^g&RPuRfH{q+RsyJ(4^H))9o%1UWT_V^#b`8X# zh%I?gBG~(KCvXwsVu=@zngh(T>2W;$rGdSz17{%qF7eE9)9O|vEcgwdl8)JZgUt_R zv6~Gid`?S=VDsSn5G$WVKU*T$d^R74(-GoWi5*Xxm<(hYIOTJml?L`M!r)4X-%12~ z)fR|9jiFEy<4>D;*gCNB51(`Maa*8`f0(zawLOcAOIq8r<`lI7=Y7s|(gvJ2mD^#@ z7yt4(N2GyGCI* znC;Ryn8!&2o2PKa1lq^PIB!a9A8$JMj<1|L2Qj_hOCz&^U}I4PKxSh>{u^o7wpXla zzc9Y(#Fg861^AzRyd{b7xj$)3za-J@Z;yh$0j-U+HxL5V0op!jeWmS_b`jcx(k>>N zkxb`cK=?9ghz(dyt$Z-X*(R-g(0od5M6np>2WcaUnTs9pm0!tISIRmb%(6y*Q^Ijz z{?oRse^fAiJ0c&B3u`8=MnyA+8pn`LkT$iV*-DLL%bu0?austNT99MTc1r`B7UfX+ z??I$1t}~rGVPg(Zt0t{)H8YjkT4-&ht*vG@QsZE@A<_<2GyAEXfcA*A6V*(h zGqhD0)V5aIs_Hh~259d|+fdz%WI7IbJ0-1oZL_>{eA&v^{;sD%EsXCV7e$L+5a-+} zURq$kb{dQ2NPGSbn3Y*5s&ju7o{ByHu*V5D&!pktA4o%CB|ea5y55Fb%4r(oLT~XlJ1Hk#?q)Y1IWg z8P*#2hBUBw0^j-s3$=mUszk8YLfTNPVZ!_dN&62bQObdERN zEHU#|dxnQY+a+!It!6n&9tcA_BrSZacQk=H&@M=uW3}K?XvNRjg8`d^ZL#OQ88J>H ziD0kN0+ZXpH&f!|c4kaB)X&(Cc!P#Cuy+cBEnuGco55#XJ?&)M=x}%IO zV5<3RBw=ThN^L))x=Nk5<=NlG44`%lZzD*TcI0`F?GArE|9=*~^_ch0`lgDp_R$8 z=;d~gb8aW&hReeZH$=?grIW=Rr8kF+o>eBgSzE+m@Gs)LRS8bHzipa)a7S_GGZ;-` z+3$p(QMW7?O5`?9xoB_W=$}E3qV(&av-Du|CZ6SiY5iiHof4<@GXw6#Va5+YyLQPY zj2~d;QLBsif;4G$2bs5_1#cS`O|Y<_qh8NP%UORSgp(r{DxE^PeGXq+Eu-;B1G zO7r{i*h53Z(lo!{Oh>w62HF&9YdTX~Iu7@#w58+BRBE?RL~*6vKGAH17CbctEtWK}S;5A>UKl>l zv34i*!Y0rQ8!w(7VNNT@565|B?cH7?`G0Ul4Gb_fq zUD`FX%%{}y9*uG4O3QoHT%^`$HcpVVMzc+wyP>U^6XPVs+5A?_F@33hFc%|&rF}5h z%()v+$%n8UxgvfB|Fh!0UI0()c$?4H3(Rrm(-~e63#4^^(o{f?BJi_`abA`7v+;Tv zfm-mvJtM8w5;K+QzQ(ILsw61Cr_4rbMOVZ)1EdvQVfI4{KJhe;QySQW_|=HJ3Qf2~ zca>?*HgC)`XsxAYrMv`jTz9INz3rGvh8le zGH=i=xIz1h^T4CUJHXS#JHZRY7})JRL&goAf*bc`)4y+gmAcy@Me4T#ew$(ao{jpw zhJ(A;L1$6H-g70;8{(%Dd#^DE`r?>QJR9Sjm3HD;drTZbo?OUojL-6XdIgf9)svQN zwP0mv9i@Ryx0_L!Cn1iMcygWDia}a|KF`HC&q?d^oQcVVHtBh^?9wJZZ&ImosQS;+ z_H8wF`lE&Iy$z=2g>7NTRSKJhnP_3VQ_tp`cqS3Kzx-X48Q+a5{KgdYHlA8U%M#i)}nSVGYZV31LDixcQ=-+q1{_{W1KUV zj8mP7Q~kJ@gZkHsIb?V<8Ev<-I>9+6cEKqDt0#fGi%Wwa5tj$&nqmWS`5b{1xqMm# z|NZtngJN!n&dLCLpLK#2eu{CvlnAzB2E?Bwg1zxvOofzm2CvwPqym3qUK)(kbq?)&ahqM> zoH@d6FXF{sk`Sth{(S|LHY7f|P6otCovsJ}^Okfj@ugihFXxi?fhEYGiaVu&?Kc68 zs+cShtlyX*J}VI+7y69};^z_(gJDGmZTu|}Z0;V4${z&r+GM+Pu>H^$i ziREL>hxg!SXRygV(#Ve@LV8$y<+4Yh@fPWEQ=F4f%HAURxD~3FGQF_AZcAv9x_=VP zy8j_+97ZeTRq7gB0I>Z@s5`_O62bN-p&<|(OB@nw3JpgSG7nl0Y4c)DV`#ka)aZEwX*QxtNWnWeK#Oq=C(Eo6*69_NTPf@h1LW?5A-e-l|sGma=i8 zX-I8eQH0@0n^)8ffz~iwEY^8I8W}gK_c8lM%*mbcANf(F;WH;4Z?#y4v02!*&X>?4 zHPxVut*IhWJ(^dLUoLds`L7f+fe|RfO=V)8)6#A#W13SNUml+BWo^3g<;_TH-QfE^ zMq0NDW;wNauzcSnZC)kw>4^BUUC&^dXS3AJ7`0!{^7Y`y#m&KAiaUZUmA7f`0S_hP zm^$K^#)*61VU|~jFLwhLBZsyh{LdRO36VzkTx*M*RMkws52uFFNz6o;s(iqNEyn@}y466kh3e`v&*#5xF7^&_O!S)B< zjSxpk1bbo&Mov8{ksLYQLjh!-?g-ZbGrH>ua=54j_Y=5ZNCexjRU1NlO(NKQhA&HlOA+h#iA1oMvK<593M7(w2~@@OJti_Q z2XaCcdvX}~R*sC5vl1t#uK0rKKP8ha41a z3&ffd!M0kyhS*3V*sR!ylzzP8u7gCd6;mPhkqEYV4u?2OBG`Pl7++rQC?B7kIuB~3 zh(Ci_#9&krhc`f5e4Q;KdFplE~2JHrE$E2Ny)>_*624*_a1-m!FH7X5ker|;d=?!tBM6fN-0*H$w zg1s+yf{mM^DV7Mfm)S0e-$(@8L3G8N#X9FDg3YbBU`IV5CRev52b+HUd44Ix+7iLu z2&do?i0veT&83n^*#__2=q(X!e`Qz$ahyc3{poKb#787GYVe?1mEe2s8xwzb4`8JV5nEDGf85om+6{?t%ux= zXNEMexs-{m--ftMBKXRnpkQimoEfbF+wdmrqNDZ`6T}`8e;Q_{GhvV6XmzB4O>86NI1OT!#A(CL0VE8Zf%dqx zGs8{sFtked#yZQTRl3)-f)<<(?PY0Tuc-{=K-?)Y=U%gl8^1dOmzuP9N0{Bz7CwMZ zQEhuD3m-5e(eDg=46U5Bj~_6p)3B4+vAEQvfo=2C1Y&!MV0-#oLmViv^;q*Zwk}$4 z0#1yydd4>mABToOdP>p|Qy)@r8Kg~;z}}-Ua0%i&5@D%3eL4zrE$r*_rGf3hi+&LQ zlGtyiIlzRgpe5g6j}B~pLvs>HnicC*k(e~gw0a1K`~kF^rF}5VjDZ$B3ayhgu=%DI zHg5fBtkYj&>qpIQCd`30P8!%&!|M=dOMLxNuQ-7V&=yO(@TeIu0~^1#2(M0-1~wnz zN6bL?#j(x~iQO05v+^jkz0w|CY))b0!0*tGOZ$DXsr)dsi%S>;Z;$!n61#1Kr*O#9 z8eqf-&*;6-no0xP+WrJ$2Z^6NWezaIlx49_KWQn;Y~9=fZJac)t(&JH&XV{P5m|;5->jOATjrjfu-cGz&rY)&TDc3K zqTeWud;vTIR|)>SapeITVBFo%79;C3GxBj{L}QFu(vE*=mQ$l)#w*fxer>kS!Np1= zjeKcf6Y7M!=VgeOB!cbW6WVT6xY_On?0upMT!7e2;)Ok?FSGpkTXa9Afo(z>a!i)^ z^|vO5<)Kl>E7G#QGsm%UfQB9WrMW+u3iz-dqyvYWX7>!XpSoztQC%X~e*C9LM<{(lXDPI&*QzG#`0g8raq$T}Qr>IPV;c1~ABr zE+l_TBS)GPG-)1p#+;nm7}q(P6q=lLCgW~)d&W8Ukof}z98Vq+(`03ZcqMqVn64mPkGHQ;1e=*d;oO7_Uq?+ApRr~Y`;K#0OBQy zU_11e{uD);+ReekEA}kJZzY1gamgi5Ltu$l zqQr^KEwATWg%uw$kIzM)jz%-7 zlEB`vbXW!Pc8TPXU^ObJZpZB#ygwYpp=vecvwgua7q-kYSAQ9|+cins? zL|?isjmOB1Ik(2u7s)xo%$c4!6_map*0f(7U%AChzu&1Zjm+(s$5Kp@JR;0I=)Kcg z>A_yzw}3;tbEiadBojQRE@u*9?+{_oGhFF25$ObuKA z8xf)f(0dZekxW|ouaqRh%!GD9N0gqN*z(GW8WY9)qxhCqSJLD}F|w=W)g7IDx#Q0G zFT&i}^zweE{4Mr;O)qcG8+=_(52G8Tk#D)hez9+$d0z$J8s|JqMxM^$I4AcOGkg*5 zyZ50Dg2cbNt?lLeW7HS>smSXM=)8QvUc^Ok2*lkI!Pe7b3B)53mt1Sg;;INVO@Sd# z8@qMW6z@t2=0gif1KW+0EBT#gB_>xg&vE0j*ZG~lq?NtS?De#2ey46*n_<~%rqB|! z!i%8wlm<415r`Sw0db5(uqR>^mfv|yB1T~?!PbE;HT=#e(z?_zA5yDO6COmj+Pze$ zY0gvYRm<;mlh&)2sreMN^U!8UJ73H6f)>21w%=JM4Q!tY10cR8aX@YJ1~)zn?SQni zwaurw(E8T#JJ)5{9rvwc$}WW#1EbPT(qiC&Lal6?-pCCBMof3gzX`IA+h~~=Fz8-urIXVrGdQ% zSb%!i4`W9 ztuLcEG^%@2TGL6U>>6xL1H1R6f$a$S4G;??g3S~B_L;_Y{vNjAVEehBj&?Un1bg05 zLE7C7lnA!=L65+fE?Xkl_E%_Lw^Ab5{s2!mySF5Qtw?*jLlVJOq~Bfqowi6|E7AZj zRU+7mFvN5ENCex;q=DZ&i63U!%A~R1I%!}pVURw1TP1?+)kXup&n1F+VU-CLKwx7) zXTOtTI{W$WvO1mpN|VuBp{rjF@oaD-GM?X=hY^}6rUz|LaUS?S@nP^JG5rW1w_FaM z7Kk6wiX`w$;*?+PQ1R_pj&ul0^|UvCQq-q}3OK4o(AgoVFvXNwk89+5Xq%*g`AEOk z8?#aOJ*bh~ZtP`qi~elh7hApqowOf2 zkG*YqCWUQ(pzJg}s-=~kX0MlYXrrZp?e)?g;(Uo<`|H74h;K*)+e84orm!c4#E3G}g)p3F3SD)Y(!n-0U{ ziv>z&qq$e2(%I%c6f7_qTA6;fV3V`G{zhOmw7$|-ds^92PhpvN)nB-Kz8A-}w-fL`!JZgs z2(g32hI5%?m7XEp+~TGc^apMDN6MuxZ=n<^i{Q&S$mW=`$a~}mQlWK~mb%F6 zCkJRVI$c`!B2#KB_DuWH9BE+Fq8F-U_EMOHN}RpajAz2t%lytcX<&P+(7?3xV7upy z%gonE7@%<}L$IsjRl4Sw#P$1))^AP z_VT7V>vIyp_UTQR*6$^PZA#j<79MH~2DT!7TyK^Lwjxbj2TKIoBGJ`#mPD{EQdNkX zB!cbc^m+YOBG`&FevKby_YSsVLx}Yyf~`oq*uE0MR-}LIV-mrh7|4M5uEdO7bLbtM z{x_fY5o{lh*$|WNwFS$5*LFB}Lrask8}453;s7qZ?{@}C z1KZzG2JD2du|%->6H$nP8Xx$b%@S*TVEVp_t?A*rUmDn6BAp=?8ew-0Hvf7L{X@F- zrbz_buM%kEJ6s~z{LGX&5TBF?w%yCDPyEgXiC}Z<`$*~k6jsd=!CoL?fL6l4Nu2bl z*}4E9;A-AypAd8r`x{Wx6Qe zAkGJO6w~(jUdurz9SgIxV!{y{o%Jl1Bdv4HsDFPn{ec4sLucy+HfCph{kn4?L^k^6 zKWubqx8J#EwA~17{@fXVok<@OU!?AXP$OG@59Y%lx-)k83%}FMh9#c* z!hVGFe~CVzG_ZHhn^%RnNg_FN$v3hOd9P`Ta2>4dgER$7-{(tnaT6}4hF|%eqGN0c zz+NC^^8$$NB$6W;=lQSPOA%(qtM}sbyV9@TYbv~sXYF^mpd^LA^IHp-J^TF5cM`## z2UT#x_kQPuM6mrlcNC)U0b4AvZLF4xs5)dNR{g#gu~yZ0Zh$W9Zn1m!N=vSdH0-0@ z&?(Nz6gL4sF7DLH-V|?RIdYZO8~5*5=^pH33v}KTVB6rFh4{5Zux-{aLOdZ6Y@2oe zNiC0fBKy@N)I*zyQ6UpoyE5k62Yd#6qI1e zIea@e(UxGzIj>_A2%N{)ywU>aZJ#d%+HKNOq@_X|DlPTAnZxfKmO`5;ZRvSaZ6UtJ zYyOwtd085nCFTWv08^y&5oYOAE+EY$Tc(r?-Z>3b``hodmqw1{@dO}}2YETt@Kmkt zj33;^Ip7;6Tm2pIH1RI*Uhz-hMp-t^1#q_5g~#ffS-uiprU5J*(25eb+3UOblq=Ul z7WkiC^4BinYm}+>V8A9J6{q45#Ih2>RxEW1miH3D_KWXU5bu--zS7AIyo@y=t$F#9 z{dT9g6Xz_J2DU9*d5AAc1XDyvH=c>oszGCvbnp#`M;{ z$(wKL55dsbMo1R9EuIDcvnrNg^Bcpu)?!c)4vpOnv6Dow6${1UM^cGkFODeK+m9g# z62aD>Z3Dy{iD1(Yu>t{TA4al-=6SI1gIFLDY{wfnkHb)jX|_aQFD^2;G9E91kqGvB zfWbc?c9ID8ez3eTB>`U(OC(3?<~jhGw^;S|fH#O~4ZlrHOZeSlI>G-crUQIo95r`L=l5&H)lx&~ zIctGd?;XUncpogLwR>1RC*5)Q-fLzQ(;8;Y;-=sa#N)vS#czZE7Jm$8=aAcuZG$)n zGOkUBPUaXZ=&hhbIY!KROlR`v#Bd>ZJ`&T2{C6?^$Lsl(X=l6~PfQc=9%7n*XNzh2 zy+KT~@6g*?pv(7OG2Ok1q~(x9EA9qbK`-v%VtQ~d6VrQpvzVUSe~9U|-6_Fl+O5CitQ6B*dymIq zho0I;rPJq{uU}@NX>Z-r#rfv~y{MOK1wE+ui|IFABGIOy|8pHNeV;pt>GwQPOrPh8 zV){ET5YyNBbus;%zY!k}EyT-46Vqh*OEJxrOBA-- z(p0&XcrZ95ripT%nC8j8B3Q?xr@?VeERbnz+*3?L<0r*5GX7dTrND8n!ABLQr*Uy_ zF%65K^f>I$sQ7s?{fW1WX+`{n(jzQB_xrP$ z2EXMoih>2Aac^@m4SRcw`2wv6#e9+0LXUC&Y0SG#E9l32L`)mrqDeMWy6@Hz({;DK zm}a|!#Prw=iD|9-l$egX&x>iK`=*%wxgSL~pl|MXT0y(qU&VCEO~Cjx9vRJXYl-QJ zd#jlCw*x&6d+xR&G3{*^i{WJJY!=hZ_G@v7Cbnm^K=0aO#ksSvLz~*_9(%U2PP({o zAz0&yJAem@9|KQ}qz7k5(ig@%$iy^heOF9x)?>xh{?nATL9rd?`|m^P^g z#k5CFENOQ@E7V3}TA^l&>3aIGnC_o$4{%@iTGZ zi0R$ARZPpypT)H5{98?WoI=P=75ht8YRwSp#_i^Me9 z+$g5E=7(Z>Vg4rO7qEdccE|L-tR<%B1_E{8MXhkwERsgXl0pH z)@Dju$`mneDeH>qM%i3U6UvTadQT1%(`|B^m@bpc#Wa`PDDEA?XVQIIpqu1xVwy-M zl(U84=fcWjnnt!1(=4*Lm>!W?VtPZqET$*qFJgK@7AvXZoL+FlgBv!v{am{6?9Tu zC#Heo>tdKCIvpTwAocE|KbEG?!lVyc)XgPp`Q7aSp`so>0z7U(9pUQ8Fk z55zPN{7p>Lz#=JjXEY1!D5go^1ToD4H;QQrcu`CPz019TGq`M=lmLiPq!B6 zQ1_LX#&k*7*^FpNS6@sYy1rui&rK22c5a@SZgV+en#>&((_F4(HJc|rBFOcqYcUPd28n5mHbYE9wAEr7q3sZ_svhGMh&O$>wPV4axGv^dUPcrvF%SZJVCHV=ct=8yhU9&)5@U+KW9ermNUTV!Da_ zD()M?Lfj2DQ<{g}Af{(ndoiuThKp$tHeFop));4rn1*04i)jS5Q%nP}{o*;`GvcM- za&^@H)99-$76P~!>F+g8Okb~cV%mAVDW;3pClMX)U1!B~?W$bY=0mrxE@HZLO%&6e zYpoczTp{OMEzpC@U(aq#53W=(y|+4u>A5vfOs}oU9*5zp72`ZEosLy6h-p;ylb8lo z*VecB)0nD<$2k9Vq?)4@G@{xkrU6ymRJ#FWArG>3`{HL!{33U!B=ZcxvN=>l~~O!ud1H`(-bed;5o+tV5`U7o%d)7`0b zLz|wiO|8UqYZ@pH(WYsY7HH4(d1M3FG9}$?H>Mp^3o&h&?iSO1$%yH?^uCyGOW%s= zvh=H%?n-})X>(L1P3=GJjXI^-ozd24n3#4(4~uDI^t71vMem5|T69TFx1w^5Y(8`; zYAU8XQExGwh$e`;-^O?tC=hKUD(~|C7g5_Z|n-TqQ zZV=Po-F&s<3r`)(a_RvOcRz~Vw$fk5!3zT zRWV&p_KInCa!yQ>lay9AADWxA5!2LUgqUU~{}R)~WEI%!|I@qVEv=wU$pJC#NJ`ye zGo=ejD>2PShKXr9GQ;Dr_tNN9(&-TLzL?G+zliAw5^QbrgcC@}X`uz!emM7w>HM)k zOv8^{F^xWc5Yyiyrj5;rwjNc*bn|E;rin*aF}*v6iD}sp_Be!Zv*E;Hw1Tc2Z-{B1 z@v)e$8Q+O%mT^o>kBm!VT4NMzYYRk2j0O>I0FMSSEiL+q>0~iJqy;)yJT9hj#cDAP zE8Y~-sNxGT4JuBE=}Qs3)$W*f6m`UOq3A58`NaL=;>}{6$HXCeO+2FoT1@1L=`8Vu zn1&KZ#q^Q*TTJ_iqzt=b+D23t(=DRCm?jaU#WaU_SWHuh#Tjb<=?1Y)E9e5TS4{VZ zV`92K1l!r2(e0s*m@W^k#dLS*C8n#xI5FKEvc+_9cwX$kGlVE_Ezq{%M={+RPKs&L z;A?MpOml{0F+CZoi|NA9SWNSUeqx#~OcT>=VX>Gd3tPx+|7ou9l~&MG;ZHHW6v}k4 zJEn(1s+iUZw~6VPFj7pTgh$2nM_41KFTy8c+9BkNX@d|ttp(a2_&eI2(e|LEn05!( zi)nMvLQHpqUShf$JSe7{!8|ct44xO$yGjQeDypr!>XSaGn_h4%+Tqd#Eh6O(Utk&{4-R#nYVynJrN>3T+GnuSz<;+ zuM;y6`h79upAU%{_Z-*F7LMW0&BP3I9x7&d^E{8k4#S#X3Tc7i%-@I^#r&t3(aYC% zXQp9?QOj+_j8?u^%qZpgVn!$Di5Zn#AZ9Rf;X7GVTIP}Y{Xe5Bzg8kf zMIIM37&5-6-5FybyNVh6_>`D2kMD>X>Ud2ro1P(#9U@%K?~D^Oq;Zazk&K~dwZI6* zU&M@DtbDi4h!KmU#Eev2DQ1M?>taSG?iMp3@uHZ4h%I~Dd>DW@Ow7Q;HI_pTBMuL0 z1tSeh^|2c;!f>FNk%g(NM``so8p)UG0IxZaJAC?Z9WWB zYa(tR!a^S{Ff8ppF{9BQ5i<&Hg_zN2uZbCS_K6trWln*37x*tRBg={puscQ+nNwZN zK(gjwul;8L+1*;fz_E#928_)TGf-@?nDJrj#S9DEE@n8`4`N1v{VitnSDk^j5RCfj zC`N!+$Qhvp26;UtW^C6-Vuo~`6*H2{9mI^n4ggT)LVnki<~(2HUQ3wxP0a_$x zX@Q|WwT9YE8RFAV%*dWCVn*>)8D`TkLT84U(Kj2!47k}Po(wKI+@@!M zO;<64V}=b^`_HJDuvRb{#)ugNvr)|0m)+t);6KEOaB)iCYj?mPmozbhTQbEAYMCi! zFv}a_-3w8re`$fyDRoEKj2M*CPs~`9N5zam*(ql1$yqUDPO9B!w`HtJ7coOjMu{0( zGDo}-{3eGs2VWr33z`eNg`FLY|aEx}&<&jItpwSoiX*NQnNey5mY-%p7#(A`OU&}PK3?w!ON zzDEd*7^B&pQDP2g4~sdDeXbZo)i19IE zjt-xtG#I(jL$xn@jPuVi+NCGjopES(A2EkvPZo0+^#U=6Pro4M zsOjBej+U-4$>zh6(HUZnfL$DIXJaKyu40yDi82-YMoV-}}TI-Mc^>;;7y&THrX|uf-g{dsNI}yD?L2rWm5@ zR2OrUZYwbdb1dywVh*7_Jw@$5ht3wAYIm?3TwTnOvbT#lKz5v% z<6^VL91i=Ym?K}mCC4Btpa?w4#NQOfn{9ckLq7?gBX$GuBs;2wxTH8IJ!}(Yfgck; z1^!5!11>ksrkPSY&beFs1o#WBI(-irHm-c+G|}Bmx6Og@KKv5-8}}1>F)88 z`1cSN5+AdPXz$TqOnZ+v#I*N_pKa67-lL6}_8yDGwD?hW23rcLBm zV%kI=71JiN(n4DZ+C<*CknKOJkv@@aBP;HVbM6q+CUQtbzYBJdV%kJ<xOUi1+pk#W`tOU_fSjF#|G(f-A%!Frg2gY}AW7PWl0~ z;o_y>Y>&fE9{3sQ&OyHG$EN42);|#QRqOdm&sVMgNe&eaJABuAU=cUKQ>Gx!N%0sv z12+>d1@{v3?O>zCd^^|-kFo7fagGtEfY*xC!LKTPCiqh^-%bL1auHj01p(?oBl!Z1@L2HnhHKErm5gN9)}&83huKUa_B1fyAshqEN+S2 zaT>U!n7$;H#q=e)Nlagoc4GRH^bpgRWSE$?BvU*NJG3QvT$}=4wuJ3J&MSj%U)Kf< zy8TLt7<79^%%Iy6PubJNnA`f|3EkCVj7#qFSR?Mvtdc`QgAgf{R5kdSA)BG9Cp@$N05^+_8&Y^>^~ak%ms(I zA_WU;B8kQ%IB$sa!5@iJ@Dk=9#8ts(#5KV2%j^zngUgHSfo~8u0JjjQf$tJGotF@D zhG`)kE2fBBgXfAfz>CBk!7IdFz#GNg!5@h40{<-T4US!I3&*!eUlU=xMY@*9IRAW& zbaSoXYoyzY@fK<4PH{S3uon{JmB!8*aVGc+aTx5ZP*vl_d#Pf+gm0jjFX3A(#yj|& zPeWSZ8=+!X+Ku@}sD@&`5o)-YZ-iPZ<{P0t5vPEir|q^?!8eQ3!5zh!;DO>Wc!D@Y z6Wm9+Pz)Ccc)l1WxXv0dT4(R?3vjR`n(CYc=d?HnTx1n=T>0H`aV3kpfXjtXt++3Wr$+JIC|(i8FGca2QT$;Pe;dUIqd4??)PlRlD|I|eSKebEo`3i# zWpzKfTNF?67~dx1@8KwZJc<`Y@lzh-&EWWZ%VS^2+u28U!OJK=ihs8oczWVm?_7H6 zi+k*NdW|T(K@_*OY2vxFo>6-LD86Sc&Oa_XFVV=T72~3KW)#nf;ssH>G>TV6@%kvv ziQ>%>#{Qjckp=M1DE=&pzl!30QG76p&qQ&|v)+Nl^5_dkaoH%Y4#xM77-xmQdQmHy zM{)ZozB7u4Me+D3ekh9PMDe01UU7v(&a+n*oSZ1$9L4WP@mEn?5XC2>*thP=(Fdcr zd=yvrIAo7LHEKnA6nBo|eo=g16i;l) zAG!TzM6H+;#S5c&c@(dW;*C+98^znAcxM!UewlIn-(Frov}zO|^VspKntlDn$xaam zJ!8((HP6$W9ZTx$<1fLSU3$*hZRecbbk5o3=A6B1&L@Nf>^4(iH<@$xiaBR5m~-}S zIcLw7bM|UEXJ?gjc1}5GXO#09n6JQmf#$0<-=z5t%|l-b3N$~XxgXDGW{|9TRm~e{ zzLTGLu>NDscWM5m=6f{Xr+L2SNvH{Kmu%;uBBdpi*E~h@s+!l(ytd}`G;a`Dk1Az` zwKcD&c>~SUG;gZ;)MT`Jn8KK*C7VE@gt8{ZO-S=CGWQosC{c1H^rtbc!n7LGT1?NH zWp2VVq0fQ4F@1sQOH5y3`Wn+WnD$`$7Smo#-(lK^>3dB3G5vrkAJdPR4q!TnsQ}YY zm=0n38Pj1*zhF9o=~qlgF&)En9Mf-@P9!^hos)o5m`-ClgXwone_;9((^*XCFrCNr z7p4oC{>F3>(<>}zQgxne> z5{?u$fmefj%(Agb)y-4mlE#{zuLVn*mE)6|nI#nyf@UNaC;kB1|61@flb;)W*lf%V zrkW=<2a`?DN(seGdVWIL+-EiirzYlhs+~}!yh+bZT5Ia&2UASN%}J9@db@;1W^_hE z&D`7agLo%Nvx4A*=Ce)-H<~5ayW?|@cTPwPm>*6Dr*Se zZuR?_ytBdT=DT)o#iI4bjULp0?BMRh2Hx9dh`DesSl4WA=U!_nw09?)AI=49o5k(j z3g&z}w`y*!^TB5md|h%s_a!}8*c{4ougOg=mGnzu(SH4Ub?$KUps}}%8TH^GQz4jC zDkZX%cF*9kE${8eJ>)PD-~{~_G+&lI;PMbFC>*I?Ml zVW`X@T^bD<+qwVvPJ3`n?SEVQ2Ol$X`jb#wU`u9hz!eEpjSjWxw4BwTYX zpyQ~4{YSJKHE!gf{$nOyounm_#4_!))T9cDc1K*i{Q=kNNyU;{`n}xt29nD4YA|SQ zm;Pgi-ZE;;m|=rPjk!{cf38rKrrtPcY^T9EOOY+wj2zTy)cC=Jx(pvStV@UC_Ohyv zt$HgwdOu>;4A{r4>|Elp_SZCN`NW&igr|H}^R zFHb0;L+1WJEuK`W{67xkN@X#{2DezbxXxZ-UrJ4?6t(TWNlERsX6|@5-J~QGi}QO4 zTTV^5y$4P!Yt6g4u2k7oYUCpAP(NC(-w=0p*TMIX8~ngnRKnPC540I>PZCm@^gvSi zP#4`vS8aFIopIHg){z}utwwH%t5n?u!~S^}L?oz>B8Km{Ajk z-8XFP#9MK>Tsd-HVLy&fDD7Q&pOi?d?!n%qq;kAmuiEI!8Q@0Svl2?hb?`37$wiZ{ zvlnLl<0fu9X7J#v)^z!|;$6A;p9mByojY|_!lGhk z;&OCRo~fUdoOt<0GeyU_<*wYzUL*H(uvn$U%gvQ}eVki9a#z)j<)wq`CDj95DQ!)? z21&)dC0s1Gdw@&0hX=S`I$T+gd!oB1AAQiR;Q=n%%BBC?U1jEsb4%koWL4oHN}Agy zxP?vA_Y+(*>g|LQxi2hFc*N(s$)wzrR6e)M$^_TvyU{$}D5+cShNlzWYJBx`_{ab4 zM{sHL;)JBSxzFb(3~lybpTGuB;IX-NUQf#MnVi=X;&L}sa$~#s&c(y~Y$-ms3!B4xvEl#y!#fub z@1k-48_(^+QO|92qP;uXywE10s7X1G{r$J+x54u}$qeg&MxfsHaf#P@PwTqvMh+Y? zZqVSmtp|_Av+r_SV3NK`K%0kjDgP~9q}{xdw9J1>YC8p&v#a!<(p+`@d-=WA(QTaQ z>tfK?=#l%x9qwy|eK+Q|?e7jLWKzCOO2}O|!QEZdJXf)pJ($uq*KRn3fstdeJAUc? zgvsUX!FfU*`^@_PyDQPXv8x*8$kYFF`*vA~G|&;@aTOYyDN7^_8w{O|EIbu z=IQ!LrT*8gYl+LP>y<8~Nr^4i(Yt*r{D&(us@G%gALdS}V6V?8dCWvzr(T2kKh;~R z!rZRf%S~ejKQMT#?S=NTtuwk?*PGh0y0I$$hvG+fvkdRA(3Qp`(kMiV|BqhFSOQe|J}XQGQ41~>g3H$UB58f-B_sdQYS8chT{}pYBp!PjSF3$f>+w-IdNrD%mpsj z%Xgf1pEz+T`6hiXmM7)lU4%uPxZyb_Wr17PET8M96q>#Tze%2Q;>K*5Tfel)pX*jG zG#BYcc68#V<>VHb=l;tV*VKtSRm0n6e&gf{MV$D=LHH&MdpbABoOseLJAbOD7ODYt zs1tYIOWVYkZF(orIz}roke&Ue$#^mT2C2-PqYrZttHq?#aWuu{I79%8akL z@mdzxUDlghf5rT)GJ)Ki7Q6Q(nv8XB^|^gU29k*$g8?(063MX#L%$T)V zZtU7A;eivH&359a&E6NDGAnj%R*_gOAKGlXtarfjnodcW*3~-6+%XWgl_e><@7uF>_~{o$KAYz5;W0y<4k(b~Y?cF!?dLox@H_ z(@ZBmZD66p5e^S5RN!$s^j65U`*Us;RNw^6T4smaIq7MwE}cPWZMv5#A4R>jP(iIn zOZ=PlxE*}^OzjukD$Vknr8w^VB2MeM?Q#y2r`%gS83*EK|B~}%c1+I4-*zbsXkhFlB7V5t^ip z?lr!{rp89MA`UELqx)tVuM$!Cj@K4)xIb2$->bCpFM6q(+F9=xy%Q3C5jB}@wqPl) zz&ld~FS=c;P1?kLjc~$F|LZSZ+Fse7gKXcWqiG3IHQGDJH8&L0`d8EmxD}@jNiLs& zA1__NrR4Agc%?{r$$i3?otyKLdz;T!u<#YPX3V5bruHjt#l*weafJ%Dx5IIDf5rU^ ziMniZ??xiC;Z?VJkx>1!P>C@y`m# zwH1)-R=*(|8M)zKa(405|^PNzV1Fk{lx2TYU4?pj}{(U3()-0u9JuwAq3v;FW6SUsH-z)^7OE`Yq`c+! zsCnX8c1y>Fg#43T3wlJ8@jj8dq+@w2+gYR~~tbE9)8EP^|LywT-PgGAN}{OQ8%n3Z|jt|-H{DX)z9!Be>|%g=JI*%;pLWM#!WyRzQ9I65o7URs9#)Zb>u+qmjaeQr*??S7ql?E17yzVNjE zjz0`L$2X>3%JEw8(bG~g{6}`NWoPx)#?xh6|4T<3RW6jBd-fgo9^Mz3@4Aiact;k8 z`=K}Pbf0&-PWNtKHoS+k5{hk{a%=HqHlK3`i68AaYxR6-yP{)@)vgENr-Gda4Qs_l(&7>q#WEx@oD+a=tkG0 zQ62q(ca<*sz#Uk>pw`2@{CsSU;>y44B;V0KFTnNz=Qf@@=J7SUx6t9i?VU?r-PZol z9f-`cKXk9b`BQ6xnorNlXrJ6Hb7wfaNTGtm3f`x36qp%u&>!li@%3ZW^wDtf}QDww&(oh_j6-EGGu~vCuoGCt&`&G$$)m zZi2MWLkIuDx&!U9CX}0)KHW){e!a=~)U90e;5aTf{?SPfRd{DY;n;yxR< zboMlcePQFu^^TeapSpj<9J<5I{>)t%lYh)q-Q~Vk^M{ASlWpxbspRCn^Y)}I>??)?^o1TiI3X<$0a#PZQ7fv7YY=+q zAeQ&r<*iOt^b6vehB4*gU{*SP(grp-oHnE0*|hiSBk%9;uod&&3${YOTNC#AJBIt9 zf=f8XC$gqnuHs4keo9&;f2K+I7fv>_zi`WjaxT!{NCzV{%Spl}#9js$GP= zx#1bRQaW6`6q_}fr9054$ulT1pWFWYlQ2v#%VLS zvmcjbWqPM6$(HW>?=$eTXK2uO6GCf#oseB2=WM9DcRqjoJ={Cz%rtC_>hZw|&ey$F zQseH4NsU7Xde+GbHU9164zMH+3>)eGmB8z3}@?osJ8WH^Ox>`n7wUG z`LEoyG2gymc6{Zw9a4V~3R)k9=e3fCyiutAFY!R}B=zAwbF&BJoSi?=@ly+zcMxEk zb7AhVoHN-Nl7qr_Nt@!`RW7fA`KxlyVEg;Ez0)WK*E6;^qrY~mv22UJ#(XI(o-+g5QPl4?mCeASR_8`>)lf4H|hfQYZ9&{*on6q5^($xFbdpLLb z)_ur##^mgElTDYsuHPK})@>5!Py4x0a&GOtZYeZA1*Y|P?)$#QrpP|`)?&BoerugI zg(rK@GE?t+x4a4Ob4wN9UQ{b9USxZOJ>&(Zs(X?pPQ6?w^Ynmi%eR+J1J%o8ulOgj6Q01QQtMp z9L{Ig=W4ysXD?jJceAmNj^;$ZTQm3TAKe^Z%p2F5nFn#neSW*iIq3EXG+dB2?!430D+*PG} z_p~kDMV9Wv`fSf^>0bW8D_xzN)`bpvC64WI>C9lZrx{M{?2xw0@P80>L@(orQ0h`D zwT`?=KDP0H@M>oRL7Zr(ea0;@H{=&#*99V z)o;9HHk@`F2GUTw4GZk~-|~_&Xlep``ns>iT|i|-7;nRNej8`hk(nd|zuUz*qg^qjKAA+0%4W@c$Z;;l$pkdXM0uag<-CJyv{Yd&@p%a*!1hj(mv8_w4>=WzEmDGf9H z&;MjDxQXQ&J}ZuY<@A;@+5fKbn-vi5p|)C7E576I%sZc2AqpXo21RVQQfbiiL%Rg@rIMgHemSx{LYaXkmgui={0V?qFdK zpe>fRQ0nSNg=L!-6t!B~!p!@5?!CZ7``!2b=lx^m-gC}#p7ZN@p7WgNJm*}|IWy+E z$@Na6kqgXIB^Rh-(+11xF`KZoDS<{ZY3vE8!=PefN25pCkpU^TDVe25ios#AA?S(< zTP2rkOXO2!*tNqiEL#JaquB(`i4?~_5St2^bSx!uDLpO3J6_hwGIVt(VrFl$^YvQ0H|quN7?KzRyi1}SS`+A`=$eUzCK@);zBEG^<}CRcqg z@|4P5Rs=l_`O=obX7)_b1r!yo4#7_353yD9spyIv%V!fVP#5W|;|{@!V4=Ll_QT`F z7+%;GWWRd5_#Q9(VJfSgAigWa``B|Pig7%D%YNt%(a!UWS>|N%12Av&6!C81i3FB4 zMVux)A+qu*;$8fCd+QYOc|M?I3kE3*wQ*U@Kl)odHRyzrUH0r~@g)t!f%kO4u4D1j zk#*e+mNOj~5u71T5wc=f_6$U4VG5cdju)&k_LdnUZf>@8vFrDM4J`Xure6G;bqj`e zFt_b7YBDzU1%$LDYn7B_)FKm7a9G3~QRnpZk#-N{DE07*eVdSOv zQGI!B8CI?e5uSaS0f6wD8v_7b4Z>f!rBnF4Tlyh{Pr0R2_^4ZYEyC4q=@j18pMFmU zSBHq_+yE%Nu@9g~^DJ7oX04IqbE)-ecquc-qE}}|v(i{`_1!ZwO|B}+(*eQ`#CUOO zYrLUqt*%rV#mAjdZ07+}J+qYQ;>3uEO~(=Tw?2Q9GwkC+`k4-tY5f|?K=sT9mI*jv zRtPJN6K7kmxm9(iQIm10ud3*~GK5dNrBnErTl!Xn54xpOcyC{N;g)~Z=zv9=smUF?w26G z!iWAK_YtOl^id$SKct=06s>s)ZJ%Xftuw_j{4v%!Qw$Sk)iR%1Vnou$wgKH~mAv4< zjQ}+5$TCaKdIi-Y*5OEhGJ0&>r^-}J$*aICv&4YA4S|4}F2l(3bmKZVyu4a18oEfT zmV(!i!WvKq-;Ln|GI}NIH%knjX@DTvkM7VI25{znH6XKA7AlK-jlLfr2_T0br>{1^ z+GY?V!d50&ECXr{m1%wW6Vgzi))=m`62SQ8t{`n=O@YgWh5Qv(X8cUGEu3?4ZQ0WXorZ@4-%I*UiBc$S<|0&L#2p$W(jaz2a&iSg{p1C+FA4RdV&s zALKX0RC1ZkLP4~BXR_GD3lFbg%T17kYqzs9llZi-x{P_JV46${)R!b?D$`_UGFy%~ zQY6b$#1DNFTL;qCOkjBn#F>;mlz87HZXnUTy+1KE zRXo7^7R)KU!*2?8us*3^`tBuSzVGZS`jVtcN+nhWvC<{tJ>Gk=AOn;yFq*uZ8*lPuI z?6voaFM1*nLxI#4;uwKXX4wxy55uhYAexfYZTCwTO*~)7(pQRacoocvnO`uS`K=Nk z!VHkJO3d$z>Ru%-B31Dr@$L}?a}v<3G_Gl8;cER9%3&{k2s&QS*&UZT8-97#+dd## z)8XA>)WjcUkr`s#xJ_y_SSNnHp5yqU=C|_7#>!e;siM5bFJ&be;xg#2?HS?|{5E^a zYVm{s_0?ys*d*vh*18tcAA%2~hU;1O!{QG9((XsZdnXgU^{I8)kS{BZoR9-kXEx}I zM;fVsT;ZArL3?*6+H)TfXA3dC=xK!Sx`Fg4b&{g+R|KzyA$IOMuh8neb&6=Z>lEu= zCl>k6J~J?$^TsjDqhj2QE=&FZ+mYzAecrd4m>p?yx7fHqEHHgBVL; zyfvSo@^@^YaGV1IO9^Kn94|BG?2jpZvC^1?uUPhzn91)5WqY1PSGO_mr$89%S=m#f zKeIh04g;;=Jwli`j@3OSK1@WFTrh{}a>XeDhV8a@u+N0{6-E9bPicpt(4LtKCiI=% zFwift>sdvHG@6;77Vi{ppTI0nqb;+`Sozav+BMewv^biIent!nNVsIHmxJv%Em6Q9#2^Q{-*z+agi4$6Lkwg%u&;a;Je(Fv5F`nvmfL_fZoxi4dY7QakWI zhNz`)qQb;A<}0N`r)(k$0}REr!O+ejp6!299JPD1I68>zAc17rfwjaB5Zja`@sw~D zjbuLCZrm*X3#(vxg=lfb<-q{Q>4DMlMM0W_iq z@5Ck3qRz{c4D2A2nAX6-u4PN2R}nAZWE?OH^t%Ii1cjrJrM6X>U#*@bJcep-t*M=NW5Fr z_bA|@ohZUH3GuYKL+{a!kwQU<8qg!56p`^v*QlMtx_>V|DLwQYI?db2{SeNw{{ZP8 zd4^T}L7XT(6olnI;;}b#@ekqyLcvxxeXDr4RcQf`pyvNS)OJv1)r!YcFQH81_R+Ut zyY)8C2fq~jQmGrEEll0LOc85RCk`z zd(2nM;6}BMS6K&e`WBE` zp4xF;u8((_+TOVyEV>Ns)m5_8GVzZKpFUQczCU?-D84PT;6P0i=z@FO9 za96F-Bdm+$tx@v^>GA{lJ;IJE`NOu6O%=Nz?cU;DW^U)8-23F*!d>GAP?JZk7J;u=17`^jGk1^NOcWj-F`BZ(^7>9U_X+x&T ztZs)m-Wsx$B&Fe9tQ>$?zh*Ax~ znBa?(AT`1h8g^XvYQe7+zcXcgf@3eAaAtc(!pZH42`xqs-KL^vU&%8H(`bXn6NpS| z0ULn46UaMD1$?M?HEn+x@3Ep`b*Z^(t2wPt;?CA)ZnCEEtXeT8ff_sT8fy=>bv zyz;gudRYK}3i;ORZR0Tnp|@lnHEY*6A}o}4S`B9+Y(v<348RZTi@kCYIIcGf8a$UG z&JRzjfDX@%HdwC`bhD%5J2=mo=GoB+2J%tiqw&*IAg0ttm$40W*#f&`9dRCfnSx=+)?JVb(A$l6j(?{ zbygtk=qQWB7{*fO3j8{7z_OUzieDLi=kP1VZx4RuFW~EJkOYTLSMt%lhq`bl(uDXJ1^p^X*=+# zE+DMKvmU<&{2ch5+)<3{o{G6MDD)zJ?M5!>Tq*CB$~tz7_r)y7rsbH#mpwf2%*E0( znwSh7;YAjC+iFdq?RT0Gqi|<0wQ)xxP$zN?D8|9EnP`RX*~!E)MNIa!+zt~*6E z(>bPlV%M?OiCz0{PHbF_MXPx)ROWmKv+Nba9xll4)CoTtJ%SE9cy1@bgLE<*S6jBK z@w>KHa_JP`lw>JElengEF5L)EtUGP|Nc57Q!Vt@_c;K@T=WlqKH>+{b-1#(g@RHpx zimQC{>+yldiRgl>6veV%gxWD`LE4%j@5btYZw)S_dUBW(>3i;kZ(arOb^n1%ue2h^ z#ni-?xe^->+v;Vm3X~d!pAO@`rxCrY7`bw`deWTY&d262k zA%@VRDUfmg6M(`26se7gUgeG9UKLQ)`9|KWsylr(UN_};J!Xh)0||pSE`sdOp$WD=T-Gb|{*zZUZ%1AqLb5lYG9^H| z6Ub%6gtU`00A4pM}A*kKhagb zoHLYjJ}%pG+KUV!T#X0do)tpwSzkU5*i@J8i7D~JkT4~LS(mSZAr|v0W|eF<`&bW7G`2IT7PGDikFC z1)jU~W{se?X&^cMZ|TiLFCz{Un05o6oAl<<5W@k(@!m^#TN1fEQtceY+)m)GLK^H# zqX}P^(dscu)yqmz7=TviH}t>-3yD8a<{n)c^fkmMQM@0;Ujo0Cf{3?*h|79(TxySD zd1{Z@oC?H4QHek6i#=Nbw>UQ3GZo=iY1N2uVr-&UCc+1b=IoHek2l#k>*EzR4kO}+ zpZ5!ioF1~;2O}Um^)znIuZs!ys+rXR=DzGzAH#dqZV%_?v{)^Uq6vSMI;_Y&nqg-9)s2)-@4L4EYfS}XGUiGIdy=wKmSG_*btG0#rssX+llxNiw zAY@@Y$iqMxsI@>kr>}rsn>nywo)>$SgS;w0X6VLIjs1v0D};0qY#Cs80(Otl!*5q9 zK71kfDD|>nsUk;{E@tJXK@@pARu+)Z_WUk;&)W_mzrnQw3JPe3P0b}|&hUV9kEO3MZ4|?l6+bgk{9UELbRXmve`tkS^o>vq+?Am^D zxOE^iF~xTkug5yPk$IPzxxy{;D9Zf0lDT621ksv6|lBd?5-5U_z`Sur5I^#nYTC>q(_*p!`HN&C65Z8==`^<pO@hxtmmW%Pfln9ApNG^t1?;`W~})Sqt`G zdrCM=kR!p7#7QG&;1^!>%IkSWC*R5=>#^0V8H+V<&&1zj7c3phge=O6JzI;${XrIS zHi3(@h>8z2{H4QDxkwlkT8Ml4V2u2&rL3nCVxrK&jbHjDtYix7Kwfyx!#=n-t^m1^RR!fi(ghV&!I0n&}?@pMcX4WfC0D=)qW z3zrUM%1A(C^cnH-jlY8@DO5KUZm_+kG1`(zh;iN7N#M0a?z&Cn{Sm&JJ(@!V&vl-z zImf;fD#C$)#Ota(Qh+VGdACJHm&VrAoXl)L?QAyQX$jiH-NV zsCHC{Ez#>7Yp4?AtXMU0wemn=M}jmjXkBxRnx_jvQXxcAM*jK?nY7SER1K>N?Jkqc z^B79fVGMt;r7PqKlJs*YN%ZHffw2*yFnh`bk)T5t{KeS=dT6n&p07zM7B#8*-#I5@ zz<$91$?GJDCGR-&CsmC4JPuS9mx#gtTDbn~7nZkFNivJPr#-k)EBQHz#(z1O;+a>qN}XS6J$w z73I2+j!3ux@-^5R~PSm+2u-nS(v2fXL8G$ z{9NpJ4c?!DJ5+I<@tK%w1hT2*?Vq_2#RC#2R$tP1(_a^*2i8I%Ig z-BJr2N|iyOUgTOpgojn(8AauP@;LEQYzGJq#K{5=!jfOl(hiCl|KA7FM{dyn97t>5 zK#FVs`#_2dAV8>&o-~*cBJ~3UIy4jm>X>Y!iNPc5{}|A845)cvKn2;#+DF@Q?C@)1 zkab9(B>NwutLdf+#Hb@oBNTJ*ywc*^=apKLlKd+lPB1bt%Q zyU<^Y0Z;1T|H+*&ytfc{8a<@TGA_oyDvlGRQ|#jF*jR3$a*14tO!b@LNNh=%)-&57`sT+Tyxvia0tZVf?)9-eGaQOv5K2jGD2M z?H5K@qq^Q5ypr`^K&|ZzBVly)zYC*?J{tC%L9o9SMxLR}_J%ln1xEh|naqij2FTd^ zFvz%8ofdMJeyE#S*g9MXWnm`zCbN&M^)}v@=5Wm0XD}CM>i^dJPkjg1VsbhYS;$}D z2J^^alZ(4WvPm%pJ+jNXKak{82lSY!hCgySD5p*>Cv#9aX+%g6!HNgzJNu8Bb;kTK{bHA2-tI&<$82WU0@ckUHio89KPI1Wn98mzhTmuD=>qf=f zt*ALL(IQtMAt~TlOn?bG&NB{z40?GTg_|ejcQz*}8yYS%SJr&MQu~CWF?L{;Q4fK4 z#pTEf#2nwz!(Eiuj-6add*jC)gwHh_9ap;{h)H{&W zxe46BqLRqP;ay;9Y*Kc1Chy_6$sruqc+Il2>FfNuCc#n`$IXMOO9uyG12;Y`sl%(4 z=h9;hn6fW>rN%wsa>d~t-Ada*eB6QIesWJ>rBYnUrJG#eL>akN#i+zo*7>@qV>L%a zU+b9}GUI7n$qGTOtpo>05(lf{?Fh?TuQbj^;oeY${ndAxljNOF#r)}ij3kUvxnvaCNjf zOD3vAKK$Gl>siWMBD{|4*txgFui-1zPzNWmi}sE>aT-5<-c6J9m&w@kxCkdSbG#Wc zY|Y%BtP;-4Qo>D7E4fqzb?GwG{}rrsFXt9_R3&{M5h4C~L}8aB!e zewZ74sS4i?c)tO7->=-@{oLT??Gv+p&AnHVVYpj{qiz|7Q-(WVmL~zdT0oD<`BSm- zZVbWuMmT_1P#99pTffGrf2YxPlTNT9Z8CM(mqvj`NUyFZb zGRYVGYDv>j));?3{a6*&B*eWH3Ks!)ri!Ppjz-9q5a2mV@`boIMhDpfL7`95TrAVz zoD4qqxSef(TMV`SJp%|m2O-Q=5iU?GMu%-+2meXguH*mtgDl)|#z_%sKaG-AEX|EB zw~C6u>oo}PRt2xmjs6B(&Dadk+_)j{#R;D0sm0ihsu@7^VIvR?8HA`xMRZt2Gzsav zdCfMsJlr^_;Og3?;!1bJwbA6f-ez)sKi5{orBGg0w_)gn+nwJ}r_E8zv$y5N+c-}; zP>9o5S1}XPCTUI_L^WE!lJ&fUHP}xXEU-bmZTNaRi3D>`ot_Saaev*%QX1fWdgB(( zh(cgrp1~>_#DIXCm!X4Z(`Z@WgIPtM1#TQ>XBxyYqt=5sjMjZ1q;i)sXT%*>RtS*%(PICXo((hd{ zkaaeSVM#xRQ+ddowc`Xw8}5hk%tAOD?+JL%#(R#*HJ0LY@ScnJ8F#xMVDMwd^5f_2m#OovmZJD<;?JEo}KoI3IrhDYKmv$4wVd0-KhC~F%BL}0fO@?>wa?R)X}aFx-cfnv<3PAC)dM>63%+w z6(bfJ&tds}OQml=+gNUS7AMb->a=CNVsd`x2@Y47cRzQ9Oihj?OE<*A8v)#Bi6OcLxzt~xOamEyF4k9g%aRT0 zK4tp>qtTv1p?l$SnT_Xm$5`y4q0&@g8hcba6&sbt9vxQ(uEy34XT%aC#i;o~9wgN8 z+g-?5h~Fk~XQ%B!h)(xImzvIF@R#yq9ktp(RDuk$(gL?lsHf5UdOsm!9D2f1Qzuk96Y}bW!dk+wXKlZ zHVwsjXg)C?cASNsqTn(*Gwv5*$* z3dRiwq0u5zfD-OcNI{_9Mt<61HQwXb@sm%f@fyVYsqj8VK8{u(II-}}Ddf+l4`)GN zGpn#7U_)ewKR#`gTe`u<+FIc0wTWGAf#SN9`J9HQ-8U;$v{^=e`C8fRt@$PfC#=P= zh2KmVNLzYKP4h%CIqE8_PAzgMikz&9i~sM4sSli+`QIl2&DC{(#R=o?Ih8`ztl=7^_8E)YZLe8Z26~`tp&lnH!DNZL(Qe*zbI9yG?U- zLB9;bD4JaFT~kEgS4RmA!k1Y52ja^@aszAs07gqX^>s$PFfAEpP(}s;Z7TR(KE6-v zXmfEkef4|~lWRmTc{MztvvG|(VL*PuQp)_!LZr+OWYK5Eh2uvQnp}RN#N#9vAq%q5 z^|FgQ;RG)DbkCp8s?K7BZ?V?Divhm#v8(M>Zp$ZE!!IYZPN4IezZ0twI7EIZ&cZ?_ z^+R!$@ULsE_Cu63asq4p5RO{K8SFZqb1q-TJd-Kcct2MMiIQb<&Dx0C)BKc*j;=*q zoynD?v`PsB#&FE!@)hNpKEmEODFp`4Z!vP7-tM^w3*5M7$Q7M3zuU-pTm;Ld-MNpW zWh$IuD1F!^)S$1ldX$!JuZ^9Uv#yZU!=HhiZiwTiJLUZj%*bJQX*d2U{>g5|KX zR(Snil7o_I4$PUD415-_Gp%T|sfu;BLVDabSp`4CbZzj&+{g57pc~UofJdrWb5MaZ zCf5>PL6rhGB;h6u@}6ufV1<-4cBl;{9ab=x#<1p(;Hvt?Qu~~bfrCH7%;&^luat|x56N{-ToRFA2jM4sWo9cI z2iebl&ZWYbkVPBO*b2MOuAdX13a`d-UeXRyRq@R0t5a^mqbktW#QDRjzmZv5q?jRf zAhJJ!$Xd?B1^ns}=6wNk@8|1S^aYT>Cu>=n{A^=+@-vi`Uw|+z$YUKB#4?|E6I~TJ zS^!PwAE@0Wh+U7NtmP7X?LqE_e~PcJ`f;zS#Vvof0aFp_+2deblNZ#lt{};)cPON+ z#5GjgEb#kvzfh-EackK>L3sU#i`3 zK>Tet)GtNx)D4#3cEg+Jf87m^rSeRVCemp*QiAm*3w?~5nUiUWggMsx9Ssz2R)@OH zf$YWo9GZ)={so1~sQH+j9ex!zaDkGCZUF8h(t7~sp=0r%<9yP&YJ@$Z1LYVs=Qk;` z^jxAGHwzoh4`I_8J8SS)E$a;Lj_ORhInk)O5Wf2*pHX8p7eqOo-~iK^)R%t#2No>@ zoWInEzyTo2+_|PZ3I#PXGXU<;oIhyPoLh?qnyEx;Bs@OrpS|qr{Gid*{lR5rEeM!e zR`HV0gzzR#M{26N;xJe~zbg+j24{m?FimB)FeZH_-ZczrMOh=949Fg+IX{=Bd?ro| z`)Dz=m{QqLS|MvX@*M@xbZltRWVZ7&@$RIvJZQxyzQf^)cL2tWo!1J`_It^t@{VbV z>!Qhd=2O)3kZsjqg{Soz+Tmce?YMj3&?F!4NLi!9vQw>Xt;zZK4Fg)`ov;kd!gjL_QB7s1kN?nBR>5-SnuC_efQsU3bI>eb$+fBH_dz)Op zOtR-(7C+>rw@YkmKpDc@7M3%1=;(3unjt$^3vaKGaTRhNgzp_J2nZk24Xor#F=_rH zZ_wU!{d)^{g7xC{nP6Y^u6!kkaIB5$h8c@9{Pu`ODqb9m3<+9q7J^>Nj-2-JU;t)^gm;HdxB_Ds# z{CyX@g1laT$C}NViQ5arr7YuLVg{+PC;ufb5pbp`@N4mcq?nB1$Wm{=`L*~mFPy1m zA+geU!Ga~kHE|&U`h9~l)RrEW{*AcG>!fGX7eM0pMtqZy<$f#1(zEtk61oj6s#6JP zc49_H_+%%}3IKszd*vj zRc^QaNBo5sj;v&sUJ>__)dRr0=(D%-;v(LZeLw)*z#4jSIIVsq>+BU5PRYMQNF3J+ z(h_voSu?{z-=ySg6bl0p=N*&urjPzX(CD?JlUSBheEadYb}474-s&R!aS=x+f!@-W z9S_vgqR6N@y3|tmk-v4{`~KEXvFW8bI#)4azja($)E}LpJ|{104%Eke1{2bn_x%AE zs^Z;6cwn^0Lh7i<%3Sb$erp5Dh_vEB4jJ=}n!3x>TQD2|rtZ8vEo$n{TK8Wxz>0wt z<6D*BL0PW9-KbpJWYqjczKW09`w7I~CzYQN5lfLqL}qp=ac(| z((S7YLs$wgjStAbVtwgHe;I9)x)HJt{m(}dcUtbv!pgxUmqJ1;%WORt|Jqk>WM zI!>5tq$wl*JT7kW5ueyfArEKYup0hzI4jpk!BhTHNeHRljX&ns$6V&G#x@GkO+x;a zrU`{Qq2vY@t)HCpfg3u;xoy0tMkl)w;LnCsx_X{ zXnwfd0rFzm#zoTf!&<$hSX`vmI1zaLhDa}jy-`hgi;{NaIlK!!T*Z)mbRZXPB0S77 zL<*j#Y`XLsZjxu=bSn%;gtIY1ZXX=%vdZ)}&I5Ih?%}SgyG4&8T^ZX>PI$60qF^UJ zgd)8WhO*Us31)R6j}-wfTD#)71LbvkOYeCV>IjC_i_#aQpp;9}Ydqu-D(YPvRiDCA zeWZs4jB34)boY{1gQ&9PLg)|*D!w}bH&@N8YpGGx`EtB>VWe$yeG0*Sx1XEn5DKH@ zcdPt9>AQz0PxW?a2p)KDVuqp8YIL~uofrKb37FjP@kV;pMpideni5epw_+tWBgVWq zB?jI_JBqnf{LFO2nM?!|3Zrq;g7mJn`neumhvLAesXo@DBUi|aWx&6_N7ssX?2u`y zE0y>bdS9x|5-;N!r^L&6R=D9GD&rZW6p%<9UK&OdI^6=* z+l_{Vvh-on#JgX)T=OaCTT{q+*X-k@n&Wf}Pt`uK4Y>N1qp?3@mn;Sr09FCp@ytk*isrMMclpLpSXkM^sEka^8Wf1;$GX>`V=}+qAtDt6_x9iP(4T6M)fH)qr)m) zjo$%1A&AkTV%V-DE#0Vj8K>d=q8kf`QDv>L*1ARS9;V;owbae*zAgLm}Kh zgH0bPjUWHg8A5WR*wrH6wxxM#J=tnes=o_HFH8Atkbjk@nQf#r%{Mh$U$Q7&|K1{4 zRrjr6j*(ITD%7OCvfL=v+qNd6Q~@0-+1YoQ8U3aEg%?X%g}?MKDRrw_)){-*C@FyV?T=_RYF=DxuM3dg z=iQ-71Enxtc&U=r1W9*;@~A54&~(_avM_DnQo|tX56sBH=#Q5YSbVVbcvxzRQcNla zYJyfTqi(X7(m5-iOZ!uHIy1;Ri8FUrL7ULTCEA2dq%r^0Tm*#+Z7C^~jm z5K9e(RdOfKvO=X_gxz1U%rJ>80(RV$IF0wp4MYjytYxe;e#8r#;DNE+sCi+7vIqLY zy4^bIWg4ssofIr=U(XtJ5U2=uQ@Cs!s|}Y%vG8yy9L$e`(=g9*El~Ji9)pvscVK7u zkRNe-NenZGOVbpX6cxtk2JZXcVZx&Zhn)9LT%E}nK(wXLE`7&Xt+CP_K= zz)7SAj&*U8yrhCVhEcNx``?^5#f7}hN!TA~w^+ZyG`!{Tukk*AnDAN~zRj~*v7*#y zp5MpL+#!wk9cYkI^IXvGNvP!Ji)_*)=?$SUp0!Vsg1w&GK+`ZwwZlxQOCIXU66&FS$tF*h4hv96+9yj*!t)1N#T01@{*O_f#&Ua9`E*PvnrP6ttK-eA{Hhu|Jz-33j&v^bp0A+mO$tL@ikNFy*N z(^dKnVSe{W5x)K5C|ufdi5c#Zew>LZb=?sNrl%{3zKOjF39);tc*Lhn3)`m-YQpA1 zL-T2s0KSD_!-@#R)3;xMIOQyu#*#oc8)Dp*tM4>=$4m_PQ^~AjrZi0|*x5OA*e^!SQ$tzEEa`FI!X6s3#&yto zA_{BSo>|f#1D^08$xT`xb;XHrS9{zSCt6v&K?<9ab5>;|(w<~f|18Wg4xxx^9ed)U zQIm6=Scl@8T_-NGQiJra?|rzdAhkult3dO_DVCNfy>NH>jQ-V}YJVgRcG-KlpQn0p zG!5SlE9bxLUHQHqj`lE&LORbvlB8g1aW;lUV{-1p?Ndq6q)xHrNoeBYDtlg%^iN)R z^f{I`M_N6x$b;$_5&}16Q(2E#acz91t~VLjyY0*S3z|1mLhM~ zGe_DjOOnj z0%nqN^bg#-AR}wSdGvl{3y!dgRKP6Q#!jY6 zcY76<#jY!?*u5B0nM+yZVkuuLEL%O*<%&%%tY9^ZrTGDCHY(YBIVv)?gX*1<%)FOK z{}fE{zea`GttHY>!GtsXR8bR7tlkGj|G`mg&wbKsI1vo7QO}HNvhv!r8KhX6CN)Xs z-p=s)NTVkGyghBH^s0yNoTYTgU+I}SDB%HVX4n#clk+*+kE^i#iSwZJIIy_VGqbx` z?E@%%(*u$(ZnP?W0MqR3N{YjC6TA2T$^HiB@u2i>*!^pF~QPxXrvfYePq}SzzRvBUGH>Eq)|)I$?{NM1vVW} z#Mk%hxoHluFr+yG%$c4p{U{{zEOjNA({POKS&7au>|zb_a|7#GDdop1{MEDt3Nr9D zznb3=7w%zbT5Z`wWq{uNEP(+z)c}a>?U<l4!?SRhEJW|CUAIfFbeTgnQpZd5F8(ba5;VzNH15@tB{Tk zSS>}w#vN2|v`U8@j*Wzq@&RXej!l5JK z`8~)jtsH5hnuhmjZf?9jH3)afX|prrz-70Lbx3SeGtxV$K5B)090(s(rp>v@D3rq0 ztn@Jm+u1gI&0|o}gs-pKd)7n66edq#gXZUCPeF0s@N z5Tk`X_KFRXuOLkHWVKI8W8g4%<|!#GAaNUda5{R6PFvtI6Y9OhO@GamUKrw=c1T~6 z=C6M*4J14R}5}kYeed8Y<;xiL_fI6zsH@l}h*X zLgZz3b&E9KtH__OLty^DN8K=yrv6@fQxGEj?H=1CUoT;(zukX_RHPC7TI@S_Lp2q= zJnasKkt5*fz0&hS?8sE~knYYuaB!T2K?5fp_3w?$L7b2JUPk^M*5kf8*5mw6C@g-~ z2kYrq|FWoKR%bdnHq|XAr+eU(9 z_0KMs zF^@Na>|(M#{!K6?c_;SvtN>xR4)RVM@GNxt4`rQiNnyTj-igkUmswz)6gEQkLL6}7 zbB;X1jB@<1y$zisi&>r=|7)j0=g7sZMvnir^PqENIJ+pvlh5CPr=)Yl56t^0l}o;T z1HORH5sgeQ$CC@+fX|U zFUOPr+knHIbNFy}74hNs_LzEaeo89~Xt}CyTUtxMZ(Hw8_LpPgnm*Syr{7vtn^Rod zgj;K6=Pa&TcFqD#8~dHJoF7g7ttVRARoT(Ysq84jz^8bk3AaKOJfAko(xlH5O}P1$ ztjSr0o5u$bw_W-_UD2Gw`rJ`aLAbjJH&4lkdGBf<#-@XtCz`Wu`~T^Q<{Vb2HdOXR zn$hz06$Oc@|oNaSWy+2o)dVd_n4s94ZRnz;U2WxoAXB-=PO!6JI%eHTj zUy#%HG>bkajgC3(2*npKFg?ROkPf~jKb%yu!uGkf^t-eOJ@Q2urrw_pntFfO&TPk^ zgZ_-$ez3H2{Hz_fXbqRH)*4gD&thDK?BZp{6o+|!+%7!L5SW>GABT6^V$U);BPm{S z{c=Wz;+ITea-RHB$H~jdTad z4==@M%R|mIn!WS3G)!t+s^q$HL%zPl1No-2jsl;c(ayGAlm}}k`J@|pOJcuoISY9Q zCWjlxSSp;WCf+C}lCYjseC!pq(&snkY~8D(k0EEQCBn~Z*_C&srzgG-DRXpaJszD^6M^HDDq1Qw;MvEcbG3`AO%1M6HPxBeQ+g}Q!YDhqs93VZm*aFVYo z?kt#Zak=06!~J17&$>-Yp6g%PLOI+4Agc$_cyGnKFQ$)3r7hP_4a%3O<~z*F-<75X zUzaa#rFu|(jNH;TH9dn}MO^}}C#w0gjohLYYT9HLazY9le|@N$cE-rfSM&Y*7PjL& zhy!UoZRAdLG4ly&e8j&McI_XFk5(#U@q@f}HaS09z-oZg>)(|oSC1d7HEM&{@kOFH z>pCILAXk-02W-D%#<8sqX*Id3IK${7adK73A(j9;kgH0r?5g4nJKOK7vKxlyjo5$J zHA1z3tBRpfS~xLmfyp_hi#R}aRWYN-6eX;GKYspnlrfIgH%hnTc3^T>Nt%!I0=P3< z-s1mG_GHDLVLD}{s!%lsZZCuzi!<~n;K@eLS=YjdBm6s&>6@gn@XK7@B;AI49xY8$ zu=Tq{uu{6*nEhN0bQQD7X*!RF5et$ROBLd3OwNUy+`@oa5M*)&uag_`2=Ayg#O$X#Blx}xY< zR=a+u#qXv%NK$YFT6U=J?G?w`EOG2hzrRyaD*QNh1JB;bhh;hiXV<8S;lmX@>5ze$^Y-P~H7qcg~@Mc#zj1$t~~fyKKM z1aTURhpP!JU49;9HhO*y)#)_a0dJOzr=i+nDH`=Yl%^{inE8DQ*TFN4RJA&0{y_RA z;ER*8LA=q`Qn>2AJWM^CjKUXd?Kx*8$s^#in%^dVHWyAu(whOF%2z|3_*KSF3+>C> zr1u5k6OKimgN?K((%y0oRw3cyE!KXXG{bu4a{&VIVwsBhVqw^9wb+X@>@^ppDSW^` zWJwRyZiyFuV4eSvUKB1=*-I}BR*onqeY(%1#f^#|CaJT#NKkNw2DoErbEt#JYAA=3ij0jS=C1QPmS{Y_%fIFF*Y+kPUO-*h8uA67e%Se z{FU^8?`d~%Pu6->ielYgNw4{~*knAFu1urww_aBBFKJ%V-&asoshZzoCjp!pOJIz^TU6;6NO-V(|S@hS^>mm+L@=6`9d@W7% zRj$^v{`p(@Koq63kgL+26Xa5Q;JHjQE+sV{C^9#0QSL9qDTGXYCAS>lnJo9Jw9xmx zXtmX~M&T5EEw945cq)t4Uc)l=WEaf0(ai7}%$=HA)Y97~H0pMLBaN9M8(!l=8Y4l^ z9O$x>Xqnm(mj|Qk<{|^VTZ=x)YXwXhwwJJtU&m6v0ag4hxpihA?S24<=Wjq2k?hbn zWJkkiufCBMAz0ff=~(BtlEjvLD{VqVN2e5S@A_6c%?C987g}i)`{hkf7Z%8l3Rd!+ z^fS2I@;#&>$fE9hu%x343-!_L-``8KeBT>Ib%dhZ{|SaCNqW|GV?hu9k(3{#DOkGa zFw1o*XYD{c6EL*5 zjt?$Kck{9JyWstZkAb;#_zu!m0wl_qX|QoKIh(EdKv7onx}t13zQe}FBX0E)&epuS zAjh8jlT_p()JUxYf;I^^saLTw4=wRHtMkzQl`z#ls|`TdUgD{RcMd3_ z!AtutJuO4DVN~PtA=-JA@yZbG?#CfM#O@@F{#+V=xkr;5vBc@ene zxtXnJsiU>>L~0w2zOw9L6{EEiM-=&gzkrLRJ5>lr(`K}>eYAF!5U^AJ>=|TyspX|U zB-kBD4W<#PM+^Kt$dGK`8jKzactPf+cN<+cxkzka8HMe)SWAe~ecd5ivRm4HLeY%@ zf09wZo8hupUIuFHavFs{ZD46*Y4qz^)mX|@XFoGm`x+mxtz2$QrK@BBcv}qH8m^t+ zUymk0cZX|}_<%ns+C{kQq+Dyc9)H-yjJIj0+?{`wnrP{X%ZtNA*~!a(DxLBj7Q!EA z6wg$6jn?$^lcZ*$n zWO9=GVe={GGf5lfTjY-&gL1jF>EJ2-B#;;~XHL@oL`=ZarzrhjG6mQKYY6j**5a&* zJe@#Uy-Ib3i}iBV#k!Q0MuX}8;=@|;jO~Z(!5p_0oAAraie=jYZ{|4egGO$->oYFO z)ceLhdG$iaWYE+4>ifM}>Qrrn^?vwcJGavos$04T(jyVSX;8d3;-@1%V^F+^cxc#1Xa(vpE*h#{*23!V(%y;hm|0>V zvX-?opXu6(5zC?K7w?lT6`atCV*y;e4YPLzEC`rf^(93X=Fn^X{RYL_4;3oGN zu-kH6B;hKv;q(}^egVcvKeB=9*R1fir^RaD;KNocJ4Z#F9?EuzEez(gm!U)}K+#MW z4`G^dnB~M{#$1ubO5?Rj!5Q*hl<-kCAdf%6A`cD>uc%;G;dBYn+-81#*Mna+UGd)kv-H)vyp9C#!pYVQ^v zG_b5h?Zkx-<`{)sGF8EZ#Anm+lhq}zg9h=zDu{ru`r;6-NBBI^oeXo}!IQL0g1APC zi)(tYg>@uq4+syQVc7)qLfTsoBTc@Q7Zo{bJnN4=iJ=LBYJBa*0$US2MP zlnc3x9{FY^Qa0lH%jo%(%1F>*Haeha5dCGIo2~tY%50sZEthHcbUn>5(tK_<-oY`IGc2yrOw0be=eM!qaFevB0XiqC_qL|YAuk*cbvq< zA%!8|e~$Z2lR74L&V)B4|M8{&8#e#S_bwH7mJEBCbTL#=SWyP#HGEBPT`s zq>w(Hg)Gn(30XLBv;cE8)+j9tpcy=ZGvW(C!3EE;=?k^vrxmQEjv~rvtn{4TSnR2H z@Sf4l7Mv30;G~oUEq_9x2f>tuWIC45h>sY z)-&A_?R#G7%i|0@$8-y{`NHbOEbBgy$vcUx>^|-N!lrTT>V2qeVIvDn)2EfgQZb}rREDm-*-_x;)je1E^ak@u8Wc(m$cS@&!IDD2zCZr-nb zXs9P~3TY7fHR%;Ba~b+!vNlHip$9AWu6efOigpzhEF0dU;ZyPQhA z!A>qmb6)$D-CVAnKT+|c@2b{EkwEEs-VpWuSvWulmNK|z(#4YUvJ5I;1Iu2ay<@6p zV^Mxi05xiS!67|}j1toW3*Kd7A;W((4Xdv+IRa2`Z#$FR;PVk@L?4hu`VS!BBQ zK3>Q2(lKe74`cDhz4bXig38(PIUk5$2!6V?F1KspC5jKtz+dc3CPMZ-gQu0bJ(O++VN6>jT}~6XXRJ1=zH+R*ql|+JXh-b zFS+Plx000uaKuWw5oO?tmfm&a*f}{q9q|JF6RTI-O@ty{5y1^4gGBv-=_K=&2fFeid>%AU6zxECuAi z?r<-@{^fW`JKnmo0`UVowY^z=wd zM&3rb#cNi!ntB(VMtEJte%>#BG=>AJ3m><7Wk*`c5GTz>rrt*inZ>M~=(`g8nJy>I z9*CRE>g2fYw345lq+=ouTil4deS>OBcdA0ijE5`D&17a4oCTsDIdyBeE zy~)_!OFpesW))}ZUD$^322^GQl}&Y_dYF12#AQm3RD9cY+T{EDK^|GD}?buPY zFKCu!EDqxl0h)S^9V~jac9aNLYRmCE@+_aRg{!p&VaX;|wptrDVwGQS1s7IWG5QUn zL0G=9t%!JG{#w?tS{pw0AiNZQ|0SJii`T>Bn9juGE0oINHDU2J6$vh<{VkHQ5?aBYJUR?e9_wKwI%33MMbt9nGcxj&6B#a-(IY4KUw6R1s3mi7(d z_s7_wb=rr6=Uk;lCQ642GiM#Vvf_7!_u^ypO;K#pquOBWykjaMg~W3Xj^K!*&0LVJ zOlUG1g?R@l4)D<0hvU4Wm1^i3+fa`;G?x1x_w<2ge=JYWrgU0@sX z4CfJB$(OT=7x6iXjz=-Q;@nNtW7^wAqsjHpAlvBtLu}Gx+A%@6?zyF`*t-eK#YJvN4!0?Yz$R9)bT3=cgaj-r;G$>%raG+9}q*EJY&PZck<#KbhULs8HOs#@lbF)!8v9H>*G7xIfpgaARi0m5C0H{a}+rJ zs;CA7?f4b02HLGvH7mHEvc# zyEX3TqU&k{vsur2koTdvO!qk97{?5cgLBZ6&rSXBJ^5Tve@~WNV~)qQQzjmw-FLUH z#K~Iz^;>dj=5}tDp`9!0c_$AFLJbRi0;Bu7Co?~R(q8+D*`Ck_kALksxBRe?6>LTR z1#*5zI~UhMLxH@GCs5PZirJMXw0C-)iP3W->(0>zM;w%G!hPf5h_F-{`Gd0J-e2;h4Fn&=QZ{IVlWLA( zFw2!a^&tjFTtUvjKp))XSe9Sf*BZw?`6Z5L^0(rSVz~th(bQmEHfT*&w4nG%U$H2% z*fBakhcvB%y-qMU3P|3}k66Pam{~O^IEc+Ztp``cdj;!?S4udDE#?6Jo&T{Q<7v_ zq3-LkL9;Y>%i1M%BV}|XDJr1ceW>{ETG_mymy@}QZ15NyMsM5qgd;YqK zAN}y_CVq68Rpe^#2|7K{qE{>3-qBOJ+Pec@RYvV;{_M7wEWQCYsYfE9!t9W$UO?9SiQ1!ET}EpUfTlxDi$ zS5);<9{)sr55K94mdJf5oe9#^1L(*r5KQG4VI z)GAF>)SMz(sO9(YcmD&Fc|4wK(Q5@E_1K&e=DS++xio4bYg?^J^q*6!FPyWNg;+Gx zrIANjz6FQWk?HKR1F#NZL<*L;W%(LJ!kf<1}@2vs@Pr__K?(C1}xInMbb4$+mm$u$Mq%j(do zOvMNu_ZWJ zeJ^VU;M)4k%bMxItGO4qjiP`RJ7)?@sMc%`OS)ot>(NqMPmH@L718(`rTF2jy;>7C zD*jn@Y~yp#1lR>Zp{Y|NGCp0kZF%I7SMOIX8@HJytkXmU#a;Eh;~r_9rr%hX`uYgb zTK{w{j<(QNupazAwDOp0B$-;6)KR|uty1ztl`74hNw}DLQCOVPEM%u#nyX{`)@lAO z4SttZzXFloplj^JD-bU{DzcMWxay>?Udk4ep=)H5z!mcT$5+R^KADc4I)Ord__k9-X@PIygoUyQjmJi!MDS?O+o z(C)G>I-rFx`Tb@$)Kf@c6jj4ATQvQ9N3@ z?jdm?PORhyZoD9{$PJpvuvb~!%+ogy@%(w+qZ~zqBw`c~>NxEVS zOr) zDuTO8NZl#S(f1VvtdiNteKs&>t!7*lm<1_f66l+#uYflgsjosSam`VQ4m1TUd#h&5 zw4unhp(}lfCg{K#8l`X-#Jd5IBl|+UE0b#*fZ6)9v>`}a`wMAHSjSe)kU0@_!SWd3 z&iBBr0Ne_cCxiJAzzz4n?fbs7edjs4?_#o;sKSD|2>wsd#O#7PB7qO)@eMdc&=_r-a6I19aD1GHs+7R11YM#Zd9>7RZns-5JXV^TYc{arH#IN9_1u*=HIKnX zR%D$f520mkb-20dbAh$gfnX7co~<(_wl zyfkCixCNuW4*MYXU&HqMX(m^n4K_ravrQ*EHPrz%u{~pVkszUGA-o+na8f$fOGtzYNKrsdsgA@F1BH8&zFp1*+o`Uk2B%WqpYDGiXB6DB5fOML3s%l zy;mr&EQiTEH6unX9*Mko%S)Kqd03@nC<9>|G+GTv4+LzTCGXo%sL2{UD2Owt1^!ic zYDW1FJBw%3u~QRfwQTEFc7ms@Hp_=p5rYq7Ds<)fZ<4xgGB+iX9wyze;2HjaG&9h_f#sQJt~W{#r*jk<2HYSV;`d3w9iE6Z zeT=z5KgoQi^F7ymMZYe`mzC_oC15YCi(OE3=#|d2Z{fG+O;*Hz_pqk7Abye;vyj~& zHF5?^+O2saIM<-7%F%MWSxHV|Rl9L>an}z)Sun^sHj^uL4{JmDULjl&Ma9?hrqrwD zryAuwnyG%`a+duY&1=CqF!%Gq@jKag=QojxU2N+^a6uekGtEyZ(F4W0Di0(XV2MOgpF< z7o3Bb>7Is(&f$$U2Q^ReroW4(w;$3l5m7%%8zCoGgATXAdje)wUFHqL7S|f8lx^zY)#NqRSF;4dOK4v720egIIQx zCL%RAAJ2X!=l7map1CC^=Z|Ae&YKs(4RG`U^@P|xmqh2?#O}d2SwjAic|fx+^%R8y7|MzhCn@Y%0P`9_3FB%qNVvw%=zJgea}7>I2Q|#JOo_Bg%Nf5$p({Qb#nuqZ4)L zQOysOCx58P9c%`~Qu{$5q4gUr<^CL}E>Z~Pc?FR1e)iFj0 zrHF5iazUms!S^#d^U|>yTLhW%J$Wgt;UjEcv--0${8waG059fQa{8h=D@GekuCpne zw-Imfi*&rlvp5Hi@V~eY8mkX#F89f<(>>J|T|1yMd8b7( z3<~RYt-&Mj_E-`5b8u1d{oeJ!>#xF#c;EV40((L zd*?ybV&u_Pw?FldD%XueB}vCMeWt*4t8XAJ4AAwNh*+MlZ&saeV-}P&8`Kc6RqLwq zu)k!jR~L{NO6?-cB$IpPZ0v6yPtJKwY}0Ygmf#y#yQQ@;-3iT8&)is#v54ghEibRb zDBhsi3I&(S{lNqFUCO7r@Ju$iacbFoIPJZ$1n=F(@#A;Zas1aL)^xRNAw7XqYmYF@3QPa0?v0^ndOfV246Y)tICj6TYq1Hrq7alH8D#FNwt&- ziD=Alssnp~NHEofd~F*YMh%tjD)s$pI&1x-CMMW$?t`&zT+`q{Dqc%t^`Fb3T1;4g zE$>(+?G)&i76VG|K?I6qrW<#>mZhBn<=MoFPidlHp+)G}Aq2#>NI@l@&4q5Cx~CU= zH=UN4prUTi1&wD;X`Xqg*VoNygrFpJf`nFAm7m0tTfpI75?K}fLjF!z1_g z$1OYXxl#OzpOo!Ogjm!OLTIZSmrvnaOQ<}X@EPV4rj>v$5$j zO)uYIZzc2KMEmn?jjiW3fAbkitiDg`TtO_~@$ToTl67Y4)l3@z`%t=dK&xPRy;VrL zG%Y0Mbe4^^UC>ykg{RVB2A&AVZRinOUm!U|3YI+ab4%WEwDI%!bb$`n_;cW|9&I#Q z(^4L>YAXT|_xc;FHf6rmH)Ue^72C&FU)!GYD~ZqHuML=7k%@|DDESFKLzrFUs_!fi?c*Y~$`rnkU5IMJ1lZ45N6a z48|0i%25l?c+%jf+1GA;DgJYdB?XOb>1kQXBOoOI>R7nWvhC*Q)NjkUpF&gC&8=Y# zm!V2<<{Aw&4JHjXAJ8k8H8B`a574P+jN%_>v+%2!UgHKS#g_5Ib{KGpE;|-lb!*4x%?A4@U7%TUpw-n#$ls;B5&j=0OU5@?Cc3 zTg`m`d3$*SbpO&^68+~jaUj}jnD##|XXa~~*G4(gNhu71vQkUyW2Kh)@1mCT0!We~qcabqubYg-}q zzcuXp_m3$X=+br`z{4>g(*7!x)IeC?JZ!= z>%gKD%`EwbrZS>g0YBAHe*E`bD*Qg$qLQwo4Xot`6x$r}?95G^z8rq+#!cv6e00HD z|3on+gRb92GJ_;?S}O`u;lIAwTL027=2?$^jEj$tc2ZgT_RXEbRPXmlUxy{icR(Uq zv@CS>!RK{(3s0yMObB%JYa;R0Z1eY;m-_nA_>@JAFHOlUZ>xS!kg%B>>!tEGmi%w1 zEX_N^_Wm2v@uPQ{^WTs}9v#G5Zeiy+a)E{4hPIRumJ7E*rao}7+S?$8AIxS~D1BZF z%lH8jym{^H%n$fZC6cqG_t!D!k057FoGS@sx;vWBgBRgw!?Ev!?qFIh{F?~iwX{pbMS)OEIw)H#ASb(gJ3-}6|O zKJ!>fdOOH2zTq+a*t+{L=O|%Xw`P%;)mY;u%aHk&%_rm)LG$gMy`Lb;b3veXi}Fj- z?^dz|NnR22Khe}0n;4Q%p(k;~s<%77~dpgnYDsR`fqYdRkh-bG0 z(cCwbwIzdX&GwTA`_HfAq@&tTo+Z79i)uf4ob(>9>HX#Rr3yID@|R({QgMWZ2gtL6 z7gc$taxY!TGFyPWP3UI9w?9UpKsv+vjXLE>75PiT%bH%dMBMFY2;*< z9VD-k-d@jIgXCwVw?|UqcIoZjtVJV_koKHqzOwwfwEGiQE2A~Lb6Ari59oQhTkEkM z?;guy6*TfK7b{TYrzALXM6tJrEC9iLX9@MvK$kF>Z+$&z*RchmSabY6RUo3fKxWm! zsP3J<>`1U2BP~c^?fCUyfUV;lg$4AGqa^&s^^g-I7GxX6x4oJs-C;~%#XaN*>Fsw} zO%K4@{WWv+Kv#A`OCSU@Sr09i5cvtIehIr3BCn8k++{^Q!a z%99g!?BuR(#T{Fz-DsoPi&&66ouL?x=u-&!Hp1QF43^moZQKr*0=?v1Y5N9(F`W55 zET>D`qv<7yl{^fz*!BsWK4NC-cCy$|v~Gcood}g*8?vAVBcdf{&g8yLdM>0-9Z5B( zV8l@SCU5P`(i^?3OJ}vcVHm(SH?Rp|$bK`2mGIx; zY&U)f&xacR{rd8MZ}|L~e?ZhEZfo}3+VFu?tI9ve?$9@H>}PR(iR(#+09$f?qnku0Piux*RT z^83l7rOglyOpzaDf9WUpkQQ8K?fvAzF$+4poihqOxV(~4MnKMTIr++~b^{4U5 zK=}trdSxwZ9}Jv)g|EdVHuDiVOj-vddPJTht=rt#@`xM^Goss#?eX$x(O(^l#@I*Y zh+iJ{wPRUU0!F>+5VI#>z^bs;6XenURWJf@yIF@Hx{y3n{;RYGvSy7O!D15SP-zXK zJS57gQEQe^f9UL|zqG&xd^8~3a=3b6sr-!D6VZ)IYzm3;h#{T9s~YqUn(xXbWOIhm zgei}EQ0MiaSQ*IDhRII``Vm?X>0>p+fW8$+iQFZz)?w)I{5p1Hm^`{yK^p4h=RX|^ z>&6viFhi0Y7F3Y!MGt090uI?uvic-BHLQS+)s}9Q2s3HJq$SDEL=;pZFGOz>e7fap zkq>GxTz(>~0BY;^8@lBIgRJkeBf|-9J@U-m@<0`=&oX%g>MnpIt`S(j1!q|42>EwX zK@m%MOdb_h0K*;Ut#03-uCi;a^f8PXWXY%a?-aGu#$+tmf(~X&2AL{wvV+Mo{GG3( z%v`BZ%M2s2f(t`f{zyz=VG`Rr5(~(>k~v4pLlRf7=V7!EZiXWtAE-hdyw^vf@<&%m5bR-o&0FeOjH$6s|m`aq8nnc95?9z4jw0u=;Sy2UtFw<_N`|v%L5}>X^I>c z+(i(K;){1#U5Y%v*NbCu%o8!eTmXRd;Vd*2WcbBrSxu@uD(J#$XxNHCJZtfc8DH*Vr}S9&U6poGq2(gml!oDJBtYJK8N6}HHorvwbZ32*_ z2zqxD!R0JEO51l*W9vk$F{$t@yY-~}_g@^Df&=Wb5hGJD2+mvO`H6+#;KaRzQYmIy zdxhZK#9EWPxi9u2U+hKd2BGHJ*uhEi;IImm5n6GX+HFJ^VEs*!$3+#=e&)=|eP}c| zHXp+_siYh1I+i(^*1d~mnB>RUo0H}7(tM27WcjJ6!hPPwP7Qhx_l{|%S77DECDS2T;;TeRrX@|fpgtMI3j45n1%Ec3^M6p>@<)ny(;A5oH ziZLj(j!U;9$w#tL%xP8&9YY~$VH~?PRURC%FbO@n@}CfMhO5Z;bf!E|TBu{CnY6_f zvCEnA|4L}q!D({hkhvFCDGBbowu6wm-KPw7?#nc$|8Z=Ur_0BrxnSU?%Om{fK<)Z* zL@Y@J<&S+DcvP6dvY!Sn&IYl28aTSpz~n4U=E9k1o!w^XoJ=gU*-#110`18@&FZq` zUDCpQW|)C-Tv*J^GceB20iS1J?Jl%<=Zu}1At&~FuCN;%(4ps^ZIqvp%Y70jIniPt z{iI20_`oOik};p&Q%@Ts_4Uv;+GQlZ@SJXe-~%b=HP-a3d`X%W$m(Wcx9vKZH+IaD zm-_r7T0b4lO6Fk3r*Cd-m?P^&v6gkrm3Kh8Rb$3hzOahZlgnoL!yxsURx^~)L0CaQ zJ_Hwods;FVHi}dC(~gF7Ip@NtgS6A>#x1PnFnn{d7^n7U`*P*}Y+|n5`#%B1|GxmL z3BXfZ3BVK5)D7%bt~_RFCeEGE8=ZEZW))-6fL~F!!%s$g5bDfNrgU>&)or8r)JbN} zlZWJH#&Zn7_`zwfM0w^t6~l~TW^}i7pKj@aJl&=`_*G#|x<_1+C-QOWq3fC{*N&VFA$1O%6F+Aelfi=-hU!C3! z+XT5~fM2+~9mM`sBWZ}`k8$9VJqjxDm-FSs+|0AK0e+E0VYvu&2Z=y4w-Ga_8r-=y zA4eUiJHY#$3Rg7ZJAT&#X?a@LI8DiUaNIHuu#$P$vAL|muenmaK<^kJjDXzaGIPw6 zhgdUK;`@h;Vg|pMbhqCLhvfN)+i@eD?mMoJ`D)em5C68xC{EcxD-iynBd=S(O1-}Q zZ>i*kpFHOy?+_WpQF%NUs_9qgc^iF0dC(|5g7+z%Ui!r;6_n?A1eG}r0aSRn>V_Y# z`o$^p(4c8u9m^QR?DOTYu*v;#gU*$aKB#avsREQI9gRok%eaTCWpaW14)FhAfjq~H z|KWx5_ul7_h4S%01+*~0bie0X*0xZ7-8yNIQGB8&ZzfuC{8(8y54kN)DkI%IvNFH! z4v59nW%K630EkaPU8gx!6Q-v|&0FPoFb`@a(5K_DX$Yk9Qcu1LD`s`Aai9P1mKJg|mqdtF)Zw>&Co5LXqAhb!4Mp`e} zna6+D1#jZvZt(V7AHM*XxNx3H1*~8GCe(WL{ZPVQRIq`&(@>w+!W+9UsY)P%c?$qz zJ9}P^h#7wv75M0F#8;1>{k+2lPqsqs^OyK(Dz!U+=UTK$icqzkV57S-rCxjSezjd6@mf<|&IIv=fD2_vDmA)bc{BswUiwYzcK znclnniH)VY6)?>wYSQj@a}`Nvn(GAvueB^>Mvu_pJuNo0=K zkrsdo#xA*jL0C#?O{0!?Na%~@5rY@mj~!ceM88w?)&D3+7>uDEW3I%~l){z4K6?wnWY$e`-HVDWQqJpN+J4zn;HD6lZi1I+gF_cL$i9J-Gpk!tyQ1*((_7`na7Hk zV5=W9+`Bm57u^Nw;z&Ee%**7#BOcjL<6;y?FV+J-mOwtZ%2OuiBJx0(kM{yR55+Ti zBgFCu%4uv`CjV2M4riiH{bt(^ZRCG-ChB~8l1I2hdUFUYP55 zwexf{;B=X#Ij6Z;$ct3I80lS3MxE0>VFsT5pp#MOv~8@Ir$6Xq)H!W2tLNztIvI6N zOJ^-Sy#esMoQyiBDO*aZS_hK5e2h9XFR&z@-h%WlAEVC9{mjhMAM`Qm%q(Meo_+=8 zyL^l~Gp8^I(qrIb)Tx6d=6~@q>U`Y!K>TdyRIi$(>SR>Z?W8MQ)BVfjb{J7(yEz$k z^<4a)PDYJtxNGNBulolZtwJ$wIGC!@}( zT;~|%QFSsZ>O>XrlNYIhI0*0Uf)nz|e|0kIe99|U<4#8Nxsy@xajs}>6o&2e0PAux z>I$gj5o)qgutNT%h*jN}i;a?N7(R6ocDMjc^23MzTV3%6qW826nY9IDL7CDF=SR&6DqN+;*Z8|{Y zgJ8anZZC4`+J*d-F(Jh%2A?aq$%GS<>+s#MRF3K_UqqWisak%xMJ+F!=_>!-O;);8 zemD&VK|Qa z*G*;A(HQ@sIlN8AwYa!=4OO9}XGs{b$9hK)<-AgE6xt^B~qw7={|MvWm*v5eAI<4R zdamgd=t26p(_F6a3MBm*Vt4#u+fYoyZyP5hkaFLq=iE-f9cyy`DAT^gY^$JFZuxVd z!VbMGr;na=1cLDrl@sbwuUjSHPBP&W-Kr3}@5DmrQIGedTtX0`4Y5ar6!CC+e-|L` zzgotUsv)gQC}T6Lapa5xgT;TpX7&7cI6F~|a~-^ZI;$aogzlMn9WKtWS+2v_51s~J z^AL0nTF*|sBF~qKB4KDDhmC`CT<6o*5L7wShH5;-P_+Goj!_(E=hJ6xvxHNW@6FTg zDVmA+yS|9O3ug1_1FZU0IWefHh}>8;7s6So<5l^|p2LZVU}II4BoYH`;3C$3$hhsvF>ks&EQ-tOt6WW0%*XqggkZ{F>Y^u%-N)4?yjw1+t{q zARHPDj_@^kfVhX*Uz20TIWAb=JVmN;7T$+9xc^((CsRRk8;b_N!ioE3*U z-#@~-blPT^oKyC&Td&Cj`?iyuxicHZ>2s6w*-u!~ujPKdAr`*h=Ba_a?qW9%-O0?q zmizd%qUA@K<=66fgjsg{TGsc3t9(R@ry<>eg3e>TIgI{S07LL5qeTW=bD+g`G0?=^M0Umwe%SvG-gO>eAplloa&CaX zQnWSj7P3(7|%jebMa3MyyvJiFzirpX**D+Lg(Im~}X9XkC9 zD`N7}nA$>&aXwYnwbr^h1$I7}vZYpj%HL8Av;TuEt5${pHbU`ZH*4ilViE z;vf>Xnw%51;ukYJaiuym6ChpyMq+5d!H|O-&ZU@~fYyy6ezN{pIM&V&DFVt{fK8*UvE*TGUhwsMr}?Sqz5(4CRM^#`BR! zWys=#$5s}@k5X*qup!}ljAEZ0blOZ!piYz8;eUiy7W?e`rO?WmzYtpa+c)J0Lo18n zV_8C-9MNmhDMC%#B`u4#&2i0$Z<-SAzIAr5Ahd}1&2is3JJ#)N9=AG6XF$}ET^Wf^VPS~d zmPsBkv}L;@6D?9gB6-AsaI)GWC0qFm)>{6x!h+bc%E-jBT?r_ZoOo@&Ij%!6Lwj5L z{+dnt-o4&T63h^%V79w#1$I}xV0WNl+`R^LT+hCPhNB_w8XojfK3h%VGP7F7Rv?Vs zCWMog3>E+s5#0rZ*H77cK|*B~1ey-Mh5HEMEPJ~g9{I&Z_Z{*}2^XQ~=!VFnLSiGG zK4yPU?q@w{ixg(AaS9n;b;LZkAR#TY+j{`sv%0;97=`laF&050iHQ|dQr9Nrlirv9 zi^^(C?Z8s&HaH(^SJhZy+i=tbnOQ9(-LUr?7V#(QELbbz3 zM9@9K7w?v{??TuPg)9A0A74(gh1SE?9pSWFSL0^EHl}_&?ozBUiRrhtdgD&Pn68Dh z0cfX@o7&@75nFZ8pG&Pzd|Fy0*aX{i>+3LZ8EBN-VtB&SC_^G|6!Nkrg`}3nUkXi+ z7bLj2G&+SlJjiTI;5yK8%T2&H6y@0jdyX){_T0MK?r^MGf)~)bS^@;TCPy{Z-2fWA z06T<&*p|SxwV*6EqAC=m{e7BQI`m=giAvH)5>>>r+51f9rk-ORS0;jDbRAvNqf@=f zyo2mfPZHt~owoNE%oItzw-v|QkDA?g#vJDgYP=vx1=Qnoahz@Y`ua}W4CkPc-K15p zyk1{V`MfOP=<~>WSg9^i`j&?!2TB(;~9Q-_%qlTu!x)RJgT_X z3HJzKrLd>=b|QFgatcvKzbQP}Jym5;Z12*vTcnCg*@?&j^O1 zg~^^4CS!Ra&Mhwa&^pL-j^KM-UqI|_hOmLp#1d@LF)(J@gVrpG#PbYRz@HQFJe1k_ zvkuRGtZ9$@h}c3KbN`2c2@tnrk~krhg}*I_TEVBmhVB(QlZ21?3UdYI(3KO;zk1S} z=6OGacOJt_SH89u`FrTy^SqVHs^3;t8-)w&Ng`nsgG609e=j4fq%=Z#ZyX=w_Y^us z75}wuBY8VO(Maf^v+}kn-Zb_76_TBWs`=D5-k(sNl|PgCi_6t?R%%PzXDa^}IEmUs zX%DnXXgdf7Boob2)X*`|q~~K+@QyqnPz#G~GyWo({T*3n1r-Pw^AEI)7UFo^$j+^- z=JvEg+W|dl=W6-Fy07&+*42@Ppix+Ne&bhIQZ$KWIDBJ*&3h^#M^K`TLUp{oOsLY? zh`}qHqMHp*>j+SfR+={+6C&~Fi@yN;$@mMwU(Znd3&hZSp;eKsyJL-xuM)^!`u zn9Lg8K#qbc94f(b{zeVI)EO?)_SQ5H1I|RwIELzbxKYcw$y{)o3wOJ@m&0SOj z>*oT!D40{NI|X8#ck^wEE?R_^zTI{yzSB6yi`mwAY!Z_{Ep_CH7RNxbWMht?d%amm zd;KE(h{5>J32Sj6syALJG4k5-d2g1|#R=K38b!@TZwF8BL`YjqZTZ{pl`{D^^1$dr z`lHZL#!hJz{<55_?9{ol&=0SzXA8^xjU1VYxsRsaq_ty&9FRAG9dwLSJ+A1!S>&X9 zN0d=dFhcbpx~bu#S%-~;aOvYEut!7uAiBvAUOB|te*-jl`7mJm6HH16Tu4eQwN#Jp zo8cA}=F9uxAH__tc$vC&b$~U~{EgWRxWL0#X4vYm4Lk??Iq;GCOYT-MdtG+;A1^7u zAZHbOm2t!VkC&Xn$Km*xBw?{#=}T4jYxtf6 zLPPM~STAth4tIxYq_;H53mf^-SjPKoSzV&lP*t|-Hxw)A2Ceb;fyiuMkUT)+Yh9xy z${J_i!OHi_eKZ50*)##iKr69S`{mw&@S6=aHiON|w!b0w83;;|W)&nJG7-!KLDS_` zR(Db|;cquQN1r++AP(NpPkHuc+Ho`aY9X}(C`S_4rY;QMxK8f_R$qCH3oP4!_4S0@ zhV7D84bdzTzwM|0sIppbc5}BM$1kZ|uRdCs07TCwgokwP2o?Y-;xy1|rVBfxaArB- zJ3?ocdKQemd5t&|999XJ(1JN?&IA7YA4k|{kOh*Hl%M*2DRH_jK>X%iV(D3MRSrqC zc+xVERswE#2-35Wj`k|O>~_h?GxNVdPyP(%6E2&}a80_S67kRB+09y! zF8H=!3`o_+HVLu-OUpQYDor0>z4OmuJN*$M$dgjR4k&@Ke!LyNL)M}e(sbWCd~2TZZ2F2LGa z`1|t60Y1JdTEP%$g&$4dHk%FoCv^cieY6XR;6%S@`QM@mqv@qRPu~uau?NwC z;MtIrP5{Ce(N;&u4#X$A(_md=#q9D!$mu2jAGVi&{eg<@=n)~i^$}40fa6|d&-Ng@ zxf`^a03L6;g>{Z!~n znu}!Lm=6))mPEmp(ta3e7a0k083{UWs~9NwZhDq&-=yg$maIfG? z(glaxX~QWKjdAFJ?WM399;b!`$q8_~xeGdS%5s0uP<)?84N^&#SWioo8leBIvikU? zN)QS}M5mMILwwf%n8MEeR*to*TkIeGJVSees`m8VhvYWbzk-u!VZmKWU-Ma2!SQi0 zRN5~1uEDO(T_1B$uhVVR?b9vJ}-z@q0H&&+^iWkECXNd!`MZu}Z zHV}kuZUfO>yeC-e=>7g3`p_uM^IFjPS^FI?O~r^Ghu+Qc_*D)XvUIKBpNbhc1|j|N zNtH?7G`HDdr{FHf->t-bghMk7KNeac#&(vQK0-VAPb@^AQ z^x8)cEw#FjQJ{=0$86wgIZO~xF@%KG6pou3Lt(ZFHo-Lt`FBBTM^nDHJdXNyJ%*PQ zdeYS4&EJsvBP1ECeSFKmg!T~>f{en6iB?9m^nOdX)fnl?8_q`$#|j!fkVmd~OA7&R zcZ#taIA3YZZ18AP-}F%L$DtC7Y~7=Hw!}UkAf}r zf>;6+F827C4gFOvMo1EOm!(UgNSDh`|Gt#c$T1Gm8^}2hAB}kU&jY_;bxENebHN}B zdAA`>^@XUF=OfQr>PQnCJelY9v(WoGL57-=kFCFW%lZcBRGqs<9i6=8=#9rmpqT7I zF7iH~;7AwZ(gnATS6U_{!NEZh{93@lp5P$ZPTLhb_db7Ldy>khgEymh>p&~!3?Do2 z5fyf96AS1Agd^nglC;hSL|cV4%--m!$4dKFuQ;nleb!MF6((G|wgk7Lw8PG^+u}h#f#i?C#ChU4rpig%EcwFEg&g7r*;6R;C1HEZy>ZtJ9Tp8nPyCbE$5<&Fg-)^~O5Zh*p^CgVRJy(gm&H7$=rG zaz%@?9zI9z#~$Td20s=xPxR1ijF)-1IgJUQ`fSj*W~+ZEcq1FS|M5-1`yn5ZLRG*LV4#@QAS}%Y! z!GjM(hQAW`5ikPc*dgu)ki9M_XL3X&81y~CQDKbjI@x}-)^oBA?;>QPwO-{ZKH_|t zik)H&dYs^Swl%+nUigSy;}gj0bNskyIle~i)tZ@tjqlt0;bB%Vr+B8pe{_4Bd$glX z7+nuXTe*nIG^sL~f`jLNZnotf5^Q>bcoleNoCUt)SN%g$D^fwlPW--f4X(~eHawt} zjr)Tf8z>I4%@QKZcfZG8_yZ*9qG%a?Inl8i8-n4Aol8zIwzS7WmvKl(Iglp$PFzPG zTqX;1E_%!I@kjapC}#~vtLGg4f6F0kMTc5$gT?BpoB(-&c2-OU)rt%C;n=$)Ad{~p z0&u^B%Az8LerdfMg}L*vR8(&qNHaM<+eXJIqj0N`%HVyySJUWyu$x>HQuw}(9chAM zKQuechgIEf{3bM>I1EJ?cvxzVuhca1A&(0#3Fv}#rGmAd zkaNS{xs9sH6spf5gqOME-eB!9=M4UDkR^{!MU+ ztqcA?PBZ&yC>-rw%=Vs^R}Ak>USm2vl9^n+x8gm`b6yU>dph2eaSeKu%Hfwy{gd2B z{0m#~C;0`>@b_c?{*(M%aLI(OYA(81_Mf2`fu`*Kv;1BEhsneVpMO$F-GkB^DI10Z zMR3FV3HzTjvPtSajXBTAgRN)ICX$!{vQ^mmHK2$Ak{>NvLV5@RM&T>E&rde|j!wBk zy~*`(-)=3Awc)x#p(d-TLw@tNvg4pAv#_7XJkp0j-qXf06${F37T5Gwsxqr=cpTcHlbnnK1bMjb6#F51*~i=`n&v;DD_y(j(hBm)i};zPcym1 z-mJb2i|@6QthEiT`vl#%08N-TP?z0XJ*0@hrwdST*|L^3T>$L$huD=1u;$zA!UpWSj9tyqs0dRZRg2@#hn3Ug8`Ad<=v zcCQ;KM8VH`C@Z=QFfT#v?lRPdUb@&g^J|#L0xPG=A*7k2y_3dpIdJCuto6ZThpgZ;=mcuPf`ik`|` zj&FHyR{ev#FyLP|-4zfbY-2zDASX!wT+iZugfZiHaEJV({CDY}2*-X$o)ctQ$*oX? z!<*TyJE-j&=uq6nj9;F|GVfw%`nor(y9pG)0X@I%N}=xk z-fwe*(ogwUx71K(`3cCiau2Kh3C4)4nn+^?ayK2F8Y%dp6MHP;PsN&?m*C9#9;*FE z4$Hg;1o}rhJ97`6e_~|7qZ)(m%UV(TYAs7}%OiqUH6`MLW#~rmmZVHsBgW``)Gg#!v5-+BuPYvj`y(l8+ODYQf}MHfi%M z;x=_YyL?uxwyvUA-%5Hv z3FqBn=+*`{&{z4jbl!#duFB-FFBaQo1L+}++?Wfb$AFletvgw$A0VHf#>{@o3sxcw<`+S;gV_~5( zj@VzHgoCzq9$y}d{kt%yRl z)#S=guNZ^M#|ks+14W^J9IRe7At_@kr4x8Zpu&(8L#5ONAUXnIa(+I@;~XfQ#(*j} z3y`7lfs;1b!i3ObN$@dLLR}F3w>1kzT*8d8slb9l`RwwS-zqKt)9*`7?n5Jc0thaq z>xt`XXnsTRb%d!(LCvcK!7&QDHM5`$^aprc1h6&mhe{G*RuiB^#9Y|lyaMG12yxA@ z5^sJ+5UOVj1DbaT3C*K;`I#&>Kp8UnLJm)VUy!rLg{5A17YwmTmlMfy5j;+fx6c2l zZ-()Bp2QXgDg%K4B3+lDzj25zD`eS7 z8AnL8ZVBPn24#8Am6o3*F%?)x-0tBeDa?z*I5q1_ZzJzHl(ZQQ9V=H$P7tR|1!0K_;jSt;zkl44g;=cxHSzC}2 zB-O*YWsovDXqnSXaAA0_fEn<-6S>_916_>*X26>k%BnR=Vpsv3aZsgxcWmXL6R|j) zxeBm(Xp|?S&JD870X+m?NKAn48QjZ{6*5o`bn)yomLw~=5$AiRfvdqS7+n&HxMm0^ zj}Ne<-eD^5I6VjaiEJFdso_(6tE1;{h%UFkka(^jg;lavyaW=~i z#;a!~Nq-aB?qC%A{1CeljL$yLVH0}Ldv9j%q5Kr^$xZjR8;~D2z8<1vij%iyb?R|I zHFV9cpc*<*fRw5lM{usM9z)-Z_mE^QTJKM3W9kLEgG+1aA5?7=-t5Z~dMU%;WGlOu zvIBOj&R)us@$FnSVLZ{ct-I+%C}eb|c|8wO8Y_BO87Q_h`@_l@MaRFIOJCLARim~e zS$bnQvxh2LmKCa`N^hV$p~__cq$>bDkF|#?x&Fq3_`t=Cy_Kmcq~{f22aK+3TS1HL ziC7C=J}>V-dRpxsQ;4uZ!g83k^j5+oCc{sU(r@^G0mIJ!49sj5%$A)VgPi-1rm>7L zB_eTaf0}IwADdKp|5mP0L(f>>5-|&`K@pP8>S@os?G7rrO=5*~_^`Y5TvwTE$1!$`qKOQ$)siIvYiS~eF}Ca~T8lqb_+KU|*auEA1+#wHD7b0yqG!e*VG$+q~K&CHcq z>7dYzccOL#1}ddT8sj1roFHM8UeaHgBmHVNJJ(-XD3$p#Llg$+#3WV_rNCI?Haiog zM1;M*4Q8SVI4;K$g^DZ}B2Dg9Cz%s@{;w~_;EAkdE>N%GaF8E6x={)4PX+i?g6WB) zsqECOcCX53MFW(majPaGPe!?P{D$CnB!0oMts08oaQu?SHo@^~Xls84$CsTMpp5Rd zyjWLNazyv>a=JrHz`0#!^;)G*Z>G!Z%)%v3%|&E|@GPaaTUHt?(kd}Qokb_GTD*5b z%>aG0;L}L;(>J?)n#FEB@M$)Sj8^{lndKHwgYuzFHq^dG@Quv(3JYF5OmqTHZv#M< z4}#P1r4c2Y0h9a1ZJxXk}GM8hH}|@{5ksC{#NLg>Z((>B87~x|k)z zI#Psy<9~-V%`q6O>cf-p5(U=#!_6$@5hX@~r|0BHl&6Z;K#C{5UFJ8w6tVa+%7&Y; zXRjH$Df*}SvOeQW@0-!ucC_|;eQDX;r%NeZfMwIb(v-7;Z^{87pt9MoeoeDqZKdc} z2cKh`i7Ono1w-ExbdSQo^c2YN3+ZbL_AvI{Bg$lJdOPIbhVe;Q$)(tsEHnaR1gxI_ zK?fz(lY-uc>k2cr=^UX3dR%rl{*L_({plmXlD`2S5gc~(w-h?m{4{lKKl&@J>cH=a z>-*u|TB!Q^1ug8&!PU}gJg!@H*^QA$ovblV87=;s{Sc=lhgH4XAwKjwB6Qc?SBA6< zAR1PEn;GJj=%;(D0=wp4uWF((r!G*Fns=3FQj?FZD|70#pcnmpN{{U-3%}M_FyvYd zoNNC9O=uNH9BYM>P0@GL_4PhWuXp%;k7ZNK8sfpB8=bf^b{cB!qyR=NzSG=fFMkOv z?4*sQuQ!7&{uV+1R+D$*yF1-)25|kCC{^IbA;7x5oi1~# zuDkty=XRX3>rtQoRE_!~3|R0>kds zI_y|{M?O7^DGCN&Mf;ga@9)$7*tS4Y4g)RJoxx`DqRNM3-34Wj6ROzyBY;IaIkLQ8 z-wjpf09D9A>BfPjsf~!Jh^bo>EzUH#zh9SP#h`6?od5aaH(=OS&ONC((iaVga=X)j zAJ=}>G=x@yzFrVW2OGG;@6%`!FpoveF&4Z` zhMFJUTEM>UfV-B@3h8W=LQTkmiLf{C6iUuE!hisXa~5lW-v_CB4f!;i);GcN)Cql4JEZwj8>&tY;e?$2rxuz3_6W;YU) z71B+(bQ%htp-9JUL%{+qS6>(10P7OU+J-7$5_5JW5!9_Ro3$n?qr%n{(R||0)9_KW zd!MQgzZxzDhbc?33|Z|kY|dqi;Z_ag17sv5NkMqt-88iNam%aVR!!L=Rm@CdhX4S)$m=UWF;G%#|4*?$lw%V1IoXbnc)I!6}KDu4-GYX|wfjP;*R0AnpKZbo~O3o8KIO*%l5z>8YBrQ-}D&BS=j`3QvKCqm?lJ}+Ki6ao-X_J*_!YZ@%6+&HFJzP^o30fW2g>Db}P?HQ&SXRawk})nN zi`g0cCYDS?yW4CymOWr*EtJkipECLMcmp;G%kMOnE>iSjU^ZAhvr$NjV@HaV$D?tV z(v8D&{%VrSnyu)~IXvgDQpl5dI7?Wp{Ej?9+$-4%p#v-hq2_7^t;w6{gz9@&fZ%&I zUI7Iy6MvkI3q0i~sO7tPg1A=`&61v1-~u54FuH;d-+T2YGxPLtq<87z-+L93ZJz$1 zCy0BmZa_#)fv5s^b7**>K?P&m0E?v_cg-0Ds{d*oOB5Bdt!;1wi!SEw5Kc zNSC+5s6t$K+5<5GixDkZ%Gp>;A*ftFv7&)mY87Wmai)aL;Re9+dk~h#iNn2h-gsE5 z69-{w8NV|$-TzfI#~bhlgeRzEA_2v3|E_MEQUKWhXMk%wjpX-D#E_toIB_o>qz+#t zmKvFjc5~w3oO}~-9_j{XA{;LmcdLM^FL-;40wQD$dVqB~ae%$2>E062 zbZ^me^1U!ZT9nV)mtak0++|Mu236L9w=LF<3otY7QZRy(ck0Yitx;Ign`JCjMn6^j z8EKl*$Zp&fDd5P2xi4;}IrEM%4G4{L*9cD{r^{W(D5psc9UwqP0sjEtHkK;Mxfx$$ zp=5b`$$d23dznkYFiH>jW#DD<;3MMR3xkNrfuN|PyaW47%<8?A=D>woN8s=4J~dy8k=zQPKrht?V45T{O)!jZq(lb?>B%HTtb@mFNJS1?1rlmGhRS%jcu zCVfla5t-5LSz&G^W>72Gu~!O^m>HpPlwlkuESpFLO!pSY{)?;ik9FatoE)Sn&#w z<|Q{-{R-?z1z)qK71%03iZfqSUZWe~)#Wwp@{0;&*%J7WiS1N{7895I;1N+R^-xV8PCRgf)~ZQNb%3&`Bdif{?$yaEP^)DiIO$ z_n?1Aa997c{w+k5$(7hv+5mf{GU6%6A!6Wp(5iYY-ut6(6N>9|AY`%%AVgna4G!9X z=X~{funVXPUUAVOYR8(7y7_Oow5n;#DjYDY_p{6~g??b! zTKE2olok2ugxF^UuvAt>q|c_YH43pyAYjX6daqZF}xbng$Pb(n5df;)7IRbfBl)yXsb(ewPbVdgbozE@R@9NQIw>Ad`SU+#}b> zo$)jH6CZ@1zSsj_;Zl}xxV)mnE9a$fgsPz<5)>(JGD8LE;1n$@sZbUSy=GfZeH*&c zE3HM8z-z${6#5m9?PgwDy3I(w^ya~gXe>e zDrN8x`_~-OcJ8v!pVZW;X|`PfEv9?xv5koBxOEPJ+DLDfwpJP7cgA$D<}+qqtEBii zlh(1iwUBh=e8!w>K?`5&%_3g{hvl5Y3@<4Wlix2Rc(#gwbGDrUt?)nqQgk%BD~;Yi zXjb3p`Q>KbmTkWKylMFEoax>hpRwI9L4uOKmYsPCP2a$-yrc~1Jx`sP?4J5|@PRpj zB}O4?8r*82MbE*z>K+iI=k~KrFDt9T9*0ybD|&U}duAuD*H$Z!iQojQmA-vkaqsFt z4|ERD4{Y)T-sBp68$K?Sh+ZknJwq;YBJFy_V1&t716)+=BAA8T&|7ge?OkMA=xyfa4>R78XkQBlcI(MCWW z6b*%p5|fM+6%q?|QYx~+8DDxX-AgyTk{b(?in?^eqM|gT9E-Yiqb`*d6%`tF(J-;7 zNM6qWyUyOAS^QK$)O+!ym}rUnjzUgoa7=A|Kp2QVXO zO6e&ail;X$9C}AZI%f0sz2;P>%V=GQCcuXmuZv^uN)k9)*Wg!vqMoFTOutEjzLJ?&0rUL~$D!|p3xw0y(T=<0ykYjJ1b+dmf2 zZ`bbGZgAP^FkpktCD)tyu2OT<&?GEz(Dr-R>?{~K{cJbxWigN8-;|o?c-~PAVzGhY zLG!rlbOiz#j?~L*d;@}XN1Z6I^eiep}Wfzy3bYBVUL-jmj0}c)$;y60mbLR%V+ZooAGx zwt9yDL8cC9?Gu+}y5zcE5R|;hIkmH}5y^RGhQl z{ew)JF)i5X%=uhDr>Fn)d*AT0mv&PEi=K^xuf3R2=%#mcVT!dCx3NM0r1VXASx*-` z>TzJUH${t`O~?IRL0`yxt9B7qUpDztt~KPMjO&KsBx(JvuT#I>;( z*VE)sZ2|Q;i+Z6MuZEZMZQPi<6cQVEdHtfcpj-A-kliA`!+=InJsyayB;x*;D$%cmdS~9 z1UMR-n(fp8%cMAQ8w|bzrX&|pRVQWpmP{}_dzU;uERd2gXY(0 zhOMl^92T~g4xDD`W;6DEQ`bMZsMGgSg_t(#Ty6I8O4M5QRC+65-)%q6vmS+Ue*1mA z4A04T2FR&G3{h=|kfMJ70i}i+jVSqJlTYGXI`4kee8a2-`U)Y82%HXCKnrykSj>N! zc!ZAVkFUyMN&9hC&hXJJ2|LPh)P=%bdRGoh+CX>ZP=M?70GD5u!;)sxWjVtGS<+bK z_Jy8X1TC*ENaX&Hn{PG9Sl~z~-o&0*(5)eht9h zlUgrLP>6B-oyiv&F!!{MxoF(Jl%@16*uZNZhp9XJfDGH3(lZx7A$%#5?lN6u(%jU2 zl~}xcksq@%nZ%FpVw5v=A3&C4|oDr()=Af z;R!VJIlvJ=WDeb8gAO*&2TyNmiI|E&yg4`H5U_c;QJY-GyPv?qr}=Q|ljf-&2J1BL zcp8@CRd4e4r_Du9Of~8ky@c*ox@l$EksT65?J3%Xi$Cy0ugsjg8A~l^mL21;FqWir zqX%UU!{TQs+zzxgNABnX>N~|amRZM4L0Z^*gzY)c(Df=({e?PrMbWS#C_M{jd)8t1 zMx-)y>JAKva2Qo_{w0kT9~!u0w)rZv#W6o3Xh($B>-JGB+&vrH0xaAVhoxV`gVuEg z%)0xoTcBHo3; zWGmbnmI{-i4cRBqc|r$%+t6)PEFG+KGM$QPf}gg#K!*p@uLkM^dT2iMPdC%uHjA_j>@QlhT?Mt|plLF3 z6E7xb|Cyj2^O$MOB&C~}@4QbiA7$`%gq?l{x`%FiBpIo7gtb2dKlO`|u2+oyRtHuc z4>G64Ie~WakDH_0Nr;3@BI7Gy8Qp_GSgp3g6t{lGELa69r^BmsQhWPpoY?-y(*+oP zSL>&W@tb(qhZBWDSW~o3_hR;;8Z#>8RwwQktiZJe-@bx8LKZ>`SGyHfg4HsAta+5a ze=M2>04T!@U+CU&WD?FI;i3>As3=^&*@vb&N^ymd#Z}Jxlgy)>Xo&>@QXo*BN~k-O znaBp){?-cxRt-l`quwcKLN36)@hm-FhmA>(vN9Lsx?~6L5<5msX3}_SKA?yeXf4DJ zI;}y+b*-rOWHvStr8ky=2s%RM8g29zN5`D~_W05IYO$|gSHu?B5^+0FPit6OGMjj> z>tQ1@FhqvOiMrbLFdE0G_Gg@*o(bC3ua6F37b*2Fk~PG|1kpzQmMfROr-nI3oqnby zj0GbN|NJZ)tbV05G+gQ4-fIZjAdeHCU%v=!{%&ZgemehRMI>&a|K0 zVa$J5kJ2{Vf|iZUTs=xVT@yhKgKl5aITgkNbWXj-g7%DMhK|0eZ4V^pKDhQ60!e5rmF!2PzV93Ny^;{Ij*c5aR zFmSL-9qf6?!b*UXP$45z=x!Wss9-gYT@gW!yYZ_yEcOYC7rzpR%^_G6KC!&71?fc- zG1j}#uF-o_)f7&kb<(g`k)KkAd?;SZ5KSwG4rz6vL)Pz=$g-K=8pa+#z2isubT!$5 z+maKxH4$oZ#_c>K(QI?Nq2FISsnyZQDw#z;h`j|d8dm2uEWH*6FDRfTSxAV*@d!p= z@>jItp+-8ga6O%+JIakK(Bfe$xz;JIbV#h@AkJmY?~XdB;nH+A{?!DiTC^KR6Na=) znBFmOP={jeUUABMPQs4aXaj3Mm>Oz?uCk$)cQ#XHWFOzD6yRKYCdAZqd@hz+=i_K2 z`o^=b=1!)|AMoA5tI}bY^qnNTUFcz)R>RGiU_+DR4cu%&tf0c_lN?iUb+d%%l{S1c?>(j< ztkDF&viBIYuTyD-3Rwue750gxXOH^~abkFvNc0eU zpcMU~Ui9g7RKBh4Su02Jwjv^6ad;5(3aP&06d6$ea^wLJG;m*MnERTwL zuqi(w_X0WV>2dZ^@5!HIm)Ef!T01s1*=Yj`-3uovs-W9Nu#1K@%{BCPC~W%sk1Jhp z9q3a#p${L_743GVHSrOph6Dq8kGUhZxzl$C#C6PLTToR|a$QBihJvT}%Lpxq;Ig`4 z{a0W%K|65891AucZdY262o~hf*<_iR+vgrTuGG*IMp)M5$4nqH-?d6gm6_z&)I@VxOI$pHBz7EDA}&GA#)R~EJlfju46U$rjMygwi{_< zN;|RC^@!4L-HzU%B7iyn>+6D&Fw*?t7*gx1rv74lr5o|@7X@P!ziQxHe1&shgVD&1 zG62o*VlId64)22i!{l>>hYW{F6D+oQoAn!j@g12>zJ>^K7=L|+!Vy6ZXGjq2Em$5S z^|=USmOu>vx^O`7t5dY>pG00p|HN=i>WH6WFrXzYUYx#eNPjL2Hp+mEJRY#t9PA`% zpcOT&__sNZP8qORT=59uT7bS9Lpz$jpothvyhMYnfr%H(uBVtO{Bxz-`3QPJSS_+| z2%^mm*x-xK2|w@7lvvjWqklZLhqqyNKBaV6Ph!3f-Fb?3wR1T-noJ5P4t^-!bjuzZ z4wdtMJfqOKJ&qp*5#Y!B$CM0r2<|osS2BTl<2?)S`0W=Z8}9*l&&7LCNw|XT;z}`G z30x^$8C*GB1zaUu6oJJgzSN)}escgW} z0*E6Fwwah|-Wl8rRia<#7p{ateYkKH4WD<~Z-kS6d>d5*Ek0ljSI|XSi7s}8EO+N4 zFuD(*>lRnZRPNek^d?K5s>2#8s_XKq8#9H~xQw_6@w9=qGn5fCWw!7H`kkPWD0@h^+ z@@R!<(v508Y-&6t%z99%u^vM=ZT(7V6Wyc#gWH?Y+MP-lnC2qw2O%hkHDdmF2NWF| zUnneo9BY3(X%Qo z&N9W~8pBN3vhTg(b=2Ca=Be0~mX7W_W6xNY32s!n!Ur$$sEoBqj@YoZ*@;>`rqs}F zCdUs#RKk@bG~zpVe@0Yc#D$=96AlJM zC~Z3InET1mj(I~a0NA7LI6`a>=osN0iGys@&wYu>x6xidoPEXXc{(QlVIs@uVBh2T z%C~V%3d@AyO&wvz0D)k85W=KWIJiuFvwIWjok}h3+e1Pb0FEG_ zgCfd6nJIl|?x%!->(`l_Yh{z6+cF%s3qeKmm9OlJnSok0o+fa~7HR_*jzQiJD*4v= zS|4$uaNe*W_avkZE_95|)$i*?1KQGI@s3Mz_O5(XJBV{>2XMY0TSd>V>5fEZ*(BlU zE$qk9rBP3E_BJ-1dJ?+mw}aubU)%>qr69s_A6O=On&K=5s|oLjM;itSD;2GyKN9j` zAUTP*V8iOEZFSpQsdXr+&h6cbWranwR170=GdbkpH4HCs%SgP74BtJ^frT-yuQ2_H z{xZHCb^^kLz6CS=Eklrdf|6nVRw=gr7fSq=QkkOh99#sF4i)055~_w} zg<{G9HlftA`Mm)is+d=M=7%&01bUgCDcT535-8n zsWwEef;uZlfy$6ZB??u6M61s|jm-_ODp}|Ll@)dFG<4=1uPx{Hs|W^L=Z!Virn zW16<3nc9k#R4QmFK>iNoPia(vp6ZTK8F6P{UbgM*{**Yx&qw?Mln*utF6sONM#~pU zC0vz0W|GR>LSi!4E%qqs;u2A4di`giI!Lj;{`SsVsE#%Yr?Cdyvb3$PzXHE;1@nv~ zNy}<2A!ZSSb{&9%h9rG>KyktChATqmO=we**g0bYp#>l~^Y|ELOuoBMall5v=nt3F z(5P=MKG0|{0wcVRTyuDI#JN#MAvgPKV(0d2R zw0_ALVnoq+6hUts2rkTV-}}TUGIWj{+nR`sfwc%EmrKHh=FQyLWX(gZ=1|@hPqP>c zF^hq7Fa@#Jw+bqg+2}iXV*(cU!w>MT1hZYgl5#Lw-3{ho?wW5N5!PpS{DMOUBNoss zZ~+vyF67vq*`cRjJKr3!#9*2YzRpfGq!NGQcd+z$#gH7o#*owmE0ffT<7=ehwE(AO z4XN9!o-R241p4ix=-55bZ->wTbm4e>OXijZ=5ap5sLE2bv_zh|0NVksy;0kN%YRUn zbQn$;XnnU+!*d}U=RwGBxmHh7g!feEe*L}JI@VA^tkGA&9>qkkyo&o$_E0fEqBoHV zXQEkn;sJ2F6F3+ybSeM!D)UI5FxUM3Ft*;hZW|`d3+k(+I5x5+@MsJ&>+=!IfNkJ)}VrHB&{7sI0YjV$Dqi*cIEst}pDEYZZ< z7n@g29z6+5Et&elA9m`bKY`zOXQPMf7;WT&Z5sLn&3uejxP6H^n+GKNnhqa{Gy5ur zQTOxucysK&tIbox6klXldy%xDw=uX3#o*F_hEm2;5oYT0{Z`^a1+)+>wG=JyQ_MIA zV_r9u-syr|3>+J0Gu$SkB@E}4S7Rxq?<{Y++8oVmm-x-}$inT$F8=)zzXhH+)mdm- zz^_X2d&$T~;+ODJ{IIH!2ug6F@VdLZB_%L4hFzDw3$~yO_1@oqk|)nM#|B^xB^YnD z@>$J$t>y{C*kQ!%yjX^zZ}ZsM<}{u=$2?0_aHGZDy9Yk<>Nz+qq~P%UAeNoXhWcQZ z%HqU^#l*VHr+5_{s~-$&-#6DB;ThD2K~<=@2ex3IdHM*&iZHmmLl**3zpLr$=n&r# z!<5;Vd_#Q(OylkIu>Q9MzxHRt8Wr6@VKc{uIChRJaQt&dfj&aR;+RwyHpgrHy(Dw! z2xT17sr*eIbO}Y8Rl8T817}byYXT{)WzI-qj|dTq6bO9 z-G+N`2=7MoBO!AVK|#Bm_Krc~9r*5vBcw-o^h#`0{`ovnq3?dJ*y|VMgzZ9e5lYDd zrLn}QxbduqYtUQp|MU&x$JrLl>EIYb=wc`)L-16m%R(a#9Ig%ta;;_2lm_l^r4e{5 z-4#IZq}wUpvEy2|<<6q(ZB{UCntCK8oN{`+tU+KcF*P8vI$BcV2}xWTZE2aGZY zLGNm%a3$RCk6B%PuHdT~X!P1fq&ZYfVkwO<+q3kI?ohue+GH^USI$!RVx2|rT`N!- zpvigc{8ZO=rCvYL*Z<2Gj#U?e^fcD8NTd;ZhoZbA^u5* zdARc!&9h+AR5l6y1fE`CEDG+Jqcjv+!sPEf1X~>}IW63cT3ppWRiFC8G#S;T)dz(g zqbJ^o#vYw-u<0`hv|tCru>sN@L(^%b`LL-yhO{3s2@G;ZV|8yTs4BAdV_QWbxGI~; z4&2?3#X6ItFAfJaQ`SHrqbXBxI$B&^f%Aq4PYLO>1q(lYwxA7F8G~U&1quQ z2_p6C5BOCgJ^e`67fQYL30zpGO`mZy1-|lOP~D@-#}?^Hq_B=c9*h!vEMn{$EwvG&DO?^p6P7@S!*{Bo54YT0ft>^Woi5z(ghSaK z$9=qc^(u4t@+24%xD06EvwCQCib5@pf@^bbJTrqd<9k~zG6Wu-Uzl*KrFokr1YP=n-{GH1H8uYs@3MC z!}et;r;vt>=)y|zHMH?Gyi42mH+TB^ZdgJ@0g1Wv!ljm zM~}~*#8R)BA7{BfXYCyu^0FgPE+sC=P0Gp3L6Dq+4O{a!Y+8RwxM<6|ybbGa!~dJN=2-GKOFA}h(et%$ z-mocuDzebEh6Y{Hoq!5{Fva|IP>jZ3_Y7rm7xcuB4%a-Li*^)E_6_n{8 z1R0cAI)aHD@7j=;XIYy=MY}Vnz><3hUN_%jS%U{M8Axa=NZ{um_X<3G?pyOvZ=QC} zoDit9C3(a8+&s8^5{Ic=``$cF)c<=6Jp%YG3q8gj{_vdnq;beHRKmJ^OXB*RP5GdJ z&t2kiC4aul92PFVAgd$@-Fi#XmNj>=Wx1R0vMkuVWmC=;KIA88f|f4qI=%5H^Oer@ z&G~EckixPx8|{#*1)J~C6BM;Xj9Eij{8nJM|5{H3fUK*5QQb`$Ob0_2;A9x*H)^Cb-8Oct%u}*pCag>uv#{30*g08s<-Gt?%I%_ zyZMfMi+xRgF6tyZXA4!UBt&P;0CmgK5*I8)6TD;7m1%44fLw0fuVfUo}5JeFH8m>nat^RLN4y$-}*xGDP@ z$UwH9*_D5k*_O=(8#Zppzx!(BCv&rJ-ki5=!?qmW_^UbC6Kx!#d-%>?oQw6Gk1`~= z4j=6|PxtV&WkEhV`5B{XH5l9ZbA{fcc#cV(7>q!JfAegN&6_b}#=Js%<>6wJ`k~1Q zME_Hc;DJpCVM%x@4fqeYdxb^OOAF@p+VDb2nd<33{A;9VJ3?9Hm*M{6%kUsPhhy`* zAwzx{StP!UEWvYREmDk>UxHg=#iwAT&qg6#4?OjZ!jQdA50Ma-AYYQ`C7r)ERGoU* z=BqyJ;gnw(ePLN}NQC9WVQNvl?53AeI3kcSO*2xa{}=H>2jV5dBg>-L2rQ*+k)aYp zZxwL#V!@Nu!J!BW6+;0hbh`B1L-1n53L;4IZHC{soj($wzInKMsJcqwXMEM5VUaRC zxF{**VP5J4Cq)gC-*l=dz#w@O@j?J-5PwPXC7)h*%NLyn3W~3ao&o#{h|y`Upcnct z9ZvpHy)$K7+V#9*g6bW#X>EYNB0eSKVbLx;(ZXW`)%2i^7Y4sj!uV1f!^;EJsfJoN zZwyo?8(y^Y?m#syV`JQ4NMaB|HuvI5WurgBVlTspie&A=8>17O3Z9@~cE!-zpcom?gu-s2?n)4 zmhzTh^}4{^IlZ zdVfG9zI&zcqxmx^r9e9VteP{Yircu&)MrgbyslfY{h zs#o!Op=zLC9C)VIP{4eCGF6QYZB?W|FpAQt^(;=Jp)`fq#ZQh>0h-V&xx4%rlm_n=D>rte)^&-zAg35QVR z`t#Iqb%G%`i|5mGLn)Ajsff^zEKZUIRJEvKyCzT9Kd?`t9qa=DEKN$x}SezQEvg8Q^%^K z0<*>p&_L_~4TrNN9}lPLd^8-k@qn9&v4^9%8;ms^#ywI3F!4?Ro`0!B)Dt`{3FD9c zLUpK*1@CQIPjMzsh)_q*M#_q}*7H&s;7j>NIC6Zc^bc?=@Dg4Ufr@;o__FWdw}Ohi zKaF=rs1wyvt!Gac#Diq(+n4xrtJSfjQF>mA=BeYLLKM`^-YV`Gr%v=icBMxUy@I!n zQ%4W?S4#%vmLx1)>)8j)DT0n)`K69 zfPN%!1c4)lAq^t~o`Eca2_MDJJ3x*xM(Zg{;w|IUDLyd>1Bre(iFY6$Gev>Wy;y-L zHl8(I9mNYHRNrB-z#Fula@4k|8%cfR;J0s3L;1q->QK)|6BzUB;`SL(YL4;hL~6+< z5MSMbLbT#G6LkWQn4pgJsnmL&%|pt0JS$Zl&cDb}ea&E>sR=n&f%sDHzgi6^noPY~ zPmPOLk5{J-@c_9mA}N-vOF7>&K^+;i^0UF_iWGEFY2bAeAn=Dv57`m%WEWOb%jPhSNXQY0fyp-=stJZlPl(!dB@wA*@vI+7o}UiH@b zTBP-wh_7`#YdkchHbo6IcqQ|oXf-i#`4t1rCloO)TCZOP&y5Bl{>i*3TAl1Mqzv`Q z!fFD;|Jo@ar-u?LwVs;b=(!#UsRs~BJZ4FJlo*tkLoB^>rH6Fvlt^h5<`}y z_0DnguBqrl<~Ac|f9}2py(q=Q{^3Q{Jnc#~#E_iM^YFwqe87`MM{5JmLbcv&Pw<*6 zRs4Wu7Z{StNRfy0;21T`^F}bh5KJ06g0G5EgFROwh^d%>5WW;t`+y!4i4B0unOT^o;{1}Vs^=h@TLn@3(d*pUgr>%FHK0a1gwupL;c)_YI; zzUfe~F7QgJ2CqI{EVKZt(t39^@XYBDp`Dq$7*D^QRH!TpG+i`gB}VJr*#VHa{Atu+ zLsl}h-dz^pwSUiS}NbBC+h-l#@vCsku_*9|w;&;P4XQ@~DP{~{I+J)JbK`pnuePF!UZ15#8=inhpQX+<)G{7(6(T&jn`d7IdaCkx z`BiG1=Tnq+E3dc;?c>L*)NsR7^*qR`UT=81jOSVru{wiSS=FV6XM2h8D@h?jllDGm zN4#RN?8966?Ahv-LCGP5m7a!AVAAsyI01u{UbOP2*{H9>S^MH(^1RZ-v*JL(tGjtw z96rBM!aL&d`HfB<8V?S^tW1tqZ9xk!3?^t33I4O1m&c>9Z`*lmJPP}6F^sOHeXuwA z+yph!^F!2zp#<+(JWYUc`w?_Y0!VM(jWt$viQ%&vZkvPmmJVJrN4?(jOSB{f_heYr z;C*w!o7My#I~Tg>WHYzVh3;xg;tg}ra@#FDV4j*DJU?uZB5;9<_+0~@ZQQm_9mfyO zQ@sow*wH-?7Q#840mswx2O=qf2SlI~7;aOC8oEk&lnnv8?L5t1hbyor&PFM*@$UuioOPk2Fsp!oL>r{qxnah7ke0Za#X_5pL*=dcEu9T9WEdBB%6f zeIckr{3x1b0V-s48Mj;yb)2;Tnk3ZD9ShV&eq+(-)E1=pb_{=aftnXMXV84J3Tmg- z@U%=+&88%%j;n0|v-I}u%ZjwV8LfD?bN75TVhF3%`eLJyA6cIb)A^2@)Cl@5TGp=h z&9p<@8usO*S1g~c`ttb;)lfr%m1iwPea_9~)eBLd^K*IcLiNTe@q?;cGHeMn;&1H1 z7`$7xzC{VVVv%~KPoCCybq$~b-kzsM__8v*_ks`%F2dB2Ap@2KRd&7BhYO6*R6yff z)A*h&Fl5Zt>gb@jxr0IxiSHJzFC!95xv2Xk-gw{5OR~_!@4p&#za)!STn+h3ZR9No zU|3qkP08v~&+9v(MWT5{JR0qLx1yAeWHl<-`oUnrHj(fOXm!s_VNACsqcU!e;l0Ud zqghQnVKJ(GT>#Hpj6u^a{;1U$*;Ou9CtZ0};eY~@oY|6&Bri3ksf^$Z&6%Jljas6P zn`Qx&tM%R5h-a}0|LH@?05$F4poOImqKmb@+hXw%zw$}8&b#@-)iUJEF~LT*k`$NOy!0AMFz2A`t?pj@Gm z*6U+QR|ka-)RGv{w`hHLAd12$#H>r|Y36?ovXjb+tnWO+TT|58fiq_h&?G-Ni+FS@ z*y*g~nW<g&V!dkazaz-!b%&*EZm-z^4T z>i`%Y=;a01z=9|#;$?VxmXM4^lZ=I%!8oN^>)Qj!!@{#xpd$ff2+;a?2@hRL9YQUF zWb&Hv>KJ~HAtJ4I5$2c4~c(ckx~X_I#oWc%FVOV z(A=uKcy$_5IaJGA(~#;jQQZGJu<4l=dY|Z%sr5aZhJ>rg<{inu8?O5E2d-1SJfEdX z?GpSuMnDZX#9&Ae10V+;Xy`Q^C}n}J5IjADw7%yt(7Ya*z2MJlu2&~|JcULslaPBuU-yvKP=|W%Ta9~g1=CO0m}sGzL3NZPw?m) zK>CSvo^=B(pc5{bh!z@YC-C|k)M1`qrXmh5?OULZ=D*y4n*Fkwd#^xZUqWs$=b{S- zhSoz3U&Zju73!?{t-vueK>yQ!k*Zye_d_wxsM7jcqk+Z_e)k{z4sQB2;Jb|qF^>PT zLLK7ST7t@H=QYdKh{^s@THh%mCt)yhkeVeEM`ZtGe9y&qQAF;{K!u+w1<+2dJlvdy zFd*P-JiS^k;pq<<;OUtb!Bcan*7u#a;HfzQ{!qcwSjNnDyykJojc6O+qhc^Sq>oeI zyAfSOR|4<25jEHaVOR-{b`^8mO7*%0ef_PV;8K3LHVK-+4;AES{`h_=KL);|NNNMV zTO>bLs;XC?W=GSDp?pJm)J>>&B^%M}^-ATNZ-R&+^z_c>C7J4+z{q36Yxyc+buOy zB>+$cAlN5pxg_68g4XY?kEwOb6l3^)?-M*=m3pN|xz_Jf!;@C2E2K@)ua@g^bu$)m z4bfWvtXl59TAesM177N@qb?x=L>uhD+kszN7>Zh?^{Yjw`UIY~7OKX%TJ=yO$-?fZAhemCJrVNCB`7Fe|RcL*VWXhP?up~A}kUgleGR3^~jKh6VKek zhh|}hCJ$IIFd9ufbNk?E!dR;Hk0g#Z5Wb!=i}0yOUad$xl62rWGd>%;5DX<(j_}S% zH9W*EJI`2@DoX1gWr3DRr4)ks`7D@n5wYB|M$HTg|9G&!LWy+&Xy7Gl)R|Ml2m4Sd z8Ov)Bpyao#LucN9Llo~^gV`L~qJ*iogmsX|nysqmgonKM`;_@|KZ@e7x_;Z8qge5j zZ~`yMMiD4;lq%kWqEryO!&kzK8N>d$rFb3z>D9X^p!!YJVMJc>^9j@A74 zVNe?i$eecs&rAyQG=G0BCNXVzha}nBk!3n*h)9c1qBK4_2Z=?>O10L%pqp|KeF@|h zooRoP1H8?rxs))zYP9MX>aW(wXsCFMsQQz^F+Xq0GJucSg3;H5W4Jp3MrIlsQs9_L z15Ga!X`|_7`18(n&?*_RJRn=0@0p3{FcS5S_MU90<7$6ioQ=l3DwWq|!@^tbplO$} zd{hop@|sj0or9s)+AO42EsUg>12GM%G-&;6TL5Cd0|Q@QOl$S8BZid?&g~2}tSjZ6 zIqF=$>cuLJh8459M%SC@xSjVgI^epUx z)rtLN(dukIbOU&`tCmM^KzZ(M1v67&n~&ge<5fR?Kc)l>f9m2D8!)!|D>&_$c1fm_ zZbhc0HlB7XNZP*}jThbIt?Im?12fU-=nrDF{zr=U-KMTtF#L&uIv`m@9UOAud8r;C z9MW?r?+@@a;2A`oh)GD=BRV(joeEd7hB` zLjk}qpZD~ZNnDCYqe?*g6OeG-s(t(bFU(WN&wtVcAd~*n#rop%3}{pATK|)_|K>Xh zeF?rhc)&)?2GDCAUU3icMogDH*@b9iZa?-Tzx_IO>=2UmzsCTiDb2@D5*X%VLA50V z&*kMCF-rb>5qEDyz5l(Icj`|!w`_tDQbol33n9O46NLOJ#vPjw@Tq9s?&4n4)S*Gc zA_mn|F!DiR|541lH(^!g%-{zkL?5c#c+6(RKZLot&164j@nSqZpUK1bOjDZ9GL^N1bMx_GNywHW?3 zVc+fQBudZ_sr4WAN963wm`&eo_?FJoZbvVDw3_GLj&a-3Muf$b7FMG;pMWwBnLk*R z1bjkK>P)=(c68RS<@4Yz>hh85{sC!~Wj&b;N-!!bP$!Mw zHg$|w|9^@RMU13qgm1{y`u}qTbVgnr;Xk%b9c}DCSHj)fs2t}g#-&XPyu(C&|G6UG zDFW=iEC9$hdLw{~TkgTUO8>c9o~nC(@aF~hs8@LP|B#C)9b%O7#ywaaJ7xkv?dG8r ze)1kQ)Y$(+?>+}~>ahUimZ2LNLkA3K3ksd8_5Wz+*$y?r?>I>jnG5@0=6f7!B=)_f zgAchpZ5#%KA34;aes3U%;!i<7pjq4To^Ny`P8rR*=%W{pSgrr9OrBbZCCj(#@u`x+ z=J5Lp)k&U>v51UcU!kG({+rNicrr;be$<=4<`$b@Srwn2GA|!Y$p~)tUbN|3+L^4jRga@V@P8 zB#=@dr9gNezrv|TB5*7%osAoYvU=re{r_&lh$V&s9ODW`l)OI|6C|%W)sbEZipWJ` z@S>%tA%UKU23iXwhMLm_bQ)W*a$?16y4K&*g(n6AGhnY^4Zu9|qJ?6^7wErU&|^Zq z(7^kVQL5*Fec-PS^d>Oo5%h$nu`2Knn;)g|6R6Ma`fHj}&ZF;CC-F&FAOi%|rw^1g zO$(&br=uwQV&n`l4!#Da0wgnS-xPjeraIPFsnIk8>J=S&#kE*bQd;p2s<6PKX%C(j zF)@tS3^f3Y2>e8!vY!i;qZ$2C%b^5*KvfoW(D;byfJeFKF@rR8E)J>mf*A5O%>=F} z)!cQXIyU4YLs0F8YE8qBr!k)bq{X*}fcvXrVFc97Reg00;H`El`if7m@yS6=hS~?~ zwP7TicHXiDrk)KDF`xiY0uRMh8@J?R{-VS~#=f|EPCP>FpmGGY@`SAz*HK-jYT9t( zcP)>+1M7Gc%B5++xqv_#P1oqtL)33EP#scBI|#;2B0e^2+UQU`ad|ra|E<>V!nfTN zh6ij_N9$veP)!S^8iwU^ojQEMfPJU0k|@de*o!=a^|S)WEInW>H%Z?5t8Qrxf@B4p z9n+4dgJyAq$UeqA)}87Qy?YB*whS_iXhxAOL3rj3E-3l=QlTxV2F!b0TxBBe765NX z%E>hSJ6f^to2CW_v-d7fFtQ$DWA*M&X9SX)&WA? z`EXTmCve2_5*aeoGsV-+6pv!2tTLrC#gqn@4!{H#375na-xgpQaG7||hRb7$A9m9F zRl-%n)xy=m)icEliTP5C@Mazhg9mf+G1 zC^c{uaG-Tz9UQ_fMA;V7w=TF|ghSGc0^nld65xX2QkmCtglFPu!ZROFhGz*}Df2XR z6DdySX+)-RsW>6&z^ThTrp$0LWoiw|WP*!?OJa&Gfhlt*4J|PCG@v3 z!}1blNN;3@>+Q_2t{BgPNB~jrlnGjwH>04P!hcVOPP3;+@SbU-ohZom5(#85!*Oy+ zI6dCQ44>pN!^fbk8Fz?%63Ps1C_#%qGkl30j^#4L7rRA*tI{uF1Tm&XrdP#`Lyj<` zpFf_h%&0n;(YK2k%_d-(c&}zgrx~Ch3`tCp82!9Of>{BVB#0{V=w!y}p>W>J7>~rJ zwZV1ZJ&74(Gnmne#AY-C>jj3irkg}M>k59Gjwiy++0Bdz0BKjNc?MlOghd%;-0b)ei1Jcs=sa!t(Ikh?ck!T4SRPu94^B#H04VQ`Uu^3|Qy`wtbBVUsEF8%=8h1^Jb^A!+x7UBfjuyH+qcZaV6d(xcxhiU~d1jI&8$qBg`}s z3=Kw22g{oFO@40LT^>#aC4CR>JN(wIKl6aD_n3YX?pC;;na2!#pWy*F3@#jQ8r&?n zMQ|(O*23B0?uNS;amw+03J%S7#+PtE!SyhYSQ8x5zz@K9#IArtoLDFGm=%jiv3uYS zz*WM%0CyY?RS^3j68t;dU*Lu_ulJ!FrthV9URQz{q3JKd|99R|qE7JDaq%s5&%nF* zp1Mb!I(K>)!p_0fuOMvt)o?fCy4Mywsh~UHmsJgp>xH1OsjcvX@ae<(kv*8#o#r^) zyhoj-POV;$tycs6S6zAwE@8T6{sB}5`gpyF{8BYO@XS_3*vKe0kFkFH)ye5#q3FwBO zxk`W&GI-NT%p$Uhp#ZNJ;KWcK@HFzCh+;pJCov1Jehka+zWS_?`f#*tlJ#kW)GUelNiek%uRW;6XWx>3BJLC6uW5w;JLyLrHB9;8#eHLZ9_kspw8O}6wSrKYfeeI9SZWL+%9x8_S||= zz=fFK?IwQ1E@sc|kYLLI*bVSu33hXr7x8CNE8my~U7vHQAf7=feb+?9FSRRHsjUe$GX5pZ}{QH}E34XrJr_vxt-0Dny3b@e7j$ zb`6&Dhf;=U=|9PI- ztWFxjXxHgsS;s4}sy>P;{-zp$J4FgN)o_b0rkS|_rI=>s@)lB4Hx~etMZCE{D!Ek_ zEL^H0_9_e2dxQ$BoE^y#*g6CZrEGG+j3Y+`n2XlXN>Xzhft>=pt(!OfNMN2nV=qe$ zo990OBA=H-MaVoXF8)IeS@d#@kgr*#`1UvHM`>RENctNXJ33>6iDYnFJ^VK5KLP(W z6U@LpeW4wx*&oflC~HUG`F%Uet7PnzG?{-T&#PC*2C|JE0P_W?`(NeW&!`a*bz=kp zRuE8kyUY}VU$i4(d5Qjm~aeo^xA+7b-8en4t_SYJr$sT}&x)TKUK(XGZt0ghO zWY1U{OSud|4?BQBqvSmDs)C^x@#_UY5^eY>H8ou{7RJ*m1D^4R3)R&*Z_+1AB|Gc>=>KM)8}}9R3L*cw@T& z|Czx{zS6-0fYPq{X8}(;Mj*x+?2R)bWCMP`6xrPHFEpn5DFP$^fMn>W1Epk;zdlcv zxC#DR>2GK3O(y*F5%tYf>4(WoZRX8=7g_OU_wS|Q9ejSvA@Y7FThwwRYV@rq1lH)y zD|E}Gu^iwD36}Hj7r={;ni>0NfWSU#=25l4+KPZ(C$P36o=S`?Ch#M*#GPJLLW4}OH;wwTkhq2jQKAKP_;!o*H^TqC^tZwPt84?YjJ-Y3Hj)Gf z-o|Kp;P36c-*ccB1$$dskiF%y?s}2gzkCICy>$a%3&3#_Y~jTx)Uhh-s|1)Lz&^ft z=n$B>{rSNDOJM!^Laa5A`LB9`;X;&{VbBwbQqR~s9y$m=Z#<4Q2=`0sh^gA-~U$K<8N zAYYBUWjOSgdfZH4LVz)u$?at7D<%-u*enBLb(IVg8dkH$9szn_L4o9-<_FokqC0?p z089dCl_8S`K&1JuP%D@*l^J0gj=d}F8cfLzge(SlpNx*pZbYU>H?aK@>*i_HInpdG zd-o{;dfG*KJW(z0zAUkP-tZ10dr>ZL3(PA|gu|pPd-qd`*~OSb!5j;F_a_M!@$93B zOf$FdjS`qI&b?spF_ET!*?Ti3NdD_~4~QRouX?~w7GxmJHn4vS(_Z*7+IU5stYQX& z{acpZuTp1-N>dW--+vMb`|-^NNE%I1uzx=(v0BMFOfIv33sJ*F^8g51|9wh^tRDay z0csM2CH5oQThnmSt`-L4+LZ{|t{@#vGbhlf-_wu_|9t63qD|LIf0Jl$O>46U%iHw4 z5Z!4#7e&{v6?Zp@VG8E4xr>Z*#Xkn%)q)UzY~>c93*e0s#Gyw4HUYdn4?d|#M_x_>~ehE)+UqQfQs`;Ur3I`ZIuQ5L2P{(52RVq%=V|CRKc;O~=u zZ&Bb6E-`^W$p3wTqru1zWaEeqCZ!gkMuSHmP7nk~XY&%muCM}IDzGc8+)Wtf+S!M~ zdcnLq?<5R!@a)3_BHRot`yT@~vlQ6t0-K57OeJgi{-gVjVny+7#yd*$FX%!rZ@TXS3UZi2;-{yPex99M%Td2{C@cI)P|DacRJWU8=;T z(P%e9rTN(tV)&%Q=ZbJxPhclbi+tm8&YEb!Is*G>sKDk{@R;Mku)e@PN)nhYfoB05 zwlEf$lmgxV5HCHBhI3sM@E=6j>!Nrs#mAZi`&hQpbZ;L0IwV3u`*#z({c#=M070h4}flfQgyFz4}d2CZj;eZ41nzb#pDDQPskX?fF%Z)teG2Q zxI1jfSd~^-*eC5G_DX(GCAEST7uM`Au$xT0!f!~(s^+VNUcj;qYhEgwOauHm(%%CA zU84CIk!JH>rN0sWC#1g_{yO2uk`HVCQ2M3q+WgH$-SO!{*;fx|gWcXusf>O4Pf1rQ z8D9}6T*fNuO)+y2_nH7wE<|P7VLXPHBpKx;!z!(AE93<=V=1_o(Bp5mXMgq)~ zAU3zs%#Lz%7Qovjh_fwJ!#9K8&qPnJ+?>s8Y!q-62>z^G1YE^Lz*XSrXU|Iv9Ie9G zL|FyWKYK@lGpymMpT7?(ELdB?*cZVf;Mxi?Q=zPb0DK`!uugWr>+*p~{k9HP5zSsG*|`9Pt9u2Q zS1ktZ%0?9JE2$+m=JH%JH#VWAf8`bdHm(6y>wu-Ol>$nQxm8*UTWf)>lL28Vko4vU1Cz|p$L4+AY|FO- zd_)Ayx6;&6gn9=U)hdjCGr*xq2?P8iPy_J+WCHV;yPVf}PUz{X69DYbnXt z_3G9utBOLd7a^+#LOw+yWsm+;u2geRRRVlSgnX)!H@uI`|IrKV1%dsem)lN~&_BH! z;J*a;^lqs+pDqR{+uYN#8+^J1m@MPdB|_*Ap<3Hy4|AxFANc^eJd5_)7AX>Z*2dd` zIiEw$ZE*r4|9}yv=zd|uk-sfnsJ}F@uI+B=Pldlx`t#twApHf5eG?}Ap!b^vq6aGk zi@!;i#+^U>xf7=76Qa-4i$i>PF&h2{g#Sn?{0~ciny?1HsY1=mzi(BkltvKYV&wKh zH)G%K69syqoA-W*g4dz|-##a>+FoISy;uxPYK0ezx#JCld#MUohY0sl6%9Z!HDYJ% zKW2d)w)22!65S)Hn*UrOz$3eP2L(K80=7(GM@>?Ij&=Z)t?+1vu)$ul0ILxJU&Hkb zA0hJVWx%BNeZ7oV6ZU2s4mk}I;ofZHErh+B2Ta;f@8)s;kAZz24NMNPKF8L?kJXS{ zPfr%?UxqYJ-y!|r!s(N;Dv}vH6DR!;pEFlWe+B&M(q9ArD(UZpAGbV!&tAux;D1^A zo4NaAObC6IjW6QwyZOKGDZbgw*mu&d_+~fFf`EzNMgf#P#kWzi{eO!BekT?4w-_&? zA4f<~(jgV|w>3ibd<%WsA*YYTqRic9~=nKhwcBV2PoCYe=ssTL#9D{ zB|zDE=>9ioet5Ea+8@8DHD07}8tVf3nEZ4QK&kIfV**@&kpOR&AtMJsG>@})NibHZ zuhT`qUX>WESzW`P1{2RptMGJ_1kXUxeLqr!JTuT=oUsCwYVwSgSAcv~IfF8Nf0GQ! z54v&O^-KdG*>Rp}(8CQ;zDoyKD#Cr2&X1&#^kS0+`~E`#c2w}n&mctSs)6+g>>RA& zlf?H(p3&n=G|2;n(R-Yu`@~p{Ha1;4^n>40w%k;pR>f^>gN_S({lGZ1c?ihfFM9A(KT?~dOzXkyON`SxOl)EmNzt%E#Ud|f)TFaBZAYSw% z&GU0a$o@#4uY($@_WV5p)NmX(6&V>6@Z!8^-|+K_A5m^2*n7TH4`?vLfT6icgJ&ya zKST)7vsI`TgI5>8Gy!^b@$4@V+ZRIl!+iqt_2;F8sn8fdR0&MQn1-avFa#C$gBT>i zPu3p5VW@{6z7`>e<1N&HD)9a~eV2%KBe=!McMv+J_HUQXUfyD;! zm{SOc{R`|D$)i|14W59ZOuyVJ!{HE~jx_@Nv&0&yrD4v&1?(RJo9Pnau$PYg@-K<) z=9aG!4twg@FJj>X`|Ehx*J?;a_gGQC*h9y<=gL7~2K+ZkKP*(5zV0r#$jk1}Wxaz3 zvNts(MKSiPXkPI1DAFH>MOJ`P92Z%+sSQLdLE^s(3&yY{L!Y}HVo0$7JSnJ6vCwP* zVlPGN7et2&KX(tOB(JRmC?@sb=e9FQG7Y@DAVvpoR2zVXZ<^?ezgkNYM!}Tb{ z1=-@R&lWozXqzCr&?qv$-Yzsb_6!0PJv{tEHfZ}`k1&<6l~C~cdZ?rxF@I#Z9=BkS zHE37{=J$vJ7W}*hTP{@WKV&_(iCog7B!6%-T& z5fu$Rm{itKVWHdnQ#g^LQqf3(jwLCTGh;JOSy9;xO;l9WP?D0F-tV)Y2RPQWe)qT5 zU3cAe?{&4~v%mY<`~Cm!cklDQ&sIP4NCIpmyVD9Xyul|E-|C~ge}#MbDkSLEgRHN@ zGJXmuB@r6Gq9OllM&PND(EiGHsgZQ&478-83~zld+C?s!RAlch9-FwNUNU}vb=`ypCMS3` zd;>H%rF1Cx5~xjWLLgN zyX4{*d%FIPdT3J9chu`0siyC2gm!?#+}Ws)A#GO_G|7`)QFwZZ9TLx4X)AdkgfCe?xl`>35U6(35_80%-?O z7H)ZLcOXvBC+(08n%oHw*?0u;6w=|wgCv)y>h%V)JB++@mzH$6RQGFy_AJW6orfeY z&tB4F8u1?I<+f~V@B8a)JBE7J{vb!;SS?R`aXDTM@eLM_2IKYa{oC*z^bW4n{_dKzgJiO_f?3fE2gLDEiVKs(QNr!%B$`eOh@9+J8I zF@O_)rWvzEyR+e$W<8M}xn1x{Y|Uc^i)TZ)2Rs`IZLw&Pq9KPp(nW(KrK^^1b2X10 z(mr!=us}E${CnX%@JV4*1CKX^QLG;CO1q_4)iGlVrP1^}uD0cM$5?K9&Vv(7Dc3rF zAdyMoe&uW$H0jFE;+coKd`wT*Jo~fVYf+pKOk3AHCyR#3bcP+y^;{-enrKLe=Qh!D z^~5Gz?_3eIr&&8!#7(q1AKFK(Rp;wfWcP*{+I806fU_^sFg;$g@Eb^%_mm#+gC)@S zJ;cw#zcacR9G53O4$a9y>Add)gFo_x-p8{H-P&P&4L#Cz+%~?y3CD_ z-h9K-X;7!`ZFQ?thP2~uZQc4+G^bAAam2BnG=Q@ADl((9Wbf5{(Mq84W2Vd15-x_T z&Ctfkxy?L|!E>3`If*qqm(}8WzSqN{<*;V(W3A<$OFs;|TrY-!^byyKx!kW)fO3Pr z4o90mB4R%VDb3!CFZ5%OUiu@I`>h6ub6LEF*CjML%jGuCwo7%sT|#efdRa{h`Df=s z2J2&Ppg>*7u+BK!MC|RRXWT%6x|zYFSa&n)C9t)0NP)(03QQeRXt0hiYu&)i0PnUD zvF823uNtta!v&>vS;-gcaKU(IP3t|hE)R&-MB~pu3x3Phy71^7OF#5W_&M3)frxbB zCkZSC5zSp`UHM@XOG89MRqq?K5Zb6AQrF9!FEd@2U+gxE8ymZTG ztL5FQxd5C7FD7ff(tM*N(0a~nD+<83C2~>#HWYww3ftKfXP7M*TApaZdPY}kU?&?= z>#K`K{Jb7=8?^=#NVV=7>zy&s>4J>JW3bk}vuOC~l?t_U95jAoWa=D8KXoDtz2hPB zof)h*-A2iDYlOxxXiVK2_XOcwe?Lfv`Fj3-R13Rx)w);8tp<_l{uk*kV)*vr=hBur ze#@l`z_Jq=*_r%No_^8<{B!nPL>NIeO6w88VFcCexd|y4<!T zglRyqo}j^Q5Q?YACu}z;L(kW&zH|KL$#NNr!Cxj!ExQRm&BeRiuC$(-Fxq&}S;CRv zJ(4nn-?QaLi|On%X6^YxTgn1Fe%cwV$Rdc=d)0PP*o z8tAngG{i69d(m!kv0(|7){7rau$)RXw4Gk#*lvil&mr#6l0|dZ3rx5kmT76daz*nK zEfm@T(LzOwg7&g#a2#UAxmd!b_2Qc@mUHPgJ2Wis(gOJ>6D;+jpGPp0AOYHFJ~ski z1tM+K1!(;C*E9-F9+0+9SSqFka_>mX#L5G9_r4XnvvvKzmTM0MSq>f+|D{;zGj` zGcAZ8aIxHsekd`fG-!P~ikZmgZArw3Zb=0W3EELca!ai*1$eWW3b#kvZz8;{1(rLeTQ&4Bq1;QPT{=A@*J)2Lg551hra9D%AxPMUpMVYT)W>y z4lgoGkENSTor zPqN*F6g_^r6$RPe+I8TWwzvg*N!)rUq{8^o#WWFl8~iw*HxVNRT&vT>5@<(7BYs7X z?qI#kG6~`K=Z7lOBzKzB6=<1+yy?$xdrgxtzsS%cph+E@6v1hm6a`KC`AJct#X?)l z;Y^CvBRz1vXgf3>7n-7tnF!EOKl}45M^m&Py(xy41no6GH#&)4q6S)~je%Cn+O#ov z^9<>x((aPGG(aH&YckqEtBnL z;9ZcR(YX@k8F;hj3A-3%@Lf-_U5xZmF=l8lh-TJv4ZAdG=R`}>%SfAr?7NE}G)%LQ zeWcB%aBs5R>|ou7xhR%+ggYRRwfHEq|vt2?X&5ywB3_4fF zAB)jcNLx|{O{&6@vc1&htw0tGkg?hd%wi+6q#S5fe7U3?dZG)otfW)_#oEd;`W4)G zU!#R+tl@o)(S@eg!vzPAUrnj?G$lOHvL+VVK(*0BZ- zb8N6%8xDD;$Qiy~I^Ne~E~+I1Sr8)GoPq2kZG8|l z>CM)ohch&^z>pvL-1SXdvRx)#>rtFDtDp@L4ZmS`f|gYT zO?thoB0Z6`&5h8uu-)cHy@0fw3~0Mq%fU}Lq-~3bR?gbCcy2}8lAygMnlbG((6ZeO z?cc0z$565}&fSi@A0(}Jdp)Puu?w1v7vby_Kg9)Fazmj_<#TgGX)+34#UNh>$98_cycM0}=ROo+sNq5W#u>Kryslq7`%VeV`HA2+m1q{G$=%V-)T)qDAni@-gJ!;8UXQ;xfnT0B!Kw zqUFO$FU~Eb_(^#b7V80Bti3%Ez0eM9R)}c_WVQ#{94bB29#lUJaxHsGph*?lQ=%7< zc7*I^^SMWYILb#dpsf}y!?>R35d<5$Q#3ujtF^b~C`u^wah8q-(+_NcmJ;NA=n>XR z!ns2%q032&DZ%BaUoW`??ULACqL)5_mSeflWY~Hvmvi7)9<-m>?pPk@)UnG-3*(=5 zOvf(kx!rK?$tGw)Yg(<#ikryIp7 zlx~=$_f$UT%c%xvGM+fqz%BJO(mTY;*E@Y#uj-C-&y_<9VeMQw$M3v?Cavwf;`p5p zhnC28=fgRE=TS?CNG&~I$({Y1+0cH+c34J%l}dq@i_Op^Z5O4*yoH)OL~b%~Md-F3 zuzTwuwDI=?GbtbL5A49#P^k1_tH>-{4S+F{oI zfvE_jeL~ke&)O$r@R1g1pCapre#qLV_;yK8Yj?-@Jd#_Dn1}laUj&a6z5@#_uLcqg2 z3D<&03L_H3moq!e;NJ-cfXjuE_Te83$Ag=M6O}fizc9ibF}g1BXBHY8sQ;3abSGF z1QBvO2cw7)%;yWi)B0LTKfez=hq+o_&qgG*4P+zaul zHPG(mnotLyQB=v{&O#e0PoAHRk#|y`U4&TAhM!&3Z}x)W=U1RzXYKPVdPpEf#tp%6 z`qG6pgGb{#HW(RWUWPVmzvxB!1=w1?!}+5wu=X8R)zZWP(^V9~sP9?4+Q{#Hen4tR z%fR7>ecYw|&*;4eh?3^cwL_7 zuA}0Nmj3N}fSy1xgo_Vtv_z)4MvtcV8ZM~WV|p0p!s~~gO&YyB8N+>)8B+){#*r2e zjYkA<&LJ8q-k5wow{s#s`$Bd}&`L$aj8#KJ{TcJNXepwh9*wynTAFC6Ph$f_!)g=b zTvVB{JTinM5T06T?pz9yACkbl(AV4ZTYbAk?v!?)jbo1s=kW7!F~mDQZ4$pc zgqs;7CBD9>1d|@&7#e&$kBSrj_$?&)q0yrF;R(!1g?}0?N}7XTsNOi<8aU1`4Vn}g z7(oRYmoXI)^CVDat_tvjqeU&`fCJ#um0tXt15n+f_@)fzAM?m-juw^6mc6n#6MLa> zqn;2go2Q?f12045(Ic1*;ZjG7;&CzD>*zI;t$ucn037gWQJ?W8`eFhCCU`l>6OT68 zMMV6J-jWJ)R$D5V`62^iVc(bS4W8VRebAq8<0-yQ>~P|SRz_GMK?p^`4Rl*z%pBP8 zc%@B^=fH-?8#j#3d$u9)XDUw%YXPSe&R@L^R9kZ-^K~tBqhesX%En__+WqwSRIU#0hLU zxloS_MXaXOL3@<7DRp|;0BBR`-nw{*r%}lt`fbNuKQRyH0eQe%)yl#KXN`8fRufJl`}6QlQDLrXU5s{smeJ(7f(> zQOpX(tQgu?q80Oat^nm5FWpT6W)_ow3v)pg#KB@%B~81a4kEwtH5b&iST;kHjdFJ3^G6X?MpKF#w`8vfcQxfh|$E@lSI=yTe<=XoxZ_*d5KwI?TH%N^gl}6*u|a z)zJ7k-MqURpUXnJAE#h`WV^@Fu^CzpyeHa3%i($F=Esqo1p`GyUqjO($n%@FUrBN#nPAwpij4(-!iR1einF z+XQVb8}2n;zact0@_XSS7Il1k!WbIp4G{k2WrTe0 zX^Z3rwojfL_GLh87DN2LV^pVo$gl(t5%IUf~<9cw>>REyodFY;urIzq=|>xe!em9L*R@5E~&zdOnNliR|M@F(TenP&7T<2W&JuR@ z5asmrY~I%hx2-?PIgLgyK~vtA2D0>|A4_O`OZi2d`N?P=-aZ)zElbSe^a84}`^he! zwf)h0m7$eDlY89$60X_%>!8UUX@4DS2aqF)?fKjT0o*wqK+YtFiWZ8`EJ=ZVF<%4RYOgi5*)y~K@dTx=JBnD_A~r(|7qM9{ znT*_f0Tp>=0&6dn(6h~uK`S3^OZv)h`NkY}t1an&xT&;NQbGQ3Q_rQr>&Y@`f8^_& z#G7fVm?tkn`?qKp8Pj0;fhtrsnnBfSXH7QB<*|*w12R6K8BsWm|qW3+G-id~ZReBUs5i#(mN#>uN&4Q*<$mA->d@-<+3o^%-RdJ1U377FXTjS~Ja)Z*+I&-WpH;5rxN}4Iy z>#cWfqS>LX5<9uqzl%z`RvrW2m3uv$uxe{x6FY9o?*>4U`^>v|4T&c)%e$3ITPMSW zcPsHdH!7`+vnRxr$5FmMp7t*hc|d|EE!fKQR* z>pl_jLW_7sY3VK^UTG1L<>^5pHi}q>mXkh(#X2+J+Un49($|TW#4EeapQEm(?`QGz zdS29L{vr$FITpXj;)N0B`b3D|vRI$U>%qt?u9jhE@yiH#)Q5{)EhADy%(|w@)a3G3 z%aG8&s*&yizHqgSBDVahndauh^6PAfa@+eln^%OG8=@ipi!B?Xc^#d(0X1-aI}sb$ zi4r;I)z-_4hHo-xl69u1)hJk_42#HeMr#yKgp;Gd9%J=I9F+z?PP!ho6JCA zG?q+R>g0~pWG-eM9)q>a9N_@)e&Kj3?<71O@$A~n%C_EjL+4-Lc)meqY$)K=eABGg zEk=*M;VGwce*E=0-U~j|I4AYa8W;)r5(T^y0ZG7@AZOe24|h=uvV_IS^%V(v(B9 zdjc&#lqqdfcMju+GGqGnc=NS&uqlrRb7Jpa>E|XFJfF>kXM@@ zXVE2x+87pbra-G;&6LvmO3Qt`tC@~`%tyejLAK9s%P?jR(z8}+**r{e^{nOMakZec z%I?hvS1sKJYuTf?W#B?u_BvtYZ1w?Rl+~3l!tzK29;JfGi6)7~5QmCoaf?_2ai)kR5u)>;_IPp{Z3MYhhKVaesAx#6x>_ztC5haS0TQz;w#rE z8@KTF&n+c}jE0_I^4t;ER-QXv{dIZvs8QN|lR1(-YS?$MYY*hceTziIk2f?zboEEwzfX$J zA734(cIh7tZ66!@NAr)duKsjMzHNhf80*>-IdtELY}pfULybz_lTL3G5vQ{lqqLoT z?{e)K!|nxKdm=_V2Z&{p@zb5vwbvMkd@l#nj3`-2uybo$qIcH+I?=tZC@pUTU#%BD z!hDm`7ifm~2#bMm<;Y?P#G@jHkk>9)_Pzj-fByuN$6Sa(WGQJ03ZdVxNkpx@zXP8h zlqd-dN`lDa64xNSH==vHYY@ux{#jyKM?Wk>?3)iUlf}OIG)bMr28a^RzL;iB%gDdS0Pev&2)9?4APHk4@%b4)FG7c)7@ zHXRp60H(h%&qBbaADGD#wmFnJHWWOZdEPGYd<#AtfPeEYVyA!)%#Q|3*3HicpA#J^ zGk?fT9;eMxWcQ#5Tswjz>##eL%P#{72>mF(`l6f5{HU0`1x}lgsFK z-ol7PyKvzq@M>mq3f=AyGx>sUSIJC1pxa$zUJ`(bCNr7I<+EE6GkJP;s{uQ5mEqyp z?OW`C$+5G$Sr{j~`|t_mTiIPI;MxZ8{jBeb2TQFcugC2>uudM1+mB~{qz=50nLG`* z-@=SJgv!zWG2ST%#erv;$)#}nDrRye-2O9Wav|Ko#7wS(J4hux6aNt>@yyteD z&rDu(J4&uxL_O&E8tddF*Hiiua*pdciS=*H;9U;hA#b>zbOMTioZx!C!#X*q^^|~b zo>9u;D*6?$MB?XSa0=_>dDbE+zFi0Y!qDMdRw=6=v*`kO9JARGgPjD~LBQ6{!g1ie z!pIdXcOdjpD`ovk^dzNhp3LL{);35u2s~Xl3Y;WN_MBk)$da-huxP0NSl5h-fZG~1 zMa{Jt%+14a;%ehIt&#Iq+ed6ePFrnX3uh?h>dc*t zHmnf5lkJBiu+A?sN8tLM|1R91l)W7@`S`Ru0%WHiJENG%si&Q9FmT`r<`x0RonY>I z>0@BZ&UZHY_?NPO%IA`^PH*nSw8`P%k*t$rPVYqKICn6&6wNUYf=;f~h+vn<_B3GWtlE>hd1-|8$@p zJ2%;AL8ww)2Qx23)^(lByvPjR4p#Wx1v%7}>J6CuPj-D(xCkswj=W8F`-SlLMeQ((9#xsdcp6-K~5_X#5~pMA_r>%h+oBLO~tW+r!zKL2K3 zhQxHUFfVrpOY0!t72W1RNBD-b#%@xH$Vp?j-F!k)3iuUf^2yjuE}BxMl&_6-%nMb% zQisU3qA%qfu1W3`eWjCGQw)v~{SsJO1bIz#`0n5XznDj<0e^tZE4 zP6Pd=n2tJ-?f#Sb0Qm^?U&?%pbZSmW!7*g7ztjox1n6JFIynIJKP8+GmPnAlKYzJL zJcnHA>B2VT->;_+^NYAn&mq$PpKQj?Og=!q@Oq{(zl4kS+{OHI30ShUA_M#<)+-T- zo>C`Ho0SUa$ogp%Q-D;uR|CM381iHnAax5K>>MiK7N0<_>v|W9l=|^SHTd_e*B67&5u^Vnmu`Wd@B#AV z7I;HANU7dZW?!N#doL7y7g)Maa?{qkob|6zKYD*A906_?M!-QH!WY0{%;bA5$dSQ2 znA@v@_A&pv6kNkhF4lr1Lf;`meSBFbhiZMsFn^Dn=p*BXt94+x4*5;%^E%u7fa~|E zV=fg~{&iZj3GCZ91 zd&JP;%?vsZUJQq3{kZuVe$4P4B4hmT(g8&fJeg0hpn?Q1VYVXm!MWgEWw~F zm+i@UR>%=%a+(!#k@;>Er6Yu&R16jjJYo%;BaEUMm?n(MHL#F* zE+RefMP_n%HSq7kNaesUndd4j0}9<{lRQroa!;NEE4Dij)nmU?yKvgKL@T zJ{{`GOs=IuBZWy{!@LRshd#-ik_i3-b7~}*#{@3qE($M3jEYQdqC%V4X0-#U3A4)% zQXCe;ycV$w%VS1qsIXU<;Yvw`@uRg1Tqvm_lURrABsGMe7hEu7P7UGincO3(q3zfP z?vK>aP-eJ2QbX}vfcmFg;O|HceU=Zv&ygC+?HfLglnU?8`feYvlzk!b8P?&)NDb@2 zjL95o*i2^lEmFfCVTQjVHLRK$eu~uaj?C~+u@ZjMno{5j0a1rsYnD%ZO0GGYQ#CV`C|Z>?=>!Gnw5$eM7l$fpCA<><$5*} zEVcbCQV@YGQph2=UKjz4{3kP9=BSZB2_yBRf`t*-C>|Y=XB;&ui*VJ(*OS$gdOSg;p0V(;Xwzvc2Q$0jT6YDiyFfN4f5Wi z#&%-e%?ut6&Qi^iUWXD~pab1Lwb>rxw zc##FqDr($(;RNu5%$^8%9QS%Acu-N}f{pl138q2*(t889Y(+S}-?bQ)CmEJ0BCg zJE$qy-2a;jWBW22zfyhmNigoxLP}83mMm?DR8nYu4 zfla^6JDF#|QqeN2l$z0zbvP4HGo*EFZUjrMhVuY5Luxgg2B;bLvHi9ra53|CGg#^n zoCByCd|xoZDS(=Blly-YyaA{f9%z_$Af_=R_++g9S227$Hth@sOV5SX{wjtC7p6R< zCZ>q(vASQyNKxM33_iy?R`aWv_k@eV4Z@A+|7W`K4wmh!nbNUfxxSh?o^>qKS2N>< zaiN*(gpq=o4+`glCB=mZVCGrY3md^wk@p~BGbMMi-d@cz!v^7-j^Mzoo_qop*sEC) z!nn|^smxeWuVyV`#!7lMOUfH7=+!KK2r*&hyqd)WQ4?0ot69>FkL7`R{D@WY;1BpZ zC!0|JXVvpgc^M8!$AYEsYPQ^7UrGRnu+7U!V2RMnu%9jc`O9_SbhfET0qqcD2C{(`m$L_9uMcTsinA^LbdtdJBhxrD(85UByPSPQMYvN+hr* zUBycKehbAEo6j~_gRWwwPSiw!-(tO{0Q`kRcB-*+of(VF)!kC_vASH{9mqOXm8-j@ z6T#(XET37_Kz`RwYa+bD05vg_-$cFjZ$-XNMypIVKql89o7n~ zIkVX4^DE%B%vcYs<~%N31g>KKj%;KAf;m8HZdcZS*asdi+zg(_d<{i2H%t0|tnXEG zpWp-6{lI?^4gkwVv5Z&6adBYDE|?;ktFTlTyhJ!2oF|+JE*4G#|5+IIBkp_QG}Qlj zKC+X6-vOyy>7rR+N-=RMc(*W8Ft3ssi)__A>bPKowY6$qqj0@a^QrhqM@5?-&P>Z@ z=W}O8YgN_!eb5m;7N%l{Q*6fKR5kxB9e`d5epmPmxLFv1-P2FF2|R(>#|-8oqc5bZ zdy+&C0zW8>;=AXtFd}!4<8|J_noe~OKgnYKCYT2lW~|#(@svY|ke?mQJ);@RG*x_@ z=xJc?56oD4sp6>!U>{Ho)|s);QpFz^&IWUTV0K_(rHbc)1{P6*x%ru~gixf&?(KcQ~?fffUnlWcvbc_vYb^U>;9k1tIt(pF1KEe481I2i3x8?*D1g zpjw#02S&qaVKsAP09dkp0(cQOMOqH17L8^btO8VvBqt^!s~7EM9c%v7qQ5a?sh>*l zW1dn6p2sVr^mR2yY zO9Fq&j1_e%QS7mjP9<((o!$o|zRA2Z27HYftKyVnnKTb9hf~X@@&T;yQp-|=Q^5Jc z$i`(-VGEFgWqj{2V+og9-a%}tz`nwW^l~1smG<`Z7O(6tCbOkQP#@6;oKp z0xGp)zLYnXPN@~^SYK1f#tdLSGK4Kdzj8ZFp6wX&FNm>flL8+u@*7r7n zvzf8%NhLii+yH(Fj25)dVZ+YbvSSBRyQc#_N+ov}Mog2bXh=sylQV^bz(<8cz|^M6 zCJp?Ka0d8u;XJTJ8cTZAN_6L_e>kBCJN;lp+z6IljNa$0+{pTqD2|my!g1hAW~{y!-3G!&pCnNUx$k1J}nY8@1|TW~{Dps8uiW4wluZRZ^~4PNP;`7d=v` z6o27^;K{;8;2dTwmr*IyoDcw($*7bX=EG*CQacJ~gQfqcH8810r-%NZ7PzbqW255< z;03}};BCxUxT03`VA6ad2Q0nViE2#Wkp2M6Ow^izY>)LNYE6`I0Cv1UW+*)p2E#w$x7Q_Gji(NlLAg?vq}rtsBic)@Z18Da@~Q1WWy> zLgd!{h4u3>N~OCpV+Dpvmvgc5LZz>f{vS&&RJue0OD$Bo^#2!-jp@?6VP%ENaN!Hl ze2|O~aIT_-6e?pr^JUWS6+Q!&)^WKS{Fdm*-StYi0rh|VAlX6rtzRgN*sb3sjBHtOw)$kNMpIr8ZC*6IX&`n6WxR zZCEc{0Dg`cD-P6#zX~HY8>so=+)uA4mE|Rj#AH#|3mvNoR2Ef0;w12c%ve0299b{$ z4i*iltdE%M6P4PiF=L5<+Bi@+11uN%ss{WB>sSY%Hd23p05JVuZKT^S7_#;d{& zN^PRP0XpXRt4%Y(2;ck-PToWpRmzO{@M_Z<=BtR^Cg~_>M7!zttT(}M)2qV4;BSR< zl-k^t`G+#_TxOb}zFBHJCZem&PqTj02L4Ri;?JSjxxoi8;ap{VFw-ww*;4Z{!CYli zP9UPU5J2`gVH8I;jes$g40FX*_M^<0BCfJeGGl7E%Km_vCV+2o2j?nRPe(0wdh!k? zc&jaZr=mI7YD+AiU?~Ex7A^+!_|DZ*0zSby=2xpNuM0;gwY38?W>c%J!NP@L9<0)2 zXtfoUo%(-QuQS-;oS?bSYAd&0n)0l+{=g?=rn9^0!#-wDG!{zGQqeiK1X4Wy~S8elU z#!O$eO;UpyzG@ry?KH7hZQIEo-ttKUV|m~n6<06Q4_)eOx9J~ zdkbFy^Qf1m-Ky>PupSr!zKGGpGX zayTS_z75z(;RBc^s~nQ0!8u@RW{6zyMR1|TL>!JHa1=8SFH|bGoiHk9?lfUUF83&N z1o2PIBaz4*QQ5{?|Wt%hVL9F>;vA# zJn0PhqA(JW=Oc`q$XjZ07^$IeUFW6o0s6je-cDxvuxg&9a<(1(I_t5>p}enzW0bmo ztZ*85jc_*jG2wi0IrCfueE)6Xo2dT}$O&&Fe=mo?=mkzPCW1}b0R9> zgC5MwkP{Ei7rqIWNH0gEAN-p2`#xCA^`7?tRe{lb^PHNr^!qkV;u?T@B2XSsvV2qPyR>nl<^F+C6|73)j?c$z3E~?UqPn z)A)aP2^(bxfj<_mRO)dn^OiiYL|9 zI7GM^jNCQ)|E-8op)|Rz$o9fgifM`tgCBG#nVs2XZce=LlZ`C$SBEA#~41;b`z*g^??JJ`yeh z*9(_{zZXWN_x53?FEH)BhZz0;_8{y$AO}!pd-n+Ef{zO4fh&b~f&T(V3brHQy&sB> zdazegza7Q5S5m(niP0tX+mRSOT=-xD4KzAYTD)V?ml ziQpN+S>VOONb$Z5=3M0NK8J7vxIk=n(1E9TXU7@vF)&hgA0n~uoNy%gZMK0^3bpT3 z(Gl>Ip~6Yv*}}QtwPIfkeuh4Gq1w5mfXjrd!LL{x9x4|HE@9`A9B2anli8F3z9xK8 zsr{Z{*qds=LCj_wc(iZ;cqZG^0>u5Rh0DPY3Ri&-3fH0j?|%_HxTqP~wZB@p8T<~j zs}J~Je1aP@qHgY3;L=_=5^Q`;1bQrZ2-~~u0#6j)2c9jANE}=)T#NdDa1-yi z(?xd*+rfKZ2L!3fwr6nt7Z0{myONd$i`j5>74MQm!oy_nnEz>&hZ=Ak79JKD96 z$4-vLQz0ih;G%~f1tYKyk>F#((co&aK`IY@C!C_xQ%V>W`6;V#2Dq0nTEtUBg|opE zg>%4j9kP>)omAmGa4wi4u?zg9h5U%N>renbB3uW4Rk$Afw!v<@$^HxBd~h>!87lA7 z9fdD}dkH%(V`r%BAiJKPCVU0FP`DPHCX9fezF!ytKfPDD0eoDz5zLWuD{BJ3E_yTg zqVP@dM-~h9|86hhe@|cI123ADDzXc^gF}Tof}@!KKpf9Z-(xOX!(15y-Ygso&SO4{ z6c?2WBauatTW7DJ{vTFy0I57YkomO$@KWI*aDi|!_zmF_@K4O=f|dHcMD$!Jc!lT@ zU|l#8{3qck@C{;za-+{EJtG01LkgZr5+kJGnJvO`V2K3$$*O0bW&M01xWdxnPgXrs z#a!(J{cRdr@V{bZrPmui(N4iGK_J4RZ$=7(cvf-q80JWUuWE1ri7*^K{GajNLZ z_To${Jr}6nWS_064#pl>*Hrr!KJBEx?Zn?|$_+MD{_0uxwiBN1=fo4($gqib;tfvx zuoLfb;z(*|8y{`w#5N}mbmC!}qOP3&9i65rSBdD+1)4&mGX5RS zb>ib-#|}C02kf*k%B+=NbK(og(v}N-g}_<@Xoih&iKi1IaxDRu3~#e98Q-QmO6EBo zSmwkicoXke87o+@5C=T@gJQS2}1&m`lm|%fSbPP?SmA#zU2lJ0x51<0J@(4|tBukG)I`M2LPH^I6Cq~Y-o{Q_Za=sHk zB~0l*hFaQcRO!U$o%k&$zU;(ToEW*%dYx~a_+}d)M^3cZ9PftwZ{6wZbO4p5RgZGw zyPeo6^~YB^>1dX%=k9c3)Rk5p^+VX9jz8bJqmHA3v>LtX#P2w9trMf{TkX*bTKEJy zl~%SpFBO%)G5W362%+R#xz355+QW$^C*7%Sl)AR*c(d(jy-;aarvp8mIJA}9 zxl}9rA7hR2vhf$=WB!}Me=$ll_DvU+{S4XJeG0@$$FCA<)QwF$OkHY=?m8 z0&bD=cNhP~P}R`g?eaH3{+{8#7-|~FF|y>pNy`2juG2nC{^rTwLiy_`7C;OQLj-L6 zy)1w0L_cK+*9qwKFE0GBKBw^sh*JVURSzYX#i2_@Ye%6}c^a1kQp?-==u zlpBUo@;6%k#>n4T`5VW7U6uSr1nE3i4rSFpW`?JTw`Z0E3@$5xH)4Qv;%{YlSx%KD7sDzFLL57@3@yN(T`O#6@6ZeaTf z8%CP;pRvKii2XJe6{5%UM%U`?f(-*3Z``815pi$aZM<=N^LEG99vcP#-guz$?uZRz zByWt?yfM)7#z@H93tK0QUc51?^0s5cRlU1l>xvCyFYj*He6e-M=7+5ZHh*kAu?1l3 zg)IJ-&5G|Lyr;Z&+r$Kw%23(7~6B$zQ%?`Av{#ve`2Q&+xHMC zB@`e9Oo1YW_UG}Jisd_Ojo2thkW-X$drR(p3H}7zzp#CZV@Q;d(SO0;e_)?dOp&F? z{eTTQY2-#P2X@}Ub{PU?5wg(!H~gg>LADtsRRgAMLv|V^cpiVLXsC$(jqP)6EyY#~ zJLHu8L;R&2MN!zF!FCSYU$H%ltr%Mow%=oOyab~FY{+u^Mf^p!+dsheHnuC+KEn1s zwzJq?!S*NEpor{m;V;VC{vQ5PS)*v|f5%_c3ws&1a%?YP`vTiH*cz~Xi|s3HFJgNc zTO}qdQbn*=VEY5MQfw!&RbhJ-7wd$-r?FiE_r`|GgvzeyR}K3SY)7H>#NQLxj#UI4 zw!YC>x4dMn(GO+W`soKY+OqToFI&C!qD{83`u?77R(&1qZuuwZA1_<~rq@4{t?qsG$O_vLeQ>QcK<`;;yH}5#<~CB#h<3ZHVs@?d zv`HUZXWgv-ZKm5$eSd%VO%>nHa(mlc@za;q()Rj4uUfb1*PE;Z^@JwtLA~Uvb%efd zqI;$8f89E;BJyL~Xia}K%00Rw|GG6o3y29DlDZ*zMb_NpRTCymoESS}<=oJv{NJ3F zbHkSERn69Z`bX2;dwPa$%t%_6l^mD4V$I~0`pqA$gY{RZx%bfhr@P;)|MN#{i2mes zcYpoHH20v20XM8i-L%+>ziYP59{T4w?p-VFU2I>r_guPk;j9@WlCmacrf*Kt{jIhx z0WEtGtCF)OtV&*&H91w0S&NP@c-idkt$W%QH~ZwUA#w@h1j9ZiZ0NG2q`36i8CiF4 zOx~Crd#6n-5|#Rk3y(Mjz7lx@T?+pEuFq^mjqRrN&SJ-d~bXIces+8sF8#8}- zLCtRK>i9*t|KY4V0vMLDF>_V&iz;h)pZ%hhZcPT1~t_k0v9<(kpB+Oq5pwWX5I z2y>RhhNETANnXD(c|#U5A#3A?$*Z}LV1+M5+58-_(vt2t?~ayn$C0R(fbLXVn#3Kd zw1U)MwgP9P&dDwHSBjD%_Kl}4)SoI%Y-W0P>e|$-EmKil+EPw6?2}DyK1R)ZtFx`2 z0Uz3I-Ko0XaZ+0e&`Gc5xOH)zVN}O^J#BrsVusmmJ!cFFP0E^(mX^Najh~ zt=*M=YNNYfORE}eqN;=XGQxXsJhLuI+!094`m2B5yoXgiKJ5ogE^o85yA zK&1`z`K?x^Kf2M~2lbG$3W@O6XJ@;6=wse=bJxoj+B#Q^8D(x_gHH++;UTJ>Uj{{;m7Dj{CVyPo05IA+*11`yR&Kd+@Y% zE7CS5B@d2D&ceO0wQtaE@4KN7gk8XI*|qeeZKmD+lPM1pS})h@KiS;T9*pZ%*gm(7 zY_G-Y7<|mHcx;~glkN5%x8X}0)wXsOLlfLPxoSfzrYv)xt&v=D^rp?$UJv-d=2lVP z$?LeMe!Qm_C)0<+n~TJ)Xh|hU>63rja=i^4#P_xTKcsOUvE9*ew~P>4`@mMAr4w%v zTD#U(K`j2a4r$_BLjSKjlK8>+;|2fxCzP&qqi4HLp+Iru+Ygs_Qg>($}ZD zXB*vzkCU3YMQXFr_5QCKclD;L-4V*L%;XKpSv;Oy$o)J9ZvFKTlQg`Z{~`9y12&!7 z-#TZdCE~vr`Lxz38pSxmKy~(#URhI~2nI^4ojBf0ea*fXNH~)p48X{u{+j zBTe1wXSdBpOll$r&H>Nx9gVaEV+#$7O a+AoKuZ5c=7t^c#fv)!ns-Z3oH)c*hp%S7@3 delta 270994 zcmbrn3tW^%7eBr;y9gqhhHxv_ZC7N&H zw)^z*yzAwri!$qUcke2HAR9T-O}ENZr;8k*^z-fISvB5G=ioYB)llU{WH(H7(;au$ z={5{k4*B+KQTUjf?uC{*U16TvtI2H?Q>&=v&${Vuc%Z#Um0_)VdER)zO?P#YPIqHk z#gvtPOh??GnVZYt8ef?&mRedj(*=tnV%8V_7lpcm>dc8w8Z|| z&|s-5G7>@&Ajwtr4;#c{gWg}M&G7J?qtzYQO8GY93m?6=o6ctW9(AZkUVh5q%vF53 zkMhL8Pq<=Kk_QEGi?MRZAPhG~f0vZ}(Q@;)ZVK(q-NnlNl$UP$BVQ2<;TMib=?rVBop zTt5*p^ecm&=uJO7SI1s}JaaF0@hNn3{OG0l4b2Gb*b?P6)VvKT+jK^i?s+TIheoyR z1PG+zN%ePmDJzEt@NO-Y?L$ZMx!#IrR$KmC3#C(5Oq)(Vw^`b5AI%40N8$`kn z@>Zs01@p6>%EGL!{1Y!_e^zJys+aOxR!=_KOGz3Q-MTYzS8dI$E6+hS^J(IPdn!|g z#TbjIGv>nv^zH7xB5!5Iuo(Vs3+0nxJ^8d2uMO|oYj_KECLo2{L}jYk7m#vut+nqu z0IgkBXmcfUL;xS&To zj0oaaJd~v)+GZRXzha>@#jiiURh~9ES&OMDjd6dtUs(k}IJ1iaw z8yOk=FqL}C{-J$qUr7r68{(n#9vK@PMHH*ibuc;9$s}ae+(Vf+GN||$cNCAmuLmeR z1E@8SDy>e}I!)a@K;XWq1OXq!+7_x#X$;{yDs>5ZwUjex*#M>~=6?yr_sMytyIT+m z+Qs~8$vf(dbywm?b?BQ&)T{q4;MPrA^+bBL?EQTsbG@0OjEXHj(#+ZW)w1&>QLy?E zz}A2yn#GE2Yw-iBuk;Dw;gTIMZk(tC?G7Q-N%t zI_O+CB6i=bGf}N-R|7Quu}vCqYo^T42@JdJrnLjw7qql>UM=bJNjGI%PCOqvQu!`t zH^26_vN|_C^u4$Bph}`o*Q^^Jl7nJ{!bV52X-eDCNuhmRXaoO(=1XXy%~Ak%=#*DS zClr6RUazyJNlWp$Ov)AIFp}j3+VZmt8MzQu=azpzs`RqIwZOx2t}xB2r@pUfB=A}z zftO{{ixB3@qz@&ZLDEHbGBTw~-#k-sZ^F=9)01S|3CLxZ9`f(~ykYKnwT)nBz0h$J zCSpCLng?b2ewKP#(|S-lKdqxq^`Yd~GMP%r(=wS($sSVwuDA{(b!K0?xjJbv{cin0dM|k&{?<5ZfI!O|AXFDfC;@s`Ez^-U*)R= z7sLnl0G6}RY9VauZi-S+5W>&H%UoZH9dG$dLty#C@CIpXL9-cD)rLyKUq+w(4# z_b#6ax8Q=66Z(qRp6u>oDG%EK>S!H!fm-Z@OXqm`XC?Q^rEINo<;mFaIg7!RWx+k^ znRT#cd0G2=z^Y2_`uJ6*O!Z~0r(gh$n=Pq8(p$3W*HDo^vU1#0{*2`+)2Fp(3ChxG zKl+<(dY4pf=2~K=bEWdMiM7fHh4MY?P}N$rPM>0#GEzA*{Y8J3@GYx_O4wDsVMYE( zW#Thay$Ii0uudOJm|s3K&r8Mp8dcHoq!|gU6+x^8UdGLOy?KLVNLe{EpM9#_o*Bxv zC;^2LA&VD4Jmw45-1FsgU%ZP{Dtac@re~Gmg^A5&E5uCYONDJ1Yp1L#isN@)QdSoQ zC3?VLlIXUqTJkJTzC^T6TXSp6#}h5Bu%MRKjIEWv&o*Q1eI;mC1hXkU@cWdKkKZh1 zHhv+US)qM=EKUm6ti|O+8;KBw>t(LOqDAF}_ZNOqR(W;Sa_Q#2^4vQ9+Kb9NbB9zG z&xzqIqVnyzdh8^WjW0aSW+}nN6T(dMKnioc4W_w|b;Ur4)~Rk&{gjI0C)lg6m9*yT z{FI=Q_PonkrGH6uaKc=u!GZEL4`^q5Ynqo+1y1`Z^GZ7LLuV>KDA}p!27l%8vTUB} zuk0#YFk#Fr7`mY3bC=w9LGvLVIpk>sHDb*&pC=7Sky$O%o-)BG+d~>h%ToX#B!Gm^ z4Z7rWR;h_p?aybG)s`N7w!d=DGRCFOq1q%r4n2lCPsR?$vG7#o$d`PX3uoE=I7x&v z?qucsms>UB^uHfxIN@}xRX$vB&}#wdRn|ew^4TLR=a-La0jvJ+C5isF$G~U}HaiVP zq1N2Py+@GlBvg{iWF(Nft) zlJnAGTMbMPpFm~Qn`uFROd_gVom90IE+jpw^k42NkNtU z*GysjdcN}B+6@tX^QmgS$`E+(|QjjuZU8nG0@(9OE#pz(R71EkHR2{2D zLCU^$G2!n?6b~oL9*LrLWk-;rUmwFBQ#!2g%P$61KEA#!<3Cg?ue{xwpRKHX`|ZAl zp!Y{m6E~bf&=wh=Hp-oi9V4EQg;&+Wjy8iF80S3i(?&7Bmq5z$-Wz;M8>Qu@1eo?d zn}YcAHp=Ktam-gK*%ZJJw^78V82_DPKASTFxUDxacmL- zIvohois)R{=mbfK)k67V(q|7B8R|BXxjC2`M^iQl0hx;uLS#s8#Lg)vj+7+PsdC~} z7--Ny=L08>O+r9txf5p(jbHhLAhghlWRV~cn(aiYAUz;Lk2-N|5&}Xw1PLUDNS}zI z0f5x+#FQWrNgzliDAPZRf6fV$_TzCSosh+pAhBy%KpXA4%8%4K~sWQnk*q;z_x=RU}>ZiXODz{rBo-5oN^?i zL?=!KO+um*>cp|p+$B1mPMkdw0y?*cWm5BKOj-mY^n-+;s}*D;h|p<*(5hkEq!Bs* z2-%XeYvro3N5VmFqjG)g1Fn_eE%>x#Of&8I0h5{QU(U&7TC;XI zXX5k_<<0Fe(I?C#NwTT^4N{o>BUzPkGi^Afaa|Xpe78OMsVC6B%@9&<-t9D|)PqM+ znP?9nli$+0_|}EM=oVXZchhFQDSA5)aplpe_Eeo(_95P!)xAQM`S!q$Kdfm)wwiZS zbKj?H&3OSo#)+RAs#M!M#V-QBEp!jesmrdC;9f?Za`OdLFgdMXVW<+mBO#!R)<9DW zoUBaR5zIG)Dsy-A4mguWRWG8dYc)C_svO@D%NMRzZth6)8j2P4x{-D?f38%_JKHw_ z99>yCd*@?}dxa_AeB7NhF?g5M#9_NqN4D&bVfMwq7hR?vIhqvKwybY zx*g+=1+h4#@K{v%og~Q9avIYO`R#XqH888j)1IwXOlOlki6yH6Y`7__&-ho)IBR9RCQ^B3T8I*Sz6D#U#GD_Tm=oD# zSEKs-{QhyOZq>f5I&g-%2Y;Q?B^PFrrAPm)ZeF3?@)+QHz{9SGzGmLi2CLd zIoKJl4WLJa((3!JynB%{=zCL8Tf(tqV|=99(7cO25tWwjt2irGG92anH$Ua1Bb2}T zOyw_*ME&q$A8_ff?G7ZPPe};)wh@070P^>&7DAvIum=XJx5qDV2`oh7)J5yHMC!J4rEvEH2p@gezQpxxvv>T~b`6yB}xTD>@k)o3aiwpaV5UzFt!q%vUhWjqNEZL&SgO#)6qQQfu zw>G9QY0zj1o(Kj>1dj|CW16#RJs$7JXj|-34lrE;6vuDFAgV*8aS4Z^Bru0m`*VV# z_P$}Fp*f3;+~&f1xIK4aDH>MsF!6vVu!>w*)}A^S)+i0@fnlPUu)4ai0#7v3^3$*y zvcx`MMg5lLr4Y&b!JVl7rxKZ>1 z!~qG`??!J)O=#o*bED3O0gGTkDy$j7nrkq+mIoewA*7)yo(3Zlj&BH7jLI4iM-4j1 zr}rab!Phx<0_Ld0k9D9|X}y2BE%E@2O{!0+BfH#ULK+-+QEk#IJanW}WET#g4h()v zaAAmo4s3*oE_Ee-2@6nDR4;(nP@4u*5}|Zkqr;VIQ3&$=C_fuj97RCb0n^q{|6mOG z8HjATC0-2iVo{xHEL#tgz#zq|nC<1}b*pd4=Z4j{<#W^OyYjikxZO=RO1$dD+VyA_ z!*#2ZMgiRdX*aA+kx9(8hSfb}l3WR+-K`HYkCt1Y+YPAQZ8lqt663QN- zvLp?r(+x}m>|uiWIAN*F(*c`Iu)9MFdT0 z78*48)|RXL>Dj?X1BblrhRjdcf898?>Q|KCM&2s1_d6o=GI8>Dxy1o6j3?bY7;?x< zkFP2(w!~Ls^ewR99J0((AG6hmz=IvKELC$G)Z7mB@r4TPj?SRo zmujw#9_SGPW#4WPK&EbMsY8|q6)Dt(6x7F+jMP$AIY$PTTP{F^^}V8Wx{^JqPz*2Q z%MW4_8@F31*I=@286_4QnW^|;Xc9(x3h94ATMm}~&LFGD4W+L1cJm^yl5MhY^*1rA zN^eINMOn8ItCpL_vhM)0+9+pbn2-(GLG`r~D;ZcTBo+cN_7GNu#NyD_;)d+d`i&B; zXHlHhMiQ_bF_t+!o@wAqh0+}N{(|Z1=Su7(qvb(pqP0TSI8_*GmC_^A+`o=#aGDOc zGNsza9)x;Q8Z!)S5Z=nuOjmr#tzI7tIuZ&Cm`-+uTD4i^guZ+szu1ANTk)5^X^z7Az8a@4Z-HKN{H`KKs9Oj9;rmXC3Zg<(TpDnIDBdCAEz zM$M-heIY2P6}g^4R=~&2rzwgPL)w&+z^JkG0BN00PF7LViiH(l>(6!dx3OUK^~aCV z@-u#I71GQ>`tAczdX@^dTLwVBee^~7C3|KQ5u@b*;Am6QBsM2WwtZ}52B;g8@x&nE zx7;#?(iJI`u9%8nbr!Qj#p*P!p9NZd3`NNr@xm4jHXU@PexlaKbku?9u@P5ALizdu zRLRX~>4j%wMT@K$qgKS0o+{+qR06*8S>GImYLAMkOPyU^`U(0|vPW7Lqvb!yxU7vk zxPfB`Q2lZI+&gTvK)s#K8ZCBY9RBGB-3Gm}qN=>+kVV$0UkSL;UXc#rl~<4~jCM-~ zGFBUzi@4(b z%-Zs5%-gaa06X3uAXWyj)?r)Faj;uaBA??iQO2AE%LrogwM2?j0jwqrdd z>IE`ktsvezR>X@NtyyHTb9M0o5PaEUrRaz>9r=*r6ktU>;JpQDH)9UcJ^_?A<{mYU zmQ$5#BsW~jsj*zdaDIAxXy4KXLvcKKLIG@BkkhP?D?r7tX${#)mprLLU$q9P$|V;1 zEvb++h;F8nC1av@5C(YGo9a?SCymyMNKqTe0(tlVQ6I=6iU*;;Fb2B*5O;Sq{Vll% z<0y@`^>nslFmXH_zH0e5-bi;<)6WoYCpFCik)DXOBL_e58>GR3?~rZ^0x1ewB$5d1 zy!ybekQ#XuaVQ>&!%Nj4r3Q7nL8*>Hm7%$ z;5+Y6mA1_LD!en2O+I8{%!Ba3fCm9`ng9$0$aVps!mCi-W~r)yGN=af9qQXaf>xvw z6yZ7G^KF85Ca5h3T9im}SOBjfa5TWb!lz0BUGkZ9^4Y;g^A~xW#{rQX%!Wb|QYs$! z#o`j4Dp)XkF<8YWW=T38Y8{ln_<&du%zBM_w6E-6g{pO90z&2FRW+_;_AFfyb<&OW z4D$nXBVW2xq!p>4MP-_9I`g(vaUp~Sr8O-snLYC#2$45Ngw$svAuVr9R|z#OE}8w{ zKM)$I5mKLxgtWYEpd?h>w76vU`sY`WFW96@2aK^tjd`$X2aeK&Yn*6==eXOO z>}#PXDg;DAYL`e-0VY*`HkH(Po7(7@qt}h?$Jn%~t@U`kCNdK17>ic6e!6%ol!X+N z7X4}*TQLbrqFJU2QZ>LchnegFv%t6aHg-e{{lIe4D5&fg$*PZf4XN`!>7cHRV#eKA=rw?$SsYhO%VqK@qR ziD8wUjU2VOEWfAw8P>L=)Zipt-r!TbLv`d?oPv2%4i_ z!_Z2tn#)p$KN$k6jkY+{;tkxVl@#yUKn++|#KZO*(^rsqta~EyJO3Bjg2RHqDxjjj zE$uQMK4`}4k4B~1l*C3*;qu*{B95~tJ*t!5^ImNa_*MUQq%36YcKJ*x<|0~$GXs=gk0L|#tGUkQtp2-pj6`XPbKpH?j#z5 zDAm(CRnf+S--4dBen<_&qICo#?O5U=oe#**Qe~{zU;des3uD8t#kx%bZ^D0fT4IsdmIeBf_0l%j zv@wKH8{L*o^ztVrV^6?sv-yktZCM0DX@xPKwU#Rhto#*Y?7y{z#I+CryoV|Rj+*~- zzo+f{#%TM#rrW)pDbj^-VW`_a4P&y2Rulo0`}TWi6g$5I4sRnV!WZIA6EmqpbNs&! zO%M&u#%BLK?Bb3IeIDj1Lff%!@wd_5A@f>ola9rz$??ENY!w@~^vgPn7uvB7JzgLV z4JLU^Fs*abV}jP$XkGFlQOga#zo~u>mI3F%gSgO+MUEX0nshMmC_3ACFwlouavco( znoKhI|8p?#Q8of8dJrj$?${U>5-+V$`BmD(JPrA{R4Vd5C2u?^c*-lNQ6GZ-uk?W` z{=ezNBy<$6(0|c~j-(I$q%3-A`Lp_V7`KNy9_W3$v3UNH41Q7=<4ufk|>D7(z+|DsrC2- z)+5n1)c?(Tl*?Lyz<#v}INk}5i zh(O`rf%)}qfRvom;+KS`(?Wal~~a<@Jx?TEMyVh{+vTWK7*2b#6rC-M+@z zumjLW7N#YLjU8BUusk4B58l9Z;!w>OTJ`nBwov1|$rp*)d<1&F-wY*ICyAckOM+5~4`igwOuV_BVe)t7~c=i9PgUZKFz z>}u%$)jXn#|8MhXQT+d!N5wRco&d@}*;SX;q}*p9`pA<+>a}`8+k;{y$v10M-|!0z zmn1NAKK*O)i6c8caQCmUh2) z@4v0tIJXFq>!|B^Gz6hfq`HH3IDKezI&LEDsAtXG&x;-R+@z6^Tv}e0T<%a=E|VGQ zv==__)W*VRTvB<=X4#=R)YJo->UcKss1rza$U$h*gFe)QXa98eVB+80>iZPT%P|S; zkr`C)Jg^*kA!k!>MCf<|Ic?YNi$egL>o%ugF^9bC#PmcqxDOpY$&HZ@jy`O3^pBjZ zJhp<){E>r|`KSZkeHqKzP)BG3wJO!oxr4Zw$fAosj*~MOCQs*BjCArjxSaSuAuLwg z>gTANd%VG!UqxF-A4zwtZ39Gvye$@aJTVkEV-319EBs~NCm>$dA5)>_SEzXTIQR3F zIJEs-Rjd-RnAA!(A`S$Y&Kxj(X2ogjgGfs1bBvoxG+)CfCxYapHbGsTi!P*<-tjkD zy1}$L+|}MeLmzOoL)vlc_Pqwj@?laAv#D!KHBY_XV@gp;mq_NGhxlR#>`h#QW}c?yMT zJn`>K5JbZ?4z|*PE_H3LGwxE#2T>il?|_)9bzENJ>WQ{RLNOBW1B&-ji%)@FCtJpf zYFKjk`sa*g>%Yd4bQykJ_cImM>V*_*yk<(iS^peR?ps0XPhLYM=XFgJiuE@@@i2az z78T9m#GH)8{UrAgj<)M=%2FKeFzdbW(}drDVu=w-fP70e>tYvAyrr5EW6;e%NSD{H z*p5*Mi8@a)XW__QdoxHId^D#d4=Svcz_e(ua}@#TBPiOww09dSYsSbJeeVLLk> zr%9~;{T}wXX4*-6Bv+O0It`&UGcKtjONi+sH;UhS3P%d-=zf|iZ1EJqU6DCYnHN08 zP|6ghBQw-fynsxz%Ty99Hg{$5?yu8E)6rafOIYhDv%R_S?}p5ugjLpDWKhP?7MYRF z#cX7n`BNrRyxR@+Ln(d5L!2k91j_985G}hS)0Z*}Jwz&HvMH1AA!Z=ctbj5xVr_TS zf0EKS+{G7!RY;iw?!u!7>zGzXEHB0e41pJ(HKo*VU;Kxk(EQ$e^5=r9``bQ1GoCMpp6wq zzRL0z>;R0ZJa>T18(5>fPg7e}(yuS<4r287gyWBJ5!{o-jZgbaJ-5bsJE%90sP(#` z9>pa%R)#y7xPBN+v_iB7PI2cEG{xk2oSqs-^)+H;Pu8aMMH-*zo2kWQD`dtQ}sku$_?N2u7+o5gs4iy_juS{o|9>&+5b zk!aP2MSFMKpwsoNp8F}eu@8yfD-C6(2gl3lF5X{Zh}72~Y7n(64F2wSN$dq& zbWderAwQ7n^yG333?;L28OGrz!J@B#PE|vN7 zvjO5tD(e+_4>d^ksSt}TcO4yJya5JmS?lP8&f^y`us>T_d>4A+!jeZ(j_`#Z+nXd(DXx&-ZNnBfL@b6O726_agne#Jn4OF24uR7dsuulY%!KN4@ zbp(_8vVieL0M?{U0uaG$lZls?TZ7%S$tq+DL1HCjiVB%ZkX-?UGgXC5C&)+%nXW<# z3DV#%R`+G5fG?{s*TC9DQY1BA?&4-~wlB-?vT!rHouLK{VUnz+(^mxiX@PvxTgzFC zf`wE75+hq1#D{fyKM~oFxr^d{tVL$$CL|iGrc(tO1=dTe%0UcM`bhmdV1p(%&21lq z7t-u}aKAX&kNt}e-X|Vb&-AG8smV1yid24{kPe*{tVzvR`!&{lTb52G=UL4MD)k+N0XmOz<4=~wV zBFGMh0NR*rgcj56+2T!hPL96VEAj@j(R`@MzIiY+vQ~366(yEQKbN-x<#dbDUp_Uag!!AQn4WAn2KXvymyod6)W3mUlN{=m_Cd}w_PspEL2vfQ1MvNbq+U$d>NZj48h9zzJTdp0 zJ``8R6iGv>D^BFFcs}cr_%nx@`5c2t&t-l1VJ=?Gg%9^R7w^+^1{Za?Y(3A;5yhif z7yG2KtOeuye-%%SLwL+P%j8B!tQyCf89INU(~0>X8G^;Zam*+8;=AM^J}1|nA#1Ud z#A}-Li5>Kh)`{1_r!`GZwpHQuk%^&l!FGA1w9A@pAj9`0gl)~ocQA})lZ3I-(7~7~ zZ!&GFTQT^Ko#!z>#_d-{U_OG_mn~J9%F1WW4bf0>V#*|5K(^&cIDAf~daM=|`OL~8 zis&({bHpZabcuNLxX@JoDvz0W#mq5mWVfD+BmqxC^N&RZE2VTWz_jd>F5}g3Cqz8(KVFABBin}6uz zD1Qjg2-J4`@;k_xA+VAMN)MXw%`Fc=WvW^nn#g(;ulc;8!G>=vU@MaAf$|g>zH#b% z71}3Jz?s~+^+XS;^TZlpFJL?zRVSs7YP6;qu+T`ybN%i6eA9A5d*knD(@z1-UQYD>pDO8VgVE52fZ)mQwRh zAXJ;lHx03Adzb}ex>G4$rZrewSdJ960-Dz{jeZKX`Y-eztOroR8m*u!3hHOVJ++)t z3*Lck7#?A3@wC7D2%E?W z;5h{g+@u_Vv(vCvlW;aTW0Z{H&aXBmx=qfpkDtP3GxA)&c%03{)1LbT;}S6DNmfe* z9jCIHp!CkFsf_XIIbzLIAU!2V=%=wtUXmkrOk=jzQ$g97_^a_{cPL!xejKWfPnen` z#y!pY6V6*tv&F46oLSM0<*C!zR^OxOf6oI&dB*Mi^~Svc$Kvd6&#=!~9>L4cmfv>F zfQyayO?RGf0v;qlhR@E^PC&K<`0qU91Uw)CK|8;40um)4bmw<*qSH(^j634&#WUG4 z#Lef3p|e=~KsCa4JR)p;%wRts{tboiiiNXSnx__iix6J%n1l@0J`9@;n|b28xh5oBj!EN9x1+ZUXR_u zY4X0@|APT9I*!x#hiH4U0NMTD>8-iPZ3aKmy;%Tgp4@rVnqOV=Iz9mf`!)du^c+nH zhCd}3_?eVdNpAu^(M$oT^pHpS9ULvx7QJCB>U)~Nub_A@ol0BH$8Gr@mm<(8anwvB zd=KTN)gIKwbtE%-7uC)<@0fdDyfqh_kwrP; zAia!vEYp9hJfil^MTk=ek~O_mD^|~AJ-u8N9b3+dALbznuo3doS>f{nI~elN#(UV? zIUb>hWf6uI)7;k!%SXgn@yiQrV7DET{Fu+7gHq7OeFG@e18e&j`W~VTjRTAW<^b#x z7-$F9o+@UqLeF0>VIc!F61B#CY0ZF!VIG73ByracD#$A@V!B6k}w{P#h) zw!NT)jiRrvh>zy8PJBm>_-;O%;6-!bS%jC!E@!>S!eUiba7K#zc<+|nPdsdly$ovg z_+{b_d@EGsERCUT( ztLp3(#W0Kqc`@C>S~qQev4sT`|8E*>pl~Qt?b1$?VKp>O{UYTRAD4%AJyy5kVTI-U$|9w zDS~E9oh%(=zKBr+O72mS`3j5k(ZH}K1PwhZN?u{#^YkJ1$Nt6eg7A217HoK7W7C9< z79GLH${M>^%+_Fq9b)hO8jELq;vw<40^^C}i(Tz{U4+?8X*3x?k>yfZTqju^3 zPJKq5`n(!K93aE3$x076XrHl!P2&8I1LE}S*us3YUvR-p!Hf1oYGLyB241foUT-iU z^AAqtB6*d;PmB_5IsbCM{ThWjg|?ZC;|1{VkAbn`+p{>D*G_=XR*9rHSid&u`#{fp zf!3m)l+4{h%_r{Di|Oa|{^HFyuPaucCWo~84F^( z*IxT8Z?f<85QQjOi8E-tKf8J*-pxA?sT;TF@%`U=7`JEYS?y9xcMQy!c2rVYV=(6Z zY>fT0z7+i3G%qeG^21ocHj8^JS#;<>)^?zF0_gWy#e$p|%~bmC_tCdcU&W@ggdgl! zCh_iNQ3tDeDV*gNcu;RY-cB9ANGDU(Xq`asY!}{ZSi96^sAA1sZZo`QGo;!4x3g0e zponj};$a}f=Ln%_DeiSzShJSWA$FEZjS2^B7c3(}%N}NY{#KE>o;}WarTAz)JI7aau>b3A_5^FObBi{mwrsH* zHn8@bM{E%Z8?hXpjuS)a3DhSy(k^lA2lkTpSSQBUbPykIV&UPNG}Rk|Xpbg}ypxz2 z^q%;66T8;sf;vUCPZ7$yYPs&4>m2hoVn&7jXVPo#WF^g5Eor*=ZW6v9Fh6hgPDSoQ zp4ljpKVZ?GkDvm%77uR}1s|}Wpft+ED;e}2o;4T^`Muj)?+P1AP3{`@zu%Q68;6{@ z{US^nHzS?AUwT&@`G6G!dIIxrhWyQUMc>UVBfOrfL)+zBm@pbF7M<0M{patB)tgyx zD?4zA;4d5S1cN_r5T9;lcWKTZ+oC$ySGG7E?7>YPY!UV$>)}?ms$39CS|r9%)>gu`n^RVCZgoT|V@KRwd^(pJ28?yLF*s!x@*!*P3!ShtOJ z^3uRiraf!K*V|Z+RwbwiaR*#bpWaouB5pey!SS5CoyCP#tkz@uUD&$DZQyEm-QMmm zbwzJek#x*oE%t9`FS$PZuu#*%bYjt9nvjTLKe=+NEQI;|@Uw*$gYdI<1j% z*S)EuxL{{dvGr*{$fQk<>#H)3CSA4WdXUMOxKhOJU~!R4CAOi)Om{V4&uF2I1T2rF z85wV%u>%`8elb^U_?Vgf9I|g?_8SvxXBCnkayfVVE_Q}0XXQ@zEoDzO<>?5@@u++RQp{x2)f!EUBlsdI0tOMT=_I z*NYe}FF0rowdCiDoND$CYb)+nGgKSxw50;Rv3bhU} zBna{R1S7Jlt0+0d zo^CCHLgHQgy9-AQ;=G_PUv^h;CtYv+T#5iEgSNiC_t^c1nBhQ;uKDWVQfhR+Ao zu-<%27t!Z13-({EjUvqv9DdO>2@_8oW+pzqi&%UZE8f9)`>%&tIt$pE47D?_gW9=1 zesmk}i63Q2{OM#d?n9%T;){el;?A%yY)I1Rz)h+MiR{Ek7_)+UKT$FN+% zF`Rac_2Z6?_79G+Jn7QAf68p0G(j=X!cLDAZ+*%x@}PzGvd`EU#_yEdzdpg{5vF~@ zNw$#tcZ*eD5GNJWdW`Y;oMm>Nn$T1~<&;P&z1JYOVD%-kyZ3!b^1b$==rk77m)nas zPP34RC-5l)?aPu)zWb**K8Eqcy*QAB@%XPXyA))%Z@ z@TPX0dSXfcg*?lAOCR}^yWd4$um?G8)-PYMQ_;0F9TMNyq1gEH7m~T%Qrm6#1QzB) zUz7OmOExp&a9d((H+co}bC(*D>Lk3^Rut7iB^R`{FRf##Ec~jJBP|@xcQ?maZeLM- zTpXg^Jj2HPpKzW!3x5e*E;-AdrKi_9b|WA>@^3i<&{n@M zbT)X1T6mB!KXnz#&&BN3D$2}&1O^^=?#V&D&$`-wBev>(_I47h#Q z4{SeUzG9vO4(HWYVx@zbA_AU4TbU{QFK}yKADB3Kwhpb87hJce+rM?NL(Re$sUzUw ze7C)d@&;2|ilv!8MI8DC%lt78?3pW+J5pDTk7VSGg?}M zzVHaV|75#?A&&jYLK0PYeAR*h^h%nxjV?GQ|1`sagLr}Murc?baWviz!`GZg3;%mq z6hQsSd(5vH_aAMCWY%(?GFpmAWV-XI{Do`k zRb=q=pj`p^=rF>U0;!;tQIxdc0et2#yJ*25YsUXo|9UI_BF`T!%3ARie35*n*&p@e zdVL$y_jo_o`Bh3k>k9fT7mZ+$c(FA%@y=;tLu+0`ygn1izt;1){lv%+p21W4iDe=D zBi{dO`>;^nn(=PE#iL<7o@2>d62>R+cm5-8!1?4S&x@nsd?vhn@jwK>q6UF&_P##| ztQMVU5?myMz+QfBO~L!mW7F-l#y{?Q^Ldx z$TX92U){v!XdbVIeHp|zNULFAr$U8)Thx$YU#mhz1~T1c*w?gBc_fdpFX|}`8MX)E z&_5aW<>e_)+Eby6TBz3_&1I-ppbYi86(TEBc$5tFN=^|CZFx|E^*{3L-xbx>M1W6` zTEDN>b46$U*oB;Cn$f+#lHa_M(OI7m6sF@tdTP;G$^W@0R`p~-$uc}^RAc)xJj>>y zGZAe!4bS@Vyx3#nZPe(j=4v%pbXJ)x zOEYYamv$Dr+wq8r{X4@oOdF3HFh!F{K%;;FF}#h~7sI`RpVzR{2)hw$ z^7(t>TAe=R_4d3OUvyr0wC5vxolXLd99PFujH?&^mGzq+l zdN~{TBvGVw;8A={qIk3e59co?ikCX@9(-V;sOrFjd3>TcPvy-MMMDRkz|SU##E!_@ z6T}F79gDx2AfD<7R!S1Yf{r|_`-2H+PaOb_n{Nh5ZsY}C8cNA_4!%5%(;s`p zc@XL4i(*$W5M~(3(mP%qvs)OIOA)J6E?}Zo;d<_d)DI8shtL;#>mn*S#Q~W?PZG=RFOy zODnAvGBnX2mjZDRNXB?j3A9QM(I43|VluK5c^H4Pqj)-z58w+sh{{AhDA4%Ey@rw( z5FgRnO4Za`$rf?KuM>~LRPWk}x8o1zi}9U!aOOKh`m^t%-eRD{zxOTjJ@z6i42F6_^M9g%VeG!cNq4(ej@@5WmiqaI#l)$ zIH}1{ZBmA`Nn=E6XZ{xdBgTHAGXxt;VHEXMi0O8$*o}1^BTqZ^APPT4{W&%20pRUU zA})m|bxqasK}o1J3AN-j!9>ww%Cv9tjl9Xgpn9?2BT2lH!Y8-6FXlp3xcSl0^wEEd zxk&EH7w`y^*wvNy;ZH@2-@EcSK08{Ny5SiZErxf4?~|Ql-_wmpdGbGk#D!G8h3_6M z&iChS`5x`LS9|UoZD#|xmw|`062=T3Ibww$*&1y1R2BQm7m7O5U^CGBx6&Th5#$gq zS?O?uoW@Zyl2e}E!EP1E`jC=Z|1DoplEE!efv6?#a#gSg5pn*>5{ArT@lys5X?@Pe ziPrcBwQ77sUM5_rcYMUWO#WC{opd3cf7Ii?leAer0w=@%yhST};6VN^>vI0T;U0Fp z*;1amm8?}y-Ed7pr*55m#PvZu8mG$kz`=ZoKKO!40cY4g0T*R@0^KITL$%M%;y4X- zjJCfzjOQ>OJ5u~OoLl(i(e`QCSb6!?(PHrkcyw1s+xL#(6>M0Lc1*q;1hVMzlp4+2 zf!tFY=-~B+r0@IGCP3Vr$g2n$FVGNjKCWGTv$g_~5QIbEQ9Qx(wycwn&zgw3QIHZH z?~dZ_>DfMq3u2-whj(BD#q?Yr)7&SQS_-&3S_J3vOrNW$ZF~ul)3mYm)?t3<@>Gh{ zsm$d)xgpPfC6|BvKg77hQK^$+ys$sAs&X=3FShJ4f%m0pIm?dIqYL0#8gS=WF=#>XUYd&70 zD=E1|=h!Xr-_0Y>p7jVn%YxL>gD5PyMAwGHJhb8m9^<3vg5SR6ap3VEKD1ANk|X@c zCr`|q3OnncCzem;&+!Mgh`^`#O^%(kaT=U_JfD7=2Z-uvSm3>KM9Zi7L_F;PuH$s) z5HN#prspC2H3E9xoguw^@ySfymxtyELm^+rgYv|xLhkRWUUZFd)8*Lr7V`RLM1Ivg z-p>Bn^W2|lx%Q&PJgy*PM^PQ)*yhYB=6C$%#c3?=z$exkV@dY{az@+BOL&>5f42Ja zQ=(d> z(ZWVcJ}u$tBCUeA9UG5fz?x~kigCvBjTLbDUl8x@|C2_}d}HSZlzdDlisf|<`rfJv z-AYh8H~=)<1>K({sw%jD@kuHr*8-)#${RYO^bJ9qt5CQQ8l~$5#oOkDd&mXVB?C(D z?E$*Q1#L-CqY7Q-f`${+SA~`lG)yv{Okmn%fW$Nxaz?V4{yJDJpi)1zbbzaLDnaQc z2z9XVYb?$pXn+cB?Sj5c(AFwc=Yk4?;`2U4;U`u7(e<|pN-u{1dYYgriysphf2D!I zdtJyi$s$sK#X2g*WdxPJ<|@5NP`XD1bgm0}ouG&dAn2nmsG&2U__Q2Bvt7_og5q08 z1nuR5b|Pqq3N;Zl9#VvY{8M!6K;Sl2t9SQ_uLTe5Iv(&#eu#Ps#rv!ta3uWT8ZH3P zae2RdSxgT_vg%3U=meTbgyxClrMxwd%(D+#%70^7J5(CY;669fI8QV-?vpg0gfd&3 zHKk#KI!kn)`{A*9cIz@;z(NgOn(*ZXzI?$~5`YffUSU|yhx<+#B&$> z-#nDA{eT(|fO zPIgxi>_mfrvB0|Swf}GOM8deIp$ZX>QTEKul5)(Y9y+g>jfT!9?N*WE(FT;qI10%4b-ojczO*V z!c)76-D_alkw3SFKgNf46X|Pt|ImC?ft=j2b!$|Q5&#_!Zx^fA@`Pw=hcup}g6QfhLavzkZl^$w_Gxy&4{>DXxjT}|1gEsf0FOc z5wkwv9|TbtTKOMkrwZFZLfSVXWtdOj&G>_HvxGRYndk7*RifP%J~D(nl9`XrnQV+j zV9NLd#vC`|4tI=T`n4_m<+jpgDV+~#7#BWIzkf%x_xX@dz@K1v%f9?0-kZ7C65GLV zi?1sAB%Wj!sax?(oGI4U@V?^ftvrO!oh9yW<;PUa4(r5c+xSpEbg2m4&VO*fLDhd* zBbwX!(v~~Rq;}-i850q=B{ti69gkQl%6ITX?t$HbxMr0Yy_0A2k#C3%JNZsy3V_fE zo8u4cV-~Cw(?3Sz8SBNVk9i)&^>y5ZvjG1bF>DuP+9ywJ-^G*3rK#Tqhb=WvbluG} zd3v7xh27kZx#v(5)0PvJ?qdHQ>?x|=6hG|Yi`*AcN%5QFxxJ8P=4^3dFW<>Wjui{{ z@dNy*z+EB#H;>H`?e_C-?i&fY>;>`Ae%__o$CMc?-rUbqqK{MB=Y>D9n=EWqQyK&T zOCJI{wx}K*nE#l#wx5SZohQ7L^P1w3H6mTiBD?{j(*YhH^)sQpb|0E_K7iJe(DY&& z(3<^5Xrshy2Y5;|&mKs(5yuZ;sw{j|I1cbI_i%!poh!Vmd7G|7uuj5Kb|=`DC;n`3 z_!9sVkS2)HUP_-tD!sroV`(O|MRUd2YM$I|FlBPYtJUcBa7u@Wqe$oHQ2N{FWp8{Q zEv+OH@?K@qkJOh(&`36Z(CQe%-1ayCZ3xiVYOBAu`s(u{_n@=YF=Ej{XRDFo6Qtc` zt3S>W4F|Dv%$)ouW-k2+<7}i5UW8EO9Q^gjl3g3-P`}F7hzFQH$jxd-?7SHL3D4;0 zw}e8}3wvp%={%lZvwO-FUdjSr?K3-m#f8=MJh7kY{aUU9%O$(s{Revd5a>--{!Z_4 z^w-(TztZ!(CV9?5Y`3U7#6!X(AcLEwf%uIqq*H!rvamkUZoT75!D?_Sc5)g`zt&xJaUBpTgDNn$2g9! zM8;9Rwhb8HlCmMDB6ETr)CD&=cdrSLpZeMn?F5%J;Gf;`2|j6&d@YDEo}h;WNr#Kf!|nCzRtm z41GP;!QCsOgKtVX(#l0AD(oZ+eO!fmX8RC z!n*@bfod_eAH6MJtmO~zS+5Gyzj+KBE`F-TnMA8sMeIpfkTdJWxRW?loUmRzdy+@c zswqzLs7|%(m@cEV8gFuV^xo0~sxWt}4beaT_(Ps3akY_kk*?^n){7rc@~#1)i`C|# zh|Z8+{d$pn3iKDO6GKn^f26&6T$M%iKhAyTVbQ>QF;rAUR8&-4FjEm17B6UuI|>SF zrslqaI|9N*t`FBGm!r8>R%Tk3DV9rUCR$cjR&J@8CWN`j^3Ta^0)I4Z*L{Q%B(=q);Fq~GE6g>RAPk9vBu zACcbmU+~Y~q}+<>hu)-l8+70&^g@^T5O~dXEEmxUVc`YTcdT(f5yD#M)E(Wyr}Y|BlA^g`=^~# z+&Zn9A|bJF43}tOzBs8QVuQq(C8vBC(`buwL2>2slU{S)diwF4(p8zgo}NFiMArB{ z`#&{*wVo!NhvxC^^|&>Ki$$x}LZ$1Xg?rfV6z)FB_iAJuYUa2{g_}>(reBp{`u)7p zIw%3x(#i;1?|CnjQx>Ju`s3HB!9}Gm#a)1GcJOtYeL)$+>+r=3%J3Q`Srt&yi}-yV z_5W3A)a=kYpcISh*GZIc@8wS6$*=y4(mvYwtCAQr0}siT)vTA)1SOP3>Bv04j*$sd zeqKw%FM`g7t);ma!5H1v(yoh24gXtYa&bhNGLH%Sxy*-ZvTFaLc)Kx=Gl+h_D3xgB zeo2Y1ady#vaL*@7z62UrO|uQ)Dv+aLAs!DGa^9<#>l^ODkeL%<`)+Az z0Q?DnUjeW&R|nur4D){jS&ke+n|{MVY|T}ad_~DrR;;8)S1@CfR#MB~u{5+?NlCve z4QgD))3pEU#5Y#b%HN?#8@rOe{T&A{DDvs=N=UbhqyN*2JIGyJ50_E(?!U=Oa>yw6 zX5w`OIl+qEjNbh*kS1SMdV1w9dRBTi>7Ksq&=*&6@osi9Ij$*#{aYln$&SUL4uFCd z#EyqnJy{xI0bL}M=?^9T#Vo9=#tv%63~+sZsLTw@9P~SADT23p(h?w>;cz~V6|~7-55u08LL2P7(EiO-auh0^>aPG)fwX(pMlh^}VP`Nbev_xtAB9Te!3hA; zA2r!M^l8~G^bQ;gs7CxdTeUsV&l-*crJ|i+1)7yFpvnG7Ok|-e#Yc~lhcGuf(#u6k zaJ5&bNr{WKI)z_Pq4h;d*Ct({#)0!Nc{WlH!|ma#%R8!WbR{K?&nHu9kuulxTHf40 zl}n20imsD2j{4$CAW{Y zUk~g?c#DU(QsO(iW+3TuXt4bnn94T?iFfqUujy^t*_qi z9J^RQ_X(a_iRW zgQ9KRLUeKAysmQRpdO2=!8}Oci0qB3!L$PDFPmWom&2IS=li&%RKXp}RY)mz$H#7b z=+gh6sF%V^mHMtd2ji9^^-x65GBQN_bTX7TRhgCoBWb518rK^Mb2q0_V3nKBz3{@V zq_-@(rHCtat_|WYfKyQO-h2?=F?qP&8BP`kQ?U>s1_{e4^gAvotD@m^zaR^f;ZHcr zU=sG*!x5;q9{<`{BZ`vD3^HaA*;Ub~>I5T8$3e7L6~~o211a5Av{RNM>?)F)6r!aL z+aCt?r2sngu6fZ1y!5Q*@>mk>JAgvngugOo042EL2Ca$GQwSNYHB^e$I<_@4Q z+(dWNPV#UUjoPJIZT2Tm&oFySx*EkJa7ZbT{P?+*`HD7 z>)#S(9Gp}}Su&H)D*+j}#76^IZQc=1jwM>3e);g z>nbAOw3u#J5k9O}a;qw0O)t}+s-hLIw^>z14^tt1V+5a86@wdpiHC^53MM$uI$ZF! z60h9hVC#lQoH~7J&T}H9_B4#(-~56PlJRSchiZ>o(vXfkC%U><;a8cS)hBmP(K@=) zL5f^RYE~?GH5PqITy0T3UuEZs>R$nZ$+~7ATHq-HOwDPdr|>tPRWLY;%+Tat8Ft6& z^PzDAK6Ysy75+c#-P`>u8_q7}G`bm}XY2kyW_!sa@?ZI^M!r1cD_rFFv@}K=)&uwI zZ3i)b3O{J_6u!x9FQB27ed=`TMOj{ATA$Zm!qCOQr~-=Jn2!9T#RNOgic@4_u%6h4 ze;lj%w1+2TElV0g}i5n!$nlV1T>XM_H z2=bGOwga5VWEf}R!aVE3O=RFi`o5ZI(D1Byd$jsw}k9usJ%S-j$Y$`6ni$5SnfXi$6C zc)j@UT1-bYv^fi8z%Qx?^|y$6wT|}$jmNY>N*jk7ZX}v}kj)|jYOmnLv>xzaV0#gS z51Jo@;V9hIlMY!#qsqkL!KOHX7{w4{kdcX@^M6K_K~fnc(g67{y)eic2B~j={FgQu zKuN zh+0+`zCJ;SV-P7!=}w2%QbKjnMEN3yGOCMXH4k94%^%vjgT#cioWYBeJBH-J?BE?& zQxd7Q#q_cYr(*mnRQLv0=+!N6Wo=?tJ4|aX)}>~KuAXOle8r|&bC?Kx6yV!5kMeH(~&BD8~|UnX1V zC){XD1JS0eAs<(6$Wq4f>aW9DR;88C;Cs1}F{_)6h*&vl>oayp&5)f|3wj!4Q z${mmu=5Yo!@I?kZ?=HV%`TINldn|u{p?|0IcOJfdkzpMN-bWzwXfS&ZDVmCcD6fgw z;EA`_KxAA`$O9VDRHV4e2wOg#Zz|>~6A#jmATdliIfOn55_4EOYt>97n$q*MX5xs6 z!+l$b2<1>OdaZ?M%5wew7NTxwt6qlsiK2eHrS+;c_!g_h$56 zYf-;bp3E%^;@n0-x3J1M3o86kFK8F8j#Mb%dkShJ0wuE{IRwj2-GCHD%|uanQ5|37`6~c09T+BzVc3)ulXxaD;}gcPrnD?XbW`T` zr&A%q-}H=bg@~Y08{1$Z&T@<(%iOiw$i2vZD|W4svSf>wiV44M^h?oD}vP#xHdx>ZACq0QDcUv zPm^B|z8!kvB1}}+W*2A@7ZesO=3oB99*W2LE|<;Pgp`>@@H*$>m?j0^fS1ZLG^^AyY(fMwXKHbmd9f}I#L6PmGas53`k~F9;T?1f zRIXRH5x*M7Hv{4o&JR>L?fMP)=7c=+ElVj;^9*EgRp~sHsKyz`KsV0Rn={ z>(cG6;w7bRUFzHood-Lxaoxm0|Cce?JVKv9@yb;#;IJCFFA6m9wl776i@(?-@A(kp7L-Kk@3V-3>2pJiXsg)6VixC<5Jmpxi!SRjH z`_w85g?~E(_!z3Gfb};F+{{d$_Y~p&2?orp$}pu2^L4endM^o2lmBP~sJJpvgYE!& z!;4~iiLOd=S6bW)H1T~kdasuV^<3ly@zB}$o4rIMrCog9^Sv6=&h{wpnv*{ss7bHnA(q`k~-{K3G{!% ztwJNR28jM_$@R+s(Y(!icg5w`q+M_=9k&Y<&%fzAy>_iZZYQ6T0C~8t%F1dZo;pF#EZ%Rm3-pF&q}VK8*!qI zGE|WNU@SY$1@##WF-J(H$OJf&A}qZ@YO2$ zNOgrGhlpd!6cbgA7af%=U8#G#Sj4}_<1xzkeG)I)Dm`7ObplYdxX`!+5iPPyP4rQM zuq%IbrOrde@5+O&)L@u6seJyFZVdy@@0C!4L@~p^S~q=Oyb8uz0iRzOpAIGTQKE>c zRUa_L&)d%kx3Fk+mO)3s-N>ATg1SAWh$L}ec`u$i4i}@8F5PIuaIwL^k5O=+$^}2i zr2pC@8azUD@%!g7_63*14q6`ImS8S!7nI`tVoCaky3&Uuu+rapNVP_al*WTmTG3xP z1J{$sa_}O8nGZdZ4OWrTE$^d|;+UyQK6ruF*%qEa>7zu9uZ>|pX4VXA-2|*~u~#{D zC|w#QB9%4WsL?B8z4F-u%6~=7sTq9V1O}sdN&g3NS6}eP6_0)QsLyDzQ>k)~o{q*K zMBQiDAQ~}7^t0@NcVT1zXf1%o+@;UQh{ejGzX^|nHd222o8Fiu{GT`P&D;RALXRXH z-M6_LZ5oRKoA@{VGFG%yI{!^>uL?~G7?!v4RpD;J2W=Q90$&UmhStQLHs@sxVH<$Z zW66?^b{O4TQkfNmaQEK5Mfb-+Io9P4^&KyIDzIkMo(P0H{zd8}w5;}D z)NGOnR*G-XkVz(0#R0zx|7j0~q$(}Be2 zg|vSF%n%0@UcW-aW{K{~8&{b01}eSfuRr5bJ0OhE>X-}(X8ziG^OY+mWIrOYtgG6lYRA%NzOL?$pAm_+9A8-K{&lR zR}4~~h10{iVwO@RB5&F}G0Noc9ij7^DY(;9f#1B&{N~{Wx;z#v`{9WBS)raL=P8=45i?#9@vy7#w)L!r7G!Sh*I@z-l%lp zW>SJ9@+M?pnN{}u#9%Kf3*~Px-OdzMlo%OkPK~ofUByKP8s&}25+_Vb=O6RhWQ&DL z#a>@`iuUJVE`*#SSG%aM_?@CAcFdik?g-Z=rP-gprO8Wx*YR&@>k`qpX$99A3)z(Ii;xEpjH~m!NQC^P zdsmPCmToV>KF$0sy|_#?ufVPh>I1u)ril)X+jFP;!BSQqW-AB15X^ky<)nmx5p+@$ zaZ3Gfs8KFDcR~d9%N4%LnUgdjSHv_*<~-Fg{KssqFvLPz9fTh((gL)+8LcTN>2$7W z=eLjn_rr?$KM?*WDbNAxT#BL{T=ds8!2#a1C4%1K_&pKyokJ{8Mn+KVQY_40L{REd zz`g$!(NYnsB+B22YS);=egO4Ag7x}}n?6)I6+tVOiT29n2s*J0V%d-rRJ=^|t^16z zv4g-(`JrE=s3GTz8|r;`RrBK-u}*n-n5Ga~dhsyjkQk@TJ4}C**wZvA-vk#vo;a;{x(9_} zQ+J+#73d>7pT1oyCVD@?ds*_dsaX0@x$!x@v`!3GPJK>qt^)_o{+#|;2dWKVEoiBiQkP{d9YyNKpRyjCySXKiK~nE#3r)#r~Pj1Ap0sH8JKhda?-<{N|@LXfviw z-lwE(7R8G48O_;(Df#0*TDJuwwPhcj+=6+peM+~s2%B;;PcLNE8z^~(5xDsV=pzU&j`wQW6vaXCt#elL7N;%zao`HPXDvA4>k94iM`Ay`=L zOI|=!=M)<0X0(@zJU(!1RV4+1Li8nKH^`0di`C{;hc}?-n(Lek{d}qwxNsn z@1l%t*c+~lq>bCaH%9HE%iBcbzVC2>Lm-mCHhvO&Q|C)m&Z+PbC%&U6_T@x2s5bb^ z5l&lzG@Sw@AGrA;4SEl=`75;cJ<+G;>kP9L-BE!`hJUD2$)oo~)0!6%19f}wPMpVSY8RZ*g-*9Q=Y z>O|4>4=_dZwv+Y&=zs2ZI35yHl_pWt=|e~lxGkUXA^6E#@6qNDMO3Zf?_pjXyvIj# zF=afm=X><%L(p>9sJs@t#1U1|-lkihU^@qFs_qdfoz8T_4b=9T&lLCukGXxBLqVC3 zloY?rXC@qa#@zM|M^p_4;LsrsLH&4pPy~It2Qu#Bt#o$}#Jfjb@*35ZT~*(f9$t2 zj|LbX^4ZURz`vLh+ZstuSE+zDigi8RIS4*&TTjgniI?5Sumn+i1FbkD>iV`vCM}cM z9jitP)WG{$m_^54r=y23w3hW``5e>>Tccq7MqYd!Lkr!2)2ow95Y{&%&yjzn86KZx zdG8>Nm)wi%DCcwZ2M*qT_*}GZ?FVy(VlQ*6!|c5=p~h%P@Yu8B){=L&4^T3!Se&AMwd8B!bK%M+kI7f$Z9M#Ll(|X8ZJD`WKtV~0Cp(|%J2IsFeXtUv(x#^m` zOGm^$NsQ~h#EuulxbT?B^O_HJEgwOkfaT38vOo+=`w4bNXVIipFR{e=jzIe!h3970Xp;~;-!XoHCM(6e720T zz7nlkEa4P%tyY#Y2Qj6#L4Xq}o|y;v!!_m8!dpw}S5#N+4H)>MIxGP$g|nBE*Vp3J z&Ib?|6`g70yCiDplZBrYc1Mi1nlG*6oKv0!cf^jD2`L;I9UB*L3R>EH8SVO7v@!Lf z-@X>DOnziJ37uEgFiJX!-OX3Ilyy?Hs-N%B>EN|o{BBf{7oBb6U-J;x<-_RvlcGlB zFrxy#O6Ewtz?$ky$j6Z5WDe>4=(%qorW9+`@*8nQIgv}=-->3YI~4YJ>p8)=1gHTvjV(b=Qc5|+~Z@WRa&wGI`X6=BNY?$qR*2$rs2KdLJ4 z^zDo0P5wD}k|bWK(Oe>w*U>lqR_L*_#|a87isF|J~V zC2i&2dV2|(&qHx_Y8Z7mFWP%d&tW`rUFiO|A|R?B*darCBeo#>C`#o&=Ilb zAF0R43+2ac95Y&vk<;#UKwkWJqK?ULCXCRM2Wh=LaIm~OKgaq@j`d8A^{h6~)Aj=` zJtY#|Pc{Um&xX;RQ?N&p9$d~&rrO_&`gPNN1Gt?yUW4I`!PQSQ^ybMl@O#nLU3zsH zJDGAhAfNVXIhnrXfOP9}ZxTJ@fOPA!e-d^00RidOWzi&>#sTTprRO9VOd}xux>zRB z6%I(hF278qx<4Wy{km+LNP{>a{kn{qNDdB2zb?TO=@uGgI=FappK^z zke*#KCeU;aNY5@fG~a$&)Tt*Ox%@r^{b%)HM=lvhH=rBkk=!@9CUsgwrAcQl1>;Nj zW=NSc7th#-H#?pcMCTE*8UJ#{|M~o==umaPJ}?-%8a>Ds%6WhZ{Y5NzZ|C z;DkoHcUjG`Sm-h`y!2Vk0aJ^o(!Y!T{8poKl%#)`q_Toq4@N;1p5MxA{!~7{H9+ZgmC&w-XG zksBY!;qtS(hUv5m9#tBD2Rl7ymU>2(YiY<*4(ir|Zl4hiO|9tpvtoLucuqaWymZoa z3?2JjLGkSo3%@G{+unwwMCV~yI2yq$$RmvoofQFe>Sy6=_T*7E-pz6hDxqoNrur6~ zJ?gTLd_k+xaBA`kWS<`MXvQz1eOjd#vve--9JdW^OdW_W>d_ZeXb_HhZ*-hdmUN-B zWsDp%HGLMI>nevCWWdz0Vkj1r!NASVlRhQPS)&un31hf3drJ4K+PSv=EDHi z@NS?P>QqW)Ms$FZ&tuc!wUBn6$3Ar8hva%eyrN85OA{`Lx^?dJb5e$vn3l+ZZ)QG) zbyI2c1!xkdjilQbuoi5m2ERhPS#2mS{Z+I!9j8OTidvyTFm;BpZ|0}WUj&|BiIB#n zj-;!M(STL(j$tf_ntH1%3Qj53F^#Kb9I2kcO^j6GJvGHzye+)_A|bo zW?Kf3ake;YE~QJ#|>OqlHJmo+ZXrK{M7eUnU&u3{4p zpF1yJLl3k~p`q7MSM?N{cMXfWT1*?RL9e4)nAcU`8@wn8zyPB>--CX31fjuz3c=pn9<^W>QqNC8E{ zr@1;6WFIvNa|m~g$KglLkV-y%bo+wyG`vXEY3wk{WBJT@0A}YDo@UK$2cVqRjh<*@ zk??KuUz@y5|IIv{&KF_-xMUhVC_<}`P9fhvaVD_On%DbJ(byD_?2Qhzok7uTB5#K@ zRQPm4iF}O-=PD`w^u}#b+hnEpi$ym);8|QOTKWb@S7>vbhZfn78C}&$)aC}Xa9&d= z?S=?7y-1(l5HY5MWco|AH(jERe}O&LpkaTBx^CaC14lSP3lODDi>57qK_9SUCQZ4G z0ooc(HxM6K)JVQT)QEfYa>W{9O|N&E#{_D7Q%o@ZN*iyA?xwAD;rGsY zy}a-k>U~SJ6!Tr4($w3cUJZ{Js0rqkz@~57ShSRP-zg1fMKOpbJ%*0oLie&s=X#Z^yBG&w@ zBcN>PLDlYvT1~z|^#w8Pp8$4pQly$9V{o*_G1A!2G&Zl-9Tu|2kCpRCTghw+UR%u{ zDuzkju(6c!w+Lu(hEZVq55BLn{6AoI#?q0$(KgSX^x$vN%V+f{P-dKmJ#r*at--wv z4@7ZyMT?qm9meQ*BH11_+L?yOp4K4Ezur-7yBxYdSa>8@zr zIN}wwD~hirfrNdSHqM~1f+)UhfEZtnu~Dmg;ycALCa?6K=woX5jr0hY;>&ncdf+M6 zqv-9w(XBUV>H|@;>M`t~83uldmOX$C;_K#Tpxn8Q47WwOMzU`kI`KfXXtW%f9V9pA zEFIxf1HbxIEhD0aRO=ro3YTu8Y5#~iwJJF)Dx>YS^u|BXnt0$@sDH#N8vjtV>>2cJ zDQwvFyQDr~-Nt70*>Illa_rX1Pigc0;s}nFebGY3`j)+RbB-=Ogs$zA5!CRJXlb7M z4LZ~5K4{?x8vaNG26RTG;UE7yY)<&{Ib_MT5ROh1eb%m|lolnLBAXo<;anxd3#*Ql z-*TImi+Dx}eSqcK71mmR@oPr4M^XbkJ0xz7Fj1EzQ=llo$7uf8f)6dp6eLpcu@@h{ zFQJISZ-%4Hif~pNIxELJZy%02*-UPcgZVpc7AE zdET-OI>*@WKTf1JC8BoqJFvVlcR%vh2AH|nPV6gmQE6C-XxrjRqDg-qzzxWt8<^H( z!Kps$W70Eh)iYR4D(ypt=QcSryq84xOK{@ZCy53>6%EM#Ojy$Nhm%l9`m~lN*~9Y1 z*9BTC{LWi_a;)zf?~{hG5>tPY9+sfytOguj9FC`D5we9rJDHyPu8TSA6ZCk2bq5BC zMI-q7<{iJcbyvs($A~uAXBLeCfKvkOkhTu_IwD(N!~%Xf<`e&}9jE{1Ov10!JtVT8 zi7nkNTc*i0?=hDV*oNg00AKQLeg=S&BmOIV#6m?84`}bC)A-=aVR2_*K8zeVb%vRJ zqQcNe(-093bxa~ZkK%1T&Oy*fB46(Cww{FD24Y%rBle*l#;iA*8*~_s19nMWhNT9- zXagVIv+BxnExi|&0IK`q5-2@pr<-8@vn6pcG9;dX zM(r%X2H8#`1mqLGH@7-Bs|vgVnS*{b2O)jL1#{5vcg;yZnS=gB+Uy45P@S7?>n?Mvqq98hDLa7vm|fA#luqJhNPfgtgT5&;p8(p&F~k=? z76%1vhs_C8Bo6Y?zwo+%1rhQF#@%LY&j~tXQcNCK9PFgC(`zJ|CBuy86GlLbkryNE z$&+;j(%Z13ke&4=0AaIvyttP$>+5A%B_`!r^_&BD8#%{0b9zGsYHoGeym%@)yl4UU z`q2gQbZYtPEo#j)o-!`w8@$Ax*j2pQP3}D40#&A>7nol&#qlfP99Q90>Is}q%`Fk>d52oMnowks_+je!9+rs4RBa{p9Q%E;K<=>$$zl zfoyUp!1fdV9z`GFJMA!kckSXVIG`f74UB?*VwgH*FbyigG&Eo?G0cOq-fUPArjY@2 zond|`gJ}d9njlo~m!EOM2W1I?6*D(BGJEv`%#t#g#uZ_j7%;vJGqwz-iAldr_Dy5D zAk?O5j?B)_!RH^On)P-lH=tc{WOj7dW9%}fJUq7yqMgtoUNs<`;UOHZfij}naFO9} zftx^g@NghsN|sSAIf_LDeuB8DSVhWm%2Cz&6)<^}^KVS9%b0RZekp@+*8HUb;SBHL za5*NM-qbM}Y+zz_Vqil8izFv%6v0GSN++2&I@*)&*;5|cQ%k6WtLl%v++bI=Yg(|& zv8a|NZiv2HYx61C;(l2pwsZN55!x;L4o&`;LuGxt6`^tlQQ^5p802yX?L&I8-~bAG z-x)CE!j*66iQO(22#>35bSUj{y9_|rG3G^hiCiMi7lh+HL;I_+rRcAk_eNTBB0L&D z#pKP2wBX9(1UI#{%F;b;bW@X>_@FPKrLE*8BnZ^voSX3K!45(K+*RL(Zv>W3E~xpgse>1j=X-3!#s zLv35N&?eci1*+=#9;)AP4)bzZHCvA_bxD_OFvMss>Tq!^mSYE|#*o{1#IW&AFLjZS zT`P2qW3e1_19IVF`r1QnmDb*<(=ex$ES9^{#pQ8#=Ze(PfC0X;)aXj}%b94D>Vo>; za9aFXpm%x!Vph5Gm1TG56X1Ac1B-N8Rsj0b5c4{+m}fyaePK)ViW|PndxrTK79Aji@hO`lTF&T85CX8p zubLhFK8&TaJDUZaDiyVY?EHxo@2qTY7(lWE0f7R%^xgmP!&-JbcO5#w&YwCocP>K* zNoa=Z_*@wjK6NM_ES-yd!LtCOZ^n(2bhesWFHIh~=(pt!^gG(E>D(nPVB*T&CL+t) z1+etFja`zT2kn`eWg428gJYp(Lr_wNej(%eNgxSp7RRu5?r}|~fwoQ40Ypc1Pe3UjB zh(P8~W>-4a9LTjSaRV|+lSN6M&$xcEpnyx#js7jMfP|aWG>G<)=z02c&q9=Ps=Z<- z$YIGia^XFQh;g~-US!X>j1U*UT>I1o5@XRsCUEq?t`eEhoa=~P4te`Hpd6EA>n%x$ zh=(}ty^)XTir7~jE_L!Xyz01wn9C^c1{Yvzc+N!EEo!5hWks;{J{kUpaT zhJ}omOpc@EnV-ZT6Tl*yg6jqh%lVLit}>|S$vD}SR>no%2|%h1{ym(fI~X@w;tgSA zA3%*dZF&<}EdN&poV8K~i;ycCBNz6uik>kq{R&G!47x4sQx6%=M%ch51fT`hRp@P( zqEXy~ajRJ9HmEC&i8Kc&6v(|?HvnL8JV04YS}KChK^ls3fEMX&+p?G$yS7Yc`1;Eb z1=h7(i?-Oq)x{+$wuF zC^#Fkka1F#3YF%Z{U5p_qux{ZVDjE&q*W$Kd93q?pfpPc}p!Q>O z93lXK3expGwYPPvsEBH++1_N zu)h-3xSIB0Oa*x9_Asq1gVX7umUW2r2{MsnxF=aI@bHDJ}W}U5UP#*$)3?7vpzgXZ+h_%!F6MaZ?0( zfbVt91{_o;z&|ja<4t7s!NdYTz;<_|(>2r=(xQ3*UtdJHdP*XWkLoU|&3u}Y6a3$ynzY7;Gq)WwDJVqa__Lcsj+FK@5(@$U}bzGrrkb z{Eo}EGOwtw!Hi~vhZf_h#T`XC>T<5*I8GuE;5%FSb=3ORGtg*l2v0#*UKh03qjaZ^ zT03np;&J2+@c_kEL@8 z#PKld^8oY1mX*Hm8+mUiNE zaIVO1%r#lj3Y}go>n73s+G?}FjIGX6jER=9#Tj7~o3TL_J4~Pa&+wu}sdY#B^dGs9 z*~|`eZj@v*pEKg%HR)Z8GC*IIxj|RJ+K*rcCBG_{*JYe7FO|8HIhVD>JPFV!C#UQ@94di&I7!wshTg_` z7dEYRxN|7$x>d?O zpL0)WZzAvAY7J^NO7ZYSU*Wk)mck>C)56ATHw9J?pEp+b!V~ALChD3pM5-y3in`22 zt!hWjo2t{5Do1EzQ#C-jewaRQs@7KmKBvn~ReKp4yx*BE?b36 z13Wyxgrfj8z1rL1@(#T>$juAyqD3}S6%%_4z~gK|G^M#ZQ}l^=N(t9ZvuJ1w)hEE& z=65hG6)Nk`m9=dHozaSKRX^I^LiJMIkI<(r)WOlOhO*r!Hs|_l8}Tv-uj6{~en(Di z$2b-JfPH0DNB+DhKRcHlxqbTs#RaRcuzQTpg4LmA{l$w*1vGpajoen$wk2TE3Tmm| z3cB4MHAKr|m!ASrMRx@5GMD^SrMOi%{uF)CN{vz8?nwW%QiGHS-%*3sYCyLH;8!e< zdItu>IA(Y|+xZl)qSuj?@qAmB&5fxaHb-4Jg5y4fdlW6YGk?DI9i_KcYx^v~86ewE zC--7X;FP}YX=iKISLxQC3RM*z&nT%{-;8 zN~UmfdqI6>ipX`lCmyaOo9pK3UqSZK;2I^&FlZ4(^~PnUuP%^R$j? z8&kbg2KnE_LQtU>cXFlI=uD`3HPkuY3q3IR>PRgDPSaB4)yHc__B5nb$R5JkkJJ55 zY6IoxPsle+{ZtvhgMJKCqm=BXM3voY7nK?+7iKku=vT>9nZf-kD}Dq z%LWNnrxhElFx7e0qK~?(AA{=N9b;8ZO`RPVU8NFiJ;pSw299^*d*r+$49!AJG;KN%4m~Ve>Aa$VHR5@FnS`Jj} zC~+3*IZ%DI`qi44QhelUvEpBX>y0=%GEjX{dD%jb2C99_m}~pWLmtFK9`F9YFxQsr zXyqWZ^tBqK#;HA&9yO>>oO)jw>qFMT>aaBDFntKxz@&l#yJttVL{2Jaqjy!No2uOC zt5^+rScY`A{ori3uDSk*OFG4S;{_OA9xQJ3)wOzWj6+<}RQ%JtwL11Bsy_srXSx@K z4#8B+Urq~#r~{RW%jx?eYPwRij0VQ5-Ib{2v@TwqsXVAg)e_XpO7Ep~J3&oS_IOd> zp=zw+QiV1RRo_tJ%oH(9%~ytakVsTVD-$&upQtwTp8>Z#+_Z?!1>s;2hDZ@1`S49Q z+LfpdQU+F!r?q~*{mcU|Bxi@}8LIo1&A!pGuG-!Bd@MD7n^scx<>yofa zzVI6DPf|PaU66m0)Mm;8S86z1eO39+mEi1iiL%m_YK>64D%Wyo$Ow$l`W$*=1e(`5 zXU#};S4}@Wqrfv^7Un1u$4TAg{;`p2Be7d~N;gKLY|Mb5msP(8y3posZjV!I zDXSk-mGM|RJ)Y2j@oH>5kdxL>EN!?mA$HEzd$Ry!pvAC=Xe2Z;5r*bk(dk8sJzJ6ULv#%OZ)Py0dTmOLvP-v!7LeX3B@p&3QcA*psl~vBU%dH&8auioQYk z=)n{}Bp6@teweJ*Yr2v3wuQYb7X3C?fv2T$I>$w$+`vqlJW2HrgqPmfd|CJbS*``; zCc2?SE*8rLzWULJlhgp~iKi8CH44NPgz^HhlN!rgJzyBi7@F`cG3;4}VSmQZzd9@S z3t#5)lC}W|Oh2#tWEH+1ydO~P6t#6gLu`ql?1Y_CXzbe5M6GXUxPOND76%5}7M~O_ z1Z4l{KJA&J2KWcUh_J{V|Bl7Dhl6a3JMqEU#PqT_=P9>#2XktUL`87cXOwzP1?oDaX5_9J4I&)rrml{q}XZk+>m^++x_UI$y7(gzNJEviRTymGL zPE*?}Z{8)p>1sda$}E~P9a6!PS#)eV*h}MC)M5s>$xC-=+zcFeub=}nz&+c^`&Ps)j?i^fz{b0R*3LAJR(`WtJJxbHz-AIY4VM`#>W?Ugu``P zG1!YsdI<0Rtk?3^%~J7TvH2=}G+Q01yzx6dKSzx+{Y^vWV4L;T@3eM~+Q_&xDGmE( z{Z7Z{s4p7MU1U_d->K?cHN55ND;SsRxORb4)+McVud#y=$KiP#PAPK>-SZ0deGl8a z&U4jjjk7A`>ty6pIbS(^qt^8KT(w5a%ZT0&?7K1cPZ`E(IjH>Z!scs37 zLZ*3Yt@=JlkcMtDiOrn~#~>qn|HUT`>*uMhp4Si~E&b4f27G8W?h4JBr`GfNy>f`T*uMf4b16u zaW(Uye6B9x3PsF^@Emc466Rxk{C=Z83)JPUdwdHS(b<$AFB;|rMISCJ(GTgZ9tAEz zMYzww2<*N{Ua4wZrRgP#NL3G2)ot!9UR#Dym4#}<+WZjUY%h>OOFj=V2VIk|SRjzs zeW99SQd*9q{b_2`wg(`~^6k#r0F7#ct70yR@>C?MofZ{jkLnCj0%i+Q?Kn9|CX-LP z8s=4So#~8)KG#WuC@~#$Xd4W!(t92FYLi!^eLhaNG8d%8FZ=N?SA3Hfgz# zDQIt!bR%Fv|s~Z z8UR>8Gw_N)bm6))Anz!Zqmk-dT0ul-=VR$+2iWE;UW1(gc+$%-klrT&VCHSkayFPt zCl7e5ZD^)ze&F_B|uQj zwW&iCP{cKxISf90tAd_KWCqgewA!eyUk=6l#}yXaFpOo?)l0wDt@WDDyQ*fmj#WIqcc-ztuMxY1u#omrA8G!Z}t1n+jUI<&svm4h^>Jps)Za^X`MYiS= z1Ay2TaA`8s!p7-HLyf~79M1)Ak?EX*=Zy5k1mpdz1c?d+00%q8acp>c8b2WqWW}6y z9D;>HBG4V5cd3r1KIh8?A{9z)i-eHig&9APx2F1}8L3ffOnG{|tOxJKc!ciZE=^lf zDpA$s|4@m%d0C(ocF+kH*z8*HEEe~kG?9(-;j;9e(a-PMH4?hj=sIuP0U5R=`Lsf7 z>MiGiOR>X6M!RKBF3^E+6AwKt4ZYMYUz?xjOKCTW0$rP3l3e)O-bz_PltxP@||q1AqSBK z5L|JU*BU^jWIbe8qT&1BaM6g-Sq=#E$_? z0(zs|MEp2TM*jd}CbvEfF3b!7I_Zziqo8z#D(M`N!LjOr^fGWO2AviIMk3EVizS0|V7^Pbe zz+&YGdT$w4uN712 z@l69HC#~pYyb=m2TUi);t$;?afi~yBT5_yW1M9EBwAboM!!g`S5HK7|`qBj?z&BuF z$xNpd*DmyKs#={sR9u_TCDnCQ8ieJ7MOzxcj}U+g7H!2B{}n6>lAP7WWnVjd6l7VP zVW?MKT)J?Mlp-mQ{Xdm}iwuy-bjeKrKX@SSq}b1doY0nYmDskLBV?VKk33R}Lmm__ z&~|g}(y-tDccj^R#Gc6!;}0`ta2vjh^J%d@nz!Ae^;hlvRIR^yT#Lu1+jJSey_Uy%f_S@_ngat{)6I&zuxsd$O zC0u1n&GGp<3hDc}AXDx9%zUNTJ3QkEN5eN@%Fm5mz!mW{8uG(xO-sV5rG5z|)u%#1 zFX{z3e0d;fW+Okh!VTHDJt`@8u~ipxe%TR7W`>HQ>mUjy&jDDPj}U>RON3q zke=LDJ!$`4?APNwjwvqtJh6W`rdnKF`J;;q4rxQIQ$F z4|7b$W3DFUXV@YhRh?d-AlviqE!KjAG^g^bpCMa)W5PIK9gXL(8u+j;WUHo!>D9+- zJ4!mOHu1v2gp1aFa|!rIdNAJmQvFQ9wDYvuwA(JD2)0eCP(&{-Vt76i*}{4bbv5vj zCIb#N51Ir#u)d6C{qu+E`JdDlFZPC?dwbj&d+cf6bNt*#i@o6RTw#wr3KoY!#p(N1 z{&CDHwZqCK&cmTDvRi5GcBOAx^0dscyvd1FNpk;0i*e z$gsGpDL3sYC>Pz@Tfe>#N3M6&8U9}wop4>L)CqR(1o*>ReMfDiJp7zKyQ2=Iv~ScZ zwC%BK>FMnKG00WyV|$P$x9L9_WsR*|)+#RRvx6=!VKW03NNwCD1MpQmAo@gY<>`e3 zR{Ko9Of~^0?|bUI{&x(B1(k<)A{X_}0s8r#+Q3}*5JncXceJx?5p{i{*6iTK3@iR1oSsBC9;uDpr2*>!6SezWU8!_fODFzT8>R8XTLrdh_|M=)oA3`v`FP^jAyr)# z$7;T&0z)!9=;j9^<^WQS#LoIgcw*n$gyD$XK;Xyv3GIEXNx?f z3Qm86!RHr9)P?{|n9}tolkJ&W<#_}xFpYBq65!{8v;DOz+)XNLrEtPoc)q@1h zxdSm1a8n*#VbGv{;|)&>=iERf)cl?y`F6z~soEpKTzJZ|AsW_n!!+DGjis6N9Y&;K zCc+kJmh@dlq+u=+=}{1g5d&exVORZp_h*JBe-O`%3|U=%@<{XERUW?}b>yoD|!s0>xGZkK4_((<+aqm%vUXbrp12 z(2B4M6fa}3`q;vph*h7s4hv%;Finja7+8dbm7jOs=8ef!yVP1SUmXx&mqH7lo}~HN z4=%tcF_z)Jc4?_N;ae!Xitw)GTxNXZF-A`JHa={>Yx1j&Hewo4cRsnfa$`J2CfU z=1$I|W}Q!Q?E`;iJ2F$Va20I_dNMOLy)+GvopPs2Ra}dtbS*Y3BGkbxNUN&JUocIJ zwwhy_eZ?DU7jq97oz@B6!*W{cbDC^=vvY{T_Pv_XhC#OFAt#F4R^a}iV!%7pCESw^ z^>ya79r9o>SNsjzjvwSyySgj_ScjfnaKpam-@T~gfIhYl@q-=|H#_wC>Zy+%&r%ej z8&w)3wPPm_#AzN!g;mt32a`0?1I8O@hnzyD<+$jpHfrjmqksyu0#eCmQuzhu_?h$l z6!X$I=(B&+cGbVyjuAvN0#FJ|j6IH!$3wMc+V170rCksgp3+21xoUf`u)fwSKpW`C zmz<#jW#XxG56z77lY>;Oz@>1~JuT&-mRh2V0+M9~1BbFT-*NEjQ(VQ6D}Tn5bd;Xz zRkrx+E5CE$PeWqL&+ufGDj8FhmbHiT@`QrwIzF9OaxfeDixVf_h0NfG-8>O5ExOtE zWsrWl_c|_F+Y6#YFE02LJT6E}+;df*9L^ht4m^>LA&dnZE6C)MU0hy;0d?rJ1*bEP zatq2h6xx(|Bay|r6i*BcIs;3JT*jQ8eg@fDo%Wx#<}4B_EEzX=G#-3RL+`86%I$1= z^S;_mzArm#I;iwjIa%dImRx-QvkdD=CPE&$&vsM02WnWF zF}mLoS5Cz2B}QUSc-8Gnuib4Qjx3)1LmKSy`} z0Q~xz?rNDV_v70~UnebC06n!Ra7`W;OcQ3ay6)Nj1Sz$=iu=yZ)Q`P+9m~fey&jsc#oD9?Lz}q0FOg40nV)<&!l(UEpTm+xXd!jT?{zPX^w5A7(>>UVcS&RAJkL+4qBDuQ} z9)+;>$z+blD`k9S5PJucUeANuOxau%Gt6v@{J3n-_Q6L%HrK{~1@iWh{>3%uU)*;7 z)7!1!y(|RA%cV_jSv)&J1*|0m*v_Zv+TI|{YLJdc3I?yJ4|>dzfYTx{_%k>R<5#fY zs|QD@)$MU>4ZB;AkF)J%4YqLK$mJ3}0iHMPZ9waGT1U%Ma)ox2+wEC4r#)4@%go zy67ajVEh-H!Sqne(TRnZOY`34ObqFdh1oVr0l(IA7#I8Fko>SE!MWHgw$=Bj=?B~c z5p*$UWpGjQq6_yPitFcRkIT}+q2A8{AMH?SgZf#~%K+zAIXjilyAgJ7?-H1Up2p%o z{>NQxtZsU&Es_+2&R)dB%>BKHhuMxUUnVaP#pY^@`QDHn=hjR9g>JNSOWmIsBVqmjVs0lxf|omT0kQxnU-=?OP;grskLy;^oVn9vX2|9iDD>2a6M--!JsC z|J>{tHrl!@=iFwXI==eE>`E5u=5lxWZ;+JM|W>b(A*SX&i^Wx6@+bdgcWw zJi)&QgeN|#Px5g@;{fBbzVYhAD)X9Xm~T2zbvOzUZSPIH&Z{A5Ru5NWv4wcFk=>jY zw&7&H4JU)xs6c`1z40nyp*+TaZZ9S}HlVP-Se3-3=~5ZAI$>5{bJk|0AUibe`Yi^{ zVIacRuxkzDYc@eh%xTQqF!LaOHn7)8K88F#b08kcRs(w27=_uvIHW;W zS~TfJRWdxQTtfA|BoA3pF&ZFImAdq<=uYU(kvZcicM*lUy0%i*y-VX=UF&t3_b!f4 zlA!wy=6@C|)Yb`B+@j$pG>6MH?A3y;`5?BkWSq=!a<_Ns3s=|6lu07@A~u_(5$~c|Kl$2a2{Nk7JpfN44+g zI)M`maO{zOTAYuj$j<=&#P)!r1LZg5Tzm(W3F^kHX@-iCMZEt**_VLVbhT}-JspW5 z12IQ(5D`No#wtOOq~y{ z;L1oxN-&oC@Qo$6oZwny`J4swA6ROhvk)~|EJ~M4m@)P<2e0!Vi}n)ZSF9=o|JQOM zLsh3Jn9GGfQGashQ&H6Azuob`Adi9<#iSRlZ1lxLAKG#g){hTdtX8wl-%pDnfhdhA zNaEXun2FG%_SqKa1%-$k%D%v~0)UF(;th$R^@+YHdSREK%%qw;g#5h*WfUxp7Ns%| z3`(zfR8oMTBSDCV8u%c(>l9eQ7l>@mp??9*xQW$81V%~0n3bB`0@NpK+VLLLNX@~J zHRwDDtP9+OfdQ9zKhl_KRz^SLfUGeW1+Zj*a`tK=>er}(#3E@P#W)CGIMRGjpJ&!e z?PpCL>JIy~BvgsU;;FwOj9_CEU2Vo?p3MGb(v;U}GknQLk;ePP{P zV8e^z;^Ep5*mE6qzHko)s=tgXgbzcmi-)DdPrq?D3Ln+N!$47YC_X6O^Mw7!upjgo zCEIv(47VUgou649hW$jRAXplX$PT9pH-tjKsp6UqNgy_K2;%5kEvLI^!@yA-$ZF^) zMAlXOjdT!C6_H^NgPWDoTpXDjf%OCUHN^#gw3;y-XI!~bST3v5jSO0~!N|$=83taz z#lWAgg$cJ|pKgc3PwbH!+01N!7m?ZcoAO0r!fwhC#K9%#sk5)}*i0QLvg9)5iATdbk0woBL*1r7@0;}@^G+Yo_2cD-5s zL=H!bN7oeS0B1VSYq&jxM5DmC3e&t~29!v(1s166qYOuwj2sBiq0Z~^h_1hf>TWJKB z6YOOeXqt3g&I#sz4q9~^3Y=K7YK|3;l&5KH#EQ+3f}8+%5paOjFua73;D$Uj2p?)V za{`(hh94QCCGQwiFynNNSl|&B7j8#OO|EhlegVzk?31VLHa6ryPLiLUDF0v>y?2>| z%rY&zOgmPloh;MNlxgS7G@8~K!O~=herXFuSE72QEgUX}!a?^6Eu%2lUHBY_AJ8vn z;j1#OxJ;u#4*h6+7m%`v`kbv7IaJNI5;C!EQc zVl25)dFhIrO|hY1?ZkIU>}zk=a~6tBzzwmNDXjZ4SjC}M6miO|`FBx3^t2O{HL1cr zN|!q6Td|-KXrVa_g?I3Fd4DN_*o#TNCQt;80jUkgsp{t}_6Nm&|9DXRs8vc1jXP0X zs}+g?#e09p*GNrtp?xTbcq7EfSmb;3fJPE4vD>cP!1TgH`gnHPK&}{fjz$*=W%n!L z`A(a8I}_};Gj*;TKD(WCrV>(o_z1#D-U3fjR^x3Q%yo9*ACbprH(Opv+lWu<>ZlcB zHQHdlFWN40svj;u7CDb+xc89>|IBk^Z;k)O$3{!OPQB$Wi@QQn7!#1@Kvi{1}77 zzZbr#D7mmF8i9pZ%CtQ418mO1>!ya&nU0%jpMQ=D!K0x#YX;HyuQ%7D`Gb3yQPNnC z)|VGOMTzLRkuqh@Htgu3#fH=k!Y{b)?t^a0Y|veL`vIhyz5aSHltz-_9)m zxNP{>U-=7uP^pu!;vH;pJ% zPD{LQXbx$K^c)ek#6m>hyA3V}xbH-UDNZm5M-DJtg~t z9a2_37fR)nRWx8s%Mf0tCK(|l7SlycUJ|KUq3M$tM3zMs18$0Js?g3(y>`IDDl{Uh=;i* zk0!juPE!1>?qPVju{}jMCgXpIu6ekKi?C{Jm!wz;7pTR*;KMH>M#Gbh=!tVDhTMDP zpChI)jExO|bu)n!VNmgGtiLaE2ntLp|st(=XPpp3Oe0>%kol zjKzgHdsFgT>W^YS_!&=ws!{6KlYN+nt>vB@K^RC7v7KBkKNPf5%WI^BYl#I^X>jrQGUu44EdfeP+BtnZ51~GMPw*}~DVHZDU9{gzEKkB;ai9duZD!u5o92>O z;VNt~na&}XVP!#-p#Ez?(mC-Ol7(CL$l2!>3?B9bH-R!2Remv<<}Om42JF0OrLa5j zG%TKf({z~goS9aHv)T`_M!Rzbb=JP|nzkWV@i(d|DtqWUGtt5{=02!9p$p7BSTM&X zf*+m>atY-Ja>F!T%vL2dnQ{lbFuQhKLWR?L=~3J{iUeJB_N`8{ubF`$>{Av*++~Ro zy4YH6>Ml!+pbc&gO{5Uz1!mB~?B4RK(f`jK_|ONTq^fJ+m$@A$G{H=fiCxUI9YYh$ zB$?PH!MH)838vQqck8%X3@moNpQtPID&nkPn;2O<>WRG~DXH#Rsc(<6(#p!bx!^PG zXT%6g6oRKC%f;N0o@*ykh-Py$=RjeFOe)nUkv%D^&)`2NIT!!9t5{9JL;b|xOE6%uI+C{3Sd0;? zK`9vq5b;aF5nm#HDP0}xQA|uljBM}}1C)g{;7wgkbucxJ>L86U#VWaIEU~YfIE>lR zc@}!@g)SyHsjDe{SX2Lp3mOfliqWv$#b0~K1x<|RpP@1Ko1G3>*Vd?kQgyYFxziKl z-PC}w*duV^;U3;%t@@sa>WAsG`4-q293e}6_eC5gMuVz@{(RwDHQx9J#ADEvGH$r0ZvI{FO9TWAmOBM|$5xU|)q6OVD4vtI7wK3Nnu ztKnJM$9+b?vmBh}EI#fdf7*(-T#pCWxn%WhtVo6j!o@_373vrW=CB@r;5{%JEh0n1 z-wN#Q?;<4{K9qeI={S5aV(yBQ&TyN=cahc;3*Q!zDaQ30Mpvzh%Y7HAiQy4_s);rd z6pk26siy7r^dE0oEWV4>MSK_O_EeDs%DO{(d5%-zwp=!vw4!!W3}JB@9L z)28!B73qae!;8e1jcQni7m4YfebI)Z*|;^|xIyjWG#1w3?^+bl!kLTs9~;!EUA0BX zq68)uGLV?y2z%Z=Uifz2^}{Lr_JaBVUQt2avyiXbh{F`JTJi5Us@3a??*uiA5ou5p zJ`9oI-AgJuZed*Cs5Y-EK1%d?B=*k_qXSiw67bQppOt3(dVu66=g#NzHmUE{|Hns) zhHR&?^fJUVt?zc)XIV0$i1+L&E#RS>aa?#YZaht>1CYzc8v}(uA?j&{v%nDu>HS#T zesSJy#ewB48@_!(mc^R}g*9RMkyFn5(eR4pydO(O;ng9?-p}c88~)HxzaLt5_AdNH zNvk!GKijOjc@Kn7lqV{@DO^S_Qt+2rUA!lN4;xj)dji9gc(X0)EP4MB{@E7QyKx^e zfG+>~LA&x%G~zWOng6v#Z6Yrl%Ij^#(Fx6m@wlyOi~qrKkMfR<97s>%=eMd&x@S{d zhGe96n}wax+<>SEdS{KJ^qVo`;zBe}g}W0QxqZ%AUZu)Jv*qDRIH6SVMV1Gr78# zTLKzr`l68Ge+5(ny3JM4vYFKL7Fofc(F@)09OeCYsLkj*AaizL2gs{=-152lYyGLt zC>rNd-ye$?YXUH~86JRXMW{KH2*u(#m%mUGD}ULDJ^~^#swrRb1>X7I;l_7W-(RYGy4-I7AJE5RhYs$- z=BoJUniu|3PNB<7>48uG%@7}1DQIj|L0ToG0f6yspzE`E!A`Zm(UdKQneBBMf7c= zpp)1MQ-xgY^5WUM)qzeMXHlaxL->;C#cS@trgYDlyyG6VPOZv~%Ec);kG@ueB=nxa zr|eOO$XjdkGkfrs6J9y@*^BolE6(KO_o@NP+IvNO$6nOSvs?KOd+~bEi%ynY$MRbT)HY;RI|#FHEbn?Rsa9% z2SVy}OMI<5Cx46{^-(?Jtvc7BgO~|KW_C|J*}mf_oL2WU2I!CIxrg|4$cMi?x}UY@ zuo@wGJ*s1@F@1yqQ|jo-g&C7@U&Z5Vd&vuE#M@=7P3wM-?l5(fOHOhh1Vr}|#gLAc zc8F@kKh9SDBC;AIEB5UC@^|5 zjle{acK7D}zgC0WXmf>q;YXl1zG<;DRoF`nRq42%+tl|jp9t4D9?S>{A9cF$wQB7U z`sJID*23jOjLY#hByHHDNGHsjgH!klpHHBWiL@sZAAV|h1hLe7*$*3 zN6Kot8>x#DkhGL!e&DzoSlz)KN{FV(*jcqJl2<;Vw(OXT!%>n?+Qe;W4{Hyfpg5+E zshleAI7Mm_&Gbi)NA4`bRySBSasq{5)(O?iV>9lUJ$It$J}!p``l2MdAJQUz=alME z`5JZ%bSgyX&dbO1dna&AfR8Wt{RW2{d3cDDA%b5^u5Y2#nXZEul55XOZybNYH-DqH z@@Vz+O^~AKjDO=OH(3PPa%*x~kiHt89DG9&!d65&Ag6F*IHiX6@RciNolmL(PChfs zmomQeB+l<~HNAY0ROaP$1Za4PYL-Y|P8~~LrkBeg6u^ukRw846ilk-(y4k*13Z}X@#s)rhk!%&PSdh;38BL7f@nrL_4 zp^aRbe}6`;U`@brSLhTgna_~!$(Vqb`BHc`L8Pbkx&$*l^PCe81MsW|q(jQzkV#v4@ z;|peKqxm;yao`>fZJK>feb>`-jA#{;8c_8JR?!8z;6OBUP?WqEIqk)iD%xVsBUYI)E^gE$T;g`et@$b~u z62AKWomxw($t&inO`Q7Qz!R0w9cihW0%!=s_Z+E`~Qej!0rywOaf1?bd8?kDkFH9jpVQ!^cNj2girU#TyswR8UL= zPphYObYMP>BAPdfXp)svPn$1sw_ciSR+^{wp29O5YHoZ%SFIM$Z=hY}E`7A>4Xp8# zq9c9T;HXIx;+r8HYy4DeT;!CgGb63x#x?GFxk~k{>kYM!CI0>QRk~$;(n#B1MGc%f zHIDagt<~YKbsgOJzSi2mLq)V$|CmVYu<(yqw@DF`;v&b#PnsGN9?iN(Pa6LL`93`| z-a3A2OpI~GI-Qc@`+vP0857~l_^E~twRlWh?9IITw8Aj{c{?qS&v{pCXX_pv86IaH z92FiL`NoU!agpKik=EF$lVakh`?8RzNb7X6VVyLcLY^5p%NjK!I+{(LU=5Fsw#MW7 zTTYC~PK~ifO_~@LJt;mi!tjkD{u3s}Oqw1gTurx-w}@Z(>I&7ezHF~0S7_F4#-!*7 zYsjQ2ku5@ywQS0CHehP>M-!*UOg9Kd^mJ>Zh>HB30D8&3m*&GiK3}DF!?>v*Moect zM357s;^7J0<45M;NwZ1k{d*(F#|3E3vaSSZ?NnrdnXTaw5!UdDks`&$-7LFg+|Rf2 zSlnXd{lrM*{#y>hBPP$79&fc@#ge}uCdEv&&X|t4PmhfpKPf!g8XMj-J_`8}5gCWL zeHb-qd=%v|vOhZdBkP24@?)xXd{lVM#7N38X835G6l0w}g|dE93^IO-h%_Jkv`P!! zHAt(~Auw)6%m=6zGb5Q%BLd^XKSUf+WBP=Ti;SLb=-sEr#YD!LAVj2u&kEAI@XJA3 z>*j-o_O}iWpAs95ShJ9+@hF0ROc0UQ?o(&P#IyIhQ-+63of@50|9$Omxx$n&vElJi zIGXo(g&y4H0Um1g4Ua*d#`%tqjm449@y%ka{++B-!e@0A8U2Rp+ck8|;Gp*h^F{r% zdc$L5r%rD+p29G#4a z>o~BaXn}$cdDv{L_9~tcuc#?*Lz{ z;?7(2(z^1(7gbz&N-r&xOTD$~e98GLb+Tsl*1V)FydRh@wc1}>VkBeS46_>a>oq0z zWi12SuiMRSwfTa9S_5_6C$+oq?E|$z{I7vpjVzZzT9RaQeJC+ENG(WBNL`2rqyeNp zB->GDMmf#bkf|sJB0B8 z!?jsH+hgZ;VeDyFdYs#-;>fNYZ@(YVx^?R=7;)Limi@=i57$D)K5Sy%zM2&>LVGRS z)?IpywRJVht3YFVBP;%+6ii~Gw%@_v72kW+)1zt-{(|svf!`s#i!k1E#q|KfnS?hA z{4wT6QS3M1G=V1*E~e{q1s+BC72zpJA3W$w#B(A>2@9PFKPB8(U_Zi-33n2>0pUWz z?+9F-@IAuy1l9-_5UwKdON!u4!X+3~rbj&_e4X&0HbLAXB9Dk$0uLd4knkme#}m#b zd|co-!p8{j7I;44lY}=4oKE-*;WUBI5WYfquE2W<=MuI}5yTcE&J!`pz_mEi?n;BRd<9tAIj=R!ktFgi*R*;Us6t332OpBAnZ=~MG57^dfJv1 zl}Y~H7eprEgM{fxe|l6d;cUWZ1ui6fjPN0WUlBe@_%nekVL}sihVW{EuTg-tD8OWa za|pW;o*}T!iyWLM2a$qkO*ohE5P<^-Um+YMa6iI%gxd-nM)*46MgnJ104@|jb%DPi zT$!*Y@F#>F2*1FFxO7|85+YP0?h_H!*8-eCx8f&(X=^#A^f69cSMS4FMd=g?;oz!vF#*%EL}WX zM5#SVID+sYf%6DQ5&leII<_(@n(%6Y8RcFq;bei`2*(qiA+R^$S%k5s0{`0+oN&asj z|L+TYf$&VPQ7m#e~}mOk38X90)fO*n@Co!qo+) zH=Uzgc#HA4ox@45Mc3}*fRFSjI*C8Zo$yZrk0Za62%i;Lq3WDOkv$~vADFyFB@q5h z;A@2E5MC`Xbu3Z-gp&ovqA|)U;TeQ&QJskhBqCB+I8GkSB0NOk9facv2MJ6IR#CBp z+X_5`a5UjY0*@dZMYy`aBgy|Bgf)TbsajMY!Y{DofZMr&hyg_02az7tkvxbX{FA`= zBq$0z;j;qMbTulB@F9T<$$co{&jdb0IE3(OfoUl#Y6Ib9fhQAQOL)dBy#oRqNJIt^ zk-~x-;l+f92;7wLQo=z32M|s#I2@^6S8eMM8}V}oi>k)fdE<|c+N}n27J)thOHigJ z5V#FHWbFa{x!~sZuWnw6s%u=C3X|=?-%oHS+$7;C09j9k$&TTVmQ}=+-`jc`m!806 zO|6W1z)Nvy3_>GEA_}WaAR@QhJ8S7=?Yw65!DX`20>XNkU?2gyNpuB|7O=hs5nJmC z=(^J8|HEAkazj73>-sTF^7SDRDJ;l9I7SrXCJ0^1CGeREz9I0+1f-KMbsE5I=fv0u z2%GH0YfaN~IyY_#Ku@oGK-hQ)`8JurS_oYcKk`6B?oEQwG8j9AKP@Y7nl?$|J<}ar zIgW9w?a)M0T**H7ir2hsZD1!1=>GTQDPx2)$1oO;qhE(DWvl?^S6?!=Yq-XaTx6`t z2#r-ivKGUfbC0p#VfJ{+SS6U=CD=TJSB^%OG8O@IJG=5stpF(*I;JUm0ABW z8oLQ|3QTVl)Kr+i!Mp;q-(Z;)!CbjcX0^w{JSekwVP5-IWjdD)Wg%!07M?!@T!{%BH~#y$XL} zUWK_ECaNl{%yvsBQI+tMYnDi-X1PYi1h079n2Rk0`F^ktzrlN3Z zsZW{I`ftW=zGRB^-%RTKipi&6F)0^j%zv1)>^~?_B}_sA)Lxe`6$Ma3;nPs?G!!}w z1x`a@vkYo1Nn7wG&k;V7f-+~xY=OOV=i5p$3Z8~Sr}cYRl2GWh#qA|&WqXMVo+S_8 zLTW!ilEVf{>e7J{J3L5IO9x4Ezaf(JYN#ap43nf*!z6hZ%s+-nN}u796o3tgIa4HQ z!&HgoPm`pQ=?FAIQd1HnX+3tcU05bb-=epfZCfuXnd>EK#ukZH{Y;Xwu7g72c3opI;^E*sl_cy)8*i?@6rAeM$Q5zNCgekmLmqBU?Ks5-JzTt}8sl{8c% z&D~v=P>n3tVWJvo@%3faw7sls##vJV9pJbF?801!^QA6!lx3^GEM4`N*^F+oG^4xB z=Jk=KPtYs$9VAPreh$Y5%hK7wvf3a-ma;-*wj>IEOp;mUC9;yVM7GKG(qtukIfxaq z(mg|FBi6|h>Z`?jqb!APl-a7yvXr?+W>pV@KPWpaJS0nx56MdOVOc(Z6z#ybvSs!! zvYPaZEIeI=_-uMkVjE?O1IQfv`Cv?#L8qOhB_6lqy)h1v;AU;{;3 z&_Gd_!W`XDk1qRtAd(p`}jcUPD#NRgbd3b44hqVB>f!2A6aMd`1|XneH8 z0~G0-0g7@16ZzYris~?2k(Ulv*nklVme>`g8)hbxMk~r^V-#i?tEg?pDy&YFqArS3 zr1Mb0EdMM_MRW;NN~MeH>M!?MD^)(J{rwyw57ij;sSRHaR|ROV1m zl`S5s>qJ21>e6K%s1*YjU|19DsA7ODhV4^7Wk&fs`n{XLdT@7Ii)J-m@Md&w4LWv>EJn)Iwni}WtGkRL6y-tY3P`=^H} zhkTV?zOAYw3RHIWzAF1XP#JbstJ|Nb@`EQT>-M**j{6%~`$A>uFI8pPzg4;7D^;>D zFG;fp3}Vt82g`czaP$O~HFdE>134??!tvMoAsXB8eHq$2HS@>5ZK3$WYyAuEny-ls zm9s7qT9KeNTytAf9iIa>c;mWrnQJS2B&mJlwI0Nu{h+x!0CfQB#Jhf@d0L_Y``_T3 z=4swq=o|VN=qWe&6QXB=?ka3MR+cbS0vyIqE!RBxSevG5CxG!`t<}IM*B~xqVdqb9 zeT5xIdPSn@uM|4PmKTtd=D;iYozFDSDpmwk04phvU+bgzsaslI?w0^7PB*dSM!q(5 z^ut&$vJ6_n0ON1*WeHkS%dK0l^-UW0Sfe%I1#o8RfA_WikwG{Xz~Y9&*ZQA)#U?~9 zV7FFHZaa!^T?KR9BR+b*=36Nq!9J4;=a$0B`IIp3>?8NRzz#~JyWZ$G%kX}#B z(*MB7My+|@2z0{8w*#%ysYvfeJ~v#m0Lk*}QlzgnlQj!IYzQpU@A79GwT71MfS&~M zJ&9UVZFX>x-d)6RO%kHF;{75$0GqM2R&v)7yz4@(n&vgTNUzGDUCm;5*}r^mkFP z)XjFlm=IQz|2%zaptxJpIPF%U2l zK}_R!xYpP;9`LWdMfxo`QtRBNEZ(G99l$<8z;pQgY}DxVwPrJt(H4jehnj zM>ot0If#3J$CT6;(8T@RPyEDk)S98!iu7>)>@wV4`9iDeHm=N}y~m39gZrkV&Sd;) zHdT!+7oH&-EAvg?YYiN?!?V{V(7Us$fMPR+Wl* zixpZEEmMk4lw`^<=}9-%7NZ z5x|!!h`zxQBYLK}730ny;^rR#Y=;jz zAxtV#DRp`0RS5HHy<*(DH{HvvUZVDEgBup>pNP7{3s%9mtJwKFlkQey?vepqt4Xo` zQZyz!fN*~EVtu-CJ(h6&7RCBme&;;wZvn1&7^~P{Q8#sh@5#{oYHsRjzm4|0;q_s$ zUfH}~`I>|59>P6VBZg-}iuIm++D^1+zYQtYCmXqc1-XACtXTgSZ@E$PtY`%+hD;dE zFR#`bXxXES^(IF5-2*x79#O2XAG^m9Rfm zr!uaV<{8!6A8sN*1`zq!AjPYa^FU(e&(s@v@NoW7%~QNrS#f2tj?pPo|3x&__KK9^ z=ru@bMd~FRaK9azn}qHLgADEBmSTMowF1qw`rC>z;&MHL{(PP0p!x17*1zL-_MpL{ z*8T$EvvRk8$(P0YG5*61IIQtiv7T$#q*i!8;0)0UYt#z=o4am68L_U1p9^tH3W_Lo zSOeDMF0BDxVwAxI!cT!e1A8eB7QdEvLk zdJNsBrdM!3epsf}q(-i4P2YgG%hu;-s5;xnQ#c5NFWaOwl}pa^BQUjRmx}dqRQnrS z8h>A`ds}#ZA{xQ^KNaf}MU%k`wjj&GfQR$&9mq0dehScWa^%THiQeD&?NG1&T&%|% zL&rM56zhlh)-|vkuo@}(^d@C6HDaQrtaXR7|IP~Bypuc8+&8_;mu*4BCf+aBts>q= z3`XJuR_zR&z8Nu!d`Jxtxw9l7O5u-q=dEy-|F~HH$Y{;dx58SpC&l^%;mlFR{fm5B zjLy3yxuU`K_`ms+ty-I!BmCb^fX~ZfeHJx)o}z>AgS?Ihg{Ex<_F8N@p;dH@2X`MI zG7L00k5sMVntABOGPfbz5^SFQO2or47xv~97whj*xYfDcp5+zzMLKu-6w$sVl_1(Q zFW_OHB9m}~&|=Ye+mYV6j8aPUea5KpPzN!@k)L$u`JZaumGadReHD_ThF#>&+qFh= zdz8&RU~ zF={*Adw)c$w=qzOT@4>X!%C>gpc!(dUgkWYXi0mXLjuJ(nZ^?}ceJ&aH80q*LJodV zqPG_Pg&2rz8pS=nM47lYif)^z8L?lI|6@z^)kaaKB6WIP31*|B9#KhpGNA#qBXcH~=nE?Fc~_7-_2Nn}sTEaV7TmR(!DDtJw7WA)^e%!H^-z2HQHef} zLNn)&X|0WNcR5*AVZx#w|c(saSsaE&u*2%}+km z%IL_hCQ~ZJfRj2h`b=s#Ottp6M$eQ05CalBOPN~1AbA09dzEcqC(vzvaT*yax~2kH z`fX8(ev2$u{I+~PyX|cGb}o!a;U2p+eCW8PQO;hkEWzYll%o@iwTe7_Hwv4}suH~) zk!X*0BVDb4M;euf(sdEAzv0Gdk5*OtBcnv$BKn$&l@YfQt4s6;4r1EqNPVo!rV>4p zcU_AvAQ~_TaGCJTvKH|3O+0@O>eRT++-Wb&yluQQnN7dsF=WQ?5mc{O*0xbqn zPxm5DzwRnQF9~0Lr~{k0yF~w8#MrSi`jrNI>=9m*r>T_&0mf4H%=t!Sumy{YZ2ca- zCldiI+{^RH^xDsz_Q4!~h<7Hl=n#+Dhk%O@Vc)o!+Wlzq=Ai2dIZTzg>prbv6)Il4 zKox>oRA$Xd?w-Xx_QRW*S-c;aud?_&GCi{S9x{W!rY6c)zW+6MIsnuA2=7d0{Ubbv z%!ng=6Pe*h_+>Iz9^s`25S_J0N-)I|Wp2Ph1wGzxv>Wk?f zU@Ty$F%pOeTniY@!+*u?1iA&(-N;OoN+(MmxTn{6oh;2)n|-fD-z2={u~`V_F>pKK zuO+l1W*ztVCRmf(-shLebb7!`(X4Ck4@%JcQ1BK9EJHMV!24z6@~8)VUN)+J((h%l zTZ+pzz)&&Na6AV1Ip9*G%oYMxDCE9h!|}iVEJ#@MA6P{0I z!)M&-2+S{E@XkkIJ^O{|d{BDU?9epFDvUh`b3?4OG~maMAd5FirKpya#TCB5^`lZL z|JM=B(0>6RZ)D88d{kHeqnd+KPcG%Q1z3X+v(4C}$do2(DMn#5&f;4LuLYi9+|w(B zFPGsp#{gCAeOk{~{EXbk`cAB+6jLlQWqy)`zGEy|$#5*y|KfMB0>IM=53O9P@1+nL z@?*!)SKO~}^cA6aOs+HEPw^GdgMQcP8!N2@V^)^N!rHSBcKp&Csj(H|@G|Fr-U>w}WiT+Uxh?=7n z*#!qK!iH-I;L_TqI-Z0vRmQ0d{LXwNCJA%|Y?WKKaLxo*v2Lj`AMwmITKxi$4L}A^ zOI5`nU1=+eKgjQiEW&{ZqS1E@0Q~^;HX~uNfX@+zL=A&Ez}N!Lr(UVP6m>_z+bnAH z97K)o>oB8vc{Aqn?pmrZpmNmEmBw6i0!#I+l#DSrr9sS}Txsm}1oS6FPb{Np2sSRL zR4*ZVD$&%_IZ`pJ0?o9k_Ip|8PcYA^pmwvsw#n(6~~4tT8L1er>_{QvI@# z-_)&HBTIFEG4v7LTJs512$h`QCnj^mayAL zNWU?vOD7yRw^aYx2=^r6I@r-!g|6dPVu6J}CGy`3N-^n2^c!l}CcvKa`scM~a*agZ z?>t&Ahb4R-nYEVkJ!E!R#`9s~lap00AirMmPB63`TT1oWeA)%Ane>!zyr6ZE->Ys6 znA#lRPcER2S3N-0AI(}r*ywZ-%MzFO+ZzOF7f&N*37Cq;;w-IjM(^kO7tugZ0PSeh zOezOG0L_)gbij6iPQsCEHsIx5rFw5FJUu^0){3d&mTaW*9iivic`n-JH6Xl2GosZ( z_NDVXxdXpks98zCR=N{n&8}*- z2CnwH>4gxjkk7evS!-D{-^G5xKE&O!uT*yvGfsR3blPQ9Vyvh~0ItCWYN|*3_YbR>wKOeI^K2@rp zHx`+;TtPe+e=B;M6$nDiMA|wT6p%inS72jZG8p!FYh#9Srd!an_$Sc)x6o}Est6~Y#?Wa0t;5PS8*&1MVX=zb82kNZ^n-z*(7^asTcO0mQ$R@DoZYMKM6rZ_i$Q@I&! zD7Xy|sdE(V>|(%-KT7q}h^6{^qdj)np#A3mEcnwcjJDe_XbX2m`ame)|{dx<_RXc{_I@WUPW0=%AwrSucvn}{)+<5KY1jdTwEt3# zT4P4hIRdngq8pRRp=*qM$^e-Sr!x$vX8^mwP822zsv9}2k99xC=b$gc)*Pd0|LwL` zk4ps_b~C-RqGb(RLLo8=Keq`Q^MbU2WI(n<4now4*zgDQ9wZNP29gAcheSX^Ab}7S z@|^b8K?30>1QG#h1Mz~mLHb}b;84g|$YjXDaGU~u21*{}9^^Sh#SXwWkU&TXBmxpo zCZ09LLy{mFknND?5ETKsLA)SsC~!zTBngrM*$z1fIRnXqKldQdAu2W!x{bHNA(S?d zKu8EA0um2Nf@DCpLk>dDK=L5>AkQHx0(XOWLE1n9A!p!m9s-Jhgh1|r%Of6g5E25( z#h%NXkjIc>8~$>!hw>)mF{Bt$8M)vOX%2CR90RutvH`LbG6xb334`>3_(PgQ+#!`A z2N8+wkPJu?#0%mE*$%%lAW4vT2>n*Ha~reaH;tV}SJD|`tspUPNOQtOy0yE|cygn1Aq{pQ@o#?<#Ewj)?#3%X&uUMGo-#leN;<5HuS#8&o@SP$4~KlXne z7YCM$_neW~6)o#^xQ=jg$6>!BBrIHF6Cm-B+z9MDgp`6`3OpN<09gp3^!SDF{JYo! z@)Xx^jN?BH)mp3ws4#xRJ!F4#nPoJSSroR77y8KTAiCr7(f$qBn}Zt-iEk7cz-@<&2KWCeuKQu*RToCqms(}ErjLMD8yqEg!) zqN>7ndq~18mCc%~vJEgpVOE8lfli@C^wn4ZiX7?D(3z>vhVBAC=ttKIu=&0GkFM=R z=ot`yNH<6iNIysjL>Vy;(Wp2680?+@4Jo{%vV+%D7Wbpd)?kNs`MQ_%tI9h6f(>@C za}{RM`(|lQQ9Ff^#)WRu(Yf6z+$mM@wUmxTFq?>}48|FBe%POD+ev0HnYC$Mj z zP2>GmI5iT4VL=ehf*7j-J8dB!BB5Pi4uNFinG7ZNBglQ4`{PG9ixNV1FM}&a=1}-7 zvjRV{!ihehz0)P@+B0oXZFy}6-n5csrSIS`QR#$hY)XPY0lwUrf2|Ms<%>VR=2-9B ziNU?l`5%=m4V<)h&@7mo_71O88Qg4eADZ0kcX%)22K!>lWO9Rj`D}2`vEa6w9CUuW zucf~8Y>+4Hj!n`j3FJ+aO!75C;ozQ_95*=Uo#5oJj2J@a`YKC(r^6s?n&e?$zOD+Q zGo}TSV{&6!@QcKifa_s$B`x@CaLxz(@VwdNpyRLzc=#j8xhDCeA0Oca$2VFrw#DRb zwBnnp!*Si#n5ml_bnF&_7fWz(hY~p@zkGY-6{obDMB<_ws3Wv$v@#i;)ThooP;U>4H8?WdB&I1K1-sC)j zcn23t9a{>pHx_D6;x*7UrmjB5OFX7-g?`#@2QN+kZ0ZHj3+;ARR$#@Z?gia-x8bJ` z^oFM19Qu2v?gzb>q5H5l0Ac2Z_RwdTx+zCmmWIB~LD>_z7&;{~ z#lx>Jc}>m8AUq|mu-}O1py9lq8xpw%Tw{~lGMvvNuJ#D*5HY#hBlsTTMuVGcayZ;5 zpSbnlR+-%T5!?w?&nXw&S0TA=A5Gjza0g88WEfvY+@Mj|(Pnak zM)4EiTqlBiU~;5u{8ocama$z6vUf`U2#$buy zu;CUu??2R1yHhO?R7_Hc^nh&4L{av72LDs%B1QY?R57z9X9t1>eB(wGo}K-O#m@j$lI()I?K{ z8pJRAS?c-%+Jn3X{p}z(Ex~5xBSw(W`M*|JYV+dS76+$Gsc7oWE0PF0HZ>PL;p`BleihN<_5zQxodpg$!Yk)DM}mzetELHvZfrH*gK zV{c+T89K#!Nx8bUWI5hu08eeelI1)fadR4!j&bsFgBz62o$7+?u>$qYH=VgoFA@^AG?ZmEYb{yN3j4<`55Dc+8_HfJzfF}XHp_ypo|FW^Z#+>_hf3w#Z6 zdoSX>V3XT>(Wuiez&x46Oas#^{P437IK9jgA4;kx>45ElvdB}GV7x)bO3`{QY8NWu{ zoac<4F}XRTlc&aProJ2cccy*@dew8VqhMnes*R_qpE0UUi{`))@P~fM&?)!I_q%wFmQ~6z zA_twfu8$bweOl&alF<2hB7X+i$t0okE*n7Nom3WSlF<3LWE1a*vMnYFo&OEe2`?tH ze3NXg@Cj`#9z39dMRlTg%stN=F{q>QK@Bik2m!XodI$8k@A*xO#2TT%(mlFq;lbUJ z_p}c8zR5x7dzT|Bv@jQGlF$v3R_YQ=61qXsQr%{ggl>?uc6Z(+q4V!Y!Ovijf14z9 z-f=RLM^on-s2UWbofWw3g%~{m_pZr7=kLbDHLbM_Hc99PN$Z1COcJ^=;Gz|n#U=^e zut_V9+f5QW_uLLY6F?p`N$3Vi>yu|p5<0)V-O`{6xIB}~b>IscA(k;%d%S0I(2cNZ z>E*deLg$;2aHnOoO8K3U#$}GYsyAHIs%0CKgDxyKrlrpTCP{iU^dzGUvYa0}(V61pIVb^}=lEfz(BbQq#K)`m%XKm3vI2Rl?9u}I50kzNHmQh(D}FH@(5 z;bEqJ@;A|Hx0noUFU&`vQ(;y=dowDe#oTw%h*8+k`Cgg~t_L~5B%vGRuOP>nBy@wM zwc+U|3Ed#Y!m-^?lN`1lHn-UQglk)`cS4`$j(xoe}(F~4h zq1@pIBj5$y_?qT$d_G8GekKQ9}E5_M|%2I-t-+yQ|IE5628S?xQEWCQscE}l*B6kXpqo(_XCy&oySV7 zwaL-b0eiV<2*qA5?7A-qTKx|-?L#+O40;?e!z7^_O(i`a_{1ck8;vSGAjmRF=mtqo z3~reubc3Wv2vVLAS?C5y&lnn;By?V_4w6L=B}SMebkPhs)6Vu|DW<*!`W92C$1qu@&hT&pVexO>E!BN5fV5Y@ zCfAG#c;#r*z7!d{YyBc6whKH}z9I{lSx9SdR)7~a1eAq_BFx$ z&D4)WUr)L-t+N{A?!&X~m8ho{Cbr;y4DF0uLMBOQus84WO)oJh) z3DU3r$}hG>_GUtFa?{|Ui^w^j1=-#tp>yZYaMK@weBUIY8>H(@i48GH==_@u%r1Ae z!|XB*SE9`;X*0R(Z)xcCAtreyRrN!O^LogL7a%`3$rm5;2Ja$)D?gH0mdUOBhz|ni z96noO_e~Bux2=Wa3Li`Cl}T3knC~aY=fJt#GE#KzWBwa)m%ueMxl0D;oCmI#$wB9P z(Svhi_{SA9LnP?5N4*%;i^!n}(O+{xZ2~HZH%1Xm0>l zBj1P(bp9@-Ie)&yd`&WcJ|72*PMa4|qakltn~@u*xPNf(8xDun4G#VUa>)-vmTH z;1(2Q6BHFUR0KtdfPxqS7ZerYcW>7n8U22r^Lx&7et$gYcfK4t{p#D*Rn^tq)jc!y zzD@1zWoScbZ!a^4sJ*cq&$QCsSZ?+Z-`?|W1xv0s1F6Ms zh;b@Ni``)6QOkywCM|n|*-P!>#u%row2K?PGJ+317X$A;n;+OL$Cr-5EfA+j1e+U& zLEN+nzurp(oAYhtD>W@xXQq3x9hwg;do#7`tPeclvrj{02xAAAIn zcKv@$D{2$A;FH|fwmuWKm~qg8XJ3Hbtu(M%-Y33Hs0jr2dau^RH!^(5c8l=*1ZR*qyfDFeK)mAV1ZS#c{9yXDzQcYJ zN~8$moWAT?`oXIEcE){>-%xHn#eD)PQQb>FD74r(Uj(NCKOY4|tzNMCj!KI%_ z%iCs3r9;bnHO9FpE%Q~=j@ri8aAP}V%h>pud4SrU?J-UhX?wPtb<~FLz(bF;p*zfB zYR7iMB}v+`ohH5|v_pGwy+}K>*EFQoc0Y!GNNc;_422eAKx)TtY`NqZ2aJi)!{n~` zLw*ivc(nS}j&pt$PXG`6)*cC`XPmQLoB=){?hXD_90ngJ<7lO?OmGrT<0nQgWUNdu z%PZpBwbR!QL@t;I;-jc%hgZHupLE7n7Hpp64JqR^o<${Qoc5lA11q3)k+wqGC1_dF zE}b^tw!(>tH+VQX(!iz?eoP2#f%v?{Eobbf`d^^EBMt0**e=%lJ9L{8$;Hiv*6}w6 zcLT?NXKM+zANLMIoG%ecU_#ezq)W)92xg>4ud6U`>EnN2kZk^J==Fg(2&bJUZNd%k6uY0%2{iaA#yKak!B6G{vmEy`?)(L|Xt1|+pyn?qTVl;$Osn=tSoUI!^Pn`aIgUs4 zzzK*8C7!rwRxx4kUt^r-q=C%`{MB+Q#J43*{nhv~kg&~fG0tUaV0!`{hFJRtTc5+f z*(PgxDaPq0t?4B*4;u$g{fUpF((nSRz0`94!g(bv=P&aU3t4m(FD#b^Hc#>cV1pQ+ z)8d>h1Z=u@fLP7%bMBJ}Hq#&mGU9yBa)}vn=7kO@CM&_`9FdllU`|jwRLJN2Chbrm zQ@kUzaABX5bl#Q{E^NB?jZdw=uP6+|q>&>%L=ixwhalgMH0&X&)Ui*ik70Q*dJz8m z1%t;DtO8$Jx+otqbISsw<>S1kVmw8hdc1Wce4wBkXZ^P;rkL8~=@c2HUa1e!5j z!(u+?Cut3fnPt>&Pxd*GPd4vUTUE;EG?2Ecl)2IgU-XT@a-^>Bg8zL7;OMVA zf3o@1s%rXmMm`)3Hcwi=s%8!~jvRYW+DlcgF7@AV-?r@UzViY+97V zfx8T`r^L%OP1i2in8VT@mbTzVGnv{kXwOJHcB9!0Eyy8k+ogfcldJK;9oiSts?{=q zuGsbnv_GXCsb#)mejMIb?iX8`6Sd4}rsFWT_R_}JGt0WhmrWgqW$zYHH_myITom0n zKKgAEFF9quXnGsVk;bfb(KhCZs3-c=raosgbUx98&FVDl{Dx+zti%n?%murLAgfPEhOD-sjAe)~~&p(-T_F44?CY zw3_(gITPCQ4!AU=E$?8)K?|mL^f|uYY{6i!Uk-5CUPXzS9nJf9BO!cm=fUrLE{}mZ9c>SD-bK_DW}OZvy+E-6n0H)q;nh-6IWb zPPRiKNnL%;9EnL?y*3MMh4!kntKD46Ay?o9{Y02it9{6llR_Mq7j*9;9*pxDx9~t7#0poem^auA zyaT)0^d9tT(wg35=2060r_3j$4H<6sLJK}J+UL9}4Q%?qgA7lP@i|u{o*rXTdt>9G z58(J*wS^SL=W`y%@z9n_8~=crigd-^gLX(7IcQ$)9p9w(XzWO&cj9kJ|L*D^%SK-k zgCCyIJ3W?dD&C3g`%T0fFr@XHXu486^bjsnX@?#%lc~*|jOt38IoWK67OXxE{guz= z2R6&u)en6HBZ(#A9kGEv*!Y8)c=w024`!O?)XqQZb4ubDD^}+Gqh>U<>u2L#Akwa% zZI)5%GRNnvlh$R9d7s*^a3B3v+OJQVE7Zo!#R2l${Km{RweN!VDSj3oBJI=prXRJd z3w_Q~X;&ATId|b6c?8RmhHHu+%l_SPMc_uf3wl-5wa8*~j`>W7_MNopi%ms5PXsE! z{j^ZLO;=&5_lyx3u-xZ#kTzhsnap%WR-(t0R%E5wOs(}ApOYu8^&0aPwBY`A*iUI- z6XG}e&7VaNo?r`U{;X-vE^qyMbk@?=uQ#Kq_1TD*sYvSs-vDZ3p@pT5-DtbU$XhI!_%8eE56Uv9)KQp9<;vF$k~O=!YuT#GxqzOBEAihe`kA2SXk`8}tDh`aVl7!LtmGKnJgTs;e>E^b9@wEb=B~qt+B-1p@o{d(+~ax5+pSvTz!l5Oa|KpJEOnE?N|6(62jd5}a0I7d%0n1l}Mn4gNx0 z9$dr}8-!DIa^0 zRf?YXIqf6`&YN?TF5=9QwDF>;I0VwKK4+DrKEIl-lwg5=NRsb2GZ|9S?>;B7m@Tmn zxR%*EB)(SBE9m#72CkU1NEnEXb*4#rKQ`9%?;Kyjqz#QvuCo+sq%XVz{&#~qh?tmN z+!g^g!A^KyW0=JziC|9*Fz({8#5R6&Wj@Yt#$Eg&Ez@r{KM9R-7}ZMH9D7M)Tt=p} zzE%q|ZX-t;*p%pql9LeB@v=m){Z4?99-m4Co6rHIWC%!nvMmPeeMcB%oJd`XU^DU_ zq-2mtrbMs_c7^yR#2krWyWb2oSt1eam0p~2Cp#pPk0+ao!{bxSwkT<@jt?6lOp1)F zBOh16#FC~D*4J4GEzk7eqn^ZTxW{{n-)*wI6-SHZ74L3s1A&U*jeJ( z!X|zs(!~d2oe|RF1EwLhe#K**r=;~OZiYf@*tt|J0#I!sWcFKCG2M)b+!cSw$B~9N zqZPQh{B)h!iEV4wD1EK19tHpVEDa&QB4upep;9I=3U!F780%z6i>YXuQ)^Wj@9>h= zs+IN0n6;|<}|^$e(_513Gpl78s%)7 zec%Vg$HA|Yu}_<@Pw$9#++n|6_zcUD^Wf(4cHibi-7Sw*$N2@F9rCg2X6n6oQedpo zXVSp-=T!zTU6u&;&dva%m&#SJTeqoUuRumKwUX9R8l#);k(Mcq(NA-v^|D%!(NcS* zf$guo45Ru|BG^_Z4DpgguqU=)a8(JsRE0Z3=7Hx)uo*z+Nf6=MUU_@An%C?Xf>YMk`n+6#n)=(PQyUv3QIlEIL*!w^oU<}$6iEVB+4aZ|^#-Oc{ z2DZb^7{K6fog;Q-U!DbAHu%#gIEmb1e zOWA?ZaE&CAd9Zolzr++d@Z`Qo!>f!@aAV0hHY;#!_%>hiWiw!Se7QP{uoyW;1z;Yd zZ=$}Lac_-v?yX`g1~$RBao(gu3`tDC)oYbNA82!=^|{pyMN0){L0chhmeqoig$yT zAlz`hT?w|8uiGfrX(q95BU|~7(0WMgC~Yvbkhwg(mRoZ>hCPRB#+T=!N zD$)gyw7}UZ4Qx)g!r{z^_`XE2-Sg7vvCa z3n6xs2sZ6oqoB_r4wncv{qdVfFr^jFWQkyJlv8jt#AOn}=4wf#d>i6ciD3I{Lk+y9 z;T?%!`vYKoh+jyo-`ecW#;#9+c1{}D?COaur?!c8;%=}z1UCP924_)fTih%qrnWV= zPecQ|UGY8xX>M0DmD;_~21&cOt9gOipU@tZ_Gedfg4(y;@NNWY-*z*_AA(l2do050 zZNWvmn^x3jL3>x)tnOwUwNOtS25F(5W)-#fd*LWlx7)to%N(LMp*Jo`X%l)I-^0+> z-HEPM+PXVUZ48hKd=9On^;8QX1GkM{R<*N+Q^d!S@5f z_Wfd=T@u0Ox_W5B*#5E32NGlZo7;1cy^R#!AXGm8Zs63C@J{ zs3frMcy>WtE)i@G{sD;FBp%2%d#9k>mvV4eq`j15mgPb_3+;lmvpJ?d(giC|!lPa- zyB}ch4j7mQv9!c#lg!kqNVsx#taFPrupN7G5@M#rle5hUCam@Z`Y~x>a~@quU;)Hz zi3^@Et)`(mUFP7kl{9?UH4a*EEVNb9z~F}BM@rst-&k*J z_&c7sZNXOW;02r)Vx8BeIWL&hSvV%2zm5w}8rTkostAeOFUcV);< z^8&X%3az>{u(`@FXG`uu2Pm=R9#i~LBzy^4cWGcVA72dx%kD+5C=qPMFvJlO!QQX8 zf%5xeotYBL?=y#(<=D4koek2!-Y>eLf$zjRyCsq%4}AZLdf+1;K^i{rO>2$U%84Hb zSFLOH#o*53)!<3uZQ$p`?}6VHe+K@uZVcXAgiJ4Bp?W==(N%DJap5+w9}!muuNBt= zze~nvwI#jr`BS_GoLJxL8^F!QyTO^_bi9CXP(;5ogn_4#6?pUBw8#qZTye@>i18)| zVLOQs*|){Bz(>Th!KcN!;NQgyz=dzdw)i?N9bb>7h_k@Al51i`7z>@XV#V47xKLn4 zG5q!dzDJzCPD6(#LWn%E9tHpVQ%~`CW1XQ5>`7PrUEANMLz^ot{ax=nh5&si_DNgw zt{FEQmqpQoIE$qfJ!n=@`yN`+TWo&cA2f%k(Z`~ewD8Af=bZS|a@F8>F<2V;QSfw} zH~8lbC=bvOZ-5L?YN$t}etg62Z1|bi=qP5o{|*dyK-( zY@T3yym~{dEfMUEH!hU{fi+%%8ut^g(O~ZhSdP^E9q_+<7TU#hZf;BYB*whI7RQ=a zF@vOm?Z^Xq$b=<=y}fBclbPib$&vd^Z=49^uJ{vS+(qTl&hA~}-tV&odhIl|1DHaPJu?0$f~)@o4-Vi}3#NGA9x`0q?2%uJHu zl~YUU!M4e1s?$Ou*!wcN6J2%sN+d^et{S!D5oXSG-kGKJyMwm%QIH0Q8g?Z=@-&YhpZJa>*neMz2=ye7A@W#v~iSDwai9hKm{BPqF( z-&$p4K-?@bqmo(nG(QYtvsI{w(hHPUqY**dvq&5y(LuuorErZrg+Oq1V;xkBhr3T(1 zEA2`R)0Nu68~x5Z(hg!66*c!JzjIw%TZVg+*-ULcv*-7n> z_I_ujv_IOLbJP+#!+uFxLT6KP8FsiXGzNWD<(b&oZ$soJL%c!ax zt>|txQ_Js(w=qh~?`giGR=>C3`AS;--X^dd+E@LMUk6*rSN%+LYMDd)&Uk5=L(FJs z&1;YJJA0*(Q75M=ribFLT}Bb+Wwd^*-#M@J>&Ke+neT58`kk9P+OmFo&|F!Lkv8dA z<|R}JCY1}s6~HIN^}vlg*)$p8dE&dl-;3`D-`d%xc^LeF_;K*t;w9juE;h~c;I5YM zarR+hiB^0D{zjY+u8+=vl{*KXEB1AXbAA+;2Dj*D(^LmPAZ`eLO?(^p*KX#@3iJoT z%xnF@NbtY!B{Tv11v-y-INNkxiL-!)U?p#}8rbxoi;qTh25Tg7U$)uIgomMxlLodA zTBjgBCGk|Y39Q0lxCAXv+9g{`fCgr7NlTvSWf-8LS-!MtRtwUq?00Ek`vVF+%#v=m zRRnt_2m3<2K_b|SBOo@H2sZr(wNVnm_R*I1YEvYFJu#3DagoII zhfGDpH3z0bds*64Y4mCPSlT`e6hgXSGQ8MMN(0-cYMQ$JED>xw8aTE&vEA)H4t>}J zaGMX%$*r8U*$>;^kq&Q-q-}fHjAlAIzuh72@WW;qH9Er0lGZTCJ~p(2woV$@Jjriy zX$1GCM6mr{nGSImC4xOSrXcO(uJ2*12)5=sDU7b#uxUKGyxOCG zMcIbE>2rr|ply@QVr&z91KI=9z`TQNsKYF%k=!nVncJDD$NNjz@{!&)H?TcVnuq+( zCW&AxPKWrhM6m5B=0Ut7abC#0wh;%geAw@ly3=M^KI~mt!G6%XNCVp(*FYRA5p2b? z5a&w-dq*(fOz}IfNpz-|jnAQ&o_r3izBI5sPfkJX zDG_YHcu$|^cXA|x?Wxxh;%bQn3~T+ zD>4JmJkpBHFny@afHp$fj2Y%JXrcJW(Tz$YNA8k%BJmja4JX32!400or;)z4EOI3M z8338-Bh2*W@fN!$m7dHrybJTh0Gm!D;)?~sSdphh;kl;cW>oehv@fKcoa;Sb1d7b_ zJ1KYD!i&tKR<_jLSmwoaYgf4OiCcEHA22_`a^wuG)$hNafen%0R_MHYfz3Viw-^lZ zfJCqr=RrI!5p4UKMG$|L2)5!fh(-I`Ji&JJgAnUU1Y7YBh&?5Oy&>R%x_A%ugA(h` zx2I7rXhs^?`=}WRL);}XJl`DJf;P**d#g`N%XrH8w#L`5Qzq+L8{7xxRrqAoaEHc= zuoKYP24MTG|2T+&0agTCaU;ZP62bPH+9FTG)lp)Rr|rG0E3^U9x>_xm3ys0_ECy`b zY9Yj#62Vqn0&%fKu(fGxv)J#vD-mq(qthY&AQ59k$L&WGoP(A$(3W#UWhH{m{h4@Zi(TP&E=i1CVSai89mcQFt{ZHtNyhQ? zF6giA1?_bJ5oQPQ*-9A7Dm^)p{)?#e5oY=qR-t8;o*YS^sSe}GHSxuQzSU@HB?6ll zXQ8$aK-?kmfz{^My|_F1*ZQ5S(!kztL&0$nYYefw0JcNb&O+=c5o~_u_w+s1;}fAo zuon&6oNs;qQX)B0!$VPf6k+aB>PEj)cc?8cb))@sH|sfk3Y0eMIs5dw7}{KEi>(&i z1Z}-Eu=(I^e6oSITiPLTr2L&x7fYp8>#sbGiY}#>21SfG82zRN-fYQ#B*7w)uYl!nCbm{@U4c@lOyT(;syy$@e0s_=c)1L8?biP24L^p z2z>}~l0n?KS1Hbbp^r{fR=I24^Ql@_hgXYmzoc^KxEV2UHSZQGUiIC>fDPMFk}F+jiZIb3qm$dOZY0f5{UePm>6?De2U{RwCGbN?Zf+Es1Nc*yq!4 zp`DlZ?G@vD4Lgt&gU`?p*t&x4FY*sSY%LLN2EB%ky{RwG86y#FAD`$5|CB_qJwa#> zzegh2{LIbi{eE5|*!#viNK^RA58Bef=0%Rr+Xu0;M6msGB{v=)-6ev}i`$X1G(6~M zN(7tL?IF^bew{?H_q$Q(YY6PJX>$J;8DBAE!g0PMZog!_I>NbIJP@2C#`__nS}F8ZmKgHAdY(zPP{tnHfnVL9?K?Nu0p>Gk>2K}8#8ZaL9t97So0Mq?qp8e~D?j%@d22@P|5L zps^O{v5jGO-U@nW&l1x!d!v|M*%;p7rJ+UkMKPVR>-v>xcYJmi)1JDQn6}ipV%kyT z(bfsE7WARss}=O0{#;Do=|9Bun=XMTT&Abbbh?=S(gVcwm7XD{pY(PyeWYQc=xs~? z=)`!-@Qn^RCAC14=muiCM2`^D9eSyluF%`Wbc6m?+%^jy-w8I;lSA+uu$ZpTM?4NY zbbBt4P6y^Bbh!Zx(!rwwyyU$FSh7BbNla(tuf%jgE|F*ppeu20G2Mu}i0MK+NKE(P ziDJ4AFA&ph_*F4ohCd5wf%d{bifJocyO1r6cEW?iPwmD}HR7N4pjE^T_Tgn@Vp{%| zC~UW-)o&{?Eq+5{TKn!6hv?}WgC|!WSK98@6w_|^PBCqEpAyqv_pq3@y4Mx8+tN|%=sn zJuRm1Z26$wmVUC$#VHARzmd2a_(5^4gb)l&v_QAmU1Au+I%mc0z(td6rW?Vv#ovNE zis=A5SWM&BkeGh2&xmRB`ka{VuG`5d-+SxSyIOG&E4~oZ#r1nJ&07vFBv!q>E{0 zdb^k&rh~+^E}a-j56+FG2QL=WH*~+{kVC)FAGCr#p(RS#y`(>AQ!#x(2Z-qhI!#O) z(5+(He;yUX>eKmMOt;V4$u>`#d}fGg?l~}7{eRc?@GjDd-r$8|dU$RT^JQBn#q{h< zENL^PKW8H`{WHHJPvzSn{SGThVW(GSuOC(K(~}_b{cBd7Sl)bb}=k7 zooq2(GoKUFEOWn@9+}6*w8s2JOh?Sb>umls!mI;E{~vZ}fZ0bY=yf^SV|--5S2|CN zX)C!?OgG8XVwy<)C8l>|iPE-JXc<{uOsB|ZVwgfY-No>N3^~KK@CsH;6`ut!64Ux| zvzU&L?}%y8cwS6n#y}ZcFbx@R6w`>Yr4-Q;Ob^5xd8OmD-4 za<&rmG)xuK%dn-G9)^9zv@XmM)3NXcF`Wv(6VsuvXnC7wXbBds*8&|0yNc;VI8aOn z!iU6k9(+nn$H5I^8Vzn2(_iohF?|J-D%is4Cs<8PAHh}?)c?~z@J_9uZ{SKX{Q_SQ z(6hX#kBWZFQ%*C zt75wOy(^}P-&rxu`+Svb!8GkFEv8vteKDQyx`^p`H;Rn%9a`PZ(h6GKZ4lGi?rkwG z?aqs7WmhD{7DfxZ&SF~EWs7N9w^>Z9x+`MZ()F)wx1|GIXqp!2{I*a`$F~h)I=$@| z^JlDI#WZ#+k!mxdp<5F%z1!{*)4c5=vFF()rd8YXmO~CL+J4rG&S&us#VR&an6Nor z#PngCET;Y1TrpkO)`)4g_Kuh)Yl&5DJ~UUWC#I>|ePWua&954=iD;tsqE^s5?Nc!= z(~_>YX<(1$)DzPot)H0AXp_V=M4Kn35!x0p{m)K{;dSPetY-5(9Ku3FEzsxeelh*c zwu};XvKeBUmhBQ}CHS1L#GXl+nC4_+UtUt zmR=QW+KuVt)kaJQufbwEcTE@5v1^UE8hD?W4qd0jbmmIB(dJ1!2$QmJ)po^+JT6w^s+qL>a+>*}cgr*+g(t)NYm zzpmYwHc|D(w1?^>rY+PUG3}rp_Bia&2I>jvG*x|0qm)5z#0GW&lT z81b749{Uew!r@6w!=lw<8Wnvjra@7)TWoq76WuMQA<P7y3o)I7?h-eD*5?>8je*`0(-7#Wm_|U~i)jG# zm*tT6Zq+Jjwg5WtbP>~eXSkS-JCBGvf>(;^u=9qP#yVHUG}I~A$mU5Sou*!8^GgT|P7|9cO=3!j=?#-6rX@_4xcT=mY7x`;<#F*M@G|i#@P2XNywCYfyb&fZ zm78h@euX_9*!%v+2Va+2krgm;c}^UFjmrlfhaGsfINwQk{0LZVW;3D@%gti?uiPP~ z@5(eW{Z^hA(`V(V7@jI2r+9Ol5q(wai)p7aNK6-%C&V;Qd0tG`cK>CPj1F~358;+O7wBPt#OxKOy z#WdSUX=U@F$wpf-%{4}eX{xb89HN`Xb}i6E}--C`OYd@QEFL4laI27ig^W{{L& z3#N;~4PqD;I330GEEp@MSHUBeLk>*}p4JMQ6YLVxl;CqQ%?N%F(}W<{!4^jIf!bo4 z4zv-|Y@m;rCIb`1G#AJf(^TNO4k4Qn-30b&1x*CL7SlW6M=>n}VmjLNvDPqR|KP|p4Gz{^3T422Yr(%Zr|0ZU5f0<6UV21VA7c-i_o0viT zqs5Hfe@x7f{k397>c1yufPOyM>;D;<|Fc#wAm88F7REsQl41tn*AO%CzJ-_p_kF|+ zw0}^{0Q-4jM%F(kW=Q=WF{0-~&gWWS1pRMfM$Q-SqNWDlC}yO5V=)8d?+`OEew>)` z@Q;fb2ftX%@b}GPhQ06e7{{OS?nktOVeSQDhPTIdwUuC0dy<&Z?6t&Vf2Mn5cO5PE@_!RJmlTOr1rUngd)c>^(H%)5yh zTRu$8nDPh33?-j04l#!OMJ+IP{2ei4#*d2`EAG#<1v5rGMa?|xUzuHvy9>k!&~;uEGe-B2n4!5piW!od)ZOOE zNZe*(M&J$;GxByGITRE2UUHjhgPkd6`0Eaj@#B-@cfJ=h05z_c z-DAd`78f(zw7Qs4rk%tL6n)5Y2&0QIW<)C(7rIi+aL_z4qd-3wGx+ltG2=E1-(d@8 zyk>PV!!+BA8Id_sjA%<|mY4yT&)lK@pTU)zwSqyEd&G>F{6x&S$kSqmL;8E$f*JW( zSInr!Zej*7j`le01tf;V3_g5HY4Sr@cwP$#6?FEC87)}sPFnz@1p9~?9XM6Ypuodo z1_KuAW78i%5MTo_ga5jS8T2<)%wWIuV6XpYl;77{!RWr)ciD^>)z@FlXufPQqxj~E z8NBzpm_d6^U%M@X^{R^*q&Ha1;Jj601m%UCPqn~kywtnx#*D%nBxdy8HZh~_{uDFX zu4+G6wq#SE^SA!bnB+hPXOT@*8ju6ciMi{sDexyQW)4Ez}4caDk~As3%z3t%K% z8;`>dBjE0k&S0->F@wC8h#A}UshBZcm&6R^Dm%dD$q=rZAuTX=tF@RhTYbfh)w*BI z5Ut0=jLcdoW2RO%^kDYKfRJQ?H2`EA_pYF;a@d9PMlnK}oIAt_VREL55xV5$i5b20p7^oJA;gYpfze98iW#Jo zIK|f0InmuC1)tnMDo+jZQyDh_LYKs{?(^Jf#nb~3n%e*3HkWA=|78o5%y@)mVum4v#SA~#C`P0~$az-_j5a7f z)@H;YgMMPh6KoYTZs1Qb;{}S}XVWuIpoW<70WHOh1?Vm2nEx@6^x&Buq0i#bTX<^47vj*A~J=5Y8WAuTlD z>33cdb6ER_Vh&k9E#}DdD`E~puQlFg%5mEFia9)crI^FAKN52^_GK{#VK<&&w+(Uh z^$0C+)b%1UM_ca|bCC7dVh*l$9-;3<=-re_HX{z&yGH*jj$rWp(#C$3i^&UqoMM6I##hgR@K_N}Ja4frDaIby!Z{&VqV zaMh_c4PWCvOw8A~za-{s-2W8w-O}zfo1Slqtt8$Ws)4=K0$)=)K+G5U%@FfNen-W8 zkzc}en-O2+ccYju^2-$SwQ|ph`C7SzM{N2kb>MU$?uVD6^aY35bbLd~eOf^${l~=g z4S!Zl&*`7U^qfwgVKb%Y^h_~5r#}(XbGqD2n}#mOH;d`2+g=RAHGKc41v;+H7t?WV zyO@q^1!6j`m7QfXrQ=#-F&)=Nh-tWH#57!cMNGrBlVTdKB|pl1aQx}G*4SIH9!|Z) zG=v!{rnALsVme#6kJ(Dl*&<6!XNzrOI$IQb+@_(k#ob~$TPzXN+2VXi3$(UqINNSO zYm4z>I$P`&)7hf%6E+Q_9Xv&D6DY#KUS3=z}WVu_f}7Wv{3tu4wwX*Xc> zeGM_A@0*GleV-|2Q1Lu*OYmD_Mm+s2X2erQuFaDXPvgXlcv>!I#M1}4?Ei5BGUUlO z*KWX&r#@mvJZ%y);wg5XO~Z(%EHNXVUKTUr=_@fKo?_?Q^s$+E&83**{M(UZ9jDgq zp*W|z7Mfy3mbf?gUhy#SL*i`kOz|x60`W`WmEwKi%^u@(Ki;XiUpn8fd05OhJl0u& zO5pn^hp%{S$^|fA@z_DkS3GtX^TkC|#e7G~TruB~vRce{q`V~NJ5t{A7?l7YmQG9i z@5Ho%5B;iz9axBc%2tBDgEhtU9c(G4@8APs`VP(#(|7Qhhz{Nu(P1^XJ)(o(7Snd{ z6OYmV(kkr-yWm+n{G~*+b_gtFg~DDu#$95@V~iFv9^(ly<1vb((`q0^TbQQ{}J=OQ~SiHLRdKJE#U6+4SG6p3iwZPI=IjxTcIp)6)|6K($r(@ z0Jy94eDFwd>2GnE#59;+Ab!6_>&JVmjAd7Sp+|^wYMr=v-G%d<5Ll zW5=`2>LX5ryT%AHojD#9)0yKjF`PL<&N3~~n&UY!tvPmz>CAD+JVxIk&f zg3CN()6*!kx|l|pw~BMY9mF)syh}_wy%FLi;DU}RB;3F0&yDn zd2v(lPH{T;khl%_TX6>X2XSZcFXBva>{9ms*s~s3sJPVDx;MC~xG%W3n6D%r6=A%R zI4tHXiRX*?O5){Wyph=1B<2fpKM~{oxXvHqtd*ezr}{EmFyHUiQ@k7Rbek#82X7Pe z{ch(X>A_W&+ijgSsHm9l6M9_C_X+J1^L;`;iupdF)D_s4fdVO5=*b0eRq$+aI(Vfx z3%pGn2EQk!sp@fZF`OUZGh&#kI)8w1OY#0yU+Fl(l6b1#lHg>Bw}3+fxPUXi2Trcx z;!N;;;tcR4Fn-fO%#7pAmEIZpVseb*l)edl2pDfXF3i$)SuR9A5vBhT#idqx=|e6P z)wK)W2Hm1~xMeR*IEtT%;uoU$^(a0a#fhuE!V+254N=@|b?DlP+w2Oj62m-pyuBF{ zrO&eLV@6A(cxx2zjpC1^_}eJ{CBi7*iC^PY!pk%%iYrBN?I=!*;*L>#x5rLAD|esO zasP9iDOUHB*GKUoFus4B;;s1HTVeS`6n_`R7d*y$rtz=%TCdVxVJVjV)NhI6jvhOn z-Y+WsJ=gS*Gbw7tqfz{fP2?4@IZA&eig!fu8&UjD6n`1TC!_c~k3%tD0Y65q_$`XB zL~-1@YkOQYij$+bLKIhx;+j!hFN)JbQ41ZS_zuglY|^YK9uvhmQT#|0&yV8eQM@UN zcZzxbIqycTI1gLY9XdPVWz zD84U>bE0@=6h9TktE2d(DBk-wWB=d(d%x{BsmL>#yx)kti-5#nq#@K@_*L z9M4woK*s)i3%5nBxHF0eMDd6y9%ng$8HJgSIg0Rb|jOLtA&7AWonR7lB zbIzw=&iQc5IUj5}=R+;$J3<0Jol@Y#DCg5LAC36}&DUuDlIHs~|3vdsn*XA?AGc?2 zpR9RR%^PTb04*{O>q7?xA8P)I=0`L?rg^^RNoWafn5=ne&C6?^qIp%#t7~3M^SYWh zu=7xn>S$7CSWEM|nm5oqP4lLjcS%NI8m4ZTGBMqT>2^%rG4;UI6H_lty)oU1sSl>R zF!jZBH>Q4=`eVw%G$6T`gCIbJ*kT%tX$Yo!Fpa=864NM5_hK4@X)LDuFx`)70;UHr zWn-F%=^;!HV`2>9Bur*WVnX$pS!PdSLX)-z!XivhV_J;q8B9wsEyc79({fBJFs;P2 z3e###YcQ?Fv<}m=nAV$mMH2Y5;-qtW5Yl)|cVNQ5@KDVEzipWRwq08O-`X&FqgDrx zC74e85=!LFESd0GVKX8-sk+HJo^ZruD-%!ifThs~DCZc1KO=Y-c{O>SmF15-9L;lWo<2iwQx73q~Q zG|{9VPf9aOzDz1?u3QX`GfRIBE-@GSC)6@ye+zCixxb^Zq{#_I^G4(+)s8WB^OJ5e z%fC))nRn#(U|Ni6@Mo}!`QT3^YIY)_uvyy0Eo_cbGylt0*&nB38-Q7~=^E=%Zd9V1BDiR zZe73a15W?`eY)1W*=((xR66En(;+qK`Yw$!2aF$f+k_z#hWwo(N~))gu1Reo`9w*7 zr!ucqD^}|UmU3-vy<6@XGXC}<_e~gb|M>3X2aF%mc7#`tMy5!$V&&c8wo>)YoJz$? z#nd-*A90h*p^}})3>q-1)tCvR2M-uGv2~;bRQ`zy#jZo;bEmnS)t&B^33aVkzxB8= z4-W1!VDx}{hK##q+>rZ+j91M&{c~Ntn^BvV_Y4_5zBTfWB>HEXv`CV+k;+BqUa#J` zA@`1XV2GEAm!duz^&b`RcDd!C@xzts{Jx!1Mfu6M3?^MJvFdyMHe zcD#2KlrXb<-TwIX-6ptq$hdokv>r1KhjGlf%n`$fXLcH)oNhLIDio`Vc55-qtz6Bf zZ#Z;#_JpyK^le8E{^ut3P0i&A?aYdlVt#X~Y*O($jk*pQe$TLhV|mb0nP$M@VDf*d+6QHdl{ANDB-{|&31{iS%1Jjg`$vJ^nfG@~ z%&{`(Wk=B-(oFe4_Wfw^y0LixP*s}tOqnEH8{YZ8*0{PX^n z|9^ICL&KfK9p!&{KQp+WjW=Ipx*2)*?nr77V=jD`5SO>Qs+${wcr`SH*}5~SdR|sF zcV^tRyWYan!3o@`Ltf@hZlh9v-}#RH@7(nAaMSxwjM?%8Zd|=jCOwKWO8`Ib=x+Nz zybC6p)GBU<>DtA;-t4*@Of>&FnvfBQ?y_qSGq(lYJM&g#x~YlYjWQ26%8P~3)*lXW zhZZtP-zLSyd3O&}_e#Q~oBpx!7+sM6=o7D<)&Fxl{h!`>P3KUI$xht(*>mfaHu-bi z)I#%%;A?^lPTaI2c}3>AGh_U1oVcG%r3G%e`Hhn+7IESeN8uAX3i^GNx$u-*cK&2f zEmRlkFemPhy3D>w%p%iwf!jJ}Mc#@9Znaonc!4=!+=?}me}?T-3ce>CkL3J0A`=t- zCHJ?JlZg2+2#?RLSEg`6(OSU2oP@%IO@l>l-Kz5nW~`pK=W_LKQ&OKf^JANxSR03F z3#J%M)$#w>+t()D))xCMY)NE7MTO9+|2{yr{}o7b*+{= zag%2G*5$ad>n4Q)PG#;(gL607B}le>ofDSxLQX45wtiL@gRub(tL zb{*F@!>=Aa)+SsDyM-2|WuTlRtKFN6EozkI#N?iJ+}wAZ1hJF}YpCPD;}(Cq8XZp$icX4=PmPaXR!?$aMW0w+b5epq*V<<6c*z;Ks*F z%i#Yk8qOH_FTQZ+n1A#<@hwm@ipq`#9-qKrtVrCl>#$rt=kD(&5GKpx|7@} z9fvfsm20=ijW1MS^4H=NC@{m;xm6MikY8+*fyisYI=6Pbn;7nkT{^JNtyE?~Xw})| z(CY8AGveYO4VRyrn^Vb`oQwIwXWg4o#Y zvUoD8>*jv9b;Xd%hp?f&)E%Q#^iw!2r0@z1$W#w^P7Z*sfE zpw2y>cWe4`a!mMnw^HJT+_*vodphJ~oAuATe?w;A$hqXCjHfwInt6NwF zH0et}Jm0%IiaukuyyT|F=j2QYVPB3Qui|!pN8z~hczf+v{$=+Dv|F2((J}>Q#mjEZ zvbrwN>OA9{W$p7)=2k>5r(SlKmn^vPaj!-8u@Ym#VQ0@MRC>`XZj~|@(h55uA9dY?$%THc$LzN5aOm&==%bbjGypvof>~T|8yF5BHugc@|++H=$-;&$X@h_-+ zCCtNfHC#Hk$%#UXT7;cAF6T@rmpvuqr0*_|Qh&+A`z;Ght!-{c?cJEHsJ)xD4Gmpj zHf?jqu|ZQ_bu0SN{^_r}Wzo=ieP4B_#*{)UE_c$JW!V!HMQ809iNwFW<~C;Hy4$hQ zxxY;2cDGUo?R!jCPNC0nIp84d$jPbD$w|g>kH@CHc`#7RIGj*@8`UUe8)T|&kVzvt zCVLke8)VydcTAar#=9Ly&ABG0-0gp7Y0`JN<utj!WXlGN#Sz?qT2e_nGoL-Lj>=E6v`T z%~@*(e!CxVwV+XIp+$L}ce?lRGJ0v3+qkw@X>Uhx&Bu5b?o{tWW=DG=C!yHpN$ra# zv;Uks1UpoIxBDPAU9j72T=VZuJEz6{*G(tgQ#^T6`(m4O{n+f%Zuc}U&HO#?Xz%3D ze8X*BuVB(6gR^Be zEbBlxw@9IayyX3EAg1Jrqv23Ykvh}7)7Q=LpLiR~rvImf%EtOntT&lQ++;KCO}Cft z#NB51n{L_S->yUgH)?}orr=F?mGA2(OzvA)|IJ5O@4vSG>y~E6Tkh224UUB|dLuW+ z$D4|Sf{L2V18%8?CvFM7@pCqoo8fpnX)Ev(M5tW0v@)TSe_~z!+??!k6Vsf;-c6Pt9H)neJK~8LsK}n4>{9k@VJ@?_5B5$n1 zh12_8_mJ;IOH=Ehd%N$%y(WCnZSFhvp4olSZ5;E3Ii6gkq)B?utr`0KwkA`Y&KdsC zYj8i(vM@s76!+otJF$N;p+`<;r|pLS_T+NZda9iogr=Ru@-e%-)2WIlgSe()OuMl! zE1bL22BjTKo8F)x?af=#GyGpHwe52BqHT|(KZIlaox^vd?aZt1xkcl@*q>I}pS7@X zVzSA94+mwdUmetX?36ppx8;&4^1fR(l)tvgYE+81asTl~sPM#=Q=PHsoZJ?>aSK?o z<#KrPR;S1Gq{eB}9h@DLDc;s0u4&cj|s(og^@cIt9&Ieu#4^7!3q;8y?K;ae`};&*yfI5TaMcNw`n((_ksxs2^!)%H%K6r82l z9_f;E67y>}8tKI3B$lb&s0O@_A3x)yn=e0fi?Y%MAL3Lvyws$Bs}6H{98$OG3MW21{lna}wTYw5sgKt;& z8au7ghuM?&znG2P%eIe)iL=f0LrAs6oH~U2!wysaV?0tGG@U@Z+`EJMMb~sVo zrun#`48g@S{bY9d%@2E|olYz;Yd&_T#auSkKXJRq6-hf?sC-`d6MSXt%h_ZWed@jy zbDPOJ?6xnKsH?9{&Lp0hhrcoDpSe}c7l++o@!k8ivbt8Tv@0up<|Y-JqIDTscQ@DF zTr6@mH;`P0a(T1jGq+r^I1HNgXTxB^<8O%4zAl9vfr!ZBNhu5HQHPq2xD zP2x=cgd!zlV|U{D;HX=g6)It_9&r=O?tB$Vnr6iA+=_WR<}AGp<||psb@(k5h1^&& z9cp!`J#m60O`CQXXaBI$sk%Eg=OvT>1={5Ot)}T0?u`Gf zwC`QayYz*7BF6XXr{>s~ZZ+QrPaFSNZm&S&S!vT7IcaY;>YL$z=To!$Bz|$5jTL-6 zJN1>@z1c*bpSd|s8qVL+I6vbitsa>j8u|rpy^XT4pG`yG{F%+;e8;ZRX&L_aZ{bzW z<&4;E%}m{IP|-$9%U=-sltb$P!l-!{lMIg&5(JYqgPj&0t1Iq%GIw|Pu_ z&g{mI<}Asp^|gB?#@9I6)H>w>N*`_5arz@Bi7>_zG)$ zU?Mw8TjLj|{9WUWZ`_KF4@B+F3(fvlHSTov>W)Y&G|9)F```L2Z^bum{NJ_T^sQ>Y z>5Mx$(0I+Y+V74tY2Uf;R(L+=0k6-h%BGk+=$Y)v-)?86V$;?(?rT!cx(`%)BX05| ztG$ZaZe;JpNTJ*TTkzhm^LCuYPe`S5X6Fn_s;v)+HBI)R6p<5jL$jHBsFJSUhnhn`!T+Cubb*W zx|K>UWx?aJ9N+on2|x83o^a)jfjDe^e{>tx%;7U|+<=Zt(i^>)$wm2i6@wx(^oJI=S_H9ksP<^U{BEZ@`-_e#OtglYYgs%bjM+uWrfU zz^j+TQ=Chu=NWj*uKCHFXbJ}jmB zmfgfOCCz)ky8%<>5A=;wP2)e1%xC&xW*Ys0vX(@927Ixq{JqcE!AWVuCC7E zT{sj|oHISvrZmj(Z@kH5#wM1FX=_FyNyR3g@C@m6^>B?0$L~kdB1rm+O}gQzSrePM z*w-{WFWsNmEf#y0n~->2%QD{03y&Y+0nRTOvAKy{w*2H@;PQMlnOx=Z?2Onaf3SD# zmBn~+NjqxJBqWaZExTZPyNUG!%?77UZ+g(45i8c_Epik4!~~kvy(TVi_DZ3|cF;1f zX-mH|JqjnbiqARHctg&ayd{Mb=NFB^rB^1gQp^C8SthX#nkZZ*G3ZOI=T#v#r-oTn zF7b2U+!|(l`NYk>+}@^Yg~V2Ywi#*Do6WMtKmN8EUm@{I^JZr{UESU?!zrDut_a6| zVvU@EXALX}go0w6!gg zOnORUm0P-~d1n8kj5oc05oNS!gEH!6I3X&)D zYbHJui>tP8ZKSPia%*GLVL$vow7q>mR8<;3e(xO^xpx3j5djf_&_zQ<(;D6s@TH3b zhKYuWHXs%jwpdu`4l{${hOO;lz8u{}1=H3FTPL-bRN!P;H5DwJx*C72og^`!uPxa(Qcn`wIdh%-F{W53kEqosUcJu?F z@QeKr)FE8fFP*|G`lTO0cyYgU3TO69KZI~{zjO+ZlSgW`v+ACs+Ks?R3`(f>TG)>r znv6zFi)L+;#e5+xhowvrhmBaMjR;@TZ+jTbewGV1?oG3>k||=8Q0mRLO#z3b9boko zo*uy3rijyRwf#ugEbH<%_9L+h;qrdz6kgdceFMUI{n9BswqpT9v3@*o4${?o!> z;NB*#ly&#!MfL!o6A+O%2w_G3AzXnlugbrtMrlldICCdEbFaA8f9B*q!L#zbqu@UA zWj_8@r7bXV_UKAsZJdrKbK~CWbUoblO&7ReOso;$W{wsZmZi5pm32#2vXpqV&-6Xa z953R7Tp@iL$rA8#ycqQO^mE8hqkywPdy&1KzM=^?NSno-TDbu|Qb{dyhA;9=R`Mu< z?&*Vlco!eh@=(9^DjmkXGg4SU0%&-8d7toH4Ehqp(5M+DCeN;gGN()FhjUz?q**+L zSpX-@*vGa3hmeaAt%TdyIl}o=EluG|f8+6BIbFwm62VTt9>L=1`Q-PGoJ8?)UYP02 znvyVh!7MkERAvcI7N^Z$j=Cs=QCSY_9tIt1XWDd)=?d zPh=(%ORI51SzWUDJ`84#lBt+;ct6LUX(X_gt#%Zpg2zKub8ch0#hzHp)i-`JUe&*7aH9 zNB%RL`qJ`NvXl3VQz^|?7QgkMiIsd$KJ!H8o35leGSWqf_n&#QFLBBF-o!n##ofGr znQz(M0pqEGq3Ct7>@|NZBT6|*8#DsuB!TZVXF$bKUSeSSEXV*d^2gMQ?*m-=93 zGkYD2%@jjJXH}Ry8%UPinU1w!rWo!&>k!hXsBJ!b3fqt=KBc#GC0r}>b$HDY|LBcC zJO%d56Nd{t&z$q2(Y(l_7oZ}uE;|Yqh$fzgBKDB@hQ7=4Qn5 zn3Gcc*ttdGL!{^B;uCx`9W}Y)34yXbA~p#3xmdIrlM#Yul#eWCaT9c}>^$-QLBvcw zlDr6#0*sOe#-4K9(VQnv7vc{?K!B<4*$=oFP2y8{2f{vD7{cP77geU4aZnW~_mr_2 z1)|meerI35%vix%3qS|d=VfUB`-4rMk{4xez-Fj()IVJIUi6QbjJ5MJs7L4qfC=|! zI4sM=fjTI<8w$mFP#xO~Awg#Bcze0{tS((03{H+mx!JPrZW;{A%w=2p8R)!w422V& z5GHCk1mPs2+cy0ZN*7hSlg2S;5hl#BXIV!Pns7bKU4iaITdff9qRw3bBhsxEqQ5Za z0`qxNe3V!rz08-DJSmP3ntI;;F7|UEi>=YWD^;s8^*u-ZlNdPu_aEqM0^?y;SuD;H zMqgyD#i+&o73_MkI4`7j(?zZZziq}m{Oq_F;v&tF+3LAZxWFr^PaLSc|Y@5C5AGYMvv z;hIq{)Fci0*87<;H6UkT*OqLKB4+0Q9Q(fJ~F2@2bi{haE_`F-|xk*+6q(?id zE#jA0;VBCyizl%ZrY+70yv|EyVUBH9ag7iv6xxpY7u$~Un=MOU3N+ThI(qCW#E@Z zt%n&3i=yW->D+&v)juzWhnD3~#>Q7IcH=H(KY(w%RF-R8Ds$}m^B9z}FAJ*_=S-D@ zWv@}4#55*PWTwdzwlc|#NnoiQgYas?(G_vMs>^)6N{Qdag~f9m;W7gzj_s=yv3FL1 zcOz@9#ORY#*!4;=bXHjbJ021-Y6XSTBb9mlbJw>y*6b){EhKOC{irvM#_) zEz7|BNt0*XizZK~OQWUD@4;#B^b6gK*b8Xq5un%Zr=gC zUjtsJ0$UW|EebF_2oVK0J=;omF3e9W<* z0}nr@0dG-(i(V9iY#}p`)q0|_wkDgpesiQNz@ElMltZRAv6vYE?Xp;Ry0KnPGf zEjxcRk+I@$Q3n%15?hdgt*zQF|BgK1zGn$pgGXLlCiw`TSlS zZ42E&k}TyoY?VN4T$&yydyPC|GjbcoxIxBxs| zct+rP#130ba>Vqwspjc%$!PNA6mr_&Q}C0CxI~WQUdrQr8nH!Plw#+cqQ%lM+nTZB z61Ke~`J^hI&%n=@@+LT;(x&n=Xw#sIsQV<3+kjt{+kCFdZ9i9q_j8Hpy96M0*PN?L zsKI+X-ks;FT59=}?)_X$GtbLioEaVng~44I*{5NRY30dAs?JyVgx@3=EH9nED~v`S zpO$>9GS@XkmCfjeC&Kw!&fIOQ;liB;YgSp!18*SnW~!wVA_f_&>^z@zzMLzyr1=+H z()i6)Ja-w&I1ji=j2`=GXgPpAhiCOmF0KZ@Jul%)O@OPzx1|o?c?iFHydTBSiC+_b z&6~=(llZj)Pn$3P+GQ>@wvyMI+080(UVI_8_lBqL^rCIP5-j#;($=Ge^<+)9=j(#) z>vdtWFkvInvMCj~Q#mKfX=3(`qK!Ye^(Arms2$3R$t&np8kXjzO);`p&@s!ikZb(K z@Zw9U-kT9ZAA+_UIwH9>9pemZFd|P;4|jxJAKQ7Pb!_L3TVq}M zmO3RaQuwxmlYZ>nkKYFAN3=yHCf!O_wMh)Ol}+x55WbbYh8;#DZzg!KVu35)nytm} z*jUTuQhY<2H3QY;8X`GJ2HrBk&JRJu1<;t1g#|YdheqWCQ+D!ZHSQr;68LPic|ICh z2iWM8-}5uTZT!cP+_sNX(V=YIW^ty!#r{n&Hx>z#EQ@#` zt0>*h6&dW<=Nj~>h2uZPSc=`4$4|!OMqVf)*ftJq9@D+QKBkMSS6Q7+*&;^STB#Fl zS)V92Q`u|q_i8WxRAID}93H$k+d9Ba@5BHIZz(o&UXbU$OP!pM9j>2>xQ!EVn^9FB zcLqwN&-h`OOu@brs`1>(-AcTuuOm({*6M4FE`6)A^UdE#r*cwv+BnGA!4rYh38Y!B zRDGQ*Qhxw5GVkK`hg{|Q8dt4;kCWH$bLHt~QM@mfRh6jJ_eBHFB z^NEy%)8$+{#%>#i5!p=aJ-Dbq>#R+sJ^09u0Ae-+=N{L9S`{(N-6{?jH@EWoZKrGX z)y%$C47CkfsnO*NdLU@HW^}?CbU*}g3kj}iHJrC=x7F-=!J6eNv)r=y%UKXk(P%4< zerWWFF0K%b&INznZjS!uH}zvZf6C!fsySbeIj0JAh7m5;Zg@crCoibao&;=`$Nc2i zNdu8EJ`5jHX~*!mWG!GZ3}*4)T#rfgaJ=VFx46_Do|DuqMmwro%T<(p`5Rb>hNdQi zDuu!b=#l#^c4t&soO8Lgu*-h6sw>5(O7>&`{ zei!jvjkJ|`mK)8(ApZj~+Xi|o%Yf!ouCxmZptGFY4CI(H13Ljk2*1bgA{E{hQHjC; zlW(c$f`=30Z>#ZDP)ZS>M)3g@kG07*GdYch`#X4gX zg=gY@H|CcTyr(}|W9Oc1u+v--j9&nnJq&X}Ae9jxsV{M@wOHa)_07}T5zf;)jl8~o zV06YXH0l!24t`|1Fic@Lp*}YFWWrgwf4)GHwz?kB@V)_MFDA0_j*$B=wX z#6&_pizkOUppJUm8o`ZTFtJ^qx>HvIy7W*>XBzX8XjY9z+21F%+dVKe*o}XH?`aLk z8(m2m=C3>+lSe88jziB~QliI}W- zUf-VB;O??DeTPa&sjARc2vU5`U|Tsrg+QH%HF=^>Yw2XVI8X@UF%Aw8k$|h$;Nk$M z*vm0F5L~?iHw-Tt;2{lgG62iB?m*j=D=GOpqsimD9%}bV2t3~88RVxG7Y8&>suQ8q zM70xK6C5AGaq%e}kKuU~!_$dp6Z&GJhA#>D;uE2f5I$Pqm^=ZBc^r6T;5@40gegWt zdK5_GsGT7DRW)k4F2(+WZiXz}HIZOQmBP3uHR>pyP3mOGRhQpKt4YimX424;sK6B0 z3-HT)!kR_6?CE^KOL^Qa`)j(aqBM-ZRIbY|@_~rEUNnqD1U`7%Qp?@y-mfaE%{+IV z#qJanf(F(SLX*dU7SWGNeTh2?POE43o#I_1WRqv$cCC>r?7aS})<|LYRQ+Y<+$kp7 zusTt@h@7=ZLjxaW$hxNvVvK}=k50<`O|mAQ)SBR=>?L9m?!6rC--0$eq@m2VcuKRV zU5QoDgOc$p&ws!c*+#Gw*ys$}U2%s(+Y&$Xpfb#!%ckxULu@PhI#7rykK`%{5w(l) zFYYcNXa=GjV>|a_xunZAu6K_GvYyUYkSXvHoIbGzgC;fkWc(Q6=5v>H#fi(g=;yvr zW=Nj)K+sIJT6@IUM|!#}B6<0tPxjEBlQ#r6!p~e ze^O6QpMFC8ZuY}A+u zH216@^kdZZL+e?LCafQHt=cGwHP$9&5K>z-)~x&)MVdfNrKkm-Ii?oq-9p5mP<;=} zV$Is7E-IcpOd~L%oudJBfVJ<2fgR3qFN=Bq_Z=xI75YDRq_U=<4jT|jmH+RK93VpM zDANXYCPdHCz7F->hz@NUXQye%tMGqxXrb1jMQVo%6MH(6hE5`Dsl}+#pY4hK-@U85 zo(uxx^VA-u9x5L@dt3bM+1o5>4+mCCoWAyP&Wn0_V`Ngs!Mr3`7m^+XhYrR1-Ane; z?XOZ~z`w9H(QEXE4A8BTZJd4sCXbV<%e$_UCRAg2Qija`JA?>B&uIdrbN|l;h>luV zS&Ams{PK9kd~uS-tL){Y+I4nf^6VY2x>B6BiDYfN#KD43Ijh+#PG8|9Qiy{|jvLp) zjmXPq%rA59>BTA|3CpSTs7;7_f5y3d591DiKG4Is!a|jCPkFPfSH$6|{dl$YwpQaL zl~-G@s73HMdU+M1Rq==I<<-Y8u)0^Uf%RWPIgt7MSsXL)XY%;*be8gGafQOgCm@a* zv0CmGM^|GykKegk){9iRj&Kr3SASU?MfHdy;ReC}Hx~=%nY<7C^_T;$e@`GkmrOp9 zVB`au{4ZHBF=DDUZcqetlc|sr1*BIbnbE#>%mp+bv~$hIrL$`=7ql50+-FSg?!!I& zt1xvt)|Z&GX%14>h`ObFO&)GVqQ{2GS+Qa*ebKfnm_!#mUk2<=`8`((0_rsaitZpF zSCcB)+Cns=mzck}w;4&#Svq?UM%fY&bPmKQ3RlnMWY1OgG&`(g7Mn6js7!}~$8|;2 zR~cavaHhgYl*g6G!l6+hq**0|hm}g-j75Ue8OgN+rVWdP60AV#0efy^B$otnkkYd- zz(jA{mozoD8=8;<)mSZa>k%p7NotJJC5dP{DEt-* zH;%C!YD`miPCU>X8h2Yu=^PX^iK|$_kb_-^$5|K*1>$NK*RHHgJGj>94o?5nH|^Zm zt_ZAnbnYuyh&aD-{jdgMTa~As3&xnA*pcc%#C0r*_;nL@;j^BYQBrn#_JEjW&T-KC z@evY}`}R1QdvKYmPjkuTF7Ax1>pF`TYNZx}SSU#bp*_Tp+XmvLvKg)hbqi@+7{|G; zS#y&kR9j$!Fx#4w5COYg3as@h-01AIc6}?)zx;WnUVW%=WbzQerzRDxv7EP9KEnJ4MvYkuaEDN(1 zA{?l_XX0JiQdP~jL%vsb0d!q2YT+yB9g_Tddm4=4kyCx~*kG-Q?IjI zuVdTg$3hldC;ko_ynE`z2Zr)mM{||}kONsJbC)ui&wddHrYx*#zxWkj#!BD7US++b z`VDas|DY)eO}+*DE9YPXFe_ZXbT(I50l)7GZgO_Tc`H=4bd9-uA&>M`BLS829NvBL0i7&MiO)qm-!J|cvn%mMh)0|Elo{|MJD|i{5U=YOznHZv z@f#5D)h~V=3phySRwI5uU;MysmZHS(LA+1D_*1M{i9dvREMI%d9k_$lDDg)Tk7a6a zJT}~w_*TSYIocbay!A~gwjI&F{i6L?oDzQ%@qT^r{uh{;;xoJu@82(eKdVyW0}(&4 zUp(BDmG}t62lR{2WY?AWSi}$N7mwzDOAH^Mkz#Uxe@*S43^U#@U|+a~!WcjKos~CNIWImnIfED<=Zk4istWt&*PQa+c>AUxo>0kHVjy_61S_!=RJMgw@co+B7 z*apOHK)hE$EO?V|mk;)G_Vq(F28agSf#|A+XsCuL7U??k(t+4L`EH?#tK*u6E4L5V zsS76e&3Kdh>-}~smw~+OvBTosXQS;b{X?|8=j5dy~>i_7Q>gc z&j)3co`tbr1QcB2G4gWw&qioaMLp=WCS6Q0_KRF0Ie$5JCuci zMQ!?TkFol<#RPrEEm`;NDR%2^*iz23I0t-*)@$={JwYbcpwv9BQ0D$Jl-V8PoWb9c zYeNa8kzyrt2gk5>hj=$!e0}T1@Oy9EhVY5QmQAce;BWtl`rf!ggewJe2lm=_DARm} z>hg61XC}BR=5+alu+?3LLG1Sle#3@&KAHumgSId-$pOO&s7E zzTG*JyUbD&{X&JzB$kWFfx4SRm6{)eS;hSg4xT0Yy=lwLpg73Z_Np%w4xCA0aK>Ky z7hHQ%4HiiVqmNRIdoy#vRim`@b!aW$DjV|IxHgmf+7A5Y;+LsVY3HzCo>^paf7hd- z1QScyPrz(XCoU>7;hp!>wWOtHMb{$W4JP-u-5MKHJ7dJZdzdoyW%#koSmUFNV5Iw2 z?E;KWx@dA=?S{h}3cLC}YMo0&6Tym3y*G0+vrqCHIz;!avd?UCcisjdWxBxHll+Db z&~+{|M#9i$t`{fG>exYy0qljFPH+WqPq>I@A;LxEs(|+*yu&qMIK>y^9n~1V9PcG~ z$3lHLkM~mbK+g4gaq!^3ZY1(Cl9vMjReEPNi>Q-|nEi-o;7ghPkTfg==L{+7$VDRu z1rFfo4h;V0RmusUU+Ml`L=HD9p60pA^s4)Je9uYI6L7YHKvQwCf$xX|gd?k1@H_B1 z`s=N}jDJ;}E@a)m&a#Ym;Kb0J%!=QEds`_x`i>YXS?gQDFecA?$5{J2@NoRsLgw?X zIC5OODlZ``r>nG?JWcPR>w8@ZOrH0zs3cuGMfJuZ%XdXT_Udsl1k);OIxap=C$!>D zh(Y00-m~C^4_e|l@XkK()55tj@`4b@|!T_&xiJ^nbjLs8Wm-7qU!u$w#Rpxz`vA8t9;p{sXd;=41 zuz&_}SjdZZXdzGty`T^V5>||6ADJHqPb?&h*t#b{c6AjqH$Y38_dT;WKH$SzlyzSoCOD!84N)xfv#~`(_`lr2j7_M|mt`8B5}BX=o|d+p6(Mc(m+4v> z%qG)%@=f`9w;r0v4m63Qqpo!K@*K(o&uPQppUVgb!l~?5lekmJY+~EqgS!#5&ZhUo zPxYBMO`gG6Y`-rC1 zHp8*z@^)6#3~YlpvJK4`clH)`0MDskY=opJAarQCLlBIGCePFh5V|C7DDD8_4w*cu z<^95dNr^Oh{8qAn7NW3~#kIg8E~LlYa3_hkn7Kt9HZB!K^`NZ>+9KGgR?|>Khu@Lq zff%-@MVyX9K37}Bgt6OCqupm{6hH=+E7qG|$X3cSJ`jgTDz^4tNQM@mtA`yEzLOtd ztL1?@gsYs>I47Z|`3w~%^$vlnDaw%tCV#}-R1CgG4o0A zZ@c%~r*L8lp1oloiJ|%|*bJmAEa@XSKhi?#BXqj;D1@Q-bmTfT1E{9Ozk z@8Fe2!3G`;Oj&4jDf2$ar1L|hCK@Z|#>l#vbK)ygqWYCm;2&&8}R9AO1##5uy2Q>^_AB*xr5n7B6s#uvTrL%N47d^1i-6Xu>_ zw*af(g*Cv=?^(uKF@}}?U5sE6^ZmTWLK5p~Vt(!tKKF*nThpOaFgJ1Zv%~$ASlB+2 zEjcgVGti~%yruwbhO9gDA|_ICZ1^YF>@Kbnx^G3#G^wgIrpdDI>?(HkJlrupf^nRy zQ;rMw_X*Us&PV$?k=E;s+jkw0uH6XdESk_|-QUO;1vf|Z#r45?#q@(yb~lV^eQ^Y5 zVb}gH&YyEyF+M{LHOjh={ZuL6syJL?zjV9cj150`74Cw2rAh zW3~7ltZIwz(BZm|*C`nZ0Wx!JGh?uKRd?4`#wdxjU@EggIH(wcbYc&8V8P z?sP_3?9W~FbbRRYT>tQ*y8e`Pr)RJOZyCav*Jt9?gpc9jO-k2)wvk@73HRC1>PgXM zv9Q#-?|{ku(cwP*_Q3#?`;#fG<{x6v;9K+i#fKr@Pl+FUdYOvjL1^(GjQ~+u6sCSL zE`4wYi0V=o!yj>ujL*c6cecFK=;FUsHRWGx)A zGxG&8Eqor17d}{GeE&g6N-oJ*0394Grd$Fc9D%^OfD;kDFqdWB2j`VrF}8k=3G<`d zEcSEpkJ7ws4MzuS{ag&6+7q4^A?sRN!V0)B!YK=m7AOtA^bV=ZW$WPeFE|csVV{Q@ zmGE8``-K?Qi*sHa%R$(`7pD=!tAtg(>l+ls-D_Oh8=r!BI!hV=d>+LWUw3L5b0V+) z6w=%U3~e=^CAW)tq+`~!lX$eVo9*JKl4?+dABEj<=AyWh7e27FTlYw#1*?-){}Y27 zfF1u7XA9OQX1pve(YwwzTmq8n%i^1aEbEGxK+g?VNC;IhuP@bb%9ohT5w7_X9_zpn z_LVp*=tK^&7;%e{^LWapnM$3MR{9kQoo2_juf%(K!FtlsdR0tNUVQ%rXLwUsV z;-`Xb9+nv07io0U%GP3mmQNc2d*@-g=x*tWud?=BA2ScjjqZc};*~8gz*`W%yTe|8OL&d5XY)c{XW*u-zrUvdNWW1u3+1Kz=^20$Fb%g#5vLQHLjk zp>rQP7Hp(NkgR)al%?$BK--QF0&N$_?(o)7)iiqWMRo1{mbdzRv-_dOU}NIvun;Z% zAW+u5*{R`OMtEQc#`^Ki^R}Jmpa^;PP+DR;CnVb5p@f5}C^VXmn2^C3fCs7Vu;8am zd+8m|9kyNPQefMM?dIT0jLsSwneVtf2h`&a`+c=ln)hcAJ)hNjuAWHsv^F-Vjq({p z5lI$m7>K9}7+LJphyie;w^-H;FSYEtt2D8}+RA)?#4749nXL3jSX5tMxAiA@pIe}2 zs4gar`PR!U<|lDIZCo|u1MPbBOcyN$vkkSBDj?vCVlkDG8CneyoL(deT!4Ep3P9(gtW&%}b%7s$IW3TTPEL5r6;+nY zx_If0a1?=brDe>T-2zJmSDK~Hc{lJj3)1^~>s1BEW}S2i1I|(ECB4Q&Xn`P~@|gN; z7OR&Y70{oX_0qi$zI=_4k!KtHdJDfk0cT9zo+(5;HL()!W9_i7t0{=`3u3l#gb$z5B;NXELVE`+ShTdnS(COXG#zLz#1c1le_q zwGWVv+g_gE710idINDu#d3{#|dE%X;_vEgKR=i_VMfdVbHNKhNN2&1&{KBpXCt#F# zzkYa9)p)|Q`+GHB!84{0|LzM4p5bZ%gJ=X-hC|)t2CPb1+kG9kBXlyOD2)xTJ-F`z z=fAIv^Vzq9llC2>OI3ESz`(#DtzF0Lq7)?5u3+0lDeB(p%RN*3w01P!uKH{meD;y` z*%){|JA#3#_EOVHwwNlUvFpGQy1PTx)%Z~Uc#H`PHgt}sdTL}{^)ePANo$1N3t6>< zNd_XcNs^+3-F}X%5*kw4;fJ&G(6e@Uvj9J7^yux1iS(^EDxQHx+E+MmU!`^^&%CK-8c9yv4X*G~K$<{+E+@H?h3D+?! z@p_DNg!K@tQC=O9-~0%t=1CyrAdB{w76{vNn8jcEQp!H55}EDmC>kgQ@&3IL0kUq} z6h~En^a0-=s$j4b&I{XDvWg+nz2HQm86A-eb5Nl&*PI+e4T7Aj4m@JR~)elfcmD&gip3yT;|VUZ;bSJR7?FkHunOK%G=j9@du zq-TVxc*oH&>9{V`#x?w1ZHB~lY#7$ySI)IHq(Po-j*!Np@#=e;m^DW#wp`QR7Ecv5_-I;IWywj+7q8d>*32y44bt)5Rb8h!Tjr?3{G+s9(H?PXte zo~$^Fs4O_{3hzeO(;R2IXW51MSWAI21C(&h0${iHC=eMxpQBqLU^JRD7DI+|# zqwvYHVezM{Si$yD zOrGmIfDGF}&!w_6qe)m+-~tAzL8w^GEHRK(HZN8e0}d&l$y#I3nc3NnlVhagyxv-g zqaziLs=K8n!szVmglqFk63rY(c5AX1nmi|#EBg<2K3F|KYEN|pj)xc?T(%4Yq_RAc zD<-CdDra%DPLKwp2THUa$YmXIQj~vhxDYp1yvo8RO5aY!G`RdAl#G&<#GN#%2?>qz zR`Fn9l>wH>2xwDlZ9a`HT6g~&%1sSUx9!FyNg0!*@&3=;Zk@()>TdRLGFjy$Dcm+0 zy2Z2cgj3x$;bV<DdD+Xi{p9>zKBzgX6n``8#d^4^`%(pdZEi<>Hi+o7z=v6Dxio@DqTonqdf+@#yFy*L)adJ3XN7> zxOJuJgbQV+YD8h+p={x)_FhFkVlpHUL`07w-!z#RqKVy{42A%s1W%D>QM!2wcmN0H zom0?@`s~Xl_wMEF+`ZD5LRlDd-Y2~vta_DY7^PX#ito{5c4t^wE~_>|aIXwuM~%`X zsVui+>cAgmUGW8W%P2kRZ)>7nbuEW76J;x9CGpblgNn}3#6a2{HO`4hPg~-p6X#fP zf)qafNyRjWVHH97s6x})v7!}h&8;I(w9C3DX&2vz;u<|C+F3z@blg8D+E_8)M>z!6-JDz4PnP z(>jxT$0&3TEMk1eCakK%Eb1Cg78cRve4JJWtlRu%S~bv(5QGC|Ty|t9N&n!5!uc$2 zs+2#=c9JR-7KVdZCR=^{6Sn%seA^kNl4JfDSZ+|&TCg@54!mvn+L9eZAmIoOlfsh( zW9wGqdRr?yH&xmyJh{$MJWaw?%LPenTbeXS$X>^;rb(X*^Y%KLr%R)GVL=4DJ_CKe z={A#RN>2)N53~B2(wd-0Z;)^%=9h)JG6998#ATlv9rX4*ru0JjW0wFq0$Fjo*4NVc5(i5^cvI-)B~((Ir- zrEp_KH%9~{v{MaC>)Bxg?mdd16s`W8Cct~S(k6f;kn8onUgbc1CpDR`!tEM*bIeNIx}K+jBPmPOK|vlG{Ea`_&@uilvFd&p=PIJ_Ul z!N`?(?!&JR@%yy+1BhRUxN7`r5MQmu??F5oBo~AyTw__e(1jMXXG2(++!kB};FA@$ zLK*mA`h91A3YF4vzbn*wVe(MNBFL#G$#<9U(e95u_JZ3t@G{8Rxejz#8#`kmTacc

q<`qBh%;7ct4=7(brh|Y7VtvULDuw~G+J+K zqYDGr_2)nrX6e`p=}kcxdD+qaTghK93^6*cZ;-4yA*jPqTm?l~@Sf?Y-iWRzVBbyB zZ-s=A5;S4Ngx_&=;v^smr~8cWhipciul9b3oH=@Km%tPkU_15?C~3o594EI((f~m` z$j((uYlYjZSndufR3B|LzB($!Vc8)G-cdK_!tz0CP=Ios9Dj4J%!x*7kg~l`U>r;9 zSj}$f4U)iFFGB-?zG#10dfZF!#{SBm(K}ujanrl>c~Ivmk|y~-cs!P;VBZPH?}+?5{~C%rhrnlm3Z2@D98VtUqEg{yLET{j?*v4kL6l zeCN7r!`N+A4D4Sl;MaZ8Hi(BMZapXelgC~jNJJ;vi z<{lESEeQzTs~@~#!v_4%ed^pp#D4I+0uQf!B2smDS!(*Zvz>eJ`F^72VbGVlOtiD zgQ3kGaJydy|9%-NwG8B8*ynlZ4ru8IKd>MC1`VD(5Boe4-2vPC!3PjL?Ye@=V+lSQ z9#$!)?pw-kBSnx4Wa6WDEu&m*$+ygw$n%c+d*() zjN*Ui9=KP_qdEu*|LLTuMCLBg6cbEqKxHW-{O7Q;v=RREVy`cr`*hy_bP#k8>~WZh zG1|yMQ238}i3ab()6{`&l0FAP_vw)T=^*GHsBDsJt)f#L1cm>kD@5|&oY!#mIS9I2 zPno)Z7-QTz~z?$Ba?y-%q@3_N@&Fw!|Yl8s$2rj#j!)8aYZ%3Lye0Xi-8`RIqd0Aup^fC4+@nU|X~x`DU~)(A$9n`DOzzXz@Wn;TLxh{rq{%^$D?7W` z3N@4a)@Z5qf|}vG_vo6DAffdr%X-E)WSIN(2m+3efKH9pAg5L()2&0&q_pqWEA~IG zmb^0ql~p?}dWG*W#c;uN98E3#BkJfrXDfGWq*j=yI$PNfOH+mKv2ZyoJu|lDg5ohG z+$2vMtS4^n$4%;9)0|ME$q5S8$(!x*INg}9%x`1ydsAc`Z%e-o`mUDJ(4}UXTZ+{? z&Xx+_m9a_(6oKzn^rhvk(9+V`QKUWkopP%^@)bH^{*bv9*J$OBygXO{mkuc7(1LgJ zq4&cKO&+s#flwT8D47J9gYtk~ZhR&Xs}t>XF?HoAJ~uitLDBRy41hhurYG-=Ma z>6A`%5Ir(C|Fo7q5#=ifKo#>Ss_)M?c#PWW0et$>ZrB0ZWIBJm1gn1~caobZTbP)_0^w^`ZO0q**NGeKDIk-;pG8X>y0JWUcQ& z2Zu|OJA8hxOVd_tK&*nZL)Sa7V8Ep*>|JS&e#BXmdpPb7dsl*gQj*C%Vn5sbuJo%> z=`>u?4tKcA%)yo8^#T@WIQTutO~h;JKQVfF|ED2xBmpP(Tma2YnL` zAMQd) zJy`326~0^T%Ea{F4FC_Q8ONkF;mg~s@|cu3h6dyejQ|Lg-_QT$k{&2!9mk~5sDrNm zk)DAq*J6`9cnXU-4#n(&I)r7k;UU5u4*`J+7ohTRGMF&*f8aQSJb@tH~X7jl7za&AcsO^lc5;d->NO7TAcz=9hlV zs61D*TzX!CHr)sVJe-*hHDaj)6NOh3^yo{eEUAgY7Pg^@w08?jdQbW>sC_fZ_Y*Ep zbJ>!4rI;I6%R>7UN5=b-APDDLw|)d0 zy{*Hs=OY*)g-=^p{okbVUXW8F`}(vroO!oO%Y!~OYdFr8g-_QC|J2)2(JGDSgU%{5 z4=C%Gc*ez=PfLFk&XhO`K9gfrdfXkVIDCahBgZ$Q{yrCG7IKA(yv?)#L9aONQT z(CeX>v8of!V32=;E;}y*rtfno!kN{~_l)!j-;Can!Uun{?&ry$tYQIYA%Z?BBEowe zW)x>4FEtPObmg7}OMT*_etxA28HA5J*uJw;LR9M(SX{Gc$HHR{sG`pad7KedscUhe zk{R1_h7)jKKPL^nuU+}fl)VZO#uPa1uRn1$@hIohDxSES9D!p&xttfIs&}JkR}Jj= z;sEWRv#d{HVfpy`)@03~F8m!EFrP{z`Kzq%Q|XnUzm@!Vi~lW>75-iNW6(#6MfU{n zsVZC4!wMfQWWnd8U-5NBR_G)PD00;)6pe8mNQ7OpRdgLtC|amdwBD|4?UQ+*O#W=c zIZ)Jkq>rMreysT%C_2Edo&&>L>Kwl3B^{4&z(1t5K__GXo3B1RPdvAT=|7XQg%3+u z?q||Nk@}61o|`Dz+ZAOe1HGQ?(@Hqa9^eu&-JkgkqqL=yRkumAM%$V_8^9seykb-9 zkmQ)oKgY#j_eJik%!z?ryWO5C_m-`9yyv9rRV3zcS z^sxV5`+>iImepO7V%W(qq}Tl4&r zBdUh-!zit@`mHrzhrYZ9&OEfGsPFvg^)+sDVO8gOZc;;a}V_vs)LX31jGpFYbYXtzE03YqvedwO+aUQI7*H1;$z~2c^cctV_}y|0YhW zHEeN>EmV!qg+?RW@K4w`8jgX*<5(E@MbaGrRX%pX6~o&8DGk3**}qK;bH&nH91MGi z47o&jVk!0l*4lljQa0;nrLBOe3g*1vHDdX74g38$Dc1kJkk+X^Y~2F)@5^AKSXOzN z46$|W&}HcXuUOmtpRf~OO5tqO6=^L}kA5jdI$EwsEqu_4Utp}`=kJtD-+v`77mgP* z^Hu2wNP(Pdkey(qs%tO;9zUjz=#$r^H2=mcL@Ufr>K7Wq{v|y{!nW#PFbBc;DdykO zco=_-Eaz(}ZFCv=UItJG7l4#!lzL?uwf8348@Oc6WzMf5H()|)|6012Pk4J7wwCbe zF;7J5TCWYrq@2T^nqudsa&~*;ZhKtga{FXLmW)%QNr=mTkh3?gEi*c@u1i)NQ|)4{ zH)-Cm(@1m#e2wl!jsZvQlU_bT5DOUA^^ut7bQcXk(S>+%fp)hYhkOiA^L~2TDmL07jL{%OUa$`= z<(9_vu#jgCnEk`w67Rw)jOPR#C zB(vB-hVfLV+(BqOtC?8_8O9E_wSAMxMboK#!qKo6b*&#{SRw?yRHKY(-cxD$QxB4t zU{4P;KuE*Z7ib8ghA9k0Lj_eSgXy@-V^>PV;W%0NLkrsz1gb6e{2!cLZ-%QuXwje- z73|0JJQmANV25E`7G6xn_aqEp2{d~MHNVBNFU0T~AN0E-r9QQuiay}qiL7wAVKxC* zg{Y*Q9BxSCgVw8xNTjDpp<5wk{W5%e!Z2R@?vAA^u{060Xa~=cXVf9(1`lC_H!B`N zi0n$Y1<=5uCTV;X7FzJHezA;1Tc@oH zAYj_~IbQ3jRyx)~HLW;;F9=>wU8}o^67-F`xQIp@PMv_U5+jrjP3rB?jz|?@M3eyr zYH(;=G_k(Lkri#Q@`4>>dK9R(Z(&zQ8N&T-IJ3@GD_ACD1O<);`v5p)wBbL*=*$?S zHmo^@a$E3$&@qO`wM)~DdmoM=8gRfohps-u43otQ#$trMv695WzfJ?#@mc8|E z!|*|)NSCGMIC2U|ky-5B;E;#2S=QZ#pwNf0l5(%6&HR3FK7cD>b|oFoneOyE(*2RX zjU7@uV?K_dNWo7*X~FUKzbVsh^6vxBK^o6=|hZr7x}UjN?#O)^!0b7 z4@G(mD^}96m){L1uAk9A4CykfQPOjeKIV?}5TqBeRwW%ysa?14NY^91YU?;Ez8c9b zcO?5F8HdG`bSKic-;wTz^mELN^zcO;NMBCO(yw{(MN(^)ac`~<+dR%N0pBCbxd%Ox z8^%&58pcND%CcaC4TIM0LI;_alI(DPufcjAa?w~}pTVjo8ix7xkCG`W&`~tr@UbA| zmMVxw=VDvPg3Cq-5#M?zqC_X{qS`b58(Ef$ta+m0OX-~sUruoIPBW|+c4PMB@?%NbYsIa)0bxkqM2{kL$N_Yq-VHp^x zSU7Q25i;O7-MxmiQ1eDwDk44Qj`Visyw@;2a*DE&EWil`>=*$gtPjPKU|D!3l||nN zk+=j0NbUozOK@+*s?+SyeTFAPm!JbZ8#G$^K3bO?Wl2Vi+$Aln*ocl^(uPJV#_j4} z7$+P_A1q7)Wuau9qsC|$%#UBZP9dV~;`m+~cL8|mBLPqqVrg+m8MBw-n?n3z)IZ)3 zq<;im`Sfzu6_0Lt`YdZrFeC_1!tE>3aIf%)oy|xzjGglcRI;ZAX}wg0u2v4mCAL%V zJaQR>>q<`?!nY7sjx5mJlDOOKMH@$ma}kFnHkf_b(L}>;!5qlUNru-3FE4{Ol0sWU zY6qENZAnH0nL$@^Jj+NnM5R#~-Mmr;&7DdaUCON`G?(_3(RG2!NREKO-K|cHy=5Lq zHvC9s)=f27Cp|{`I?if%PC`M|uG1)p-h@z9g9gfJS=S6 z%PP`=x8{bUKHUK2ap!*4Wiq_4H*ZT!;W^ed%dkc;N3t22=y^vbE6Ox15LPW?O_?Be z4bN_78uA76HWhBkMs{Wn;I_|XU2_0u#?9rka3rSq0mI|M;`OZU0mH-ozdh~Zy)`up zY%wFt@OxqVS#~DN@Q9ysu>nnp#--+VmNFL&vFIQ>G#5Dk1n`C?^$6o@cmwE>@mvid{?A zC>vO=we~`48{^Wv2q)TvI=6G`^aQNYiaK{CCQul<&7{*)*T|=LuF2}0cK4djRU&y*@KA+AE94h81AQX;Ukz!gt?1Z@I!`%@v8GVK-vlX z^a(BuzX1G#TSs#EZh@kn>G6(6fHv-vgZ3_ySzL}G!9TCm(sN5lci|OQinPIbmDn`v zyZxlQa6dbM__RFQFvT)VyH%vSa1}{ni1I)%qd+6AY9t?Q@^p%(ZqrKpE=>%8}c*fVZ&JeeC+ml+$6hA-H&3esKmu( zSNz~6*@QUkxhrwT?22#Pw9|*U#akB{MvlRLR{C76MC?b-S!n8(Z==M)%1Q<$QfYu5 z%H%~Dr_0c9%JVSWw+MR7I(!?(F!CO7B&^sZ^Kdl>aU-x4DoYjmEGKpx$)O$dQn6(R z^z-9)ms;A`*jz)3kd@Agat+~w^Rv2f<#$=lus4XWpyZaa*u{pCd?!1aYls}#f?cQA z@bz0BULQQJKq&8bDp7dgh=wEQmvJm+#fuI1gq*Q2BJ{@d)rieEOITck|oXWV2zx zq|A*eFTtJWj|$odY6OxZ$_bEas84DbJ6W0#BB^^6`9jN+?YmIiMedC473ljlyy8x5 z^8E8f7Mq8mzkVId$TQ3e!f6t?=A=|}<_^Ox#l!;_eLLHiXIR^t##eS2%zbGo`Gynx z_N_||ZwSvvvI9#EkA|kTQ>TI&Y?7qq!EY>Sb7VKZw%!oO;tDV+&p6033Jk-CX34^g zS^`6odNfLyQO+z#nuyKR8FWU6l2T}dAl$P-8=S z%)Vgu33eY0}T^W+(0 zmh-3~eC%tZ5^?qeE{DD##@O=(T*@o+ufErVL*`!}!D=2gM9qGFkQRq4AvByCwI~O7 zCcHM+`H=M}m6g=qrudCH@3YoBpS3zsW}Nverw8XqV}N@j^L-5c`szv+t32nj4CRTh zTq(~%Yy&;_-C%Xf^E5k&XVAWbgnL>|n=SDN>rJgLleZQcqN4V##&K0Ist%EejUUbl zdpp@4m4mPRzJ+W?q2V5C%ykQYxiQzl6<%x1b%R(_p<(>keJww4OdP@G_mLy4eww+B zo0ft~cD-AQ8M>H-EjP@{|8u?yHb@BakA4UCaF~XIYepfhe9zcc|5iq z0d#X+HNnaJD@Xd31=~wmw#@&zTq(=h#*tpFl+&~valC>B zo?FMV9!InNIg=GXZWwPPYG2t%7_7ZrZ!gC1n*l0gHR@t)&;PR&6vn9(?rl+O(A$nG z^#r4(zxuNp>{M!SNUg!%^qP*Xi>x~;dS|GT0VRJ8K{zoNEPeHD6nZf`~5Yt*l%FUSA9rk{lL)KsnLCnDSP zq~X4h8-4ZKeYW3w3)L~44gR$uIA}Kwi+)m)hDz=CEalgRNl(_UqfCkm5sq*meii7@ zDR&qz;bKg?irpYs@)N$Gd)QxH}!4UiPX+GdQ_+oqfnJb$aazrRtmDfmO>_ znmng7)i57z^?nYdoyPS;#fE$RpBmLy|625Iu_0=3QO`)>={kOppUJKkLkrr-f>#DO2Eu4OFeDZ^N4S3Cw$F|`QW0GK&tMq(`tq6Cwt;8Y*{&ffcIC=R>&%Hd#H zn4-){2$Pdiv9@qXQkSRqw6mK}q4!r(2e@`%D-Dh$u4Ay)U}*p~1WT)@VPS}$$;|iR z^`0s0>N8NmCcVl6 zpEb-GKXKu6_@XwQ`~oLMla2s|buSS~?~3~A^4wDEG%=P{J&RRo+-cVFtYNq~R9&UV z?Pmd{hVZC3}aXs?#PW; zBdGU-kaY`uuc+L6my%IQ2UK~?XEj;@&0o11isD|!q19MT30Tav{RZK=j{lFduMdc- z%KJa}G9WN_5DgI!aX>U6L^O1VHy!b%(b2>f3rlSTG*DD5O|*fz2)fu}jfoyqRD9b< zQ+u!{!%A&X>#QVI z9F%!x4>r_gS^HPS@~bTY={<}$lxUywD@vjJ!X|+kQP~O}zec+=E1}W4_pw5`5BPU5 zW5h6ULwq!veo3wY7J3Uhz;Is?kv@ZF55KeAX{=l8@X=AK*5QyNo$AbL-k}?Ke5p2M z!O&*+dtRxNX*SJ{)Nh)3Hqs3M0rbt>k*26;nZzMO3O%S}>-uWS5&1u!{G$}8k zsd(q!Lh`|tBxYL(2$P!G;>3D3JMn6^k=K@LzY-&N^NKR?mj++w=gPojh`P@c)@rwi zQSP+R@2ZH#|W^Q^FM|vnElK(3W(kVtxfNap#VZo|?!oYS_ntAS3 zZErY4t9~6U5bJB&cz*X)ZII&7#pJ$O$+FvV3o0mgWCO(v2K))E5Tb_y$9N##gSd6Q zI=Jf&Wv}mfhYFwhAMat+xSxfE+{ZSPX^YYJB2HDwU`3gLI9T94{~mw}ix&s|hDUQ_ z1sFhgj`Ok#Z8i*+TJUPiCLL?R-0^s);h97LV;=;+K)aypWdZL5*G)rq_HyJ|<-YDy z9#Ys2f>RI0FAcVyo3WX#x*4Ey+1dLD3sCpE9G7$qh%CwO?&9zPzsCZ&xs!AdA@oOR zl@?aIV#ox3_%-d4zD1ct>!dQ7wHp256F&{6g|CA-eQt1Sg~=$dn&g$ zv;n;0_0C0l6l;Yk3FS?%Yj=u4%^WHjG2*~${IFd+bZ$bU9H{J^+3L;-o}=s>h})oJ za;DE^&N23wyO<3BOW-&vd$z1hI7Xo=y%{+ z-iq(O{Z1-Iw>w?eR1MGcP1>PhIQ_+-6+mo4atT}niTx9)k51h{rR{~c1U*v6-*xmh)acQ$Q!Y^?&v*>+D_GDitmcdx?(^fapo!Q%qNI_f%N3G9EDqy9Gw$H?@6a~^z=R1 zCnrAXY7U}Oa_y3se$BQaP$N*!E~AQt`(1#ZRunxe-U}VHS%+-po=cU@f+ti8QPL$ z*%eC=nry?Z^&9M9AvhT5L0>EMDTBl-vUXgbbtYl;WPWy=HX|3D)M<+*MTQBA3KW-a==4_UTBI*SaqH2w}YNv^$DM_T|07g-VUT~ z{FS^$q%TAJ25a_r0kCm3x-S|PNQVc59$&2uTp+!NZ}Akh3EyH#dCnyE@uXRH&#*UP&twOHB|9er-|~6_i6XiI zaCD|6N95!rPtK9M-m`M5lh@}Q=ZC8yPxHqH*a7CZe;&_Neh2b>^xGR7WC!Rw->qP6 zC2-5#F&|O2b1o^i!J_YceqyI~^i%D-;W>z~Q>6Sg^Cl99Y$~y1 zK`qTsFn1)8?{!EjJrB!7ErDox1_Z4_AOiADqTe)hQqibMIxWjdH)VU>gk9R{o;Xq} z_i11An-AYuoo#yDsf*vQ{eu8^DvtHgPHFrDSo?nS&voZu;qM;A!R|Nza#xzragY}t z!tD+I=V}jWL%inam^+4D;0=dx<_Q~deopA@L1GCTPXL>=20h6`Po%@zdxBPQ%_%zb z5-ciiZspQjP?Y$&AD{gegcI|tyIc8bPTg62Q~GugeG979aseSxYL7xYKn(@l-~nG` zMC&yk)y8uD2U<-$wT#o%(Rpf_gnu>sGOdTq2!U4K2Hypg+$TjQz&S+=BA#oFVHf0- z*$cc$Vojb=oR)UGxx>>F4z{%+wgo}v4$XD5^M_#N2+m#*Wp@4;Zg$?O$FZycmU=8N zNWk&kZG+X}cd^G2O*UA#NI#T61^IC~>*V13?e3AEOsdrUHbAbsfeAz(^eC{bM**S% ze$hZyJo5M8-TNs<=5(~+abo!1I^x=L$Sua6ccwbG`fdES`^%%eEkm+1ci(%X~*WT|n^b1IM&up`W-O z;z*XM1lgltdlZK8))9}@V35>s&AZw+6v8PQA;1s6i(_LeZ+chzHr;9~>$Lx(ZxzS2 zSwoBS>2`4YG>f|ZAQ$(@%%cDW@bg^$w&#HgvG>6$$m9XFe6}<8BkXuFMJPs|Cw?8@_X8_q-VlYnv9BTS}+3x$jOeQm`UUh z66L|4bbm|5K?^f|`mTO^`X-NmAL#n&3-IJizejoQ`?zd9J*|s?LLbZ>7w0QPjPU&` z>IdFu@&oVV8vUyqqE7Px$SPe4Ef&@()7%l#%=IU5c29@G>j~`HqI7e|h?CrM0@C;C zm&_dl^LTus6v=B&Xtjbjw?Cm9Fbd{Aq0@l5P<%i=erMyiyI0CZ;uF=pMrc*dYdStr z%xePsw*JDp#!Ibo7^)obxx32AYLy{mO3`(jGfq4f@ zDtQMqxyzIbyuUKc8d6>yQ^GHOs2#c>ZYI8Gy1y%e2+9MWL9@-S1@j2t>7DWrWoC9| zMdNw4JHN^haG8!g+?P*}sC{Xvr?TdbPj?WtK1pmTfkA*aHi4WP%IJ|vxYa^1hEoVP zR}Hg!Xpq)==~vPKrvjXyht>lKZ``7479`zRE6>p|>^Z@;bi`$VZo^z)u$A$$MHT!fX zJ!6nWB$EFWMnSv`X=iHqiPJzw)x7PrHVno~1e~qRJF-FawYpCo5>fR`M;sxg8n1>3 z-{n1?3+kqx(LUX)@3m1W1g^w00>9Nz_Ch6p=Z`otn^thmr>c&j{s(O$-|(q6I^-LH zX5Kz%RFiBQ)zXQwO~ThVdBdl;e}DZBkJn%o2tpCJnk@1Pi;64lmuo;EArBNzy%$U=d}rr7LU9N?E`TP$ zZ~Fx-4Ss|Eq|NeMl7lY8>(vX`XHclZ2Q2c|UatlmuldM8cSt1mY*RSzwi$)_{x3=P`8 z8o#ba;FtUJK6ROww14#&Mr4sk((@47>^k^Gl31coy7@H2B6(1{ZO~X?YIJed${P7Mi z{93za^pbdYngbJTx2=o*0uFA_**~qdu2MoZBs_CE$Y9-Z=L;G)iCGiZ&zE@oH&8D4 zR6!XunKaqTgyw#ujlhJuE6tEh!bcZ*)!(to|10q0f5%NQw~0Idt{oZn$3%5wsqXiP zPNhnyGOCDAy{4Vp_mhE&4;s*|gfUFQCpv!Ons$xfl6~$@-!%zm2lA=cwF|uRB&7q# zuWPRgUU{KPB{es&>>u6aO*gc!jXrgh6t~Euq4o0Ph1LZJG0KnnAx0Kq4ZRW$M>su% zkYLXd@qH~&m#{U`_B@kkJxs)NvJuq4X(5fA3J2k^rGpWEp zbRG^B+XAp=fqkn4Hr*tg8fB|l_p9G*CqFL0_kNU@%5LAyrgxUdxQUyt9Eyawuq`|d zHGW?jvX>wzJV7b}(1}@u^~-s`TiSKOUNk>NA>#`Zv*dl{hnNT=+*BjV`}jMzpn{Ya z&!fHvhx^20Zv7ri#Sgaf^xHU$KA6F)ZbQmFwVgX}15LfZj0d#=BffW$=e8j|FM*$L z18XgB0-t&Z<$#iaDW4UOcW~B*v^EOt#oh(%y_Z^-e^)zL@bpSvQxe51?`gOAE^)YvSMr2^X}|F6dOu(i-k!mO zenfxY&Eu9IL3*h`&E+4_m!nsBP15=`?!f5_Y7AuSZ&oWt`yq!_U@fmeA*qrLK)6i~S2Ar*^%@Z=d9 z=_zslQC{mQCGbX#v|8LR@JvtXX>s2{O57>#ThG(Iq> zQr?po;oF4;+}j7u?ccyte543*p`Bas>$MQ4#{Lps?ju1Uj(e7m6c@74fwW=nS?gKH z0XWK(Ld5+8x#Www_Riu)Ukqi}D&FKPO%Znu2(8nElyiJm_ zMEKf79V7T!os=q8Z>ATp@^#W0v3eXY^ux+*hjOMLdbjWzpU_)+EoNaGW<;-ClU(;^ zp*JK%4W*V7F=J@Gy|Z=h?2S=wJIaInr8sesH#hl9qs2v`T=qu~7A5c+f6U-EPkxrZ zLrwCo^1Gi$_L1U-<~3lnHO2qj_{GzIhwY_MJ<2VSQD#zYE7!makyqRr&JXmFUK6Xr zxuGvc#ZU6;zS0trPvg=f(%0ga#dWQZNKXlY5EGpwRWF=oKf}5MfNc^skK!5qq$IKO zAh-7exK*y;*ZN6g#L7|JVv-)?(*vd6;vy5b1WH3A77<5N*{&wmJD)~PTV1&~q%E3l zpN@0*Kp^02Q4Vhn1bi`$AhGI11qE5%%~o~fgzOzOGzR2 z`|4sYf=oeEUF0#If-EhggP1?J8l+Hu zEd=2G`evRmK$_(HdaAp&3SKq<6ZYDEZVi%=?z!t2FoBdH~jMtivhL^froAWV(cOI4gBCeT1`#Xg1 ziIM`uHGTN;C@Cqd#!x(wM%BYS5-~ z8#Dlf3~7sMxdY#Q7dbkigEt|cXiMb!$E2jdMU807+5;0|A&aqQk4aC5ENa0w|74kY z^!TpFcVL6Zq)CB`V4Cuvw#PSMvEqR|B^LGOYw*p|;~Q{u(FI-+i?;KF`1x4u-~4#q z9xJ^qE^6S1he@LY^C2~L-tAEaZCU5>_FY&fXVZ-L9Zy63Om2cq* z!=<6(>JIvrCFYlL$8hZ5{N?=Ga4cYcC69{7_9?o>t?^P!+-gAy^0kvCD4?gzQ$EZf zehNj~p)#;6`P8&73&D7-P?3(OHV|}T1lm}&p2v@n-U@u>J@*w=*&ym%V}slsA${Su z^46weaB+(n`oFT7Umhtv)+ZB9c~@zDGb!uF2yDiH$5Gu%AnV7aZQ=@Kdt4gr*Np{C z!pnD3tSo{jrLiw7POxoH%0zoy>~x&%akU0 z<<}~Q)!|Xnnvmt|Aq0p7lLOsZUW8{op0Ui!mvPf*?Dg(8yD`s8D|o@Gr|nJtuTN_S^(1Ei9kTFlR?7zG(zUwY+f}U~e`M+>?OO#rt^0lUU5fPv%E`&7nlbM&Etj)>8hAn#6xG|fbG7A z*X7TYUiA1?u%5A*-_68|&+w^>pCu&=LJiMD>@5L<&I>~uXI_0ZA(`M$i zvw=;4K1fIX3J4dNrJ95%!|4>mHC&;*Xn=IO8PXOzl{(61V>3>Jg7O?`ApdB#)bHOa zn6~5ptiXE?RiL8^CW%ja^5t`+vBNTP&BUD}eHyJQ=AstAf?<~@$oVG|p|mJbx+S~p zo=KRN$eZR!F--A<0xx}GF0B`S|=^iaW_ zHd8(Ar^0GyE(jXaTIj?BfN%}HG*=q)6qHqg%8ja`x|c&NJ$JjgJ?S%-XAnUpxP)b{ zUDy*n6xr$BxPwUzgFJ&=O+fX(H_^t*8S6m)FzCkTJTJv%O`iyT#!zAyDooH_!~~tL zxJ6QJ;5s&+K^th>yR)2HuV6wsN#()`DKs8+9Olm-o;ULle)oBt(h6(Bvwn>#NpBs* zMuJTO>4HUyu}!&!^1Tp1ZZnO=)zlsY-gBAD(H2C4kK1FvS$+G|Uss!ish;#5-V?9g zwtbUyd*@%1C?Wwx5x_SXqeAY6{3gMCMNMy^^gdLEzB$ssmJ!VLT@ecevl1fQ@hBQ| z8ojCDel;Y)IePvQ9r~zyU{kho|9MhiplKuI>kTple;<^%j;s8VNeOi+^CSqQYIsGK z^k0DggluVUC;V4sOFwiz+jFEdK8e7E-sT5=;UQ(d^oH$;ttMf@TBV!l1#GUHl!(>B z6L-jU5?N8-c6mo)>1HDjmR>d}OHl2$Q-~n%TZpEJVFC=wAN~f}6O`qsoH7NXY;=F8 zx}bc4nB9XJ;u5KaW%}sUGyC+$f387;1~nb}Z1x2>L5eK=zycsKV{l#j0x3)&7H?3l zlx9mig40uPaKOEr1-~-U3~4usuT*@EcvcgN$fJV$d71KDwwKc9D|yuCS%?xi1ogO- zdWhj?VUUKU?Zz)o=CsK@>KoRhzHr-buE2ZmNuiQ5*uH)kKir;M;CVTXLnVm3Gru$M|??7e}HGn+>aAIRw)Y z(r?57#grx&Gdokq6;Fbs{$-et*8m$dLF1nEADyYuON~m~g-g{w6i^@RJaM5kacF51 zA~8h5&-!E+;G#9f8x4%Te)|f0k-(Z}9q(YsFO)_OU2^yIX}CJxjcA)cG7+=8yLD_! zBrPfVmbl%~>j#rC<`#D@#Mz#9pW7Enk0x%$I3SzBpSqZsld&7r1sFR@m2MwLGe*U< z+i5&N&$p20OWw9fis+XLRZ(?wyf3(5odnBFA(;gXA=ms0h<28V#arAz${ zO)MvItbakG(W3<{^AwQNBlv-pQdoEX0OT)J^N%V}^Rx5a`S0K4Z7ZcE5lbU!+OaIb zG}Y*`FNV_AIkjeIB0NGBN@-rnw{QqKczTsClBeWLeMb(tqZUk#PR6*gHFH4ho-;ca z`rtPQ@404Y-fldT_dsl0pJ{b+zVxl)iq)CqBk$6O{zq4=&KW0p#S$sZuZJsE=ZuZ~ zIMUQ`<=x_b=Zty0MM$aS8 zrtjtll=O!kpE}c*@ykm3JILSd;MAEuj(ZnSyC;y|?Z?!a4i=M={;>bqkWIZoOdIX$+I!AB7s@J4g*uOggb&f80C>FW%$$oB@lh0*iXI8}bGqUN)j74Sb0ScT5!F&O^;|z>w@25-^_#&!g z*?+RSS05kYeg{>yLJI8rc)Z(a?&0zwKf?H-r_{XnO||^UiwZN}qoemZ^4B>aSm|u4 z9v(X_=&;e{qCPl$O0V&RElAi;LB|82gcG~p zF^E}kkmb`srXFJd!9lAqN|`(~vlitR%K~eKL;x)O9?^A#c-+@vh;C2Q_TyIy!Gax$ z`@|~rd0!q+$M5L%I&e6;VmF&zy@n`mMTL<%fDKNY5%2R7^=7Xj{ zQN(}5FRhkd5IT5`4fnN%SEOG2`B%V^*n;?t?iASEBL->L=jm2SD*|d~TX9d@1ucFn z?zeHDyW4?<4J%iN6L(R~Q@viv6Bakwokv0*yE@dkAthtjISNh9twqvrg@e4INQ#IV zw%?tVoTk2`W*xSXAfz*UauW$3K|O~SgBm-auxai z%g!38!KcK%iAsxNEco>{Tv9iO(@-P49{XJB)Hxf(60i5+dRdAHd2FV;K60O0qxR~t zaWd``TS~zFC||(~W$<3gqp25RA=HJKqwXU9C{nE!iP^!OGC;Q!U{QknrC^~Tf1r~8 zVbFNc?!&7~q@iii-6}tdE|YJxx~U#bRhaf2zN9=(bd493co9xZ+wEQTIe1qUqK|RS z8fnRxX=lOWUJe)s1=735u$rAW36G64toA3VrILpC5z56sMDK48@y}OOV85dHz5f`+ zYuAAD7ITMRUW1$DP|!{E`{*pLFQxbWd_pO%Yw$N|Ed?_Xx@AqJ((?$VY%Ie}M}EXB z%fPdY#F4#LS|Bd1;I(U|z%=-Cb!G%3j&!<=X53p)kblB3_QSuc^S2%Hv+Nvw@BC)i zzw{ge{c7aXFgiU| z)+0c9tRv1@`@6rB9v5`GRRO;zbn2#0=EidDtwx?xj&aT$$ScaF0X~slR6vhJZNg>!tC+b#8oBO74>is4yv+cOj$m^f;xCfo-URbta>0Mwy%>Hv7nC z=XHqS(2Nh93w3}1oEpqqUd5DnbLsckU-#%^h;J{js5^4ZPV+K8_4nBQymJTK3u(}} zD)FhtoL3nfq)OkRlmnB*UB>gvUz7pY4Nir6uf_y#gUU(`f;zKNp1fhB6zDap5re+Z zTQ^ECMr_q#j&rDE-TSVGD_Z9h^SS(n^rTmDI!yen{L&jzHDA6-`i+o4fqR1oI48~| zUaHwSfjmZIRVN-)r)9!4-n2>TFI-mj+oVb$@PG!gqeHl%O6d{7pFFM(;JYd%Zvn!V zFTMNq76PoYN2i$$NT~Cb(ttkgpv*3-B*fBqvopZS3-WXWc(2V;@{@sz+*DOO4Qy7= zgMJ6;1aXXoMac6|g9b>EF$ZIq4q&Ec!Rg|?*W;Gz#!7@)$^tWl7`o;z`usK zeS>|vLuF@eksgOyrUAD^HB`0`c*IR{TI4yH9zYW47%L!241){mXd@KXbf2c%Sjs& z&tCQ{-wFV+n!aXWnUc1~x199yQf1~(dE_+Taw|fbTBkk& zeLfACC4Iq9=vTqz|AC5fN)>Pzo~xv|z<&KeEp-~L5vNZn%gg)iEUj5BQWM>6GqjK7jo)Lg?xjN!2v=etYA+tjUyD!Wd{qn^#hRj zGt<<+0{A(c9(C(gOHAvH+^AdL@lkN!6XkTY*c*1U9B0jCyTd~$Xn>cJThT10ey_0n zVhPK<7|v#2M2yRZW|n>tQHEN5b7O8DNsmH4%S8~lMSJeXIoU#gm)uTHI`oef?YS0b z6)(k+*A6gFE3D#qnu?L`+WN;gH`66MJth38v{{hL*kMQ!L2sJKCv8|G$O_ z411SIuU0G{h1em@6HPMU-QC7Rov|6NyqRG*`KC!RYyr%deFWJTu}`AuxgEp^IVpygObXFjCcuKeGXysPU` z$-y3#_`BA%VBH?TOT&ZN#2NyI@cw`{lES_6ZKIndU3cMvyM62#m_4XAAGLH%RuS+^ zRq{?-@8w-~70w|O-Iz(WzYOcWT;ADxxsn+b8M0qG0M16Y9fosAC&xjx#YBFy(>qwk zueviK6tUoTmi^K@W~byfm3Rqp3D^Yp(il^oQ!`vchWFIW%RwJXN8HbPJnwctPr&nL z_j4|u*PETaj^OVgC@PbZ4s>9^fojNJUS@Xc;RSAoG&uMYvV`MunXY6}#<9G@?2Jt1 zxjS%aSYCtYesr(IGx|CB7C){$gOVByH{-Z(PC)6|JxVv=OQ)r(zdVS|&Sema;n(c+ zT7}N2qweku4(LIjbN`*VjtGa5ryuIm_o%N0^^M?D@!f0rT|E2n<@CHlV|GR~^J?We z0MGC7vv`hM5ryZC?vdRHVMUmmxw_X!BV7ekLPDflvuXYQg_GVmPC zW#u`??1T~X0p+;>&rnj@B|R!sst0||U9FFo!sqD42f=88$Ja;!Ib**82~?~F&M5c9 z(kfgALvb(2eSUY3-rdh#F+&W+9td^uyD!ym%JT(0D>ecKa4}76ziMeOc=vI?&sVr5 zq2B%vb4z+~n~X;WZ5C zq?HWGBaFR%s`7vq#{}k2Cw1r4L-V&`&1t+t7r{OKdc}z_o!4LEyvE5+yI&6EzI!F3 z=<^Yux)`Tf-FR8|N`q{9awvkKp#Tu=W#v$=!9ne0IZ4f|AZZOG6F4t%P+O8f zB%$;BsMCs+guQmF2ktDVv(+(P$hGC+)R^*Fp(9&Z?ieiOLn>l;qnV|UpMp){Y=RRO z+$O=hL)}1u3JtF>Uc0xD`0r$aYZ83>@PvKRZ^CydK8MhriM=*i(W0q#WuU)=zNo)# zykegeY8zV(Ni-{4M!ipI0>X2EQv|4Sq^S-{3^$hggL*7O9@V^wm92m*MNV<3CJ%<{ zUipTPSCm_BkhVCMf&C8kxEOsmRD0wS7RUE0m{O5S3Bkm5gDk`%-52kRRVhOg8<~i; zHL=p0w6@d{%8br{Emzt?oip6XkkpQpUg>UJTR@GXff^F#pz`$q@x$`dzvPj5TnF$q zaead~9DRH)d57X;Y3re*YVRi1AW4khCJnI3au~CylO@2Mfn}CHU{l?b=bi0hBGP8} zc-P=Py~jIDCJ=~4ooveQPe=K$9peglfO{Ur7g0CvyFRI5Hs+CH8LucD%if19_IWIm z?maXW^=pdL^O?*_OuY*L#oPK z!`zMjN=8e=SD&B|&tT%oLNV$PZqJIcTjb7CzNnI*EJmq)IBH=By@Cii#KL*IRR<&zia(5VCs@W+-xv3smbL1i=7D444^ z(5|PFC4)g82~4icbUEe8YLIeSWX7JPn7mXa(|Exjq<%J7?v7jI+fIqUwit5nE=%X2 z&SQ$`HJis7@S>kyM!yD`;5_dW7@fCGpTG3E!+qfkK#^;YdY zVh>}QiBLRqwX_u-OHf9jTqf4TckE#)(x!G{{n}0{ZVbZ~Rp-LP5pR`me*;gmELV~I zkA0naoJoUmMD?2i$<{ahOHaI+;L&e2YBQ<**OJt zZl7QyZ(CbX7gK^FDOT=-hhBU9!S20bK zOWQi%T^5HOK4>$~94x(y%Se#25afx7{jP&R2`I}}=!Us=Y5=eZuT4;%U<*oIj^lR6 z7$M&=7pF%(3z+FU;bP(jBWz@rr^&S=yzR`kYR52H>{_~FhvP$qi#b~c8-cjkApc00j8 zu60IrHgoEeZO?XYh;`R(+myRplY9C+$5MlZ`_WQRPa#$h}Y zp?U@yt9P)hmt>ap6mwt+l;v=-%ZQ58V1MAaY|k3O99fmj0giu}tLB_N>ljpR5}BNY zJz|4GTnep=qFce%<+<0zy)0rVHdo}CzYFfog?LjQ0$u0m&^^$-WVKkboQt+A|13<# zH(I9TxdI4JRsfX=${X;E1s0NX#el>Jf%tBcZ88FoTl{TFj>+IF;)5g4J*Cm;)uW$6 zk6Ad-`aCEEmfZ}_kOo{MWyN2HGdV3jbn9&(t_YNH0LT@~sSXV1d`V%;6S z>zE6#6trw(zzvYk!DQM7pADu>h0Yp>of<=!zxR4(DvtVnp`)0^J9Y|@-Fae0b&vcw zMxOnp?Hi1|h7c*UhR$K3^*e?9`ne!`#O&*<(n;fd@a*jaaNl!$HCR{X+tj8tfEO>4lE zXDxHg6`7-0RQA2{ZH(Y_f1By9+$ZVBPT(yYX5$3B9VZBQlbZSGHy3 z?}0AYe5p(wO#9TS6QwiYcY($(C_49&a+*7S15CM+W)4`B3pwPh&ivrfjadJLF^qYt z<%D!cf1#lCDeN$e-T;>Q=rdf%KU0T-`WpM~FX0N3&FhnlP5@u~gN5z?OsaoUNfMKa zp<`7FmN(JmgTCZ_k4cd};w@=O2%CZhtYj@NM<&M7!74;wvHtxpu!}PY6 z=wn*X#K#cKm>~o?rr4lYwqoSG){Q-3kQzcXZRisoh>|W9c zCL}$@G%D1~2W=abZFPD~tNiXPj*1VD&#@4FO) zIKpYbf@oV15Yd)!HnpRZO?F2q+%oND0UdfQ31$Y!#@JzO!FG(F*S#a;KJFb+NqGQB zxZaL_egrz8dKf^W*?IZ8dPllDCT^=(wrVt^KZ^XTA$nWr(ny@2c9W z_>HZz)IsDAH!=0mrR{Z9@4;S3gt)r(eMo$xR&c`y(u;m8Vd}l&gyG|tBTcOBLf!EX z$gmFew4Q)rL#+<+7p3pS{|>KPeoFeM5FKR5e)(E=fmR*Oq+vJcg?g5`shQ2j9~@7- z-OTL{H2wAwe%1kP=G(*gfqF=>zrVKSG}!y!J9y-2Da~(XMt4=;_2J7;OId-3jzNo> zk*7sen}cdC=8i+VdFyG&O%L?r(i!Rfp)27Gr?by3M-5Er!U^O(j(MiP6XuTphAXc# z(5MT)&gHWZ#~}iG^;rnL$j!)sk6_;r{vMCd_g%p^{Ex36|M6q#(V;8PcUOCTmb==i zsFpm>(ce^a2iz@B_+RPe$-#ND4QE2Bf`Yx_w_+CFQ@Y=SI`E!gcKzif<-_kW;_Xl!gj_<{$o1>K_tx5%7d-bn{FIF%yh$6F-^Nm^%U?L;j-_ zG7`S9&?~d+&l}t|k`}QN?E`6faVmjX2s@|@MH9Ira6M1?6cZY_jAwo-eb6V*kiF8o zyTeWMc;tEMThVroOBVnFkiZ)+Nbib)li^}O`kmm(?Np4G|u7`m!z?M zzDEZ_-5rQEvA-VVjhB$^Z$7;7bLk~rF+jGmvwwW{7t)|;TaTm(CieM#k|Zgk_oemp zka6>8=8m2B_`WY-{kQoep72-bg7-SYbLe;Td|vri=|xdWtnHfAYj**Fdgc( zRel8=bzG9*Xy|jE@)fq?8*BOUuh82+ui%%yf=a+fwB6X*9TU5V8TcCn{o5w;jK87o zjVs__05+<dxK;@5j`Mz(YDSj*AccOEboL|qK-@qgfyFhM|v_hXr=!V?={f`Ls)r@Xz#D;B# ziVuXTZOstCA*7f0Rg`;mF|W7^g^5>p*WJAe>m~760&nQ63+3h4r9j~wzU#X5nD}Wh z2}%Qa({-t@cyegucy$8TUYI(GBe770N^ zhVV-*Fz79t$kT74>pv~#mu^B8@8=`6YpHCo%@Q%ETYM|CC`(zlYIkyTB7} z10sL?gy-J|QvX*o&uo(p>HZtbk>6Pj_rHS`s_l`48Teo#H{Ov33_RK+S(yOUAB|@e z8VToxcToBF$9U}>!0{`=yy*@!ZdPOO`~ZMiJ&hm!0l>L>H^2J>;JfVtU;a-RH5Go& zBkxKJy>B0N?eqpA!MEI%V#V*K@w0bf*>&e8_ZM_weBnLmgn08hkNTH1*H`YN=;gBy zhH(48(BwY^e(qm@la?X8^a&l6S^k!`f%6yu*8GA(4JoYL#!-w{Q?DUI~A%5edV4ci1lm{iof zJD_uIEkmJIJiP)o3RbUVdwhty$U zV{il@)TOAK68Oz9s2HRW|7TMcwhU&%>};IJYw=CI(uX@m-BMdTaqlhI3BCel9IM_LOdONrVT5&03T=N)E>)gfgDoEkgA2I7BpZWGpp)l zDtWB5`GUT69UGO1N&;;10ipvw`_fzYe8GWErbIneF;xlmO&4l)Xrm4f#`EEyQ9 z>Ovx#H`f;;{~#7s53AYwOvcLRutD{^SZuvP$#3EO3&c@HXPf`l-YynTZ7OZqn(lP9g?6aDo^6pIJgS>iAJAW^DC=6>tqPOk6YqBO zQ$LYkyw=!7NoHr$!Q1t{UMwkO0k=MEiwZu)vy@$3N8R0zJ_{fsv2wr5ild2&p#| zUoh6FlE=WEmcdn;%;IcS{xs+QMcL04!j&k0rI#+)mwbw*8+)Cy2l1V~bU{yDF2VFl zuAM3n(prB8MY&Cbh{j~z^iDu$&FC8dVAKp><8m2yIxiEG!^Rs3aF>@56>N4pG1x5pHROU`^b3}>H_iKSy$kkUNfab5=4wo)H|z69Hw<1&Cv*?9~* z56@N)58OdnsL}xHQg3RmM#_it`Wi^^243NzqvG7bEU0h(kTdBaa9l{%Bf15kl=E8*3>0mQHF@#PY-eRYsKBozBC%NM+k-mgprr6$y2rP&hXAaW+%&y(n#L4fAq{rOt+dzF>n@ zUx8B&-EhIqWBqlzV1IYsU-v{bM8}wc@r07L=Tbq4lDpDK2-}&)Q~KxzBPh6~k8Z5a zsFZr1N^Nt8ICk{WrHR|`aZ6vFo?Ex-ym@S2-AHl!my|NaD*>#l?a+ActIP75+KyuN zJm?YK^u(IZn&>F#8~{H107$xh_&peYQXOQ~MZ!wv2g8r>nn!ejVpRj5`iO48i2qQ{ z)*Zj7W`?_(`DD}(C=N%|=>T0w+_q*~@iSMgvMN5!XFY1!)8MsQ{hcck7pGW7|u}q9JHYKV6dFHpRx3HUP#rj+^@F zhKf}!yr7>hMBF-?SM<|O>RWvbw>w`<*9MyVcYfr zcj^iQbuogtbtd1}U-w&eNrSk5knXWy2aXEzw^~b5|IRfwcht}0#=m+8M4DJ-sM+~) zqq@4@>Ut_rP)TSUP~dIk6+wX7%}|66((MiQ0%`AQ&@iDstF#rnUh&LVKN%$c@?hN) zsQ@%NNQsvYy;hpc`ZbENrSj|$t@16|5=pcuRa1|51Jrt`n)+zCpl=V>;TBmmn@<>^ zn=3vS&G!w^Eksak?jMQ?I+w}~p}H)wIGR_7>Oul5=fT7*7H4`SQTCy5DS==c_xX8z z^Qs(y$rHHc04_f1KWKe;>T^23ft2AWEh*@cC|XiPLsYaWkY2@82I|7nidNy9g!g6m z^~Y}>egp7355Gb9orPbjXNJ2T{V(b<@aloOF?|b97|II04IdX0nv0d;NS9l_@#)`> z8?w7T$q?@E$0vW~ldh`Ar*fVW1}xW=)efY1fXmgo0e!ah$X119E4Odgh4``UJ<@Bq z1I2y2iXY&uVY)v(U3kvjsag}OxMMG6n$Vn12Eu9uZ;)2`I2ciYU{LN$q$mw{or=~u zzWL)@)i1ss1}w-drch?Q#uR}U;fb_&~k`X9yT$tJ!i#awtM4KQ>*9F>S? zH}J*?-OF&L=$Kp-O29^560iXT$0x{?I~bV|%ow);Q>W_2;LC=%(1lFvtLmkh>yw0?sKb%|L1sc2F$_2o?anC(DqESU?Pyu!;_u zK^n&Fr!QkXK@1kkwXpPd*fHKhC$lJ`K1g69QT82@#N0jt_q}Z0!KHfG(T-!ev?I?9 zN2oWH8w%R~F8_F_E+KH;;#Q&8+l2IPyINuz1`+mu6_&w|>cXc7GKQ{r)!VJI zf+sLElAG4=k%OpW~-(+YSGeivQ1%toI6GpuYkc)WPK z)$<2zn@V2xD2VI{PDr1f#wxqQ>IEh0v>dk=|KU(!ao+Yq=+_ujYV`g=*LH8x8x1&v zCe8?&Y8O_bbe^UvS#><@ZQI#|dzq{Jw#)Nvm*bp08L~*5*g!gb@Q=bX0uuEO+K4AU`wN!I5AYQ3Y5D93t^+_NVDZ8vk0`Y@ zifJB!2cnke7a0gVN^U{#p{Zy9z@w%Ic+3TOz+Jwza&TeNWpE|hLHUjoGR>|ZHYe)g zzXq_e(Pm&8Jb1gq@TqVSg2uyKt`xw;t!IwM6s4LKK_uyw06yphCl%x6SiAiC2o*lC z)-t6#u38U2kWF@acIi#_Ghj8?(rUl4z|HHD4jhG^Yj?LIQC zCNcD;-F!i`E-@O%B6$xuU?%|y-4B#iS+`eN6~K_ewh%X8*N-3Z^U=ECA;%eO0CZdg zpc7XeK^=s~a7-)suB|^<(VIZyhm4kqnL(#Osz2DcKaSD;8HK za?1$a80ufm2p}w*#2ZFX|6u7o0&{|V-XnES2bP5oAAFJtDP3kAe!b0K}dV(|hUWA``F{PW7|ykVp+FmQDu z#+FWFdmrOa$F}kkZ``dzX!w0P*+w`8@GK zON_>MQ4@uwX(P(>|F;~KRmzjvVHOlG5-lpVQWBwwa=XI`f~eGv_bgS*7|)?vO@h@J60i}viw-Z;=iwPw{|BbIxQA)#*8zd!Vto-8 z3P&%%yU3*a|5CpBJ9^<@-58;Xx9?%08%0elp7r>H=VBI6H2$}Wmtu_G+nNVD4IQBw zk$p5#Hd#*>J$)!TX-x|WkVTE&3LT#e_GPi&!bD|+IM!&^Fo*_h6xKEBo^{!}E6b(I zhObkW1KM{ej6&8=JpPav0qsgOV$GfsKuchq{79kk1eO5HMjgWJ1jyrE&Y93{pqaBy z6yngyNZap~E2f^ftms4&<)gFK-Klb_Uqe?_Zr`Yjl?a$=rNJaU%jJ!_0ABN&&imhz zg8(v~5;Q>xY;4p%6|#!KZy^AIgm&&K1GO-jenZPVC2Mv>06jle#%$AeAZ-F1(zwgG zCq=d{9H2k~O%&CcsHflbx6~UbRJ_&((IFBPs`U()GP0mMlZ}D;iUC$JJdOsP7_Btk zKo#=4Rl1>lg$su4)$p!cc-iprDxixM$9U{kfW19Y^5kom>tb}V*0hL#k_ea6;UmQI z6U%WMjNP&VM7}42&#!`*PAO_IvE>_h<_hfG!jrskg)XJ;aHS4{u$3$L@y)sfLDwyY0t zMY^B(LXY%(9?%1gNuCHK4PDqfH-pVGn^awxk273F_1>X1u zDD8}Gx{+hVCy{AFXVUL&6HpZWIYg;lzcFyS<+0}EQI?i~}$Kax=j z5Rge|_v{f~TZP8$&*^-I?{=L>kR#&6d0XYdtAMYW^+ynVf#a1>!eF4$mDv+&*sThf z7uaziD{Hy4MDiW1ByL+g#*eqDji&iLo@2) zJ|gKLMi+&{L@hLEfc*AAc|a6uQC8zlgF$(M5}NmKxHP+(6iU*Y+NAp^wwn$7O=cl% zTAn8SwO}$6F>4ZjHQ=0?LXFIW43!k?r!-dw1uQNa3~i!lp%%O7Kx=p|ICM}Z3TH32 z>b=38+ux^kkarXaQ^nB8)ztg@p11eTn>!7PPF(An;K7B~|9!mhRI{t`A(isuk8#&# z-2gu^5wMWi3CO%+yDrQo0v&Xv0buj$X=0McvDrxgQ0t^e2qF$sAUdS`lSldDmJbRO z$Fakt|3xnSX_d{cJ-15dvBUBS7HW`j%355m(nc0kngU$=Gqn0^fL}fFdlh4bs#wvs zz5rb)eER(knR_wO`VWA~`fNUy>jsI8am_^S*yn1=Itf#HfbP_`zh6$bt<@8BNY;Ii zfdr-Bs2N5X+^!nn)BQhzK}Y;0q&cCA^TvX0YNG!fp{k_G1}#%bCgD+$iPD3933MhWr*VI9~2tu*?|Uu9guet z5FhNQ-_5G)OV~aK(y&rZ7f*mbgeq7A%E?4W(87SC?p!h6x>*+&CgPM?o!hx8CicQX zC;}6D5wYPbxnYYgF6Iw6v19dQX=`?!8U{2HM7A;Xu6Vj>hBq9>^k&zFJYKm4%#9yz za>o{3EO)%;>&;KB(D~Tje@xlh2qZ0IA!Rx!tY1E^sJzjPBu;=RAH5>2t6b_06a|!Dwqnk)8XWKA}~7mlB8Q~wX!&D zzt~pR7DFa@4R|L0GHq1~?cEg+%hmP?U5!<`TG2Z`t5k~0l4XUaiBxozA-|*mTS~qU zSe&7Vc&!h7Hti5%-Sl`Pkb{i5=YJdO8^Z6up&REXT*iD?bflVC3(8JEfN7nH`iuHD{bWu5zl?>-X3;lm<+k-V56Il2yS!hdi))akcRHT^MH+ z7NboW4{@bnSp!s|#7eRP@5;}I?<10`0BF&UXQ0a2fJ|@O)t?Iq8VN!{8+NKZr4Ix> zXkY@f9YpYfXq=xo4ds(8v}o*d;?S5X zr3pa=DwS+>wV=P%vPV}#U~R!v7f^*ev9c3W0i#0-Xfe zPKCS9jvd^!WO_PFt?$5&=L>AI`-fPv1&oZua!t~#gKfzS&%2o&7&bj=9;=3?o`d8B zgB+mv!W!PP7XPI)3Zr+`Anevbzz1rN8q4vHX9}Vb8@e6t3PGX5;>K23{PF)3rXW<4 zq3jThh$6t@yK|3*kIFM?)1Z>Wq0gbv2ds8e2~c~Q7*PDbD6=1BfZFLeDn4+iFnK@9 zzaJA|P5Vng@y!nkZSQ{at0H$h7bqLH3tXK)GSOqTG;Y}cbHVtBW{6*p~3d|Pi;)l%t;w~289vOLXIc%N# z7hDVw{xSkI8`zA2Hq8pql~CqT=$I22)KrJaG{A!1p+6&j!C=TJiGc!5;N;Vg*ue?} znAvXqDJj5kDQbFjDQzmJjDzI;a#^Cqc|H7{!WSo230ct9Js2~Xm&n4 zo6irU4wkMu*jO^_U=wvJQ4g$*C8r%zzvqyRrp@jU5BaOpcql-b#9Pl)H>*%QGu*MWJq~fd=!q+tN0>3 zz;gGOPgh-WH`Ac*#w22crTc}0UfSV8+XJ1SOpY+W{xq`e+?^yOWm9%?c_-G)qMACF ze}{7D_qkl?98kdoiz%QK^JRYj?b8l=of+B)*B$rRVauax{M?+fA8A0 z^I_DeTh1ji3v*#S8pN1TyKJakX;ji-Pe+!N!jATf6;bMuk7^#`z5H@F(?E5yxK{>Y z)EFGXePt!EBcj--J6LrhHh7`tLY_R$NQ^jl42^&&VI)dGtZT`P&-{KGcT`J0H4EjP z=ovy|=oL{JN_UC&X|!+taw6Ed11B-!HJ;5)Cj zA|DS{p<1||k3i3sNA0)Tamt0MJr;Z7Lp*b_1S^?YTq&muS|7#A;Mwi5=l#Jyq7~GT z8e#UJKw;L37RAu}t8?y9Z;5fQ@P;HhcW5U?%|U%$IRFK!iSi}8?hcIu-H=?*2&Su> zi7v`)bX}Z`ojZ{`fqDw~p3fVd#;L2mzn6CF_0pHz7`rNQzKT7hLhq~<<5w#%IRy10 z6Ma22$0=;ZgXp?A{FsXHS43if-K0)Iy!sUeO=sc88n&uV<+OIyK_2%6dXuZ}{ja&Y zYU{D=CyZk?%JNh-wJ3bu;~_4J7K0dW+SE(@gWwIJ3Ww+`oX}03|GKIG#j`=4KX5V$ zd?#7B`{^Jy?Q+P=eUK`{ArT;sEVWp9ik3|_=5Zv!SqF)K-o`RjXRxAd~*%WsD z3y4tnz^6~^%7#D9c-(HI#ib?(iduJaa0>%<1nDLQ#Ly&@(wHj{g|pnuqVI?*Exf-QI>; z%1(c($$g+xV~2@2-Koi@5`($h0!qN1BuyMlAxu%-V}@^;#nJ#c0HnilBuo@c8_Wfm z_Qv6wd^~-7lC(PKupgem6Kz&{bRt{7o~AyW8@n9Cqcn5uZ2bmId!#sn*j^%R+D>f< z7UI#gm|>a)VuWFFO(@Q5I{1A-6k~my_DCBNXmPqwKk~BN3|m=K?M&V3s?G=2J+|BH z!^#7UWPoao$(eFpgeMeY1uJ-NNB`b}yvx$$q4Rhk$;9-i;XxQi$;WU? z^{We%cY5s3Q9~onAF{h*X*{Lwpr*Pt@uTVIJ?XLM&tY68soxH(ulP=yL~EV- z(TlCK`d!5PO~g|VP4eFk!qBN8etWb|H(kSr1(lP}f5s-ajx_vu?j^&I^zHOo%p`+w zs#e(ge72Q+kCj$mO@}TU0$mn~z{q$Y6>lf|8{f_Ze{T1C-`?+UA$}3BtX;$GBoo1@ zGeQ(E?gXbw&fm_S_1nWsklIqDt^&v9lpv+$b)z+9NPXq`r!klHmOb|Tx7g~G6uhl< zW$Q{kC~Kwj2Vwz3v%;%S?3?q$qWy4mDL;Enix zioQkLceGCI3oiXNQ*dEdgXD_2&V}N=7VXh242z9a!>Xuz6n=)KPd|5j>5g*`TfqTM z9>Q_NoqAN058XgjKuShxDq+fDD!?{%vIyKcBl380Ixl~}&k(-oN#lTJ$q-6MrBFHv z|M4;_3We^`5gRWLO$wJ;uduEz5uOg&69jMu#D zV4KyS{x$L9fvzC$O!hnVlXX>4J z{&o-uw+8dByRg>Mjmlbq{e;@W1OiWg3(@hIJJG$Sh-QUC$Z;b?1-(OT(Bc@XQx3vU z9b^%=@4|P8l@xZJ-s*q*O6Tf}5oWh8nNnDy4qkY2dJSH9siSYU;}%ZDTQb6R&};S2 zxV2>0L3Phylnbk&AA#<@6Dq2zQF`H-xk&xN$j4bqA-GTl&u-5sy1~?U4lHKsvg$fDrTualkhOVG2vV zhqo4^_m4yVptNfLaiY$jJ}U^?^XaQ@O<@ZcQ52=oJ}=1}wMC44s@?evhTTo~Vw@Ok;E_ z&gy2;I3;C{b2Y~Qw3=*e63wSgqpfaIk|D_K*xQFaoEWm$=X$h}2Km+Pax*;YKw>t= z-!c$h1=U(tEy6%6TDOnI&*+3qI)U}J!8_45Bxz!J`JKiYt~}@hv9#lLSJC4IuCF_g z=+Ew?&pt~?37)y?5zAl-9fCD&xF#N)Hc;2b>OcQx$xe;k^@vJ?9gGSgeFft**+h%W z#KwY-dg`8@nj82H0eVA4_;lcppr2NnSLc`y{xI9!W43^YNm6Izt13v^sf)B~Stp|xt-U@pM4!}x$Pu}VQrr5UNz zP<>4@(I&(~RX`-!nE?%}8<;^&xtooJJKd|JcBNDGdgaZ+#4fM5MD?THNrKvN$J2!- z;*{%^dv+$wpqDyrwhJtK<*`Bw)Vf$#na1QsO0kYUWW}4|)9>Gp@88x;D$!_jOOmyD z;E<}TQXkps|AkI6QZFtN@1JR2^=q<;Gw1#76KJ&#vULe@7fYvO;I|M>oC!^nE2=g6 z!yT>BhKp$1V5fs17VKANRiZzf-Wsj{5qKo^Z(aofuhwbvJRkt=?(D1y81c>-NL5 zMw@s3L=as>KDm_zO(ut@fFt0%(=TfZsnAj6XgG`Do*K_$QTV!=z;5kyFDigZ9W2b= zGkHSb~-D=djB=kHR?lDg5ivZ1c&~C%y%Xs)-Fb8L5xXl1Gq8w*?R%;@6-ug+z zH0agn@zKGJiKrxb=1xs{(v4^|hieL<&IS`%?!I@?RFcK&fB6YS6@^M(Sa$+^*{3N+ z881QEFFmzSQ%0+~F$1Wh72OzptGD`}ts|b0v~u1*+J)=4RK^s{s8f$Wi6SW^ReS>%F=UA4lL)oTzYaKc^+$opamB`waoOh&U?u+@n(Xs$q{N>0+9#Yl@$Vh2BZGfz zow?;jRXN(n($L;~z3Z{3`7OmpldAv`IKeu1-8vkGa$EX@);_^I&ONnd`nkVscoFO@ z06U#vr<;nPn%j?fN$w{2ANG)liaYmwQw;nU)a}$bL8$v&aS-Z8(6)0o25p0XH~bcy z!Z(_Xb^Tpr1uf_@91rmj!{0aLQGgk#nggpy_o|h6dU*%1{@MsiE#4l`O0OlLY~3 z>LPIpTJxw!272>lj-RBeHKXY+Hp7mxD25?CuL(B}Nc zP_;1Ku!{&das&(QnH#f|uG_TO7oZP;e8{88G4N6c9os=YbR1m5|NT&y(KUP&&2Q*K zmW@XbYwf}aT7shXvO={XY7c9qCZAL&*FIGo7d=q$ly8@Ax7cLmqFwY#AvP)8W}CcIxTM+cdx@ALxH5205l(|M7)y2shEpsS1tnov7tpzJ9u z9*5H=7_W{tB6&Tl(0wttiWS|-_o}UyF9!DvVp4-wCm5d{YfZFvB)^F{N1Wm;&+f}w z$Z&dL&%F{ID|hmuDVR;}b;m`=$|cm?p?@!COh&@L2qQhw4h1dCnu;*=-6tk?tc>pE zUXMK$0r%oS!Yu2hcVcv;|Io`lof(LYPa=X;8NsEOWpt$1_41(Y6@fU;Fw1)BB^n*+ zdwRJK>g7I7hF^>X^jzN2k)D~_%Y%+Q(7DdwfLVCJEfgJ=iPCO|J(@a1^iG+FgZiDv z>-_DMf%vB5ZBvcwT&ZR1-3lEm4$82_jTCI=57ce6cAi^;tfcKPK2@us8Dig%oBnu5 z!)+EBj=EwQG>JPJ*vx~8XuBb_g}#{$^>=oN7ppwfb7lAN2e;!?Hs25>oUWM(pjNXx#&jSr!*r2nB#;EGYyA75l0!qQ(Fmb@>cV|m~_ zUvXasOZu5o>B6Bdo757Ec~B~$DJ9zPBHM$Dz$_F`zH&gvUFp1Y?RhxREfM9&j4BP5qsPQx1a%TAf?+Oiau zcrS09W}LY=aS<(PA>KalSQIN+ORZWW%}aOlm{?+-9V*TqRCzr31(jVGY!($dQf}Fp zQ70~;a7@R-(4lmArYOtER3y=7?MPdoUJJn+ryC8EaWO?l;xfdfhn^=G`zV9vzSBXN zXTk0ZSakr8i{d@&oCVg71vplG2GY3UcAhu`eP~=xk%4z*R;StnIN|qOJ7%op%IDh0U5s@79j#_u{;FM`8tz^P*DYrWKuwp#9G>%I{PV!Z26ofXTCV zOt}+X6naj9xzaNd7hk|H`6H2Le&RL8-%|S?vi1WxHl0iNpUAo@k^m5 z9+_mc4mTuvEjVeZut-hc!|pVsHHCT&aG%57NyZ!c;6RJ=U9||egkMN9P8yoD5pk_D zqZOeO|By?uuGc9YQwQ7UL4_!54U$Cp6w>?flznEDh+n%cCpoCaMCsgdq>Ooo2vN*qD8=XAAo{x_AS_ z09UI6&AVUjb;rk-PWRrr&{&bw?JXg1c;6=h;B zI~U#Ip36QSMIG*Rb#nJ?N6r8Eb9!K+V(jv39S z9O|w$=p9;pm?2V+h`eeLb(5{WK|dS|pJRMPqkXQ9SI@k;27>5V>d>`WqPUEm?as$~UIus;Z3ON(* z?pfKL7DxxHukSRGmPye@vZZsP(NnJZeWQc2bAcbW3Nox34Mhkxv>8Org;ZHnq zY50BiNq2Xu*Xms6>*It}#gcanitP6n)24tFcKJqrG6e!+Ng{7gF>Wya=DvxN))8&> zUEI&}7GR{I>8^=e+cz_{odU)xqn5XLmcB>^|72aMv9fF+d(yA+UY1Df$Y>UZCptR1Ux3a-YB131EQ)b+jGlWH8PKLc3L&!!ru z1$A`3z)g#=0c_$T?p}nvzJ4CBSY#Zv_|2W9e#_wo^^98g?IBIL%m4!9?n6Wa-p{!A z1FIwKFH3qbdN2Axypuic2Oho{0xeh1V;5uf?6^*DTWlPr*~jx18%GY>DzazXJu|!z zRhgj}pB=H9S1blq<0kIC79Piq;gQ!GZ`0h)ORqKFJfOR5t4C$31p+8ZM|FItAl-Y3ArYCfahV zYQ0px)Qu|9WmMjfKh$99&7f_X#$W51Esn0Amg&c^RP=ZV^{7`5I@@{pQsZFMOLXR( z(@Z3lG-*6xsqwz(n4OQs;LP`oz`5{MPHmcMhft-SemVCpH7*-il!7i3&gZ-XWpFm5 zRabdDCCxZXQ^kwYunKP^ZkBogmoC+(8K2RPS;7mJ89yJR>R*<9x*7<-Fl)!6Pv!RY z2(`__9f`R1rI92_y--ecBDSveH}HmxoZ5^R&o0ZX!BX>$=oRNz2gB3 zgR2xSY?h?e^=2^h+N_N-?X%k`{fd9*`Z4V+dPS2zpkf)>@ zclEIyrEMP8j>Us`V>%9bh+fGZE0H&l4W?DbS4Q-^_fPzKNe+OZulHVWTs(9k-R7aQ zb}UT7GXy%1xZR^;K@QKo-k6$rdzRKsGrY-<1h=@cNs_o^c_g?hg#|acM`#PLaAWB2 z5tcUXMy$bj^QVHqZ1A34S~vGB#2p|B8OCwLAw2IIgMOxN_an?b%??I9gnlU&D7d>= zA#Yn|9M12_FeVvx)DkJYA;UO&$vGlEnO3<_PGXI!`H3B^g7^iUW=y4(tkGh)$Z(Vv zmhA4LO`%=WtR2@RlfRN(+M@29R{f$BT2>o}&R3$X)TRT@}CxkNUb4uGL@o zv-2*{m;+%z>myN;fPH+$?x2?BeFn@IuQpECj?nYw)y5I?jcVWR(lD>Z_;1$*_oZPj z`;#ystSL-=F}JKSM!Pyr-}*-auT4c@#g_)Q``jM`+l^L34J?M-q9&8hP-g9zw@EUE zZujVw@N26OZh~hf`rnUei|E=S?p-fvhe~i}#Mt0_Pr+tN*J9oVEM5o}9BZ&9q_Dxmd3KI*>ICH=glimDeLARJB$7!)y!tJU?s^5C8O)PW z`;AUbBtMx0{cO-ZydD0u3hpIXk1%hG<0@*pCrK!(f;87W#e78`fjH z9=7xO*5d?-_=DWG!T6FEv#{a0XvnU3lgHr=Vr4V>Q(3$`}=!g%w(BF~0(?U2^Xc3%}$}r0#o9)<<(U&ee z?Zqo+L=Ug}VoTMHIG3Z(YE|#+vy3<2h|I-F{o#4Y?9ktMY#!9Y&=+`79<&(aIes(` zwKL>5ay~ia2MmLv0h~4w&k(AY7)-*jPsp1TBd{>ao$i6Gu3z)HV-pT>&>TCt$v8=` z4cf;qY=dqWbS1ZMHx?ap9xy(wf74*_W2=4@;$ z`RD7#*}<`6vg5{Nk3aV7>&APuJYu1~|FL)8G%gL|)uZ(h-1LsIm4~P52aPi2Z_LY? z#Fpl6T%UhA;xOfJF>TA)wB_a;Q>OTKY~;Jf&VIcAu#kvjxt|#$G?qDe8?$aChud@V zO<7wuZ_dfe-?(M7X**FgiLw9cd(P%;d$R?K4_VuCGV^mx zjx8HE=Wn0H(sFZ5+jBD=Ii`)gTzTh^O0^YTpjaPm7}0Rli#?#2zd zc^mU{vPF>O4`i?3xOwCDT-B=@I$vwn>v`sb!2^%|^($ll5Z?N|F`j!D>P@`-dt)MR zwCJxnmep$fBB+Pb%*)@M=}TTEHG znVUD{P#TeBHA>S)BzO>D_Xx7|qH*LNV#qVY~7DaFFw#-|ILX^$a z%yl_=+l773mTjAJwrxke;yq0bnZMkI?RZf?7!#E1mS1aHnz_l52eOgTi+?ZEKAUEm;t|-M#rlDK@^8kd$tuda-EYb)Se&y_r7BtkDEz@cJ}t=4*|eRPTr@`R zZ8ygBU%#>7CI`~7ZDaP9ZB$`+bh~k2ALQrKoDIYje#dXdU3wIee8&4P)UV|&KO2*| z#;PB5Y|Ss&*Lke^qA^ixnCoV2HaqsC&p27n*16_N_nKN*bc~H?##7UPKb(g*!b2}!#)3?Esm6;Q zPRN-)j9y~l3N=CfGN?>^8B~Gipc>3hrpqspIHZpJL`LBmX+elF^2-ofmrtLDIPe@& zBEnUJ8*xB<8R5Zm#2NWQ#EodhUl{)+Oqp=Z5u!Y-cUi<&H1_yq$d_z-DUdI2dO`4v z$YxMSf)ensz##Jfjz1z@^_PrC5e)fjhhb%Gu6S#qw@MiL)I={;@}(Y6O}KnfLm7$} zc-CyFwml`*>3{WO%UkK-p0m=mJ3m#rR zK(VFY_*u70N&v$6l<19sp&wxhzr%?36#vCH^6{Lj5+9*h`X}$gD>K1l<6Ake9;giC zYX>U9+Ba&|mr(jvg>TJ0uZ?*1(d#HfJtaJYmpGIW22GUzV!e&~1}Zq)r<7OkR7Qu! zfE5nFt=tx&j5WL&3+Fg>Y%{!SPWmstnawLBkgk7K^2P|H^R1Mj}lM|7;hY;m~e`cGUl?}jp33t@$d`Ad{PJ! zQh2pV8OixzrC;BFl`%FnPlrWJyZMp9%G$^cFLpCivi;{G_{rsM*C<2yp=pY-53~6% z{^9|M+hr#}E!=dO(qH@QS?<0}S#sI>-vUum88P`g^m!n*hTC$LD+bsAW%xTn(@~LH z5$X50@VceS)!ZJb4Cp(mjWI(Dk#e5zj8v|T$m!}PMUdYy;UxD)DwFkb<*0>xq*ICJ z<{`>-!%6G! zoB*{Vu^sE_nM$NB!C{jzO%q%r5X;tYvGz<%DlddN-@ao zB;Z%R1b|_g2f2VVEVe6A7*$d(ACQVTOZ^?`m8jYgG^vc?5$;cw<&{$ zbsTT~-FGU@U~fq!uQDlftS;`QXM#_~N^Dnt4OW&1lG4F{!> z1diuhCxVh7)U8K-+>ST~B%tcm`#bg{)w*`L`MQno$wfW$k>1m4QF(*Q z)4IK5mFe0K&hW&s%53ewa30TCMQK9y3l^uKlivJI5(g4d0i7G~M1Y zB$ksQmbE&6$9bY>u8M71MOXqbs#=%*@P7^}?J{_5ckvC35K zuRg9DuPh7lX$pA8cx6hkPfKYi;El1!K4NXF->1#Rkw^3`sHW!|oar+BzMyuVI05A$ zv=W@HMRy;f{qYHiF)W7xmQE2`TPoAcX=HU~SgxDoLQWwREDB0-6^DGSgDA@^qUve4Gn+VR&F5+bq zQBmjMJjsd5*b&xzM2e#z;3~XZZHUBMli#-pLVptCU*zO*lOPMz%6Zx(Wwv2iEqId3 ztB0a(uAPJ=uRhD0Cn+{{-=LP?CcR_QKM$OED^ zw~9Byi*{=<4~bV+U$(fr6(hpoz@3I?5s#k(r6U!u)ySU`Zd#*^>c@l=yITMp zC4k!~bWM@pSL8r!X2PEAmiqm*#RWWkva)Dk>ZU*uK+X}ZdkeW^vNGRLMm5dEE3QUa zOT?!Nzpp%jw@n6%%4>Q2RY>on**y0uG$n-@P@09J&(EfCV-KT z173YAV2GCxMv!8 z_GTDwou*hK=04ILn?=Odkk2jCQ9|DZVY)QZJ0f|-bQIzD(|GN4sFh8~8F0ii9Uo$5 zD5JEWK!D6p78^*-))sJ+QyI*kouR}VJ}&@JOu$gCO$6`-3XImwZByW4aiU^2d{u@# zgJ_U|fgeZ&kzeb0QzG=ZZz|yYB>6XSa}t>RZ5Yo>Lg8pd?&+ZRQ*zHFL3&zV=}tzR zNJd);kD7_FewfQsXF|Ka5QY3o=Z!O!k$RM+UsHKGef}+-H_+!!q&6sA1)v0^ZI3P8|xhrV07}_8G3XC=(5aNB}qm!Uh3OiV?N{DD|CJQ|U*Z*id=NZ==7{ z(8NnE$lN|U-e6JI_Z`v<{0zc+>qVZFtVC;vHgS70a(P%0FHTk_8%9#tX}o$F6ynd5 zm3{^j#jc~`KZF}+L#9TDbJJ{Pe&4Za&}W+w)SH!j>ue=&;EZl96C9!hO||j1*(lgn zFOQo88Etk0ckq%_W#j;=YDfK@=6ZxqI&l3zxMmEB$?5@6^bXHKy_+5mRlS~jw<}Wy zmUL?~DR7_Q@3b^=-CT5FX8X8pF6ziNA-rO)veG)OyPb#-G+ax4CiMFn_zLH6rMD6_AKF#o5! zRK?&E5}#4dee;yD!5EKctT0d}=7WKYo49R0*s^3UFP;xUztqH!&PN(naU_ zrLNm6ukmC8ZiNdCBj6L2vylm_y160hYv*lYR0eqUaum_i3zeY*6O4iQrHkFod#&Kg z?sgt;McFQl;f}@1xKN^|%HMgnju%_ej^2HSS6RXL5-+!eAdam z*Mc3-#S=6^`&=bYwBh||6wgziUS1B|@Vo`&<19KBlcy z0&#H64x&y9N8q+0-`{zxomVeW#u<_MhDv{D4Uyf;1*A|-1-Y1{t*PeTCCcQnH7#(G zs>7cgL9t6YiV%a-{GBf#QJP9#u?dAS1yG^C^Ti^B9)omF;(M=CBDEenuf7hf^%V0) z^?8A}U5D1|wHm^Q8baXbwX^i?GD=Jc2z#xayH_FWJj<27{5_Kr!VfQnoOvBFghOLq zq)g|(EL9@3A38)3P=Go=Ebk5?G!L)Uy@J@1hRpkjad#S+`jMAcrGcK0e7qqI{BMfg zyNn(Oc)~J_(lnicGHL4W+M9UUGG&1F%L-n#41D=2jyErZ=dUpAL%zN$#}bR_XSI{WD;YCnNddN&OL4dvgbTlFDUZnMaNUH_oGkpF^Wn@qnwDa7R%5YfhyhvE`WmGGbA%IWv z=9Os5^))CKC#e=qF!amwcNtKkS0PQv#eNldEu+`T215(Vh()wZ)CiL57q0Vn1-J9F zs~{TtIH>U%#W&Aa`d${MRBskV455S<`n$sF5lJJZWgNfndS$@C(JKQo1Z590tZN1e zRFpEv+BM@WfZi<#Ik3S2vJ~$B3%nAc6!54u%IFE?tPvqK!&z7_?-W^!zl+Ag)!~4{T7KnPWt1KSOvkz07y%d% zgT@O)48v3HKpY+>I`j@;8NjIjaJawh(3b%$0a#C9uo_k<*cF9%GzZi%kjvcKz!(U? zAmSadfvF$)aFiKp(R8u?uHpF@s!K&c&(!kQ)2U8 zmYrUU)Fu;4-1GRm=D6{s4%VR+ zq8rA*{kdTPs|egcY#geD11kknA_%*MzmutqFd}Ihi@$4L6>_Q`5_i-HNlLilm3kNz zE4RNZB>~SS?zJnC(L{Kd5>SX)HohG7cP(hb@IUEyha$Pgp+pbbGp;1|zVUyXaPQ^a zfmWj=j8}$fk#O5kWzfK=1%av+d?0!K<<$Q`a`~<}8SlOu&J`nrYc+l-J=>glv4sI*Tt@?r;lo@NhO7f^0j0eCqp- z>VrY5u52&>dLP~g@lNuYgWCggl$m|kgT zcW=f31VrQ@!$*ps>e;!vFn%2o%B2Bbk4>-=3VXrhKl9Vlh|hXQ2^pPY-< z@lG>O%|#mT&PL)>NrxWHKO2o^?@%s+yQhGAa?wk?uMvK2y=Yjl5i~rAQoRurJ{*D= zVtM06Wmf-2neT`+INsm&Xfrq6pk%rtUJK+@1mZ_dJ%bQ05e|f-%s*56CpgOdGvLA> z+~)!>{SzDo?iqJ)oa6S#KBJz=1J=7f#o)afZZq(-5NCMFK;^PkL`oCjd^~&0FT&e^ z+wuJU_-Kd>rZ?hLzWT-hoe?8MeD8(8FJdm{dv+uF^ zUV`rpxXuwhH+n@mJ`h5$6Z#&Q3vZ-tKmHZpWKl*?7lfqt0XJ|O;(Yv+iietjrvR_v zwRz}jA3(j#Lp?aCP-7Wee5hGImbTg0Ktc)4hr~3m)Qgc6n+cqPr!xrw|49(`7LJ+_!ppZPYYZD0dwvj%7>DG7vs!*IMwcm^&Ou;_M3(fyI{7)|SX%Z_K03j1~{!}=3%!L+x-;96A=xNR54r~0{+ zzI`+h01Z@rFQ|h71FO5c$q8_sfR7j!+<{&!0?|N~dN-bQrwHz_Dg%vkft3R*#50jZ zgo&SZDgy_(DQ^78&sl%hd(E(yl8ldtLJLD5Llhf1pt)RagukoNf@dn}dn5VzD-^?J zfmT8dLu>PQy-)5j&`x6r)RQ!lPq)A8G&rY;MKc@8-6=}nA>oQ!A84|X0xhb+nGiTR z%5B+jle-gSgDmX@f7b`42r_}2ZlhTMWcmkXc&9;%$b_7gQ-v zDaJTl*GFLxZ0J7Fh%cteLI?KHYk`Xff7hoTUa&(MKe8kU)C5{ygo7B7x8eS-FP)$Y z-732h6-68gQ%VB52Dv~r{K^A5!;!SXE($;v*a#&sl0nYEfv-WfMrc_oXCF0o7i~9X zW+3w8eO?6B_@VIVYW!W_6v3a6V!~ffm7pfL#~YMpH5+uT{;q$g!&9ngjA(pwE&{_` zL|02bXiWs~9_mAZg+Chfh;E<0-0-rtyNwQX(4gVM53=+-x2iIs@LFdmLk8>}_2B5z zmZRIB>v0IB!!O4D|hpg9;?Mg`2i3gM$16&v5g0 zgK#*{%ALX>)j9`&03G&AMNCpd`fe4 z!Jjy2g98K#2f_Ym2OQW%*C8kYA1e9LeB%3PANS@f6NCIQ={)=<3_Y~9z$G<04>s@x zHz`rU{+L!E7`V!YCUFN4ZQBK2aT9qSW9JPwDWm%Sh~#Q%-2cJpVs1c(w2qm}O*bRJ z3;3uBqmN6)+#3cax_)lv?whH@XhF3rS9>S?gPSo`-f;jyRl;@YH~fd2pMg{vF{#{r3#DmH8t8JXDiKwA!(7A(-{{+6^k8fsj8FJkGv3Rn*pD_Qz)7Xw zKQR zQwI|Qhv6`hOw&IF#s-rPV~5FwaWIV$frXRc2x0mKR7u3opljcA<#3l~Km*e+yudUA zoJ?;;a8OV6RtgR@TVvn_yR;XS!hqHV)o@#d=Sdi(Z$UFm3rst3q<>);OazP>20U08 z1!IHBV8KU_?uB`HlAA(2LzqF^jvNlq6Lf}Y<{d+)t^eJ0UuQ>TC)Jn?IwWpw7?|76G^^*;;tvt6ZouN8CYTa@1S3~B!!*KxsMSsI z2VZmqAyHlUiC~5-{)8!nByo(N3XUMKWZtusrq&n zbae~N85V@P6LfVI3<5ES?dJXB(dR zOg9XKMV^IefoX+Luyl9Br7R6DVY+c?OgH8NZhcF|;G2W#M%b8cR0y81PqYB5fZYz0 z!E~4Big0eK7U2Xcydfl<>GmRk2c0-kH3BA<=}HmM140%WLZX=Np>h}m!jHnl!F?M{ zDU3~~3uPq){vIHIiA;BY5!3x0sl2}o&lsjFtB0McJrZ(@7X+9X;-{CEp6YQ+I|4Dw z0P&3qIevuc9zw(qAvF&nRS(UDNr3^;4uLCnSy6K(~p5MqTCoAF!}ID^}jIn(mV~dBM=)51%LpJC{V^CrXP*xXnZr4!60&D zF-!?eDFUK!a(luFu4nowcHpvwQQsYSmp}C#1h|+%AS&R5UEk}ScrVuktKW<8-nZ9x z5wQxW-z#A4?f(GYd;71#d++#;QfDdzAbx597_In=vTE?~D5e{3f+>WdNa3xI?Z}l| z^ezq3^$N`ASV>jG^i#=v0J8?>JD8tgeq;Kp4KM>?#=uN~nGUlUW;qNp=;}={x56#> zclAD)qcHEod<%0Prk&}{2*W%P#tH*J=IwBAh9~o#FneH-5#}dho`@j}hC!*C z8p?uCh2wcQz4O`&b2 zUh9Xqw*b;iQnLp;eOcA|7-{FWr<73&DbrP4Vhy}P+b_Bw8;>GWbzFes^Lg80IGhj( z?2N!BL~>I*lzlcK0bq*+6S%hz`JP~5?2uN1mH?Ov&?LcBp0S^TL`gj~Sz-=}p|BmA zFEPy9i4aku4qY$7D%^%k(OjMZFkgU|XJA1%fpI#3#R81e@y0KR%D8%fPfD>vAh4-At-kt?<<^RPsjd|XwC2g8XDtHwp#+NpU?spd3087Rh^Om&Ae9$6%@Chnn9zvw8i?E+hLlpp`pKSMC;VJjEJ_U3<7ZtGtKp9R6d@`)dv?D7mlkoGT7n@7*t4$)Fb#$9B`RBx zf$Z5<3D)q)cL-dDe0Xl00GBoM#42Uz^yemy4FV;4Gkr^vY;K2riM0D*PZ#zhaQNI> zY1fIYc#d}J$=`EtQQ8*8kGKzj6d~6qV0J7;#Cd%JuQ&i6U0(n!S7KPas$v&_Jti>> zc@UOi2KJJ`GRzWl0+UiD1NTj;?mWO`VlzAfTdia4`7q&kwN7Fwz{W@nOUVx+j@2jt z&tE68N^T+%wR|LhP+61y&~9t$~2!~M=&1Nv8#wftes105! zHCqXsC%~;3%lSzKYXC|CyR{|&BA%M9(q#kjZRpIJJ4N}Lj-p%hZ)rz}FHDg3TG)%m z>QG|zPSk@J9+dWS*dOCz^~$J8FPzB6XYqT{B+D3NP@s%$voZGK6C&PiHlBD=i5|$d zmjQfJfMh>DfQLMzj2d-(n}|3O5g&hDMuyZJKP~O`qF^8Q_C#7c`;P_tZy>q$brJsG zaQs_8V&HwKizoUD@V-3W6yGm8i8tW;nP zA-woCst51r0G<}$J33zSxeCVMTvDmeyc5H1FBAAKQvB*H;qqO(8ujw`Q0`uJ3ykc6 zlA%c_yC@lCf3;4g_$1asgi1SdV1^RP zUOOe?K82xlDh;QQqpw|**il}gY9#NcF!uU*0luHY+nf{#0l)@7G84{+|g)|32%r1VW&oH==3*k5h=O` zfxK~C+C7Zb2TOYs?2Ba`fd6_~H+D)6)aUkapuUbc0PXhsZVqU)NZ6Y~bA(;w9gg<} zxK^bO_5fG}ut0)XzmbsJnj{&Pw@Ox89eE&`+BH;>x)0+n<;$vH3|O)TQGzje$sMHRYx;x(oG2Y) zmRn6RhE7<6O@h^uUl{*n4Wc2ySZDxj19-1=*(O1Zin0bFS1>{X|W-us$)I3=-fC9wZUtdiTPS)@@}*3c!uuqct9FyzZSio{I3{%v?RB9?bX2+SBM z++h%wy)#K-SgA^#2@OqVyt7b(2|W8nc&3rscQy+w94qL9+j&5d0Ru zcQpY!>5cjGD z8GBEbwf?yQ5X8QBwRGtSfCT{4BnTz!C)Bw2ZV)w##-HE2MbxaFCfNTnmb&)_svPfe zX+H^jrL;E+ne*PUY>`_0HwKHc`vi6Th0LMBYSt(^D6n%kbqO{7n*o+fLNHUMg0%Xg z@fiUQhzo#DfG3jY1<-?E%3$(n7=t!AkbVUqm8zA&XD- zk%_qg`w*$+hQOX6?O@8O>!ck;l{zA)dTGC>-jtQ~{+n2jrcJ6n^Jmd6SCO1DhD4X~ozo{@z>wV&sub*MNi@)-Nz8sTtf#{{;zR#p(qH?R*xPXlug0T89_gLdh%K~Rnf z2=?J%iJ>M?3NazUK1`I@8HpjIKD0}$Nn*{w?vhwD&!CnCGal^27X-GZUFg;{6~aCg ziU#Zf&;;~z#pe!V7Q%FTdx1Eq^9ZFEbwc3NUcc|j$<${AUZM~jC~v>h|P46_BBdbhb;eC%C&Xq`F=^_WF4~Y z;|$?&-AUd`4ztX_?i5&-S!QLH1>nOHv;;u#>Ek03Oc5hGnyf;AuS>8{WL#DeFxk>) z74hcR5lwasupflG>=@xLJC?Cef+ZG9{ZI)1Y!Lp57~2x|soe1f%JBLS;9NLfk7k!j z(t2e4Cx;}4jjc+*p`$)|Q)I|eQ2WVu(w@fHzxs|ff@K&J6-@ot*dC_-tB9Bi4d`4C zQ`c88)+{>7n)O&5tTJ!|0&2ceM7ROF&D3I%8wXGdvRqstk8YWg3r;t05)N}wK~#NU zV<|wHgpH*l2^-6RN$Iw+jC*O=LUThgKv|$~DCW*L5#lB=wb?I1+*HKf;pA}hS;jt< z^lZjj{5O@WCSKQ*u1}wq>H1Gky0+r;XYnGOt=Z~O&p-|4U)X0B36lL1ee=T`#<|cfZMRro%-vV?MU2bQcP?w=DDPA zTu3x)5Uxjf@q0x^@tys~+BwTd8b4+r*|aCmz- z4|x~S>_)Nkek`!vY1~ZMePD%GR;c^DQbLu)GWLZmv?Y)pl$a6}&o5+!Dv6UANc=)J zJSFkGodSFS>H8vEMDjoek9`kVX$7#m1y)+YZ91a5tPsrxctU{$y#T6*L6nxmJ_;C|s-xvgT z96d%-w~m96-$T*m&b7w%5Z<<1Y_x4ssbl)m+~yoxXy3Hi6wBry`w zOxWoXV8?{t(9AjB^7dRwc#j`3nH0R(Ku*@oMwmh8#MV zCtS7#8jH3JfKo=bW$+4+-%rzqG@YxKE|DgZ&TXy0WV_kcDjoh%0PtJk@P`6keCs0^dJ30<#J1=SDF@r}+g%|34)H{H0WCF25q-|B(s*732Ff>!CG0$31@*|=wnhQ!v64OkywC=N7e9y!4m+>- z3F!_6dw-ZG9ELVR4#1sJ2kaJs;i^~&7Jy15z$XNVMdI0?!E-nY zz|5b16LdFEsu^{?n2&_Va4t zXR7~?n0){mG^0IW-%1czN4cO-rYom&W z5r;}(eu2%X6z;HOj{Q1PVh6bCE4Z8G1!fi4EHAfxr3@YQ>&+s6u~d%z`he^M+F`Gj zc67g~E&cVK9$vP`6ED$qIp34-3sV_u7qv^fFqNO7_);N|+GS}>&EUGTz-&&&eiQ18 z)`q!mwJ0x{3vj9+45tHNTp+riHVrxPn`lj8=bk}SW0ute6hnHjbIW%KayeM{o9G*8 zmzRH^8JHL(DNuBu%V%gg_R5bYGRP@A;&8kvQeZtQds zx`j5=EjpjtbvA%kiXhk7WCGV!0h}YjDt@*FL1u$+pBTQ?W;cjFmNp0c_LT{TIVgsd z*XxllzSjk|zMSWO3yk``KA|OR(eJILZVoN)WSv5hfL%@YfQ@k2d9CoQ+IR4f@6eQQ zLV`M*1-_|96spaIjCJ)9*k+6|P~;>|x<(6ZOE$Hez>tSsGbDylbjq47U~iXDO|)As zsPnF_t{hpCtuqTCIo+uirhX|8(`=LbcBfsTGnZ}SJ+?5~Yap!?Oiu4;~BlM_+ zXArg@d13fixZ7XAiwS!?foX#OzxK{Otg34L_hYgavb+EbMMXtLL?uH7MMc9zK}AJe zCMqf_Dkz#4L_}0{k)l#rS)$Vrm6VjcQkkGp-l)iIXJtiYMMlL|+EKap##^56JKq;r z?tZ`LIp_R!p7Z>89Ins&&N1h>k2&U?W4u!?g!?g>gWC4XNQVm#k(^$J2_y1%5P9b! zE$QH8-MbdrVU&f73`h>&)T3(M`UNy^%r?u?zh+yJS!tHvI0{Aj_*U+|?oLJ3m}=ia zv}#V~>!gLU_IkD6;x`0Wj3hOcj30qqd`JC&g?BJHg#XgmycdMiuMBkgPs zriFU3zq2{gGo6co$m21ma}k{O3*OL@+2aLoJ)RzoIK6{P(k!3FcWm4NzLNm$HPI48 zLk2f16U}%5({7^H>~n6OnH1WO!kB>C?BBvsn2>A{MnKIw2*-kZa-=n*IMw4FU%q5Zsnb=(4;4S2X{PF+L(i`wOGfIelLj=@*c9a zMXqQWqS3J@McXP`0klsfLa z0it0|EnO=y$zF4lanv`sMW7o)nsKkW+1cZ_i*)aQx%obdnfIET42!|YQ9mO*ErwX$ z;TzoB=yNbTUvuNmQs^3*_=^O2YoExr4B)JYGSI(8mcV5KD>rFz|Mx0by5*Ug#E!d2enTtH8E;IT_Bi~gZ0qcC|Cv^M+z6AMH1%TA;rXWQ`Y zC>Dx{hSas;HiCsCqM;VGIm}^r;Qfmm9a{yB-zl0rFfnx|N`jW3Xl>2xv1JSW$Se}E zE=6nGpT$-u=nftt7O!Y+XR+vs>A}X~Sh=FLm9RZi`9|8*ItHQy-a1B7-8vKE2Yh(z zOylrYv=~Nf%L7e=z1--Xe3!18*Ai|?bCH2wPfLqQ2Nw#<_{Qs<#@gPlolyWi-~54E zgi&uyt&5b_?nMc;i1W2|DYW|Nm5Npl?JeEI*%MhstrI!tNIoesr+ zxdxg1B4AZl+JIlg_Dcw(XFjAA97fOl?RO#dM#*`Xu+%%#XgzL$$Qp0HikJdx^*9aw zFlk!rIDq|O()1S1z5Qby<>oUn5Bp?JRU*oylRKAhBC@U1WZ??%e&L(o>yk2r->Lp; zyp>bd+1!}2&hdXu*}x>Fb*|>P3{29)sO?~}l;&d+4LA9Qb^@BeXqbOxXsB~OqeLs? zVjGBf`ta=w7FLON3EDRChkG&O*vrsPi*{MGE71NS+7&(CL~*HBT9>AxRf~2PnxANx zkp+K`VquroWhiT4)o`uD4MfAW&S0+ZSOlhZNnrnjFg3x9u&^jh>#~)#A(-w#T394B zet2vOi!}15B^H!vU8L(YxK zbty+AEQd1(E6+5nucr$&R-uW8%F^|uXnCULL*qL*EJ_ot0NK$({1tG4hM|!C_y!q^ z(&#M<5{u0CHQe$nHAG9n!b{L*LkiTJQ4t_^Oix4dV+DD?{#ik4VVbz@G$D?Gd zpraQ-(2%xn7WOwBvz18;H$&^pS~ylZPz4FMK$AuiZqX~rUj!Ocw{h$*qL%$(@txL9 z3NivlFf4cp-EA|M!~87l+r@d`gwA(dIDyNd+l9t*=-!sf0Z(#%qYA^7WCYILUFYyd z;O>Bv-Q7sX$yXxY%DY(`>|ym3C{d3UMwBdhfj zP2KzT@@R}!k9iWUKN_PIiEQohGoL!r+lWHTNPlQ|MFab{)FYd@_jHRykp6r>W{Sjn zYYH+FRm7hk6PqG26V}j5ph@+LEa7BDmO+#LKe9|Tv|Io45)SS?o8x@ra-i|J(KOC@ zYy=He)1Mz!n#SePBW7q-N_(gcA3Ls!9>4m!MVCU8D`<2n9$EXkjn9B2m+tWydZ3|| zLrdpF$Cq=>w4v5K^a5)(GyAjIpz(c_$!62f(y_KeXzz(XyhtH!0v#(+o?zB}TuIA> z_6Pf$0DA&d3nyeLt*2SEEIrfkR|BoBXn4L#+C*euPrgYpO+@yQ7K3nmPGEmAg}Rl7 z7BdlU&y}prH0xoc%`Sr`7q!`#tU%hFWN1g(-<)KcT7jt|bSytcFwI3PAuS;gnpA~^ zz#Z<879a~AmNDD{8=r2$U1+WObPLd9lD|bb^x=W5EefQU=a}VC32icKi!13REgs<{ zLF4hQX=xJ8CdZSH%h1-dzhu+`%Bp3a&~~%7%u}>jXwop2#nP+^U$>MK(D>W7t;7|F{H2FNOJ#rQp#H~&8?vB9u(lzKUOD)>VSS|5 zOImLhuFe$ajTUG!lH6#amw3>Mpylzg8!>t#Z4>gPmkg;l73e;6HQO8r?F;s|IZzMt zgqDqJ+Us}Lvhl*4v?p=C-tAd?vPjP-?J4AG?_R7um5Q&7kcP7C9VQw^1*AQl4o#~4 z(|CAbXeH3*u)n8EIPbUkK}%z8iyt@NEy>Wfh?Yzby783B6WT%6p7qpgNy`a=R>oQm zX56-Q@9K)|>;0Wb$UYiZ=1{P8qLuJib33xHj~i>-EnMW=TR`g}S_{3Bj?G2%`bcr) zO7wCOy*{(pUv4sok&A5ZBRx|tsvpL_ZoB-UNfp|KnN_46CVvHd?BN1V?%`T!XGE(t z&gXiB!mVKKh`tmlb31|(>hrTmh4g05*X<~BzRw-jj-KES@hDCgC@tnFPDlOvF&ngQ z?C%(!JJYep6*L*m9#@$Iv%5E(rx3ZRA{T%->Fo-l{_5? zEt|E|s8!S(oF;#JL`&t4^Ym3{uZeb*YucMt&@QnCi(E!$UrOhb^p*y4HkT$SEl9Dy z(ge=t(rRe#qE+({;qA-N_`$U4?aQ1mXHdLBlHM~dIA6{zf+jV-ZY5PQ4%qOV2edQwaNr`Ul2!Ee?Lkr+zKZVUe(!ME!Cavw8GLGN3 zR%naa-?vtd-?tIaq)L7p!SVaH9GWiv%6D|a=_(PuzS7ZE;x#Na-tSAHoo8>~y)UMz_M*NC0~s~_!!Gr)s|v%xZp9IMG- zK3a5?T<}TZv)~_??Mo_@*56ZhpsMvBEVo%Wxc_|NLh!S~Mc`uLOW;aj96O*X^ApIA z0eyviz@vrz!Rv%W!CSlA%^2}HKY@BMKqj`XM_nB78hcugSP!_syn*zOg|om{Wv*qc z(grpaP6m4kr-FM3r-KIxBew>Ql{@2D#A0B)Y{Y?A3X`WT%op;&d%C+LqAnNm!3UYk zJ59gz;X%r)UUY*A4qhrJ7Jklc`7 zFO_FiH&Et-hOoyQQTp93@K}S04vJ!}2Fr|nq5Xy;8uU18zZL3UctFtdk9cVNSu+?z zN?(kY|EN&f;2xq^=sW57Tb|HlIC=}8bu=E7!AyrXST4eM{JBfHlMPL}ygS)E_PkRG z?JYjx9lUa+uJKM4G`S171A~C{-q&>Z2t?`6?;c@~umhq!B3I$NFr;Waa)J>M?U7M@ z#y?~ANF>M2r2txrp}{VQo=%$AWoX<=6?rj5RXmc67#HMZ_6tC55?tsM3ZsXR&=KKXoE&B-#)zEHH-+V!u` z>|zB+31e;#y-s{Iv9abq`mWr<{oYXX&E5!q=x7e#yHv03fjsg?z76G(gxR}R_o2M( zsG#vZj=3X@;~JVbw7q<6M{iDdM;~Z>`GFY^L+cvj z6*l#+@#^RY!@pcN%^m$XUL8^6hDqjkjFosHpNH|V!rU=Q;*|xhufz-YN=96>p+$;@ z+fPH=0*xD_x#Jd^8-k~E!!}A}>406rm?lb@IqbE@NDr5_I}Y6lS&z|%^Y{Zyh3@MH z%Q4z;$)rwk9B`+2Xr&yPPVt-&Se(&@e=Qp9HWavZ8A_&TwBh$z1fvZ6@E;z$;0<*B z!z5cp&rpfB&?u8Kfk_KiQ3S{_33m?utdtgXK`OyRU8_pe!xkoHd zX)^mSf|$e}{TH!ESjy4D*NB!(&%?WnB~v+C_)Zb?DSjMRCx-`L%p6yk(}9sJ_HQuW z`tTpUM(Z+#?C)q1gV}?@Q|moIFKXb1fSPAepwaYT3U;1}IUtx9(MCw7gm9<7hg=Q9WuZsfu+TTSh)9ZSpAVRB^HmW~sq1C*`)I1~u;yMf@TfYajpmmk=23ODw%gZjbR@LL_~6lzQvF8b z;L#gIyh$(PaKw@m)T6@(I4anPbs#$J}Bu7N0w# zqi6UlZR|+aX87yXq|Lz@$MS&IJjX)o$Z*EFg%Gc@$GLdqLi0Y&^YidruQQADjYm-= zRzZ}GX+AD+^aj?P6bX@UQ^9&gKZLU+9vVMUGB1gzM-%XvTn_OUK4o$_O<}~$4Pe)nItxusxausv83irV3hg-i%e3m{&>p4x_i^`F1EV(kQ4NRjZDMX)%v{T# zs({*){XbQq`}fCrpGS(KrN?-_ie_cvMQijLzNV$2JflAn&Q#j?j>0+M6~afr9}1T# z&DLG`Dp*Vtq#+R7tD@gj+5|K6N|eR~dHRh{zGxGkBppVDRt96^3-N^PeauHV1}vlc zl?mWWqNgiuVu0{g@M__Fumrpkxi#^hqF+*4OpshJwo+~-7(Ef?p3?8%c5B`{W=vz3 z5p%%kG8{*tWb;d#ByIEsyws&W8TP-lNiwc^VW*xEK^pR8(sIu97s|xn6=;0FWPag_ z45(f}hE4iNJYJ<42Bl8;uw?j%rwzw@+W*WCi)oD#?9L)LBF!N9j3&MRt5WP+7wq2Gsuof7dP|v zYKR?0)a{4x{Wmh^rcIHH!;UD9&<=z>g-7}39X6iZP8Qs>DRRZ!ks}e>f#gh);@MG4 zcmBwA*nHEb$T&|A;3Xnt3{IQEH?&|WG`$oe-z z+OM3W54MFvfk+M8<=e=*ReioY01U~U}5XGM&YXv039HdV&uxp{Iln%dOU z;t_9@+1@2lnKVGzJdZG(X`M;Qn%9M`+WA z3!eo~5~lMkV76GnX~M|UX-^V+!@{0FHg?O75b#mqFdjKhYc$WIO>Zf~-NrX5=G=0n zP2VP|DzDF|%Mg!?c$w}%@T_I1dz;?V&oy==amFMDye`57$NI6yE+5zw<(ob8E+6hR zcA?1Ps`zBPqC`V$oFN11UHA|KjaPSNK^q|cvUnk)IgdO>vzV7o@3B$S@+u&16tP0; z`EE~$g)Hv&tQS!=W_%!`jXSK}@z8!3EuIa4nD?L-%=BS#Po7>wSNpxl&Y66lY2F*c zcLIACL0icF_R64iZ!)xJL`#+?viB0i6Cz$Rs+H?rWa~^BY46pKV{)Ur`K3~&&1%X1 zUP7b0NeSF{6=Eoh`>yiZS@Zs2h)Y=9A1ou6{e=+siCCyt4M)5WA|q$X*!>{xLdedA z`Op>^W}U|#4{f0*g%FRVLVSa}%2nl<1)8Mh zm_;;X#oRXR?^rOm*<&cJxzcqW3lS|8T7>uuLHwJDbs`?OLgYt$=HvJj>qwmP)w8$`cVdtDomlJD3r_aj>gvWhNsdJ1NfLXJmnt$4WuDa((p$8jsF`75aYyW0?mI#+}@~ym?dHr z5AsiXL*oaW=9Au{#Xyts+)23uI~fa28tzHFrlLOiWE?bp4rM+mCi%?8W~I%O3wE(t z9%B^SAa>=Di)}nsF0O_qBi7<-=|hX}LYyHU?}}K0?3>50pv)y!nqH5@lmtSQA}I;v z2$i7N=N0hLB~t7qDE4`!qJ`8SjMU7l5HVIVvLqAYA0lE>I!*02mt-q#zL$u2VnrQM zNe(pWh)Qy#j7yF{l)7GWL>|hNAUX3l$R*n z(p{cSf|$$V*(7>Fig3;$JxP*9=a3#Fmgi8BlO&7I)k)OPXF!y$@qC7KjTcIkwm|L) zFW?oDad??GM7h|PdCQGrSrNoc4!x|1?+M;T7A=r2=H0u7VWy$x_Yn9(=}o|@ez31O z4EC9Mu>Zaf{7dKczK@=4WWdEM5Q{jpi}eG~i&r5^a2N4{#VF*9Xc!B>6`!~-peFx; z7c^v zHzdkAo>=Z+4CX|Af-d!O>0dsHBAXg0t54Bt9{++*@@chP4nDKs!zGekpIPKC@pEMM zA}JPpk&j!==a(T$rTF}^zLl!;7ZuRb`IKK&kR>{VQ-N?6NhPhQesBh*`76}HMUppP zCD8I6B=0Kf+hTe432sQO3y$br^M{zn2Ve6yGTnYH0NU%KVKGB}rD+<~n7?3cvCOPpg;HPQ$`_+mD8wam zm{%h=mx$4f)u_fxPKl25FZsK0h|-pN3rB!cyHCg6oN`_riw${7x;hD;u93UQ)tO+q zQCqzeEO(l#3&3@9q9aOMR`34=I6}sP@~&Xn>c-2%vagKGLw{QmC5|i1jdZ1@NGrI3 zL6b2SszIz%4sx#41n^_Xnn-9e&Zvo$KDs7HY0G8ERb#BXLq69a8q1}ttEs;as40ag z{c#Q6P8kjU7nI0ysW89baeoaJ)2~SNa=8QgHB)a9iR$)SCA7O7q2DUyF5>qZrKNUY z@%I{TM8Bi4r4AOYmSzLvjQ`ArIG@FTX6u*ejJN!t?Pcv2K0;60opNXwS-VrtX1mPy z3YE6P%;LR5J&p!(ea~1PvGm-{kza4f%or{&5$nc&I(1j;(~ET zFn4ogs9IaW_a$Jm7zv+RpwiO#x(L=Y#-K}ZZXOTuVLlv;lJvuW__;#=ahJeslrUMK z*3$T{4y?ydLjqhwp{?d~xQ2>`Dw%dbvmrCedIHz`M4qhV zp%RQ**NdqT`Hl%zuIoiqxs{vcoaqvHCbYw%Wg42RD~fI9=c4KEhcU7xOV`@UJECo= zKjBuTrTdGBFWMP-=ZdPCK2gM+dJ$Ql&KDCH&#o8qARZN;dG%sG#GggX=PAg}ZXrrr z)q+L05dG>nTnU|Nvhu32EMl@U-Np}f_OwDwW)X~n;X<+)eGC^8GZ&IK3S`w0_U|2v zuYIDBylv1v6wM|YD%q-kh?XE4@^iISv~KXcSP!HK!LGWN;lUoe)zOm)+)!skac7xIn_&BGwipKrsHawfBvVxaXT+Vw*c+=kA$G zTbIER@1ChgJchCTx~CeCS@+{#k9jy)Y4$mM%)`Mnw1P>&$K0FiOXJ;L?EaBBdp|eh zxt;$d@DyhH>WWGhjsb5FrVDT$b5AdDk#I2hqHq|vT9~epw}q3D5I5l*a91}NXvbgA zBiIP#9b}GMi(w8hgO>`IgP#;eM71N#WNceIBU}jnMEDB$26JEyR`oS!4%!Ls$Q&GE z$3|b?7=YoR(^zIQneCLw99{*^WFCcgEKb{*$(pp&ap7$6`@#j_ADE*&!S{rbTc+;9 z72qf^!dK%?VB>M#K{lUF*}^5@L(CHqfawF~7zAwkr!f4O1DPjX1rK1J9t@r=oDSY9 zd=o4=M|PC$=JUKG4k=e8FL%2lYqhrE2*5YO715#|*kP1jvfh`+Zf7T3^T1`fLn>J&e?DaMs z%DinWcp7sKBHeTqGug{+`ke4p@XO3QPk_%d@3JGsO@HJKGKkyE#7u^8n@KI*cNr`J zlp^3}a?%S(WwQh9zw9npD&Tt-ybM&VlTDW9644KlnC44Z|IiP7*iEDQr~Zb(n%D4- zkB~(zdNF^Da%~}%=wrmXh2#pEer<7%{d}FJl&cdnnR;~%Xa2niEESndySkG9Osu;_ zL|s2M{E($pyK?1#4GXJo&axw0DL0OUX0m~kSU3BCImL$gRJWg5cS%;t-J7{-D)>?1 zI&hpY0(M`?O!iLQcM#jLh7#H0&K(GSkx98<7f(pN)m0d&vGx|e3?3s~3r=7ro26E+ zPxKWUW!)t@>H$U@)X{0p3&7ku41=UrJGW`A1yW}Hnmv&PQtJ(2Z>2n3gps`-4>OaY zQIAo=$Sse#U}P`Z5A~o(5Zk~n3de$}1(6;P{+!wFk%Wz#vI8e==^>mB?g2)uJ+^?k z-5X{(TRz4*S>tR;0mDzr3^3Px`Y4rZ$sLYiX0v53`ysQJE#DC?1pmVQzeaX0TX82t zAB|G2xGB;{q*N>JWHhp8*=hqHJj4_HDl^%yZ1pAcuxjuv=HUrSc}kHD$2mPCSr13* zJ?99Qq5gYj$VNHXs1$hDUJ2$a8-1}#dH%qD$ns=s?!~mR$f4GQSSKr!t!FTkb;;IQ z%yB4!)~|q(?K4Wj?+PPft*M^bX$P{ajYW1`22-p_zXGPLCPwPpqzhjKQ-y*)vkpvI z3MN~SZN3xs0ZXyY3RbEuMVkCXg8MMXZ$%a;RPmzMQFEW!c#kOw? zmw~0pk?q8`d}Y(-hAHJG#WxoLc=@ycxmn;L!r9=7%w!PJYk|RbjVvL0t(P4L%xfp} zJPY`kFjD4qQ8*v`EA#vqrP{eMCk23|btEC8?Iy8KmIvEO9U_Z^?Ve|S;TG^)(q0!M zcJ1V(WLU7hl|7Ng!1g}EnPAE~&p>X`#sF5 zs0ZyOVQKbiY+U6XD=WbgiF6#?LE8N)1kk~k{g55M4#R{|WF4e;BeQ)Sq$0151HZ<8 z)*#Xy{?5EM5btfILtC2!?#BJUVT;c@nms*X#SUp6WP8thHS5nIa^5`h(a6-EH`QvS zm`v<>OOLjd0{DgXZHPoi$we}y*Reb6I}5WEN$cCvKVMN(4}1(qzW!2!Nfel=IX0enCWDxL2PX0l%9EA@knmig{uo$QnO zo@XZeWWL`Ehk$PjM=I6TQ~Lj3QI=h)BSMVG`dHVE!Z*Pum}^l#y8b8}2d)!Fz<$kz zYrsLwWJt^}nfdoJ@J?p38|GKR{I4AJ|9%pqe)V-}R&fk3u^Pe$bYOV<1FzMBOH}4=zUfsVk*f8ML z!;6{hcJ<&&WSHyf@eJ!^rmM#pW>+(qo1bBo%b%N^lNCkaKZ5;uqJH?#WG3TVcK=Ll zWGchxmVZ9)Amds7T=SjU!IS?dqMrcY5Wb?+LmtfDNZCXEn8_&CL)_0hkuj`?o@AYj zTs_2fg1(=q9^!gtr;jYEo?N-;ql>C1-+uO61ul7YUazVxr&90naAxH(i#XDBx;2^%Wh7};C`i8To8Lnl}OQhm95 zc7nAZ)vpQrfi)l1FOV5ld{jTaFK~Lw6Z|sku-c>gN%O`e9u;iwz&rF%Y)IMX5|^@` zcS5QD&6xKh68*<9!wiq={|qx;&#V4r%rLv72DD&4h=>k|U_Ok54UozX`#EaBE3DgL zI7bbTY4LXXA-(xnn7vUU zQmpSJfTgm(g9L;maQ{!ACsiR&$pKrzCz#(uc7k1)G!mH2JL74svr1*a1#38LErHPOu(o?cZ8Ap!T!PsY%q_G$kK}%oXYyOK(J)v z4_RPomQ~qc=|8S}D)mSg_(u;5!z}6%$_e5+a10pXJHgnAdSpJI6h=MV?7Lj#y$mPCbepHJ3ER49)*V0i@ne`tx}iL8&P zP#$QQEZ8xmCF`yVJOG@jU{wTcW8GQ?=F2PD3Q*OTu->7Da@mui4K?%)@ly(ZkDG+4bvZVEkR3?PQ0}))FrJ~pxPvmmc!mn=%zj`r zLxlwiqqc{QXYPR1hjHie)9fgiabVb6#xQUwlB9t1Y*ndxY{xd9`H(IasAH;ax)4?iM&3H+(>Wu?Mhxc{dQ z^{R00&*{UxDtw4|x(kkF4zYsQGQ)m@3g?F;KKGyiFQIfm%@#Way z4#b2-{VK8PcV0|W?r;hu7)9f;(MoTlBlMI$@p9@c;NAUqzZLdbpVa76hHF|~cU9irK zW%X+GNoFjkSEDa6V;Q{~eT^B*=hf(Y%*#B{|BmsJjaaahG1keeF;T3i)Pa{VV_m!& zBPmNm^H`el#1eUhG`Qb8a0r0 zEJ#=OD83$>uo7KGNze5p9l(PN(^E)IR6ZYo73V5S%JS)S@OjpsE&+eeyu}Y(Bbd=?QJ|2=bgFj(qDd8Sgf*3$oD z{j{=4*}RXkv4!ygSTC(?5(%u6RyJwhSRbuyTi6fQMJt=s39N@!whvkV)(V#5_%;Ik zZ_&$@nm{!l5ygUMyPDw38{d~=hqQugVcLXu;kXAO0d+eJ5^xmC$Q2~O_aKV6{heb!y~LLRWT?Jg*R_l zQL17nrkRR9_O4=P3L_FRS;7b)ra%}0#9R`t22*!V$JQt{sl9M5nCcdEtOr$-=<#{m`+svsA8c^;V&x;=LH7_($dxIay;$i8Hp$&Zpv8u<{h7Pn1V=J=F9dVnKuZW!>=M?obWp`U z!R)^XoFkkJ<`zK<1XV0w*3DS(r((JJ(K#EO0UF;l$rFV=0`nPrEG}2}(_G zC7cbO#7rZf>CZA_shgVqH8YmDsW@)OW~^*eaot!SgH*;nDvVr-TgZ$BY$}dBC^HtW zsW>hUJ65SFHN%5FVWpay!9!_Upr&T5XFV3>H{&Db8U9Mmv@&BInwpu&Jhu>B$UHv} z{IPHqm&d`r+(v0lnVPkaJz*`Gnk5IUI;-%4n)OU8coQ>SQsZA| z#(FRn{~H*^_dEidZDt)yo78N{6)b5|vqy_w29|`qV84P5?r_Xlx};{mC!T7-Uoc~( zlA2vB?61_Eroy3MA7NzaoPoj#U}-7a(!r8L+i=b~8RF+A_<8RCX^oMZBUwjJCFZ=t zp0J`w&EdNu^Y#qzAEH+)HP^(9bwg^d)SDeR&)kPa&jCw{u{uc2ozFTJ1*y3^g-@XW zoy+4jtoy+Z9z@X6AC=(Dp0MIaB}lWxLLZedhxJ@JI`U;~s=FJe!0^3*c23DJ>c}IjRz*5_HqX_2x&iZb|dVV|Mc6EZ?M9oLJQiQN#M9n`ToD7zxiv=Po$%%D4R)(k~zSPo+5S28SckH_g-p;%~82r9) zp;8OFGap0>7CggzXbbos%vju^7Pb*aVipc&#!?QoP+Hv49B`@h|5$yY7JkZ}uj%`5FWJwVH^F~0W3_-< zD)j)X1k}71J7pt+kEg^X3Sq#sX5Ho{K1EX1He*bH`0|_ z(Vlfo*j6i|g(JZzdelE<#sqD(;uYC(0{pXZsZwcenK27nrAcZq`C6qdWgU~QRob)6 zm}{-lQ2JQmDN;a6c|#xdWrBB@Gjx4;CF?Q>#OZ_Nu>jj znl*GSCq{X%nI@bMrb-GO6N}ZFx0&gQ=o-2-L-({QmC>0QQ-oDUn6M2@^#*>t6TlmU z5$TMVneE<)UB-v9qXta96%Oc(6tAVqNQ`V>JB}Iid)30XSc{6#OT1XesJ{=3~4uBoMq?*arSaI65JQ@dV zxWN2aJoqc-i3oUuq;g`6Qd!=t$E1RX38PrEa)gh7&kL7;e-gfgoY>f$H)8#i+BjJ_ z6f6hC)_`xbJ`LrtsjaXVIDi?JgRY$s-zBvaY`!YH!rXyGt$ns5~Opl|~CGvN&IKZUcE zda|2cHVUvI^f@G{X+G*9jkMns?dNVpm-CxXc$^^^zeE0D^kx-h3L0P1swhXZi>SgVzd2g5MR6 zQR>-N!pN0pQ`}6{|2wZt$HphJW2;in`3UEOC1BWnP|xiW{Sx>K;Yx6oFmmO&e+$gC7UZg}<5*8G2d`(wIw`x_dQ3Kuvgb|ASSY2QmnOFwDSLjJ=mFrTghRk@2}daP zLTlkz@O(*BjRoLL<-FDhoWc4!lx5CV*4LqE zat;b3(mAKZ&t>pMX1i6X?OlbD6WarYkrUg82&aQb3EL6t?W<*@5`09s2K+U1W(4@U za3uJyaFkLzT!n35A21S-iGX+X5j_qF$b~9yZW&t*ylmiOEMZ!hk zFNH6`riha;vQdAS`3amsj}b=B>5mKhgY$($!LJD;!TLMQ>w{7M^((T0^45Q3-hgb^ z{}9ds{|QFQHXsr^+cHB|JA1I7tQO!9VMJo*67hrF+WDq1a%<;T!b#vdx8~IUH*vzo zi_X{}E(5m&XM!(-yNP}i9L#J&`Mo$+_zHLq`!`jBS23Htz*~ip6EE&#|K@n`8R1gY z{}->yMmcu;CS0RbZWAyfVXgzWV|GRibNz*VzysMoS;xt>2_t~q1>z?eyhe0HI(Mfq ziZ%BQgY8Y6&tl_4*+GH*$lSyNz9pQX)Gk+HoOIVi!YGbiBfy9#EWxQ=Gle6;E7^}r zEO@ijNwZ9B=&~aVTqv9kep`48_%kp?0@=9xA8zy^+$PO- zg6{~U-t1{5Tnp}Du*>uCzb8~U2Rx3s=nCrpp4qZdfgNeWSHaoBmEb+XRp8^o)!=i& z6!2HV6z~mUw3EV{~lqaZ2uvg$ZGsk``;EF*}nfhce-Ct{#U^tYO0yB1+LLlQ{e)5 zVIB3qphx`%I9yXM^`2%p9FXC_I~@ERb>MOb{?37~H}cD#4m?0p7GD3R)XOp0kbqxa z=)mh51AcisB1%ca-^+Op`Wu>Zsz3Ik1Aptlzc%s#)yVb(tr|BDbaCK*4m`wxqa1j; z11CE0N(X*QQ%yL|>cAdNIZH$j9McpU8}&a*9r(=HV7?E2!a#KpWzoPWvj%SCz#WmL z>|Grkiohg*gX7?*p656)B8PyDzk^RB{~Hd-aoBOlK|krhDC7Fn9Q@ir|G|O(?!dJU z{O?9CY$i{(y|7he_P)q9%c*WI$y&Txr zfgf_W;lOrO zmWCauAoY9*(7>o44eaf}{tn#Vfl>Ai{?Q5=7#&&zFJLy(e+W&YzKjn!l=q=c4*IhW zyu*R_I`BaUKIOn~J8+o;UqSvi1pJM|jvpNOx&u2jr$e_I^~31?>d$i+-Dm^1cVKjG z4La%vv%V+~*3L)QZz^@zp|KpE=Ah4Y;6)Cc>cATtm?Xob^O~TL4GgsuS=x-ZslJLU5)cuyye$lei1PW z2TRiVH(uEp7AeoIv?D`)x5#gv{2q~CM9}bufQ{d)@>?Unclozj3;FftU#AM?i8qZ+ zoZ#R1t(4y?yFj)4;zWjrTK+YM$Zx3phRJV){37M#-y9{sHu;T_-&pyL<6mcs{33#M zoHK5k89e0|S!3)#%<-!{m%=5(ErUyeTMm~Bw*oE=ZY5kg+-kTra2N}Du7z6%hZg3U z35QFX=X$sea9MC0;Woi-#-vQoCjndFo`HK7?m4*U;a-5-1_!(Co;uu4xLmkha2RBH z?uOd~w^vW!>;ABINYCHv{>X?^P)@_W30DgD7Tnu#XW-7lor60McLA;p?j5*y;ogHQ zhkGCHqHfN2-*0~rxC3q#l7K(YY`6lrOK>OP{svbJhasquY6|uPxF6w;!MzSg!F>vM z9q#XNH{d>oqa3;dcNUJKb`g%E@(G+o&+b`*jUqUV(mh{;qnx+~N4anm?mM{O;68$* zw0sEn4O}hUKDhmG7zuiQ21hyd1Kihel$!_PzJ-H<1tXVVz%Qkp@__Q|4Gd2jGUhmh z8n{>Bs^GqWOM#)=kpQRz}CzXeC7o(Z=R4wcHY5{@buRlGHD>*1b* zqdN9I+>>y7;eLnv3N9ILC0u=_{s-83HU3L4UbNr+-B$X-bgRD}|D8*P9$)FQTz|R5 zy|sR3m9@1V;^Sh~-z;$t)pPw^-1VaGT|Uy+o_6o2+poE7)Sq2r_0mV2c5kH@opN{4 zAN|3lh5qD^F3pSYSGhFPiUYg5EU*+WE^~j%Ti^VqwWscS+Im2be$zTgzud*LMlb4O z@hOgvayf0%x7u8S_4YQGl_!68|HDlW`_3Ao=Y3;suK)Q@_Y{5izufcm+F33Edh);B zOZ2U`5SVqHi)-=1N^5UT53IEI()WIE9ada%%RNNXgYUR^)jzrePeZP`G}m{JvozPg zjIwmr7e`zCXvZ3Te6*#LKK8Er!}``}i$(t>&El$O!e4R8UH5}7`U?{+ZS=3ET80*% zG+VngZy(gpma;T`!Qus}t45_PNC@vcB2CSjH7z=*pZ;nWtC!YKAMI=HHg1q@c52du z6^Sbn8+g?3S5etoY z4ANV4_wcqX;7Ik=pY80?2Hzlgext>+10or&K@1qH#}wO%7k&Vm&~4@n9@Hbad~2@#C+_7`-1u*HpAv8E=di?x$8YW z=qIG!%ZU2OIi5WzC?#?6(zHb5B!-W^$kYcSU?h3i+|&i)YxxM9t-s;F{)BqaQK|`%c?cf1=DUO&sb~*hREz6V9MMo)`s%-Kva~@oZO>ZT_IaR;8tU?W1-ct@Tefx%4oNMJ>J5#oA-Y0|6Q} zuOX*VCC1L1H_s*+Vsj`1ZV>(S-=22qY@+7+F{*m22hTNNcEZ9H`l}mV+PXa$f4xr! zk4{d=#h`qbu}1EA|3@B%pt^D0MGSP0Y)dP>a*D+q9xbI9Y?R{SrAt$j{_8Sie}fh* zNll!eLK!koimsm?@Q_El$o~khp<8({qK!@Zft1x}^1Owd&Bc>exoFLbfA_T(dbIj4 z8jJpMu(iW~=7CWZ`}Vp7wTue-&&Hrfz2xGhH~02v*~uZ#7mNs*HEZ6AC39!ZqU<+% zNi?iZdUAiO2e+=i_(8*&f*;h-FgS6kfm<@;PZ77qxqc5%{zcU-V`C|*9;`js}YuY~{K_|-gCD#`R{q~z9-HaQe{ktj{Mj07 z$fN)5B~iyEF;)NCW{E6bTxu)L^fPzeo9f5Ebcu9x?BshV z=@Z;6Q;UnPTe~zhF0IA5v{p2sbeQ#znt3!S{@}K?rL)$z_;R9Uyk_XdL7IoPsc!wr z>fD4cMS9Ro>zZB -#include -#include -#include -#include -#include "DetourNavMesh.h" -#include "DetourNavMeshQuery.h" -#include "DetourObstacleAvoidance.h" -#include "DetourCommon.h" -#include "CrowdManager.h" -#include "SampleInterfaces.h" // For timer -#include "DetourAssert.h" -#include "DetourAlloc.h" - -static const int VO_ADAPTIVE_DIVS = 7; -static const int VO_ADAPTIVE_RINGS = 2; -static const int VO_ADAPTIVE_DEPTH = 5; - -static const int VO_GRID_SIZE = 33; - - -inline int hashPos2(int x, int y, int n) -{ - return ((x*73856093) ^ (y*19349663)) & (n-1); -} - -ProximityGrid::ProximityGrid() : - m_maxItems(0), - m_cellSize(0), - m_pool(0), - m_poolHead(0), - m_poolSize(0), - m_buckets(0), - m_bucketsSize(0) -{ -} - -ProximityGrid::~ProximityGrid() -{ - dtFree(m_buckets); - dtFree(m_pool); -} - -bool ProximityGrid::init(const int maxItems, const float cellSize) -{ - dtAssert(maxItems > 0); - dtAssert(cellSize > 0.0f); - - m_cellSize = cellSize; - m_invCellSize = 1.0f / m_cellSize; - - // Allocate hashs buckets - m_bucketsSize = dtNextPow2(maxItems); - m_buckets = (unsigned short*)dtAlloc(sizeof(unsigned short)*m_bucketsSize, DT_ALLOC_PERM); - if (!m_buckets) - return false; - - // Allocate pool of items. - m_poolSize = maxItems*4; - m_poolHead = 0; - m_pool = (Item*)dtAlloc(sizeof(Item)*m_poolSize, DT_ALLOC_PERM); - if (!m_pool) - return false; - - clear(); - - return true; -} - -void ProximityGrid::clear() -{ - memset(m_buckets, 0xff, sizeof(unsigned short)*m_bucketsSize); - m_poolHead = 0; - m_bounds[0] = 0xffff; - m_bounds[1] = 0xffff; - m_bounds[2] = -0xffff; - m_bounds[3] = -0xffff; -} - -void ProximityGrid::addItem(const unsigned short id, - const float minx, const float miny, - const float maxx, const float maxy) -{ - const int iminx = (int)floorf(minx * m_invCellSize); - const int iminy = (int)floorf(miny * m_invCellSize); - const int imaxx = (int)floorf(maxx * m_invCellSize); - const int imaxy = (int)floorf(maxy * m_invCellSize); - - m_bounds[0] = dtMin(m_bounds[0], iminx); - m_bounds[1] = dtMin(m_bounds[1], iminy); - m_bounds[2] = dtMax(m_bounds[2], imaxx); - m_bounds[3] = dtMax(m_bounds[3], imaxy); - - for (int y = iminy; y <= imaxy; ++y) - { - for (int x = iminx; x <= imaxx; ++x) - { - if (m_poolHead < m_poolSize) - { - const int h = hashPos2(x, y, m_bucketsSize); - const unsigned short idx = (unsigned short)m_poolHead; - m_poolHead++; - Item& item = m_pool[idx]; - item.x = (short)x; - item.y = (short)y; - item.id = id; - item.next = m_buckets[h]; - m_buckets[h] = idx; - } - } - } -} - -int ProximityGrid::queryItems(const float minx, const float miny, - const float maxx, const float maxy, - unsigned short* ids, const int maxIds) const -{ - const int iminx = (int)floorf(minx * m_invCellSize); - const int iminy = (int)floorf(miny * m_invCellSize); - const int imaxx = (int)floorf(maxx * m_invCellSize); - const int imaxy = (int)floorf(maxy * m_invCellSize); - - int n = 0; - - for (int y = iminy; y <= imaxy; ++y) - { - for (int x = iminx; x <= imaxx; ++x) - { - const int h = hashPos2(x, y, m_bucketsSize); - unsigned short idx = m_buckets[h]; - while (idx != 0xffff) - { - Item& item = m_pool[idx]; - if ((int)item.x == x && (int)item.y == y) - { - // Check if the id exists already. - const unsigned short* end = ids + n; - unsigned short* i = ids; - while (i != end && *i != item.id) - ++i; - // Item not found, add it. - if (i == end) - { - if (n >= maxIds) - return n; - ids[n++] = item.id; - } - } - idx = item.next; - } - } - } - - return n; -} - -int ProximityGrid::getItemCountAt(const int x, const int y) const -{ - int n = 0; - - const int h = hashPos2(x, y, m_bucketsSize); - unsigned short idx = m_buckets[h]; - while (idx != 0xffff) - { - Item& item = m_pool[idx]; - if ((int)item.x == x && (int)item.y == y) - n++; - idx = item.next; - } - - return n; -} - -PathQueue::PathQueue() : - m_nextHandle(1), - m_delay(0) -{ - for (int i = 0; i < MAX_QUEUE; ++i) - m_queue[i].ref = PATHQ_INVALID; -} - -PathQueue::~PathQueue() -{ -} - -void PathQueue::update(dtNavMeshQuery* navquery) -{ - // Artificial delay to test the code better, - // update only one request too. - - // TODO: Use sliced pathfinder. - m_delay++; - if ((m_delay % 4) == 0) - { - for (int i = 0; i < MAX_QUEUE; ++i) - { - PathQuery& q = m_queue[i]; - if (q.ref == PATHQ_INVALID) - continue; - navquery->findPath(q.startRef, q.endRef, q.startPos, q.endPos, - q.filter, q.path, &q.npath, PQ_MAX_PATH); - q.ready = true; - break; - } - } - - // Kill forgotten request. - for (int i = 0; i < MAX_QUEUE; ++i) - { - PathQuery& q = m_queue[i]; - if (q.ref != PATHQ_INVALID && q.ready) - { - q.keepalive++; - if (q.keepalive > 2) - q.ref = PATHQ_INVALID; - } - } -} - -PathQueueRef PathQueue::request(dtPolyRef startRef, dtPolyRef endRef, - const float* startPos, const float* endPos, - const dtQueryFilter* filter) -{ - // Find empty slot - int slot = -1; - for (int i = 0; i < MAX_QUEUE; ++i) - { - if (m_queue[i].ref == PATHQ_INVALID) - { - slot = i; - break; - } - } - // Could not find slot. - if (slot == -1) - return PATHQ_INVALID; - - PathQueueRef ref = m_nextHandle++; - if (m_nextHandle == PATHQ_INVALID) m_nextHandle++; - - PathQuery& q = m_queue[slot]; - q.ref = ref; - dtVcopy(q.startPos, startPos); - q.startRef = startRef; - dtVcopy(q.endPos, endPos); - q.endRef = endRef; - q.ready = false; - q.npath = 0; - q.filter = filter; // TODO: This is potentially dangerous! - q.keepalive = 0; - - return ref; -} - -int PathQueue::getRequestState(PathQueueRef ref) -{ - for (int i = 0; i < MAX_QUEUE; ++i) - { - if (m_queue[i].ref == ref) - return m_queue[i].ready ? PATHQ_STATE_READY : PATHQ_STATE_WORKING; - } - - return PATHQ_STATE_INVALID; -} - -int PathQueue::getPathResult(PathQueueRef ref, dtPolyRef* path, const int maxPath) -{ - for (int i = 0; i < MAX_QUEUE; ++i) - { - if (m_queue[i].ref == ref) - { - PathQuery& q = m_queue[i]; - // Allow to reuse the request. - q.ref = PATHQ_INVALID; - int n = 0; - for (int j = 0; j < q.npath && j < maxPath; ++j) - path[n++] = q.path[j]; - return n; - } - } - return 0; -} - - -static int fixupCorridor(dtPolyRef* path, const int npath, const int maxPath, - const dtPolyRef* visited, const int nvisited) -{ - int furthestPath = -1; - int furthestVisited = -1; - - // Find furthest common polygon. - for (int i = npath-1; i >= 0; --i) - { - bool found = false; - for (int j = nvisited-1; j >= 0; --j) - { - if (path[i] == visited[j]) - { - furthestPath = i; - furthestVisited = j; - found = true; - } - } - if (found) - break; - } - - // If no intersection found just return current path. - if (furthestPath == -1 || furthestVisited == -1) - return npath; - - // Concatenate paths. - - // Adjust beginning of the buffer to include the visited. - const int req = nvisited - furthestVisited; - const int orig = dtMin(furthestPath+1, npath); - int size = dtMax(0, npath-orig); - if (req+size > maxPath) - size = maxPath-req; - if (size) - memmove(path+req, path+orig, size*sizeof(dtPolyRef)); - - // Store visited - for (int i = 0; i < req; ++i) - path[i] = visited[(nvisited-1)-i]; - - return req+size; -} - -static int fixupCorridorEnd(dtPolyRef* path, const int npath, const int maxPath, - const dtPolyRef* visited, const int nvisited) -{ - int furthestPath = -1; - int furthestVisited = -1; - - // Find furthest common polygon. - for (int i = 0; i < npath; ++i) - { - bool found = false; - for (int j = nvisited-1; j >= 0; --j) - { - if (path[i] == visited[j]) - { - furthestPath = i; - furthestVisited = j; - found = true; - } - } - if (found) - break; - } - - // If no intersection found just return current path. - if (furthestPath == -1 || furthestVisited == -1) - return npath; - - // Concatenate paths. - const int ppos = furthestPath+1; - const int vpos = furthestVisited+1; - const int count = dtMin(nvisited-vpos, maxPath-ppos); - dtAssert(ppos+count <= maxPath); - if (count) - memcpy(path+ppos, visited+vpos, sizeof(dtPolyRef)*count); - - return ppos+count; -} - -static int mergeCorridor(dtPolyRef* path, const int npath, const int maxPath, - const dtPolyRef* visited, const int nvisited) -{ - int furthestPath = -1; - int furthestVisited = -1; - - // Find furthest common polygon. - for (int i = npath-1; i >= 0; --i) - { - bool found = false; - for (int j = nvisited-1; j >= 0; --j) - { - if (path[i] == visited[j]) - { - furthestPath = i; - furthestVisited = j; - found = true; - } - } - if (found) - break; - } - - // If no intersection found just return current path. - if (furthestPath == -1 || furthestVisited == -1) - return npath; - - // Concatenate paths. - - // Adjust beginning of the buffer to include the visited. - const int req = furthestVisited; - if (req <= 0) - return npath; - - const int orig = furthestPath; - int size = dtMax(0, npath-orig); - if (req+size > maxPath) - size = maxPath-req; - if (size) - memmove(path+req, path+orig, size*sizeof(dtPolyRef)); - - // Store visited - for (int i = 0; i < req; ++i) - path[i] = visited[i]; - - return req+size; -} - -PathCorridor::PathCorridor() : - m_path(0), - m_npath(0), - m_maxPath(0) -{ - -} - -PathCorridor::~PathCorridor() -{ - dtFree(m_path); -} - -bool PathCorridor::init(const int maxPath) -{ - dtAssert(!m_path); - m_path = (dtPolyRef*)dtAlloc(sizeof(dtPolyRef)*maxPath, DT_ALLOC_PERM); - if (!m_path) - return false; - m_npath = 0; - m_maxPath = maxPath; - return true; -} - -void PathCorridor::reset(dtPolyRef ref, const float* pos) -{ - dtAssert(m_path); - dtVcopy(m_pos, pos); - dtVcopy(m_target, pos); - m_path[0] = ref; - m_npath = 1; -} - -int PathCorridor::findCorners(float* cornerVerts, unsigned char* cornerFlags, - dtPolyRef* cornerPolys, const int maxCorners, - dtNavMeshQuery* navquery, const dtQueryFilter* filter) -{ - dtAssert(m_path); - dtAssert(m_npath); - - static const float MIN_TARGET_DIST = 0.01f; - - int ncorners = 0; - navquery->findStraightPath(m_pos, m_target, m_path, m_npath, - cornerVerts, cornerFlags, cornerPolys, &ncorners, maxCorners); - - // Prune points in the beginning of the path which are too close. - while (ncorners) - { - if ((cornerFlags[0] & DT_STRAIGHTPATH_OFFMESH_CONNECTION) || - dtVdist2DSqr(&cornerVerts[0], m_pos) > dtSqr(MIN_TARGET_DIST)) - break; - ncorners--; - if (ncorners) - { - memmove(cornerFlags, cornerFlags+1, sizeof(unsigned char)*ncorners); - memmove(cornerPolys, cornerPolys+1, sizeof(dtPolyRef)*ncorners); - memmove(cornerVerts, cornerVerts+3, sizeof(float)*3*ncorners); - } - } - - // Prune points after an off-mesh connection. - for (int i = 0; i < ncorners; ++i) - { - if (cornerFlags[i] & DT_STRAIGHTPATH_OFFMESH_CONNECTION) - { - ncorners = i+1; - break; - } - } - - return ncorners; -} - -void PathCorridor::optimizePathVisibility(const float* next, const float pathOptimizationRange, - dtNavMeshQuery* navquery, const dtQueryFilter* filter) -{ - dtAssert(m_path); - - // Clamp the ray to max distance. - float goal[3]; - dtVcopy(goal, next); - float dist = dtVdist2D(m_pos, goal); - - // If too close to the goal, do not try to optimize. - if (dist < 0.01f) - return; - - // Overshoot a little. This helps to optimize open fields in tiled meshes. - dist = dtMin(dist+0.01f, pathOptimizationRange); - - // Adjust ray length. - float delta[3]; - dtVsub(delta, goal, m_pos); - dtVmad(goal, m_pos, delta, pathOptimizationRange/dist); - - static const int MAX_RES = 32; - dtPolyRef res[MAX_RES]; - float t, norm[3]; - int nres = 0; - navquery->raycast(m_path[0], m_pos, goal, filter, &t, norm, res, &nres, MAX_RES); - if (nres > 1 && t > 0.99f) - { - m_npath = mergeCorridor(m_path, m_npath, m_maxPath, res, nres); - } -} - -bool PathCorridor::optimizePathTopology(dtNavMeshQuery* navquery, const dtQueryFilter* filter) -{ - dtAssert(m_path); - - if (m_npath < 3) - return false; - - static const int MAX_ITER = 32; - static const int MAX_RES = 32; - - dtPolyRef res[MAX_RES]; - int nres = 0; - navquery->initSlicedFindPath(m_path[0], m_path[m_npath-1], m_pos, m_target, filter); - navquery->updateSlicedFindPath(MAX_ITER); - dtStatus status = navquery->finalizeSlicedFindPathPartial(m_path, m_npath, res, &nres, MAX_RES); - - if (status == DT_SUCCESS && nres > 0) - { - m_npath = mergeCorridor(m_path, m_npath, m_maxPath, res, nres); - return true; - } - - return false; -} - -void PathCorridor::movePosition(const float* npos, dtNavMeshQuery* navquery, const dtQueryFilter* filter) -{ - dtAssert(m_path); - dtAssert(m_npath); - - // Move along navmesh and update new position. - float result[3]; - static const int MAX_VISITED = 16; - dtPolyRef visited[MAX_VISITED]; - int nvisited = 0; - navquery->moveAlongSurface(m_path[0], m_pos, npos, filter, - result, visited, &nvisited, MAX_VISITED); - m_npath = fixupCorridor(m_path, m_npath, m_maxPath, visited, nvisited); - - // Adjust the position to stay on top of the navmesh. - float h = m_pos[1]; - navquery->getPolyHeight(m_path[0], result, &h); - result[1] = h; - dtVcopy(m_pos, result); -} - -void PathCorridor::moveTargetPosition(const float* npos, dtNavMeshQuery* navquery, const dtQueryFilter* filter) -{ - dtAssert(m_path); - dtAssert(m_npath); - - // Move along navmesh and update new position. - float result[3]; - static const int MAX_VISITED = 16; - dtPolyRef visited[MAX_VISITED]; - int nvisited = 0; - navquery->moveAlongSurface(m_path[m_npath-1], m_target, npos, filter, - result, visited, &nvisited, MAX_VISITED); - m_npath = fixupCorridorEnd(m_path, m_npath, m_maxPath, visited, nvisited); - - // TODO: should we do that? - // Adjust the position to stay on top of the navmesh. -/* float h = m_target[1]; - navquery->getPolyHeight(m_path[m_npath-1], result, &h); - result[1] = h;*/ - - dtVcopy(m_target, result); -} - -void PathCorridor::setCorridor(const float* target, const dtPolyRef* path, const int npath) -{ - dtAssert(m_path); - dtAssert(npath > 0); - dtAssert(npath < m_maxPath); - - dtVcopy(m_target, target); - memcpy(m_path, path, sizeof(dtPolyRef)*npath); - m_npath = npath; -} - - - - -void Agent::integrate(const float maxAcc, const float dt) -{ - // Fake dynamic constraint. - const float maxDelta = maxAcc * dt; - float dv[3]; - dtVsub(dv, nvel, vel); - float ds = dtVlen(dv); - if (ds > maxDelta) - dtVscale(dv, dv, maxDelta/ds); - dtVadd(vel, vel, dv); - - // Integrate - if (dtVlen(vel) > 0.0001f) - dtVmad(npos, npos, vel, dt); - else - dtVset(vel,0,0,0); -} - -float Agent::getDistanceToGoal(const float range) const -{ - if (!ncorners) - return range; - - const bool endOfPath = (cornerFlags[ncorners-1] & DT_STRAIGHTPATH_END) ? true : false; - const bool offMeshConnection = (cornerFlags[ncorners-1] & DT_STRAIGHTPATH_OFFMESH_CONNECTION) ? true : false; - if (endOfPath || offMeshConnection) - return dtMin(dtVdist2D(npos, &cornerVerts[(ncorners-1)*3]), range); - - return range; -} - -void Agent::calcSmoothSteerDirection(float* dir) -{ - if (!ncorners) - { - dtVset(dir, 0,0,0); - return; - } - - const int ip0 = 0; - const int ip1 = dtMin(1, ncorners-1); - const float* p0 = &cornerVerts[ip0*3]; - const float* p1 = &cornerVerts[ip1*3]; - - float dir0[3], dir1[3]; - dtVsub(dir0, p0, npos); - dtVsub(dir1, p1, npos); - dir0[1] = 0; - dir1[1] = 0; - - float len0 = dtVlen(dir0); - float len1 = dtVlen(dir1); - if (len1 > 0.001f) - dtVscale(dir1,dir1,1.0f/len1); - - dir[0] = dir0[0] - dir1[0]*len0*0.5f; - dir[1] = 0; - dir[2] = dir0[2] - dir1[2]*len0*0.5f; - - dtVnormalize(dir); -} - -void Agent::calcStraightSteerDirection(float* dir) -{ - if (!ncorners) - { - dtVset(dir, 0,0,0); - return; - } - dtVsub(dir, &cornerVerts[0], npos); - dir[1] = 0; - dtVnormalize(dir); -} - - - -LocalBoundary::LocalBoundary() : - m_nsegs(0) -{ - dtVset(m_center, FLT_MAX,FLT_MAX,FLT_MAX); -} - -LocalBoundary::~LocalBoundary() -{ -} - -void LocalBoundary::reset() -{ - dtVset(m_center, FLT_MAX,FLT_MAX,FLT_MAX); - m_nsegs = 0; -} - -void LocalBoundary::addSegment(const float dist, const float* s) -{ - // Insert neighbour based on the distance. - Segment* seg = 0; - if (!m_nsegs) - { - // First, trivial accept. - seg = &m_segs[0]; - } - else if (dist >= m_segs[m_nsegs-1].d) - { - // Further than the last segment, skip. - if (m_nsegs >= MAX_SEGS) - return; - // Last, trivial accept. - seg = &m_segs[m_nsegs]; - } - else - { - // Insert inbetween. - int i; - for (i = 0; i < m_nsegs; ++i) - if (dist <= m_segs[i].d) - break; - const int tgt = i+1; - const int n = dtMin(m_nsegs-i, MAX_SEGS-tgt); - dtAssert(tgt+n <= MAX_SEGS); - if (n > 0) - memmove(&m_segs[tgt], &m_segs[i], sizeof(Segment)*n); - seg = &m_segs[i]; - } - - seg->d = dist; - memcpy(seg->s, s, sizeof(float)*6); - - if (m_nsegs < MAX_SEGS) - m_nsegs++; -} - -void LocalBoundary::update(dtPolyRef ref, const float* pos, const float collisionQueryRange, - dtNavMeshQuery* navquery, const dtQueryFilter* filter) -{ - static const int MAX_LOCAL_POLYS = 16; - static const int MAX_SEGS_PER_POLY = DT_VERTS_PER_POLYGON*2; - - if (!ref) - { - dtVset(m_center, FLT_MAX,FLT_MAX,FLT_MAX); - m_nsegs = 0; - return; - } - - dtVcopy(m_center, pos); - - // First query non-overlapping polygons. - dtPolyRef locals[MAX_LOCAL_POLYS]; - int nlocals = 0; - navquery->findLocalNeighbourhood(ref, pos, collisionQueryRange, - filter, locals, 0, &nlocals, MAX_LOCAL_POLYS); - - // Secondly, store all polygon edges. - m_nsegs = 0; - float segs[MAX_SEGS_PER_POLY*6]; - int nsegs = 0; - for (int j = 0; j < nlocals; ++j) - { - navquery->getPolyWallSegments(locals[j], filter, segs, &nsegs, MAX_SEGS_PER_POLY); - for (int k = 0; k < nsegs; ++k) - { - const float* s = &segs[k*6]; - // Skip too distant segments. - float tseg; - const float distSqr = dtDistancePtSegSqr2D(pos, s, s+3, tseg); - if (distSqr > dtSqr(collisionQueryRange)) - continue; - addSegment(distSqr, s); - } - } -} - - -CrowdManager::CrowdManager() : - m_obstacleQuery(0), - m_pathResult(0), - m_maxPathResult(0), - m_totalTime(0), - m_rvoTime(0), - m_sampleCount(0), - m_moveRequestCount(0) -{ - dtVset(m_ext, 2,4,2); - - m_obstacleQuery = dtAllocObstacleAvoidanceQuery(); - m_obstacleQuery->init(6, 8); - - m_obstacleQuery->setDesiredVelocityWeight(2.0f); - m_obstacleQuery->setCurrentVelocityWeight(0.75f); - m_obstacleQuery->setPreferredSideWeight(0.75f); - m_obstacleQuery->setCollisionTimeWeight(2.5f); - m_obstacleQuery->setTimeHorizon(2.5f); - m_obstacleQuery->setVelocitySelectionBias(0.4f); - - memset(m_vodebug, 0, sizeof(m_vodebug)); - const int maxAdaptiveSamples = (VO_ADAPTIVE_DIVS*VO_ADAPTIVE_RINGS+1)*VO_ADAPTIVE_DEPTH; - const int maxGridSamples = VO_GRID_SIZE*VO_GRID_SIZE; - const int sampleCount = dtMax(maxAdaptiveSamples, maxGridSamples); - for (int i = 0; i < MAX_AGENTS; ++i) - { - m_vodebug[i] = dtAllocObstacleAvoidanceDebugData(); - m_vodebug[i]->init(sampleCount); - } - - // Allocate temp buffer for merging paths. - m_maxPathResult = 256; - m_pathResult = (dtPolyRef*)dtAlloc(sizeof(dtPolyRef)*m_maxPathResult, DT_ALLOC_PERM); - - // Alloca corridors. - for (int i = 0; i < MAX_AGENTS; ++i) - { - m_agents[i].corridor.init(m_maxPathResult); - } - - // TODO: the radius should be related to the agent radius used to create the navmesh! - m_grid.init(MAX_AGENTS, 1.0f); - - reset(); -} - -CrowdManager::~CrowdManager() -{ - delete [] m_pathResult; - - for (int i = 0; i < MAX_AGENTS; ++i) - dtFreeObstacleAvoidanceDebugData(m_vodebug[i]); - dtFreeObstacleAvoidanceQuery(m_obstacleQuery); -} - -void CrowdManager::reset() -{ - for (int i = 0; i < MAX_AGENTS; ++i) - m_agents[i].active = 0; -} - -const int CrowdManager::getAgentCount() const -{ - return MAX_AGENTS; -} - -const Agent* CrowdManager::getAgent(const int idx) -{ - return &m_agents[idx]; -} - -int CrowdManager::addAgent(const float* pos, const float radius, const float height, dtNavMeshQuery* navquery) -{ - // Find empty slot. - int idx = -1; - for (int i = 0; i < MAX_AGENTS; ++i) - { - if (!m_agents[i].active) - { - idx = i; - break; - } - } - if (idx == -1) - return -1; - - Agent* ag = &m_agents[idx]; - - // Find nearest position on navmesh and place the agent there. - float nearest[3]; - dtPolyRef ref; - navquery->findNearestPoly(pos, m_ext, &m_filter, &ref, nearest); - if (!ref) - { - // Could not find a location on navmesh. - return -1; - } - - ag->corridor.reset(ref, nearest); - ag->boundary.reset(); - - ag->radius = radius; - ag->height = height; - ag->collisionQueryRange = radius * 8; - ag->pathOptimizationRange = radius * 30; - ag->topologyOptTime = 0; - ag->nneis = 0; - - dtVset(ag->dvel, 0,0,0); - dtVset(ag->nvel, 0,0,0); - dtVset(ag->vel, 0,0,0); - dtVcopy(ag->npos, nearest); - - ag->maxspeed = 0; - ag->t = 0; - dtVset(ag->opts, 0,0,0); - dtVset(ag->opte, 0,0,0); - ag->active = 1; - ag->var = (rand() % 10) / 9.0f; - - // Init trail - for (int i = 0; i < AGENT_MAX_TRAIL; ++i) - dtVcopy(&ag->trail[i*3], ag->corridor.getPos()); - ag->htrail = 0; - - return idx; -} - -void CrowdManager::removeAgent(const int idx) -{ - if (idx >= 0 && idx < MAX_AGENTS) - { - m_agents[idx].active = 0; - } -} - -bool CrowdManager::requestMoveTarget(const int idx, dtPolyRef ref, const float* pos) -{ - if (idx < 0 || idx > MAX_AGENTS) - return false; - if (!ref) - return false; - - MoveRequest* req = 0; - // Check if there is existing request and update that instead. - for (int i = 0; i < m_moveRequestCount; ++i) - { - if (m_moveRequests[i].idx == idx) - { - req = &m_moveRequests[i]; - break; - } - } - if (!req) - { - if (m_moveRequestCount >= MAX_AGENTS) - return false; - req = &m_moveRequests[m_moveRequestCount++]; - memset(req, 0, sizeof(MoveRequest)); - } - - // Initialize request. - req->idx = idx; - req->ref = ref; - dtVcopy(req->pos, pos); - req->pathqRef = PATHQ_INVALID; - req->state = MR_TARGET_REQUESTING; - - req->temp[0] = ref; - req->ntemp = 1; - - return true; -} - -bool CrowdManager::adjustMoveTarget(const int idx, dtPolyRef ref, const float* pos) -{ - if (idx < 0 || idx > MAX_AGENTS) - return false; - if (!ref) - return false; - - MoveRequest* req = 0; - // Check if there is existing request and update that instead. - for (int i = 0; i < m_moveRequestCount; ++i) - { - if (m_moveRequests[i].idx == idx) - { - req = &m_moveRequests[i]; - break; - } - } - if (!req) - { - if (m_moveRequestCount >= MAX_AGENTS) - return false; - req = &m_moveRequests[m_moveRequestCount++]; - memset(req, 0, sizeof(MoveRequest)); - - // New adjust request - req->state = MR_TARGET_ADJUST; - req->idx = idx; - } - - // Set adjustment request. - req->aref = ref; - dtVcopy(req->apos, pos); - - return true; -} - -int CrowdManager::getActiveAgents(Agent** agents, const int maxAgents) -{ - int n = 0; - for (int i = 0; i < MAX_AGENTS; ++i) - { - if (!m_agents[i].active) continue; - if (n < maxAgents) - agents[n++] = &m_agents[i]; - } - return n; -} - - -static int addNeighbour(const int idx, const float dist, - Neighbour* neis, const int nneis, const int maxNeis) -{ - // Insert neighbour based on the distance. - Neighbour* nei = 0; - if (!nneis) - { - nei = &neis[nneis]; - } - else if (dist >= neis[nneis-1].dist) - { - if (nneis >= maxNeis) - return nneis; - nei = &neis[nneis]; - } - else - { - int i; - for (i = 0; i < nneis; ++i) - if (dist <= neis[i].dist) - break; - - const int tgt = i+1; - const int n = dtMin(nneis-i, maxNeis-tgt); - - dtAssert(tgt+n <= maxNeis); - - if (n > 0) - memmove(&neis[tgt], &neis[i], sizeof(Neighbour)*n); - nei = &neis[i]; - } - - memset(nei, 0, sizeof(Neighbour)); - - nei->idx = idx; - nei->dist = dist; - - return dtMin(nneis+1, maxNeis); -} - -int CrowdManager::getNeighbours(const float* pos, const float height, const float range, - const Agent* skip, Neighbour* result, const int maxResult) -{ - int n = 0; - - unsigned short ids[MAX_AGENTS]; - int nids = m_grid.queryItems(pos[0]-range, pos[2]-range, - pos[0]+range, pos[2]+range, - ids, MAX_AGENTS); - - for (int i = 0; i < nids; ++i) - { - Agent* ag = &m_agents[ids[i]]; - - if (ag == skip) continue; - - // Check for overlap. - float diff[3]; - dtVsub(diff, pos, ag->npos); - if (fabsf(diff[1]) >= (height+ag->height)/2.0f) - continue; - diff[1] = 0; - const float distSqr = dtVlenSqr(diff); - if (distSqr > dtSqr(range)) - continue; - - n = addNeighbour(ids[i], distSqr, result, n, maxResult); - } - return n; -} - -void CrowdManager::updateMoveRequest(const float dt, dtNavMeshQuery* navquery, const dtQueryFilter* filter) -{ - // Fire off new requests. - for (int i = 0; i < m_moveRequestCount; ++i) - { - MoveRequest* req = &m_moveRequests[i]; - Agent* ag = &m_agents[req->idx]; - - // Agent not active anymore, kill request. - if (!ag->active) - req->state = MR_TARGET_FAILED; - - // Adjust target - if (req->aref) - { - if (req->state == MR_TARGET_ADJUST) - { - // Adjust existing path. - ag->corridor.moveTargetPosition(req->apos, navquery, filter); - req->state = MR_TARGET_VALID; - } - else - { - // Adjust on the flight request. - float result[3]; - static const int MAX_VISITED = 16; - dtPolyRef visited[MAX_VISITED]; - int nvisited = 0; - navquery->moveAlongSurface(req->temp[req->ntemp-1], req->pos, req->apos, filter, - result, visited, &nvisited, MAX_VISITED); - req->ntemp = fixupCorridorEnd(req->temp, req->ntemp, MAX_TEMP_PATH, visited, nvisited); - dtVcopy(req->pos, result); - - // Reset adjustment. - dtVset(req->apos, 0,0,0); - req->aref = 0; - } - } - - - if (req->state == MR_TARGET_REQUESTING) - { - // Calculate request position. - // If there is a lot of latency between requests, it is possible to - // project the current position ahead and use raycast to find the actual - // location and path. - const dtPolyRef* path = ag->corridor.getPath(); - const int npath = ag->corridor.getPathCount(); - dtAssert(npath); - - // Here we take the simple approach and set the path to be just the current location. - float reqPos[3]; - dtVcopy(reqPos, ag->corridor.getPos()); // The location of the request - dtPolyRef reqPath[8]; // The path to the request location - reqPath[0] = path[0]; - int reqPathCount = 1; - - req->pathqRef = m_pathq.request(reqPath[reqPathCount-1], req->ref, reqPos, req->pos, &m_filter); - if (req->pathqRef != PATHQ_INVALID) - { - ag->corridor.setCorridor(reqPos, reqPath, reqPathCount); - req->state = MR_TARGET_WAITING_FOR_PATH; - } - } - } - - // Update requests. - m_pathq.update(navquery); - - - // Process path results. - for (int i = 0; i < m_moveRequestCount; ++i) - { - MoveRequest* req = &m_moveRequests[i]; - Agent* ag = &m_agents[req->idx]; - - if (req->state == MR_TARGET_WAITING_FOR_PATH) - { - // Poll path queue. - int state = m_pathq.getRequestState(req->pathqRef); - if (state == PATHQ_STATE_INVALID) - { - req->pathqRef = PATHQ_INVALID; - req->state = MR_TARGET_FAILED; - } - else if (state == PATHQ_STATE_READY) - { - const dtPolyRef* path = ag->corridor.getPath(); - const int npath = ag->corridor.getPathCount(); - dtAssert(npath); - - // Apply results. - float targetPos[3]; - dtVcopy(targetPos, req->pos); - - dtPolyRef* res = m_pathResult; - bool valid = true; - int nres = m_pathq.getPathResult(req->pathqRef, res, m_maxPathResult); - if (!nres) - valid = false; - - // Merge with any target adjustment that happened during the search. - if (req->ntemp > 1) - { - nres = fixupCorridorEnd(res, nres, m_maxPathResult, req->temp, req->ntemp); - } - - // Merge result and existing path. - // The agent might have moved whilst the request is - // being processed, so the path may have changed. - // We assume that the end of the path is at the same location - // where the request was issued. - - // The last ref in the old path should be the same as - // the location where the request was issued.. - if (valid && path[npath-1] != res[0]) - valid = false; - - if (valid) - { - // Put the old path infront of the old path. - if (npath > 1) - { - // Make space for the old path. - if ((npath-1)+nres > m_maxPathResult) - nres = m_maxPathResult - (npath-1); - memmove(res+npath-1, res, sizeof(dtPolyRef)*nres); - // Copy old path in the beginning. - memcpy(res, path, sizeof(dtPolyRef)*(npath-1)); - nres += npath-1; - } - - // Check for partial path. - if (res[nres-1] != req->ref) - { - // Partial path, constrain target position inside the last polygon. - float nearest[3]; - if (navquery->closestPointOnPoly(res[nres-1], targetPos, nearest) == DT_SUCCESS) - dtVcopy(targetPos, nearest); - else - valid = false; - } - } - - if (valid) - { - ag->corridor.setCorridor(targetPos, res, nres); - req->state = MR_TARGET_VALID; - } - else - { - // Something went wrong. - req->state = MR_TARGET_FAILED; - } - } - } - - // Remove request when done with it. - if (req->state == MR_TARGET_VALID || req->state == MR_TARGET_FAILED) - { - m_moveRequestCount--; - if (i != m_moveRequestCount) - memcpy(&m_moveRequests[i], &m_moveRequests[m_moveRequestCount], sizeof(MoveRequest)); - --i; - } - } - -} - - - -static int addToOptQueue(Agent* newag, Agent** agents, const int nagents, const int maxAgents) -{ - // Insert neighbour based on greatest time. - int slot = 0; - if (!nagents) - { - slot = nagents; - } - else if (newag->topologyOptTime <= agents[nagents-1]->topologyOptTime) - { - if (nagents >= maxAgents) - return nagents; - slot = nagents; - } - else - { - int i; - for (i = 0; i < nagents; ++i) - if (newag->topologyOptTime >= agents[i]->topologyOptTime) - break; - - const int tgt = i+1; - const int n = dtMin(nagents-i, maxAgents-tgt); - - dtAssert(tgt+n <= maxAgents); - - if (n > 0) - memmove(&agents[tgt], &agents[i], sizeof(Agent*)*n); - slot = i; - } - - agents[slot] = newag; - - return dtMin(nagents+1, maxAgents); -} - -void CrowdManager::updateTopologyOptimization(const float dt, dtNavMeshQuery* navquery, const dtQueryFilter* filter) -{ - Agent* agents[MAX_AGENTS]; - int nagents = getActiveAgents(agents, MAX_AGENTS); - if (!nagents) - return; - - const float OPT_TIME_THR = 0.5f; // seconds - const int OPT_MAX_AGENTS = 1; - - Agent* queue[OPT_MAX_AGENTS]; - int nqueue = 0; - - for (int i = 0; i < nagents; ++i) - { - Agent* ag = agents[i]; - ag->topologyOptTime += dt; - if (ag->topologyOptTime >= OPT_TIME_THR) - { - nqueue = addToOptQueue(ag, queue, nqueue, OPT_MAX_AGENTS); - } - } - - for (int i = 0; i < nqueue; ++i) - { - Agent* ag = queue[i]; - ag->corridor.optimizePathTopology(navquery, filter); - ag->topologyOptTime = 0; - } - -} - -void CrowdManager::update(const float dt, unsigned int flags, dtNavMeshQuery* navquery) -{ - m_sampleCount = 0; - m_totalTime = 0; - m_rvoTime = 0; - - if (!navquery) - return; - - TimeVal startTime = getPerfTime(); - - Agent* agents[MAX_AGENTS]; - int nagents = getActiveAgents(agents, MAX_AGENTS); - - static const float MAX_ACC = 8.0f; - static const float MAX_SPEED = 3.5f; - - // Update async move request and path finder. - updateMoveRequest(dt, navquery, &m_filter); - - // Optimize path topology. - if (flags & CROWDMAN_OPTIMIZE_TOPO) - updateTopologyOptimization(dt, navquery, &m_filter); - - // Register agents to proximity grid. - m_grid.clear(); - for (int i = 0; i < nagents; ++i) - { - Agent* ag = agents[i]; - const float* p = ag->npos; - const float r = ag->radius; - m_grid.addItem((unsigned short)i, p[0]-r, p[2]-r, p[0]+r, p[2]+r); - } - - // Get nearby navmesh segments and agents to collide with. - for (int i = 0; i < nagents; ++i) - { - Agent* ag = agents[i]; - // Only update the collision boundary after certain distance has been passed. - if (dtVdist2DSqr(ag->npos, ag->boundary.getCenter()) > dtSqr(ag->collisionQueryRange*0.25f)) - ag->boundary.update(ag->corridor.getFirstPoly(), ag->npos, ag->collisionQueryRange, navquery, &m_filter); - // Query neighbour agents - ag->nneis = getNeighbours(ag->npos, ag->height, ag->collisionQueryRange, ag, ag->neis, AGENT_MAX_NEIGHBOURS); - } - - // Find next corner to steer to. - for (int i = 0; i < nagents; ++i) - { - Agent* ag = agents[i]; - - // Find corners for steering - ag->ncorners = ag->corridor.findCorners(ag->cornerVerts, ag->cornerFlags, ag->cornerPolys, - AGENT_MAX_CORNERS, navquery, &m_filter); - - // Check to see if the corner after the next corner is directly visible, - // and short cut to there. - if ((flags & CROWDMAN_OPTIMIZE_VIS) && ag->ncorners > 0) - { - const float* target = &ag->cornerVerts[dtMin(1,ag->ncorners-1)*3]; - dtVcopy(ag->opts, ag->corridor.getPos()); - dtVcopy(ag->opte, target); - ag->corridor.optimizePathVisibility(target, ag->pathOptimizationRange, navquery, &m_filter); - } - else - { - dtVset(ag->opts, 0,0,0); - dtVset(ag->opte, 0,0,0); - } - - // Copy data for debug purposes. - } - - // Calculate steering. - for (int i = 0; i < nagents; ++i) - { - Agent* ag = agents[i]; - - float dvel[3] = {0,0,0}; - - // Calculate steering direction. - if (flags & CROWDMAN_ANTICIPATE_TURNS) - ag->calcSmoothSteerDirection(dvel); - else - ag->calcStraightSteerDirection(dvel); - - // Calculate speed scale, which tells the agent to slowdown at the end of the path. - const float slowDownRadius = ag->radius*2; // TODO: make less hacky. - const float speedScale = ag->getDistanceToGoal(slowDownRadius) / slowDownRadius; - - // Apply style. - if (flags & CROWDMAN_DRUNK) - { - // Drunken steering - - // Pulsating speed. - ag->t += dt * (1.0f - ag->var*0.25f); - ag->maxspeed = MAX_SPEED*(1 + dtSqr(cosf(ag->t*2.0f))*0.3f); - - dtVscale(dvel, dvel, ag->maxspeed * speedScale); - - // Slightly wandering steering. - const float amp = cosf(ag->var*13.69f+ag->t*3.123f) * 0.2f; - const float nx = -dvel[2]; - const float nz = dvel[0]; - dvel[0] += nx*amp; - dvel[2] += nz*amp; - } - else - { - // Normal steering. - ag->maxspeed = MAX_SPEED; - dtVscale(dvel, dvel, ag->maxspeed * speedScale); - } - - // Set the desired velocity. - dtVcopy(ag->dvel, dvel); - } - - // Velocity planning. - TimeVal rvoStartTime = getPerfTime(); - - for (int i = 0; i < nagents; ++i) - { - Agent* ag = agents[i]; - - if (flags & CROWDMAN_USE_VO) - { - m_obstacleQuery->reset(); - - // Add neighbours as obstacles. - for (int j = 0; j < ag->nneis; ++j) - { - const Agent* nei = &m_agents[ag->neis[j].idx]; - m_obstacleQuery->addCircle(nei->npos, nei->radius, nei->vel, nei->dvel); - } - - // Append neighbour segments as obstacles. - for (int j = 0; j < ag->boundary.getSegmentCount(); ++j) - { - const float* s = ag->boundary.getSegment(j); - if (dtTriArea2D(ag->npos, s, s+3) < 0.0f) - continue; - m_obstacleQuery->addSegment(s, s+3); - } - - // Sample new safe velocity. - bool adaptive = true; - - if (adaptive) - { - m_obstacleQuery->sampleVelocityAdaptive(ag->npos, ag->radius, ag->maxspeed, - ag->vel, ag->dvel, ag->nvel, - VO_ADAPTIVE_DIVS, VO_ADAPTIVE_RINGS, VO_ADAPTIVE_DEPTH, - m_vodebug[i]); - } - else - { - m_obstacleQuery->sampleVelocityGrid(ag->npos, ag->radius, ag->maxspeed, - ag->vel, ag->dvel, ag->nvel, - VO_GRID_SIZE, m_vodebug[i]); - } - } - else - { - // If not using velocity planning, new velocity is directly the desired velocity. - dtVcopy(ag->nvel, ag->dvel); - } - } - TimeVal rvoEndTime = getPerfTime(); - - // Integrate. - for (int i = 0; i < nagents; ++i) - { - Agent* ag = agents[i]; - ag->integrate(MAX_ACC, dt); - } - - // Handle collisions. - for (int iter = 0; iter < 4; ++iter) - { - for (int i = 0; i < nagents; ++i) - { - Agent* ag = agents[i]; - - dtVset(ag->disp, 0,0,0); - - float w = 0; - - for (int j = 0; j < ag->nneis; ++j) - { - const Agent* nei = &m_agents[ag->neis[j].idx]; - - float diff[3]; - dtVsub(diff, ag->npos, nei->npos); - - if (fabsf(diff[1]) >= (ag->height+ nei->height)/2.0f) - continue; - - diff[1] = 0; - - float dist = dtVlenSqr(diff); - if (dist > dtSqr(ag->radius + nei->radius)) - continue; - dist = sqrtf(dist); - float pen = (ag->radius + nei->radius) - dist; - if (dist > 0.0001f) - pen = (1.0f/dist) * (pen*0.5f) * 0.7f; - - dtVmad(ag->disp, ag->disp, diff, pen); - - w += 1.0f; - } - - if (w > 0.0001f) - { - const float iw = 1.0f / w; - dtVscale(ag->disp, ag->disp, iw); - } - } - - for (int i = 0; i < nagents; ++i) - { - Agent* ag = agents[i]; - dtVadd(ag->npos, ag->npos, ag->disp); - } - } - - for (int i = 0; i < nagents; ++i) - { - Agent* ag = agents[i]; - // Move along navmesh. - ag->corridor.movePosition(ag->npos, navquery, &m_filter); - // Get valid constrained position back. - dtVcopy(ag->npos, ag->corridor.getPos()); - } - - TimeVal endTime = getPerfTime(); - - // Debug/demo book keeping - int ns = 0; - for (int i = 0; i < nagents; ++i) - { - Agent* ag = agents[i]; - - if (flags & CROWDMAN_USE_VO) - { - // Normalize samples for debug draw - m_vodebug[i]->normalizeSamples(); - ns += m_vodebug[i]->getSampleCount(); - } - - // Update agent movement trail. - ag->htrail = (ag->htrail + 1) % AGENT_MAX_TRAIL; - dtVcopy(&ag->trail[ag->htrail*3], ag->npos); - } - - m_sampleCount = ns; - m_rvoTime = getPerfDeltaTimeUsec(rvoStartTime, rvoEndTime); - m_totalTime = getPerfDeltaTimeUsec(startTime, endTime); -} - - diff --git a/RecastDemo/Source/CrowdTool.cpp b/RecastDemo/Source/CrowdTool.cpp index 9a739d6..63b1bd5 100644 --- a/RecastDemo/Source/CrowdTool.cpp +++ b/RecastDemo/Source/CrowdTool.cpp @@ -27,11 +27,11 @@ #include "CrowdTool.h" #include "InputGeom.h" #include "Sample.h" +#include "DetourCrowd.h" #include "DetourDebugDraw.h" #include "DetourObstacleAvoidance.h" #include "DetourCommon.h" #include "SampleInterfaces.h" -#include "CrowdManager.h" #ifdef WIN32 # define snprintf _snprintf @@ -77,7 +77,7 @@ static bool isectSegAABB(const float* sp, const float* sq, return true; } -static void getAgentBounds(const Agent* ag, float* bmin, float* bmax) +static void getAgentBounds(const dtCrowdAgent* ag, float* bmin, float* bmax) { const float* p = ag->npos; const float r = ag->radius; @@ -94,26 +94,34 @@ CrowdTool::CrowdTool() : m_sample(0), m_oldFlags(0), m_targetRef(0), - m_expandDebugDraw(false), - m_showLabels(false), + m_expandSelectedDebugDraw(true), m_showCorners(false), - m_showTargets(false), m_showCollisionSegments(false), m_showPath(false), m_showVO(false), m_showOpt(false), + m_expandDebugDraw(false), + m_showLabels(false), m_showGrid(false), m_showNodes(false), m_showPerfGraph(false), + m_expandOptions(true), m_anticipateTurns(true), m_optimizeVis(true), m_optimizeTopo(true), m_useVO(true), - m_drunkMove(false), m_run(true), m_mode(TOOLMODE_CREATE) { + memset(m_trails, 0, sizeof(m_trails)); + + m_vod = dtAllocObstacleAvoidanceDebugData(); + m_vod->init(2048); + + memset(&m_agentDebug, 0, sizeof(m_agentDebug)); + m_agentDebug.idx = -1; + m_agentDebug.vod = m_vod; } CrowdTool::~CrowdTool() @@ -122,6 +130,8 @@ CrowdTool::~CrowdTool() { m_sample->setNavMeshDrawFlags(m_oldFlags); } + + dtFreeObstacleAvoidanceDebugData(m_vod); } void CrowdTool::init(Sample* sample) @@ -132,6 +142,11 @@ void CrowdTool::init(Sample* sample) m_oldFlags = m_sample->getNavMeshDrawFlags(); m_sample->setNavMeshDrawFlags(m_oldFlags & ~DU_DRAWNAVMESH_CLOSEDLIST); } + + dtNavMesh* nav = m_sample->getNavMesh(); + if (nav) + m_crowd.init(MAX_AGENTS, m_sample->getAgentRadius(), nav); + } void CrowdTool::reset() @@ -146,26 +161,11 @@ void CrowdTool::handleMenu() m_mode = TOOLMODE_CREATE; if (imguiCheck("Move Target", m_mode == TOOLMODE_MOVE_TARGET)) m_mode = TOOLMODE_MOVE_TARGET; + if (imguiCheck("Select Agent", m_mode == TOOLMODE_SELECT)) + m_mode = TOOLMODE_SELECT; - imguiSeparator(); - - if (m_mode == TOOLMODE_CREATE) - { - imguiValue("Click to add agents."); - imguiValue("Shift+Click to remove."); - } - else if (m_mode == TOOLMODE_MOVE_TARGET) - { - imguiValue("Click to set move target."); - imguiValue("Shift+Click to adjust target."); - imguiValue("Adjusting uses special pathfinder"); - imguiValue("which is really fast to change the"); - imguiValue("target in small increments."); - } - - imguiSeparator(); - imguiSeparator(); - + imguiSeparatorLine(); + if (imguiCollapse("Options", 0, m_expandOptions)) m_expandOptions = !m_expandOptions; @@ -180,23 +180,17 @@ void CrowdTool::handleMenu() m_anticipateTurns = !m_anticipateTurns; if (imguiCheck("Use VO", m_useVO)) m_useVO = !m_useVO; - if (imguiCheck("Drunk Move", m_drunkMove)) - m_drunkMove = !m_drunkMove; imguiUnindent(); } - if (imguiCollapse("Debug Draw", 0, m_expandDebugDraw)) - m_expandDebugDraw = !m_expandDebugDraw; + if (imguiCollapse("Selected Debug Draw", 0, m_expandSelectedDebugDraw)) + m_expandSelectedDebugDraw = !m_expandSelectedDebugDraw; - if (m_expandDebugDraw) + if (m_expandSelectedDebugDraw) { imguiIndent(); - if (imguiCheck("Show Labels", m_showLabels)) - m_showLabels = !m_showLabels; if (imguiCheck("Show Corners", m_showCorners)) m_showCorners = !m_showCorners; - if (imguiCheck("Show Targets", m_showTargets)) - m_showTargets = !m_showTargets; if (imguiCheck("Show Collision Segs", m_showCollisionSegments)) m_showCollisionSegments = !m_showCollisionSegments; if (imguiCheck("Show Path", m_showPath)) @@ -205,6 +199,17 @@ void CrowdTool::handleMenu() m_showVO = !m_showVO; if (imguiCheck("Show Path Optimization", m_showOpt)) m_showOpt = !m_showOpt; + imguiUnindent(); + } + + if (imguiCollapse("Debug Draw", 0, m_expandDebugDraw)) + m_expandDebugDraw = !m_expandDebugDraw; + + if (m_expandDebugDraw) + { + imguiIndent(); + if (imguiCheck("Show Labels", m_showLabels)) + m_showLabels = !m_showLabels; if (imguiCheck("Show Prox Grid", m_showGrid)) m_showGrid = !m_showGrid; if (imguiCheck("Show Nodes", m_showNodes)) @@ -231,7 +236,7 @@ void CrowdTool::handleClick(const float* s, const float* p, bool shift) for (int i = 0; i < m_crowd.getAgentCount(); ++i) { - const Agent* ag = m_crowd.getAgent(i); + const dtCrowdAgent* ag = m_crowd.getAgent(i); if (!ag->active) continue; float bmin[3], bmax[3]; getAgentBounds(ag, bmin, bmax); @@ -253,10 +258,26 @@ void CrowdTool::handleClick(const float* s, const float* p, bool shift) else { // Add - dtNavMeshQuery* navquery = m_sample->getNavMeshQuery(); - int idx = m_crowd.addAgent(p, m_sample->getAgentRadius(), m_sample->getAgentHeight(), navquery); - if (idx != -1 && m_targetRef) - m_crowd.requestMoveTarget(idx, m_targetRef, m_targetPos); + dtCrowdAgentParams ap; + ap.radius = m_sample->getAgentRadius(); + ap.height = m_sample->getAgentHeight(); + ap.maxAcceleration = 8.0f; + ap.maxSpeed = 3.5f; + ap.collisionQueryRange = ap.radius * 8.0f; + ap.pathOptimizationRange = ap.radius * 30.0f; + + int idx = m_crowd.addAgent(p, &ap); + if (idx != -1) + { + if (m_targetRef) + m_crowd.requestMoveTarget(idx, m_targetRef, m_targetPos); + + // Init trail + AgentTrail* trail = &m_trails[idx]; + for (int i = 0; i < AGENT_MAX_TRAIL; ++i) + dtVcopy(&trail->trail[i*3], p); + trail->htrail = 0; + } } } else if (m_mode == TOOLMODE_MOVE_TARGET) @@ -273,7 +294,7 @@ void CrowdTool::handleClick(const float* s, const float* p, bool shift) // Adjust target using tiny local search. for (int i = 0; i < m_crowd.getAgentCount(); ++i) { - const Agent* ag = m_crowd.getAgent(i); + const dtCrowdAgent* ag = m_crowd.getAgent(i); if (!ag->active) continue; m_crowd.adjustMoveTarget(i, m_targetRef, m_targetPos); } @@ -283,16 +304,83 @@ void CrowdTool::handleClick(const float* s, const float* p, bool shift) // Move target using paht finder for (int i = 0; i < m_crowd.getAgentCount(); ++i) { - const Agent* ag = m_crowd.getAgent(i); + const dtCrowdAgent* ag = m_crowd.getAgent(i); if (!ag->active) continue; m_crowd.requestMoveTarget(i, m_targetRef, m_targetPos); } } } + else if (m_mode == TOOLMODE_SELECT) + { + // Highlight + m_agentDebug.idx = -1; + + float tsel = FLT_MAX; + for (int i = 0; i < m_crowd.getAgentCount(); ++i) + { + const dtCrowdAgent* ag = m_crowd.getAgent(i); + if (!ag->active) continue; + float bmin[3], bmax[3]; + getAgentBounds(ag, bmin, bmax); + float tmin, tmax; + if (isectSegAABB(s, p, bmin,bmax, tmin, tmax)) + { + if (tmin > 0 && tmin < tsel) + { + m_agentDebug.idx = i; + tsel = tmin; + } + } + } + } +} + +void CrowdTool::updateTick(const float dt) +{ + dtNavMesh* nav = m_sample->getNavMesh(); + if (!nav) + return; + + unsigned int flags = 0; + + if (m_anticipateTurns) + flags |= DT_CROWD_ANTICIPATE_TURNS; + if (m_useVO) + flags |= DT_CROWD_USE_VO; + if (m_optimizeVis) + flags |= DT_CROWD_OPTIMIZE_VIS; + if (m_optimizeTopo) + flags |= DT_CROWD_OPTIMIZE_TOPO; + + TimeVal startTime = getPerfTime(); + + m_crowd.update(dt, flags, &m_agentDebug); + + TimeVal endTime = getPerfTime(); + + // Update agent trails + for (int i = 0; i < m_crowd.getAgentCount(); ++i) + { + const dtCrowdAgent* ag = m_crowd.getAgent(i); + AgentTrail* trail = &m_trails[i]; + if (!ag->active) + continue; + // Update agent movement trail. + trail->htrail = (trail->htrail + 1) % AGENT_MAX_TRAIL; + dtVcopy(&trail->trail[trail->htrail*3], ag->npos); + } + + m_agentDebug.vod->normalizeSamples(); + + m_crowdSampleCount.addSample((float)m_crowd.getVelocitySampleCount()); + m_crowdTotalTime.addSample(getPerfDeltaTimeUsec(startTime, endTime) / 1000.0f); } void CrowdTool::handleStep() { + const float dt = 1.0f/20.0f; + updateTick(dt); + m_run = false; } void CrowdTool::handleToggle() @@ -303,28 +391,8 @@ void CrowdTool::handleToggle() void CrowdTool::handleUpdate(const float dt) { if (!m_sample) return; - if (!m_sample->getNavMesh()) return; if (m_run) - { - unsigned int flags = 0; - - if (m_anticipateTurns) - flags |= CROWDMAN_ANTICIPATE_TURNS; - if (m_useVO) - flags |= CROWDMAN_USE_VO; - if (m_drunkMove) - flags |= CROWDMAN_DRUNK; - if (m_optimizeVis) - flags |= CROWDMAN_OPTIMIZE_VIS; - if (m_optimizeTopo) - flags |= CROWDMAN_OPTIMIZE_TOPO; - - m_crowd.update(dt, flags, m_sample->getNavMeshQuery()); - - m_crowdSampleCount.addSample((float)m_crowd.getSampleCount()); - m_crowdTotalTime.addSample(m_crowd.getTotalTime() / 1000.0f); - m_crowdRvoTime.addSample(m_crowd.getRVOTime() / 1000.0f); - } + updateTick(dt); } void CrowdTool::handleRender() @@ -336,10 +404,9 @@ void CrowdTool::handleRender() if (!nmesh) return; - dtNavMeshQuery* navquery = m_sample->getNavMeshQuery(); - - if (m_showNodes) + if (m_showNodes && m_crowd.getPathQueue()) { + const dtNavMeshQuery* navquery = m_crowd.getPathQueue()->getNavQuery(); if (navquery) duDebugDrawNavMeshNodes(&dd, *navquery); } @@ -349,15 +416,17 @@ void CrowdTool::handleRender() // Draw paths if (m_showPath) { - for (int i = 0; i < m_crowd.getAgentCount(); ++i) + if (m_agentDebug.idx != -1) { - const Agent* ag = m_crowd.getAgent(i); - if (!ag->active) continue; - - const dtPolyRef* path = ag->corridor.getPath(); - const int npath = ag->corridor.getPathCount(); - for (int i = 0; i < npath; ++i) - duDebugDrawNavMeshPoly(&dd, *nmesh, path[i], duRGBA(0,0,0,32)); + const dtCrowdAgent* ag = m_crowd.getAgent(m_agentDebug.idx); + if (ag->active) + { + + const dtPolyRef* path = ag->corridor.getPath(); + const int npath = ag->corridor.getPathCount(); + for (int i = 0; i < npath; ++i) + duDebugDrawNavMeshPoly(&dd, *nmesh, path[i], duRGBA(0,0,0,16)); + } } } @@ -370,7 +439,7 @@ void CrowdTool::handleRender() float gridy = -FLT_MAX; for (int i = 0; i < m_crowd.getAgentCount(); ++i) { - const Agent* ag = m_crowd.getAgent(i); + const dtCrowdAgent* ag = m_crowd.getAgent(i); if (!ag->active) continue; const float* pos = ag->corridor.getPos(); gridy = dtMax(gridy, pos[1]); @@ -378,7 +447,7 @@ void CrowdTool::handleRender() gridy += 1.0f; dd.begin(DU_DRAW_QUADS); - const ProximityGrid* grid = m_crowd.getGrid(); + const dtProximityGrid* grid = m_crowd.getGrid(); const int* bounds = grid->getBounds(); const float cs = grid->getCellSize(); for (int y = bounds[1]; y <= bounds[3]; ++y) @@ -400,9 +469,10 @@ void CrowdTool::handleRender() // Trail for (int i = 0; i < m_crowd.getAgentCount(); ++i) { - const Agent* ag = m_crowd.getAgent(i); + const dtCrowdAgent* ag = m_crowd.getAgent(i); if (!ag->active) continue; - + + const AgentTrail* trail = &m_trails[i]; const float* pos = ag->npos; dd.begin(DU_DRAW_LINES,3.0f); @@ -410,8 +480,8 @@ void CrowdTool::handleRender() dtVcopy(prev, pos); for (int j = 0; j < AGENT_MAX_TRAIL-1; ++j) { - const int idx = (ag->htrail + AGENT_MAX_TRAIL-j) % AGENT_MAX_TRAIL; - const float* v = &ag->trail[idx*3]; + const int idx = (trail->htrail + AGENT_MAX_TRAIL-j) % AGENT_MAX_TRAIL; + const float* v = &trail->trail[idx*3]; float a = 1 - j/(float)AGENT_MAX_TRAIL; dd.vertex(prev[0],prev[1]+0.1f,prev[2], duRGBA(0,0,0,(int)(128*preva))); dd.vertex(v[0],v[1]+0.1f,v[2], duRGBA(0,0,0,(int)(128*a))); @@ -423,86 +493,88 @@ void CrowdTool::handleRender() } // Corners & co - for (int i = 0; i < m_crowd.getAgentCount(); ++i) + if (m_agentDebug.idx != -1) { - const Agent* ag = m_crowd.getAgent(i); - if (!ag->active) continue; - - const float radius = ag->radius; - const float* pos = ag->npos; - - if (m_showCorners) + const dtCrowdAgent* ag = m_crowd.getAgent(m_agentDebug.idx); + if (ag->active) { - if (ag->ncorners) + + const float radius = ag->radius; + const float* pos = ag->npos; + + if (m_showCorners) { - dd.begin(DU_DRAW_LINES, 2.0f); - for (int j = 0; j < ag->ncorners; ++j) + if (ag->ncorners) { - const float* va = j == 0 ? pos : &ag->cornerVerts[(j-1)*3]; - const float* vb = &ag->cornerVerts[j*3]; - dd.vertex(va[0],va[1]+radius,va[2], duRGBA(128,0,0,192)); - dd.vertex(vb[0],vb[1]+radius,vb[2], duRGBA(128,0,0,192)); + dd.begin(DU_DRAW_LINES, 2.0f); + for (int j = 0; j < ag->ncorners; ++j) + { + const float* va = j == 0 ? pos : &ag->cornerVerts[(j-1)*3]; + const float* vb = &ag->cornerVerts[j*3]; + dd.vertex(va[0],va[1]+radius,va[2], duRGBA(128,0,0,192)); + dd.vertex(vb[0],vb[1]+radius,vb[2], duRGBA(128,0,0,192)); + } + dd.end(); + + if (m_anticipateTurns) + { + /* float dvel[3], pos[3]; + calcSmoothSteerDirection(ag->pos, ag->cornerVerts, ag->ncorners, dvel); + pos[0] = ag->pos[0] + dvel[0]; + pos[1] = ag->pos[1] + dvel[1]; + pos[2] = ag->pos[2] + dvel[2]; + + const float off = ag->radius+0.1f; + const float* tgt = &ag->cornerVerts[0]; + const float y = ag->pos[1]+off; + + dd.begin(DU_DRAW_LINES, 2.0f); + + dd.vertex(ag->pos[0],y,ag->pos[2], duRGBA(255,0,0,192)); + dd.vertex(pos[0],y,pos[2], duRGBA(255,0,0,192)); + + dd.vertex(pos[0],y,pos[2], duRGBA(255,0,0,192)); + dd.vertex(tgt[0],y,tgt[2], duRGBA(255,0,0,192)); + + dd.end();*/ + } + } + } + + if (m_showCollisionSegments) + { + const float* center = ag->boundary.getCenter(); + duDebugDrawCross(&dd, center[0],center[1]+radius,center[2], 0.2f, duRGBA(192,0,128,255), 2.0f); + duDebugDrawCircle(&dd, center[0],center[1]+radius,center[2], ag->collisionQueryRange, + duRGBA(192,0,128,128), 2.0f); + + dd.begin(DU_DRAW_LINES, 3.0f); + for (int j = 0; j < ag->boundary.getSegmentCount(); ++j) + { + const float* s = ag->boundary.getSegment(j); + unsigned int col = duRGBA(192,0,128,192); + if (dtTriArea2D(pos, s, s+3) < 0.0f) + col = duDarkenCol(col); + + duAppendArrow(&dd, s[0],s[1]+0.2f,s[2], s[3],s[4]+0.2f,s[5], 0.0f, 0.3f, col); } dd.end(); - - if (m_anticipateTurns) - { - /* float dvel[3], pos[3]; - calcSmoothSteerDirection(ag->pos, ag->cornerVerts, ag->ncorners, dvel); - pos[0] = ag->pos[0] + dvel[0]; - pos[1] = ag->pos[1] + dvel[1]; - pos[2] = ag->pos[2] + dvel[2]; - - const float off = ag->radius+0.1f; - const float* tgt = &ag->cornerVerts[0]; - const float y = ag->pos[1]+off; - - dd.begin(DU_DRAW_LINES, 2.0f); - - dd.vertex(ag->pos[0],y,ag->pos[2], duRGBA(255,0,0,192)); - dd.vertex(pos[0],y,pos[2], duRGBA(255,0,0,192)); - - dd.vertex(pos[0],y,pos[2], duRGBA(255,0,0,192)); - dd.vertex(tgt[0],y,tgt[2], duRGBA(255,0,0,192)); - - dd.end();*/ - } } - } - - if (m_showCollisionSegments) - { - const float* center = ag->boundary.getCenter(); - duDebugDrawCross(&dd, center[0],center[1]+radius,center[2], 0.2f, duRGBA(192,0,128,255), 2.0f); - duDebugDrawCircle(&dd, center[0],center[1]+radius,center[2], ag->collisionQueryRange, - duRGBA(192,0,128,128), 2.0f); - dd.begin(DU_DRAW_LINES, 3.0f); - for (int j = 0; j < ag->boundary.getSegmentCount(); ++j) + if (m_showOpt) { - const float* s = ag->boundary.getSegment(j); - unsigned int col = duRGBA(192,0,128,192); - if (dtTriArea2D(pos, s, s+3) < 0.0f) - col = duDarkenCol(col); - - duAppendArrow(&dd, s[0],s[1]+0.2f,s[2], s[3],s[4]+0.2f,s[5], 0.0f, 0.3f, col); + dd.begin(DU_DRAW_LINES, 2.0f); + dd.vertex(m_agentDebug.optStart[0],m_agentDebug.optStart[1]+0.3f,m_agentDebug.optStart[2], duRGBA(0,128,0,192)); + dd.vertex(m_agentDebug.optEnd[0],m_agentDebug.optEnd[1]+0.3f,m_agentDebug.optEnd[2], duRGBA(0,128,0,192)); + dd.end(); } - dd.end(); - } - - if (m_showOpt) - { - dd.begin(DU_DRAW_LINES, 2.0f); - dd.vertex(ag->opts[0],ag->opts[1]+0.3f,ag->opts[2], duRGBA(0,128,0,192)); - dd.vertex(ag->opte[0],ag->opte[1]+0.3f,ag->opte[2], duRGBA(0,128,0,192)); - dd.end(); } } // Agent cylinders. for (int i = 0; i < m_crowd.getAgentCount(); ++i) { - const Agent* ag = m_crowd.getAgent(i); + const dtCrowdAgent* ag = m_crowd.getAgent(i); if (!ag->active) continue; const float radius = ag->radius; @@ -513,23 +585,26 @@ void CrowdTool::handleRender() for (int i = 0; i < m_crowd.getAgentCount(); ++i) { - const Agent* ag = m_crowd.getAgent(i); + const dtCrowdAgent* ag = m_crowd.getAgent(i); if (!ag->active) continue; const float height = ag->height; const float radius = ag->radius; const float* pos = ag->npos; + unsigned int col = duRGBA(220,220,220,128); + if (m_agentDebug.idx == i) + col = duRGBA(255,192,0,128); + duDebugDrawCylinder(&dd, pos[0]-radius, pos[1]+radius*0.1f, pos[2]-radius, - pos[0]+radius, pos[1]+height, pos[2]+radius, - duRGBA(220,220,220,128)); + pos[0]+radius, pos[1]+height, pos[2]+radius, col); } // Velocity stuff. for (int i = 0; i < m_crowd.getAgentCount(); ++i) { - const Agent* ag = m_crowd.getAgent(i); + const dtCrowdAgent* ag = m_crowd.getAgent(i); if (!ag->active) continue; const float radius = ag->radius; @@ -538,34 +613,11 @@ void CrowdTool::handleRender() const float* vel = ag->vel; const float* dvel = ag->dvel; - duDebugDrawCircle(&dd, pos[0], pos[1]+height, pos[2], radius, duRGBA(220,220,220,192), 2.0f); - - if (m_showVO) - { - // Draw detail about agent sela - const dtObstacleAvoidanceDebugData* debug = m_crowd.getVODebugData(i); - - const float dx = pos[0]; - const float dy = pos[1]+height; - const float dz = pos[2]; - - dd.begin(DU_DRAW_QUADS); - for (int i = 0; i < debug->getSampleCount(); ++i) - { - const float* p = debug->getSampleVelocity(i); - const float sr = debug->getSampleSize(i); - const float pen = debug->getSamplePenalty(i); - const float pen2 = debug->getSamplePreferredSidePenalty(i); - unsigned int col = duLerpCol(duRGBA(255,255,255,220), duRGBA(128,96,0,220), (int)(pen*255)); - col = duLerpCol(col, duRGBA(128,0,0,220), (int)(pen2*128)); - dd.vertex(dx+p[0]-sr, dy, dz+p[2]-sr, col); - dd.vertex(dx+p[0]-sr, dy, dz+p[2]+sr, col); - dd.vertex(dx+p[0]+sr, dy, dz+p[2]+sr, col); - dd.vertex(dx+p[0]+sr, dy, dz+p[2]-sr, col); - } - dd.end(); - - } + unsigned int col = duRGBA(220,220,220,192); + if (m_agentDebug.idx == i) + col = duRGBA(255,192,0,192); + + duDebugDrawCircle(&dd, pos[0], pos[1]+height, pos[2], radius, col, 2.0f); duDebugDrawArrow(&dd, pos[0],pos[1]+height,pos[2], pos[0]+dvel[0],pos[1]+height+dvel[1],pos[2]+dvel[2], @@ -576,19 +628,36 @@ void CrowdTool::handleRender() 0.0f, 0.4f, duRGBA(0,0,0,192), 2.0f); } - // Targets - for (int i = 0; i < m_crowd.getAgentCount(); ++i) + if (m_agentDebug.idx != -1) { - const Agent* ag = m_crowd.getAgent(i); - if (!ag->active) continue; - - const float* pos = ag->npos; - const float* target = ag->corridor.getTarget(); - - if (m_showTargets) + const dtCrowdAgent* ag = m_crowd.getAgent(m_agentDebug.idx); + if (ag->active) { - duDebugDrawArc(&dd, pos[0], pos[1], pos[2], target[0], target[1], target[2], - 0.25f, 0, 0.4f, duRGBA(0,0,0,128), 1.0f); + if (m_showVO) + { + // Draw detail about agent sela + const dtObstacleAvoidanceDebugData* vod = m_agentDebug.vod; + + const float dx = ag->npos[0]; + const float dy = ag->npos[1]+ag->height; + const float dz = ag->npos[2]; + + dd.begin(DU_DRAW_QUADS); + for (int i = 0; i < vod->getSampleCount(); ++i) + { + const float* p = vod->getSampleVelocity(i); + const float sr = vod->getSampleSize(i); + const float pen = vod->getSamplePenalty(i); + const float pen2 = vod->getSamplePreferredSidePenalty(i); + unsigned int col = duLerpCol(duRGBA(255,255,255,220), duRGBA(128,96,0,220), (int)(pen*255)); + col = duLerpCol(col, duRGBA(128,0,0,220), (int)(pen2*128)); + dd.vertex(dx+p[0]-sr, dy, dz+p[2]-sr, col); + dd.vertex(dx+p[0]-sr, dy, dz+p[2]+sr, col); + dd.vertex(dx+p[0]+sr, dy, dz+p[2]+sr, col); + dd.vertex(dx+p[0]+sr, dy, dz+p[2]-sr, col); + } + dd.end(); + } } } @@ -611,7 +680,7 @@ void CrowdTool::handleRenderOverlay(double* proj, double* model, int* view) char label[32]; for (int i = 0; i < m_crowd.getAgentCount(); ++i) { - const Agent* ag = m_crowd.getAgent(i); + const dtCrowdAgent* ag = m_crowd.getAgent(i); if (!ag->active) continue; const float* pos = ag->npos; const float h = ag->height; @@ -632,11 +701,32 @@ void CrowdTool::handleRenderOverlay(double* proj, double* model, int* view) gp.setValueRange(0.0f, 2.0f, 4, "ms"); drawGraphBackground(&gp); - drawGraph(&gp, &m_crowdRvoTime, 0, "RVO Sampling", duRGBA(255,0,128,255)); - drawGraph(&gp, &m_crowdTotalTime, 1, "Total", duRGBA(128,255,0,255)); + drawGraph(&gp, &m_crowdTotalTime, 1, "Total", duRGBA(255,128,0,255)); gp.setRect(300, 10, 500, 50, 8); - gp.setValueRange(0.0f, 2000.0f, 1, "0"); - drawGraph(&gp, &m_crowdSampleCount, 0, "Sample Count", duRGBA(255,255,255,255)); + gp.setValueRange(0.0f, 2000.0f, 1, ""); + drawGraph(&gp, &m_crowdSampleCount, 0, "Sample Count", duRGBA(96,96,96,128)); } + + // Tool help + const int h = view[3]; + int ty = h-40; + + if (m_mode == TOOLMODE_CREATE) + { + imguiDrawText(280, ty, IMGUI_ALIGN_LEFT, "LMB: add agent. Shift+LMB: remove agent.", imguiRGBA(255,255,255,192)); + } + else if (m_mode == TOOLMODE_MOVE_TARGET) + { + imguiDrawText(280, ty, IMGUI_ALIGN_LEFT, "LMB: set move target. Shift+LMB: adjust target.", imguiRGBA(255,255,255,192)); + ty -= 20; + imguiDrawText(280, ty, IMGUI_ALIGN_LEFT, "Adjusting allows to change the target location in short range without pathfinder.", imguiRGBA(255,255,255,192)); + } + else if (m_mode == TOOLMODE_SELECT) + { + imguiDrawText(280, ty, IMGUI_ALIGN_LEFT, "LMB: select agent.", imguiRGBA(255,255,255,192)); + } + ty -= 20; + imguiDrawText(280, ty, IMGUI_ALIGN_LEFT, "SPACE: Run/Pause simulation. 1: Step simulation.", imguiRGBA(255,255,255,192)); + } diff --git a/RecastDemo/Source/NavMeshTesterTool.cpp b/RecastDemo/Source/NavMeshTesterTool.cpp index 95bfac6..4581354 100644 --- a/RecastDemo/Source/NavMeshTesterTool.cpp +++ b/RecastDemo/Source/NavMeshTesterTool.cpp @@ -479,7 +479,7 @@ void NavMeshTesterTool::handleUpdate(const float /*dt*/) { if (dtStatusInProgress(m_pathFindStatus)) { - m_pathFindStatus = m_navQuery->updateSlicedFindPath(1); + m_pathFindStatus = m_navQuery->updateSlicedFindPath(1,0); } if (dtStatusSucceed(m_pathFindStatus)) { @@ -1191,6 +1191,10 @@ void NavMeshTesterTool::handleRenderOverlay(double* proj, double* model, int* vi { imguiDrawText((int)x, (int)(y-25), IMGUI_ALIGN_CENTER, "End", imguiRGBA(0,0,0,220)); } + + // Tool help + const int h = view[3]; + imguiDrawText(280, h-40, IMGUI_ALIGN_LEFT, "LMB+SHIFT: Set start location LMB: Set end location", imguiRGBA(255,255,255,192)); } void NavMeshTesterTool::drawAgent(const float* pos, float r, float h, float c, const unsigned int col) diff --git a/RecastDemo/Source/OffMeshConnectionTool.cpp b/RecastDemo/Source/OffMeshConnectionTool.cpp index ec192a6..d258979 100644 --- a/RecastDemo/Source/OffMeshConnectionTool.cpp +++ b/RecastDemo/Source/OffMeshConnectionTool.cpp @@ -72,15 +72,6 @@ void OffMeshConnectionTool::handleMenu() m_bidir = false; if (imguiCheck("Bidirectional", m_bidir)) m_bidir = true; - - if (!m_hitPosSet) - { - imguiValue("Click to set connection start."); - } - else - { - imguiValue("Click to set connection end."); - } } void OffMeshConnectionTool::handleClick(const float* /*s*/, const float* p, bool shift) @@ -167,4 +158,15 @@ void OffMeshConnectionTool::handleRenderOverlay(double* proj, double* model, int { imguiDrawText((int)x, (int)(y-25), IMGUI_ALIGN_CENTER, "Start", imguiRGBA(0,0,0,220)); } + + // Tool help + const int h = view[3]; + if (!m_hitPosSet) + { + imguiDrawText(280, h-40, IMGUI_ALIGN_LEFT, "LMB: Create new connection. SHIFT+LMB: Delete existing connection, click close to start or end point.", imguiRGBA(255,255,255,192)); + } + else + { + imguiDrawText(280, h-40, IMGUI_ALIGN_LEFT, "LMB: Set connection end point and finish.", imguiRGBA(255,255,255,192)); + } } diff --git a/RecastDemo/Source/Sample_SoloMeshTiled.cpp b/RecastDemo/Source/Sample_SoloMeshTiled.cpp index b6d04a8..773f8b4 100644 --- a/RecastDemo/Source/Sample_SoloMeshTiled.cpp +++ b/RecastDemo/Source/Sample_SoloMeshTiled.cpp @@ -75,7 +75,6 @@ public: virtual void handleMenu() { - imguiValue("Click LMB to highlight a tile."); } virtual void handleClick(const float* /*s*/, const float* p, bool /*shift*/) @@ -127,6 +126,9 @@ public: imguiDrawText((int)x, (int)y-25, IMGUI_ALIGN_CENTER, text, imguiRGBA(0,0,0,220)); } + // Tool help + const int h = view[3]; + imguiDrawText(280, h-40, IMGUI_ALIGN_LEFT, "LMB: Highlight hit.", imguiRGBA(255,255,255,192)); } }; diff --git a/RecastDemo/Source/Sample_TileMesh.cpp b/RecastDemo/Source/Sample_TileMesh.cpp index 9b4ae7e..da7e043 100644 --- a/RecastDemo/Source/Sample_TileMesh.cpp +++ b/RecastDemo/Source/Sample_TileMesh.cpp @@ -108,8 +108,6 @@ public: if (m_sample) m_sample->removeAllTiles(); } - imguiValue("Click LMB to create a tile."); - imguiValue("Shift+LMB to remove a tile."); } virtual void handleClick(const float* /*s*/, const float* p, bool shift) @@ -163,6 +161,9 @@ public: imguiDrawText((int)x, (int)y-25, IMGUI_ALIGN_CENTER, text, imguiRGBA(0,0,0,220)); } + // Tool help + const int h = view[3]; + imguiDrawText(280, h-40, IMGUI_ALIGN_LEFT, "LMB: Rebuild hit tile. Shift+LMB: Clear hit tile.", imguiRGBA(255,255,255,192)); } }; diff --git a/RecastDemo/Source/main.cpp b/RecastDemo/Source/main.cpp index 5f2a074..c2d8206 100644 --- a/RecastDemo/Source/main.cpp +++ b/RecastDemo/Source/main.cpp @@ -132,7 +132,6 @@ int main(int /*argc*/, char** /*argv*/) bool mouseOverMenu = false; bool showMenu = !presentationMode; bool showLog = false; - bool showDebugMode = true; bool showTools = true; bool showLevels = false; bool showSample = false; @@ -141,7 +140,6 @@ int main(int /*argc*/, char** /*argv*/) int propScroll = 0; int logScroll = 0; int toolsScroll = 0; - int debugScroll = 0; char sampleName[64] = "Choose Sample..."; @@ -511,24 +509,19 @@ int main(int /*argc*/, char** /*argv*/) // Help text. if (showMenu) { - const char msg[] = "W/S/A/D: Move RMB: Rotate LMB+SHIFT: Place Start LMB: Place End"; - imguiDrawText(width/2, height-20, IMGUI_ALIGN_CENTER, msg, imguiRGBA(255,255,255,128)); + const char msg[] = "W/S/A/D: Move RMB: Rotate"; + imguiDrawText(280, height-20, IMGUI_ALIGN_LEFT, msg, imguiRGBA(255,255,255,128)); } if (showMenu) { - int propDiv = showDebugMode ? (int)(height*0.6f) : height; - - if (imguiBeginScrollArea("Properties", - width-250-10, 10+height-propDiv, 250, propDiv-20, &propScroll)) + if (imguiBeginScrollArea("Properties", width-250-10, 10, 250, height-20, &propScroll)) mouseOverMenu = true; if (imguiCheck("Show Log", showLog)) showLog = !showLog; if (imguiCheck("Show Tools", showTools)) showTools = !showTools; - if (imguiCheck("Show Debug Mode", showDebugMode)) - showDebugMode = !showDebugMode; imguiSeparator(); imguiLabel("Sample"); @@ -571,9 +564,11 @@ int main(int /*argc*/, char** /*argv*/) imguiValue(text); } imguiSeparator(); - + if (geom && sample) { + imguiSeparatorLine(); + sample->handleSettings(); if (imguiButton("Build")) @@ -594,20 +589,13 @@ int main(int /*argc*/, char** /*argv*/) imguiSeparator(); } - imguiEndScrollArea(); - - if (showDebugMode) + if (sample) { - if (imguiBeginScrollArea("Debug Mode", - width-250-10, 10, - 250, height-propDiv-10, &debugScroll)) - mouseOverMenu = true; - - if (sample) - sample->handleDebugMode(); - - imguiEndScrollArea(); + imguiSeparatorLine(); + sample->handleDebugMode(); } + + imguiEndScrollArea(); } // Sample selection dialog. @@ -873,7 +861,7 @@ int main(int /*argc*/, char** /*argv*/) // Log if (showLog && showMenu) { - if (imguiBeginScrollArea("Log", 10, 10, width - 300, 200, &logScroll)) + if (imguiBeginScrollArea("Log", 250+20, 10, width - 300 - 250, 200, &logScroll)) mouseOverMenu = true; for (int i = 0; i < ctx.getLogCount(); ++i) imguiLabel(ctx.getLogText(i)); @@ -881,12 +869,13 @@ int main(int /*argc*/, char** /*argv*/) } // Tools - if (!showTestCases && showTools && showMenu && geom && sample) + if (!showTestCases && showTools && showMenu) // && geom && sample) { - if (imguiBeginScrollArea("Tools", 10, height - 10 - 350, 250, 350, &toolsScroll)) + if (imguiBeginScrollArea("Tools", 10, 10, 250, height-20, &toolsScroll)) mouseOverMenu = true; - sample->handleTools(); + if (sample) + sample->handleTools(); imguiEndScrollArea(); }