From b3731d6a1c2812fbd99a0ac9c079b8e0d5ec855b Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Wed, 30 Aug 2023 23:50:31 -0500 Subject: [PATCH 01/50] Remove forward-ported restriction on model loading (#2104) Signed-off-by: Michael Carroll --- src/Server.cc | 8 -------- 1 file changed, 8 deletions(-) diff --git a/src/Server.cc b/src/Server.cc index 6f1eb37390..28a3d01725 100644 --- a/src/Server.cc +++ b/src/Server.cc @@ -160,14 +160,6 @@ Server::Server(const ServerConfig &_config) return; } - if (this->dataPtr->sdfRoot.WorldCount() == 0) - { - gzerr << "SDF file doesn't contain a world. " << - "If you wish to spawn a model, use the ResourceSpawner GUI plugin " << - "or the 'world//create' service.\n"; - return; - } - // Add record plugin if (_config.UseLogRecord()) { From 52167a6e713c87b57d695c31005c98b7a736f51c Mon Sep 17 00:00:00 2001 From: Jasmeet Singh Date: Thu, 31 Aug 2023 20:33:55 +0530 Subject: [PATCH 02/50] Add automatic moment of inertia calculation for meshes (#2061) The PR implements a Moment of Inertia Calculator based on the method described in this document. The calculator works using the callback-based API from the sdformat made in this PR. --------- Signed-off-by: Jasmeet Singh Signed-off-by: Addisu Z. Taddese Co-authored-by: Addisu Z. Taddese --- src/CMakeLists.txt | 2 + src/MeshInertiaCalculator.cc | 277 ++++++++++++++++++ src/MeshInertiaCalculator.hh | 134 +++++++++ src/Server.cc | 19 +- test/integration/CMakeLists.txt | 1 + test/integration/mesh_inertia_calculation.cc | 129 ++++++++ test/worlds/mesh_inertia_calculation.sdf | 16 + .../models/cylinder_dae/meshes/cylinder.dae | 69 +++++ test/worlds/models/cylinder_dae/model.config | 16 + test/worlds/models/cylinder_dae/model.sdf | 47 +++ 10 files changed, 707 insertions(+), 3 deletions(-) create mode 100644 src/MeshInertiaCalculator.cc create mode 100644 src/MeshInertiaCalculator.hh create mode 100644 test/integration/mesh_inertia_calculation.cc create mode 100644 test/worlds/mesh_inertia_calculation.sdf create mode 100644 test/worlds/models/cylinder_dae/meshes/cylinder.dae create mode 100644 test/worlds/models/cylinder_dae/model.config create mode 100644 test/worlds/models/cylinder_dae/model.sdf diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 83adc9dc0d..6e666dafc9 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -73,6 +73,7 @@ set (sources LevelManager.cc Light.cc Link.cc + MeshInertiaCalculator.cc Model.cc Primitives.cc SdfEntityCreator.cc @@ -206,6 +207,7 @@ target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME} gz-math${GZ_MATH_VER} gz-plugin${GZ_PLUGIN_VER}::core gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER} + gz-common${GZ_COMMON_VER}::graphics gz-common${GZ_COMMON_VER}::profiler gz-fuel_tools${GZ_FUEL_TOOLS_VER}::gz-fuel_tools${GZ_FUEL_TOOLS_VER} gz-gui${GZ_GUI_VER}::gz-gui${GZ_GUI_VER} diff --git a/src/MeshInertiaCalculator.cc b/src/MeshInertiaCalculator.cc new file mode 100644 index 0000000000..e80f2cfd91 --- /dev/null +++ b/src/MeshInertiaCalculator.cc @@ -0,0 +1,277 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include "MeshInertiaCalculator.hh" + +#include +#include + +#include +#include + +#include + +#include +#include +#include + +#include +#include +#include +#include + +using namespace gz; +using namespace sim; + +////////////////////////////////////////////////// +void MeshInertiaCalculator::GetMeshTriangles( + std::vector& _triangles, + const gz::common::Mesh* _mesh) +{ + // Get the vertices & indices of the mesh + double* vertArray = nullptr; + int* indArray = nullptr; + _mesh->FillArrays(&vertArray, &indArray); + + // Add check to see if size of the ind array is divisible by 3 + for (unsigned int i = 0; i < _mesh->IndexCount(); i += 3) + { + Triangle triangle; + triangle.v0.X() = vertArray[static_cast(3 * indArray[i])]; + triangle.v0.Y() = vertArray[static_cast(3 * indArray[i] + 1)]; + triangle.v0.Z() = vertArray[static_cast(3 * indArray[i] + 2)]; + triangle.v1.X() = vertArray[static_cast(3 * indArray[i+1])]; + triangle.v1.Y() = vertArray[static_cast(3 * indArray[i+1] + 1)]; + triangle.v1.Z() = vertArray[static_cast(3 * indArray[i+1] + 2)]; + triangle.v2.X() = vertArray[static_cast(3 * indArray[i+2])]; + triangle.v2.Y() = vertArray[static_cast(3 * indArray[i+2] + 1)]; + triangle.v2.Z() = vertArray[static_cast(3 * indArray[i+2] + 2)]; + triangle.centroid = (triangle.v0 + triangle.v1 + triangle.v2) / 3; + _triangles.push_back(triangle); + } +} + +////////////////////////////////////////////////// +void MeshInertiaCalculator::CalculateMeshCentroid( + gz::math::Pose3d &_centreOfMass, + std::vector &_triangles) +{ + gz::math::Vector3d centroid = gz::math::Vector3d::Zero; + gz::math::Vector3d triangleCross = gz::math::Vector3d::Zero; + double totalMeshArea = 0.0; + double triangleArea = 0.0; + + for (Triangle &triangle : _triangles) + { + // Calculate the area of the triangle using half of + // cross product magnitude + triangleCross = + (triangle.v1 - triangle.v0).Cross(triangle.v2 - triangle.v0); + triangleArea = triangleCross.Length() / 2; + + centroid = centroid + (triangle.centroid * triangleArea); + totalMeshArea = totalMeshArea + triangleArea; + } + + centroid = centroid / totalMeshArea; + + _centreOfMass.SetX(centroid.X()); + _centreOfMass.SetY(centroid.Y()); + _centreOfMass.SetZ(centroid.Z()); +} + +////////////////////////////////////////////////// +void MeshInertiaCalculator::CalculateMassProperties( + const std::vector& _triangles, + double _density, + gz::math::MassMatrix3d& _massMatrix, + gz::math::Pose3d& _inertiaOrigin) +{ + // Some coefficients for the calculation of integral terms + const double coefficients[10] = {1.0 / 6, 1.0 / 24, 1.0 / 24, 1.0 / 24, + 1.0 / 60, 1.0 / 60, 1.0 / 60, 1.0 / 120, + 1.0 / 120, 1.0 / 120}; + + // Number of triangles of in the mesh + std::size_t numTriangles = _triangles.size(); + + // Vector to store cross products of 2 vectors of the triangles + std::vector crosses(numTriangles); + + // Caculating cross products of 2 vectors emerging from a common vertex + // This basically gives a vector normal to the plane of triangle + for (std::size_t i = 0; i < numTriangles; ++i) + { + crosses[i] = + (_triangles[i].v1 - _triangles[i].v0).Cross( + _triangles[i].v2 - _triangles[i].v0); + } + + // Calculate subexpressions of the integral + std::vector f1(numTriangles), f2(numTriangles), + f3(numTriangles), g0(numTriangles), g1(numTriangles), g2(numTriangles); + + for (std::size_t i = 0; i < numTriangles; ++i) + { + f1[i] = _triangles[i].v0 + _triangles[i].v1 + _triangles[i].v2; + f2[i] = _triangles[i].v0 * _triangles[i].v0 + + _triangles[i].v1 * _triangles[i].v1 + + _triangles[i].v0 * _triangles[i].v1 + + _triangles[i].v2 * f1[i]; + f3[i] = _triangles[i].v0 * _triangles[i].v0 * _triangles[i].v0 + + _triangles[i].v0 * _triangles[i].v0 * _triangles[i].v1 + + _triangles[i].v0 * _triangles[i].v1 * _triangles[i].v1 + + _triangles[i].v1 * _triangles[i].v1 * _triangles[i].v1 + + _triangles[i].v2 * f2[i]; + g0[i] = f2[i] + (_triangles[i].v0 + f1[i]) * (_triangles[i].v0); + g1[i] = f2[i] + (_triangles[i].v1 + f1[i]) * (_triangles[i].v1); + g2[i] = f2[i] + (_triangles[i].v2 + f1[i]) * (_triangles[i].v2); + } + + // Calculate integral terms + std::vector integral(10); + for (std::size_t i = 0; i < numTriangles; ++i) + { + double x0 = _triangles[i].v0.X(); + double y0 = _triangles[i].v0.Y(); + double z0 = _triangles[i].v0.Z(); + double x1 = _triangles[i].v1.X(); + double y1 = _triangles[i].v1.Y(); + double z1 = _triangles[i].v1.Z(); + double x2 = _triangles[i].v2.X(); + double y2 = _triangles[i].v2.Y(); + double z2 = _triangles[i].v2.Z(); + integral[0] += crosses[i].X() * f1[i].X(); + integral[1] += crosses[i].X() * f2[i].X(); + integral[2] += crosses[i].Y() * f2[i].Y(); + integral[3] += crosses[i].Z() * f2[i].Z(); + integral[4] += crosses[i].X() * f3[i].X(); + integral[5] += crosses[i].Y() * f3[i].Y(); + integral[6] += crosses[i].Z() * f3[i].Z(); + integral[7] += crosses[i].X() * + (y0 * g0[i].X() + y1 * g1[i].X() + y2 * g2[i].X()); + integral[8] += crosses[i].Y() * + (z0 * g0[i].Y() + z1 * g1[i].Y() + z2 * g2[i].Y()); + integral[9] += crosses[i].Z() * + (x0 * g0[i].Z() + x1 * g1[i].Z() + x2 * g2[i].Z()); + } + + for (int i = 0; i < 10; ++i) + { + integral[i] *= coefficients[i]; + } + + // Accumulate the result and add it to MassMatrix object of gz::math + double volume = integral[0]; + double mass = volume * _density; + _inertiaOrigin.SetX(integral[1] / mass); + _inertiaOrigin.SetY(integral[2] / mass); + _inertiaOrigin.SetZ(integral[3] / mass); + gz::math::Vector3d ixxyyzz = gz::math::Vector3d(); + gz::math::Vector3d ixyxzyz = gz::math::Vector3d(); + + // Diagonal Elements of the Mass Matrix + ixxyyzz.X() = (integral[5] + integral[6] - mass * + (_inertiaOrigin.Y() * _inertiaOrigin.Y() + + _inertiaOrigin.Z() * _inertiaOrigin.Z())); + ixxyyzz.Y() = (integral[4] + integral[6] - mass * + (_inertiaOrigin.Z() * _inertiaOrigin.Z() + + _inertiaOrigin.X() * _inertiaOrigin.X())); + ixxyyzz.Z() = integral[4] + integral[5] - mass * + (_inertiaOrigin.X() * _inertiaOrigin.X() + + _inertiaOrigin.Y() * _inertiaOrigin.Y()); + + // Off Diagonal Elements of the Mass Matrix + ixyxzyz.X() = -(integral[7] - mass * _inertiaOrigin.X() * _inertiaOrigin.Y()); + ixyxzyz.Y() = -(integral[8] - mass * _inertiaOrigin.Y() * _inertiaOrigin.Z()); + ixyxzyz.Z() = -(integral[9] - mass * _inertiaOrigin.X() * _inertiaOrigin.Z()); + + // Set the values in the MassMatrix object + _massMatrix.SetMass(mass); + _massMatrix.SetDiagonalMoments(ixxyyzz * _density); + _massMatrix.SetOffDiagonalMoments(ixyxzyz * _density); +} + +////////////////////////////////////////////////// +std::optional MeshInertiaCalculator::operator() + (sdf::Errors& _errors, + const sdf::CustomInertiaCalcProperties& _calculatorParams) +{ + const gz::common::Mesh *mesh = nullptr; + const double density = _calculatorParams.Density(); + + auto sdfMesh = _calculatorParams.Mesh(); + + if (sdfMesh == std::nullopt) + { + gzerr << "Could not calculate inertia for mesh " + "as it std::nullopt" << std::endl; + _errors.push_back({sdf::ErrorCode::FATAL_ERROR, + "Could not calculate mesh inertia as mesh object is" + "std::nullopt"}); + return std::nullopt; + } + + auto fullPath = asFullPath(sdfMesh->Uri(), sdfMesh->FilePath()); + + if (fullPath.empty()) + { + gzerr << "Mesh geometry missing uri" << std::endl; + _errors.push_back({sdf::ErrorCode::URI_INVALID, + "Attempting to load the mesh but the URI seems to be incorrect"}); + return std::nullopt; + } + + // Load the Mesh + gz::common::MeshManager *meshManager = gz::common::MeshManager::Instance(); + mesh = meshManager->Load(fullPath); + std::vector meshTriangles; + gz::math::MassMatrix3d meshMassMatrix; + gz::math::Pose3d centreOfMass; + gz::math::Pose3d inertiaOrigin; + + // Create a list of Triangle objects from the mesh vertices and indices + this->GetMeshTriangles(meshTriangles, mesh); + + // Calculate the mesh centroid and set is as centre of mass + this->CalculateMeshCentroid(centreOfMass, meshTriangles); + + // Calculate mesh mass properties + this->CalculateMassProperties(meshTriangles, density, + meshMassMatrix, inertiaOrigin); + + if (inertiaOrigin != centreOfMass) + { + // TODO(jasmeet0915): tranform the calculated inertia matrix + // from inertia origin to centre of mass + gzwarn << "Calculated centroid does not match the mesh origin. " + "Inertia Tensor values won't be correct. Use mesh with origin at " + "geometric center." << std::endl; + } + + gz::math::Inertiald meshInertial; + + if (!meshInertial.SetMassMatrix(meshMassMatrix)) + { + return std::nullopt; + } + else + { + meshInertial.SetPose(centreOfMass); + return meshInertial; + } +} diff --git a/src/MeshInertiaCalculator.hh b/src/MeshInertiaCalculator.hh new file mode 100644 index 0000000000..62687d8ef8 --- /dev/null +++ b/src/MeshInertiaCalculator.hh @@ -0,0 +1,134 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifndef GZ_SIM_MESHINERTIACALCULATOR_HH_ +#define GZ_SIM_MESHINERTIACALCULATOR_HH_ + +#include +#include + +#include +#include + +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include + + +namespace gz +{ + namespace sim + { + // Inline bracket to help doxygen filtering. + inline namespace GZ_SIM_VERSION_NAMESPACE + { + /// \struct Triangle gz/sim/MeshInertiaCalculator.hh + /// \brief A struct to represent a triangle of the mesh + /// An instance of the struct holds 3 Vector3D instances + /// each of which represents a vertex of the triangle & + /// one more Vector3D that represents the centroid of the + /// triangle + struct Triangle + { + gz::math::Vector3d v0, v1, v2; + + gz::math::Vector3d centroid; + }; + + /// \class MeshInertiaCalculator gz/sim/MeshInertiaCalculator.hh + /// \brief Inertial Properties (Mass, Centre of Mass & Moments of + /// Inertia) calculator for 3D meshes. + /// + /// This class overloads the () operator, therefore, an instance + /// of this class registered with libsdformat as a Custom + /// Inertia Calculator. This would be used to calculate the + /// inertial properties of 3D mesh using SDFormat. + /// + /// The calculation method used in this class is described here: + /// https://www.geometrictools.com/Documentation/PolyhedralMassProperties.pdf + /// and it works on triangle water-tight meshes for simple polyhedron + class MeshInertiaCalculator + { + /// \brief Constructor + public: MeshInertiaCalculator() = default; + + /// \brief Function to get the vertices & indices of the given mesh + /// & convert them into instances of the Triangle struct + /// Each triangle represents a triangle in the mesh & is added + /// to a vector + /// \param[out] _triangles A vector to hold all the Triangle + /// instances obtained + /// from the vertices & indices of the mesh + /// \param[in] _mesh Mesh object + public: void GetMeshTriangles( + std::vector& _triangles, + const gz::common::Mesh* _mesh); + + /// \brief Function to calculate the centroid of the mesh. Since + /// uniform density is considered for the mesh, the centroid value + /// is used as the centre of mass. + /// The mesh centroid is calculated by the average of the + /// centroid of mesh triangle weighted by the area of the + /// respective triangle + /// \param[out] _centreOfMass A gz::math::Pose3d object to hold + /// calculated centroid (centre of mass) of the mesh + /// \param[in] _triangles A vector with all the triangles of the + /// mesh represented as instances of the Triangle struct + public: void CalculateMeshCentroid(gz::math::Pose3d &_centreOfMass, + std::vector &_triangles); + + /// \brief Function that calculates the mass, mass matrix & centre of + /// mass of a mesh using a vector of Triangles of the mesh + /// \param[in] _triangles A vector of all the Triangles of the mesh + /// \param[in] _density Density of the mesh + /// \param[out] _massMatrix MassMatrix object to hold mass & + /// moment of inertia of the mesh + /// \param[out] _inertiaOrigin Pose3d object to hold the origin about + /// which the inertia tensor was calculated + public: void CalculateMassProperties( + const std::vector& _triangles, + double _density, + gz::math::MassMatrix3d& _massMatrix, + gz::math::Pose3d& _inertiaOrigin); + + /// \brief Overloaded () operator which allows an instance + /// of this class to be registered as a Custom Inertia + /// Calculator with libsdformat + /// \param[out] _errors A vector of Errors object. Each object + /// would contain an error code and an error message. + /// \param _calculatorParams An instance of + /// CustomInertiaCalcProperties. This instance can be used + /// to access the data like density, + /// properties of the mesh, etc. + public: std::optional operator()( + sdf::Errors& _errors, + const sdf::CustomInertiaCalcProperties& _calculatorParams); + }; + } + } +} + +#endif diff --git a/src/Server.cc b/src/Server.cc index 70d676916c..3cf8624a26 100644 --- a/src/Server.cc +++ b/src/Server.cc @@ -26,11 +26,14 @@ #include #include #include +#include +#include #include "gz/sim/config.hh" #include "gz/sim/Server.hh" #include "gz/sim/Util.hh" +#include "MeshInertiaCalculator.hh" #include "ServerPrivate.hh" #include "SimulationRunner.hh" @@ -117,7 +120,10 @@ Server::Server(const ServerConfig &_config) msg += "File path [" + _config.SdfFile() + "].\n"; } gzmsg << msg; - errors = this->dataPtr->sdfRoot.LoadSdfString(_config.SdfString()); + sdf::ParserConfig sdfParserConfig = sdf::ParserConfig::GlobalConfig(); + errors = this->dataPtr->sdfRoot.LoadSdfString( + _config.SdfString(), sdfParserConfig); + this->dataPtr->sdfRoot.ResolveAutoInertials(errors, sdfParserConfig); break; } @@ -136,12 +142,16 @@ Server::Server(const ServerConfig &_config) gzmsg << "Loading SDF world file[" << filePath << "].\n"; sdf::Root sdfRoot; + sdf::ParserConfig sdfParserConfig = sdf::ParserConfig::GlobalConfig(); + + MeshInertiaCalculator meshInertiaCalculator; + sdfParserConfig.RegisterCustomInertiaCalc(meshInertiaCalculator); // \todo(nkoenig) Async resource download. // This call can block for a long period of time while // resources are downloaded. Blocking here causes the GUI to block with // a black screen (search for "Async resource download" in // 'src/gui_main.cc'. - errors = sdfRoot.Load(filePath); + errors = sdfRoot.Load(filePath, sdfParserConfig); if (errors.empty()) { if (sdfRoot.Model() == nullptr) { this->dataPtr->sdfRoot = std::move(sdfRoot); @@ -150,7 +160,8 @@ Server::Server(const ServerConfig &_config) { // If the specified file only contains a model, load the default // world and add the model to it. - errors = this->dataPtr->sdfRoot.LoadSdfString(DefaultWorld::World()); + errors = this->dataPtr->sdfRoot.LoadSdfString( + DefaultWorld::World(), sdfParserConfig); sdf::World *world = this->dataPtr->sdfRoot.WorldByIndex(0); if (world == nullptr) { return; @@ -161,6 +172,8 @@ Server::Server(const ServerConfig &_config) } } } + + this->dataPtr->sdfRoot.ResolveAutoInertials(errors, sdfParserConfig); break; } diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index ef2166b55f..7ed4703dec 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -48,6 +48,7 @@ set(tests logical_camera_system.cc logical_audio_sensor_plugin.cc magnetometer_system.cc + mesh_inertia_calculation.cc model.cc model_photo_shoot_default_joints.cc model_photo_shoot_random_joints.cc diff --git a/test/integration/mesh_inertia_calculation.cc b/test/integration/mesh_inertia_calculation.cc new file mode 100644 index 0000000000..03653eb6d4 --- /dev/null +++ b/test/integration/mesh_inertia_calculation.cc @@ -0,0 +1,129 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include "test_config.hh" +#include "../helpers/EnvTestFixture.hh" +#include "../helpers/Relay.hh" + +using namespace gz; +using namespace sim; + +/// \brief Test Mesh Inertia Calculation +class MeshInertiaCalculationTest : public InternalFixture<::testing::Test> +{ +}; + +TEST(MeshInertiaCalculationTest, CylinderColladaMeshInertiaCalculation) +{ + size_t kIter = 100u; + + gz::math::Pose3d linkPose(4, 4, 1, 0, 0, 0); + gz::math::Inertiald linkInertial; + // Start server and run. + gz::sim::ServerConfig serverConfig; + serverConfig.SetSdfFile(common::joinPaths( + PROJECT_SOURCE_PATH, "test", "worlds", "mesh_inertia_calculation.sdf")); + + common::setenv( + "GZ_SIM_RESOURCE_PATH", + common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds", "models")); + + gz::sim::Server server(serverConfig); + + // Create a system just to get the ECM + EntityComponentManager *ecm; + test::Relay testSystem; + testSystem.OnPreUpdate( + [&](const UpdateInfo &, EntityComponentManager &_ecm) + { + ecm = &_ecm; + } + ); + server.AddSystem(testSystem.systemPtr); + + ASSERT_FALSE(server.Running()); + ASSERT_FALSE(*server.Running(0)); + ASSERT_TRUE(server.Run(true, kIter, false)); + ASSERT_NE(nullptr, ecm); + + // Get link of collada cylinder + gz::sim::Entity modelEntity = ecm->EntityByComponents( + gz::sim::components::Name("cylinder_dae"), + gz::sim::components::Model() + ); + + gz::sim::Model model = gz::sim::Model(modelEntity); + ASSERT_TRUE(model.Valid(*ecm)); + + gz::sim::Entity linkEntity = model.LinkByName(*ecm, "cylinder_dae"); + gz::sim::Link link = gz::sim::Link(linkEntity); + ASSERT_TRUE(link.Valid(*ecm)); + + // Enable checks for pose values + link.EnableVelocityChecks(*ecm); + + ASSERT_NE(link.WorldInertiaMatrix(*ecm), std::nullopt); + ASSERT_NE(link.WorldInertialPose(*ecm), std::nullopt); + ASSERT_NE(link.WorldPose(*ecm), std::nullopt); + + // The cylinder has a radius of 1m, length of 2m, and density of 1240 kg/m³. + // Volume: πr²h = 2π ≈ 6.283 + // Mass: ρV = (1240.0) * 2π ≈ 7791.1497 + // Ix = Iy : 1/12 * m(3r² + h²) = m/12 * (3 + 4) ≈ 4544.83 + // Iz : ½mr² ≈ 3895.57 + gz::math::Inertiald meshInertial; + meshInertial.SetMassMatrix(gz::math::MassMatrix3d( + 7791.1497, + gz::math::Vector3d(4544.83, 4544.83, 3895.57), + gz::math::Vector3d::Zero + )); + meshInertial.SetPose(gz::math::Pose3d::Zero); + gz::math::Matrix3 inertiaMatrix = meshInertial.Moi(); + + // Check the Inertia Matrix within a tolerance of 0.005 since we are + // comparing a mesh cylinder with an ideal cylinder. For values more closer + // to the ideal, a higher number of vertices would be required in mesh + EXPECT_TRUE( + link.WorldInertiaMatrix(*ecm).value().Equal(inertiaMatrix, 0.005)); + + // Check the Inertial Pose and Link Pose + EXPECT_EQ(link.WorldPose(*ecm).value(), gz::math::Pose3d::Zero); + EXPECT_EQ(link.WorldInertialPose(*ecm).value(), gz::math::Pose3d::Zero); +} diff --git a/test/worlds/mesh_inertia_calculation.sdf b/test/worlds/mesh_inertia_calculation.sdf new file mode 100644 index 0000000000..4b2a7ffdbd --- /dev/null +++ b/test/worlds/mesh_inertia_calculation.sdf @@ -0,0 +1,16 @@ + + + + + 0.001 + 1.0 + + + + + cylinder_dae + cylinder_dae + 0 0 0 0 0 0 + + + diff --git a/test/worlds/models/cylinder_dae/meshes/cylinder.dae b/test/worlds/models/cylinder_dae/meshes/cylinder.dae new file mode 100644 index 0000000000..64c8ef7e2c --- /dev/null +++ b/test/worlds/models/cylinder_dae/meshes/cylinder.dae @@ -0,0 +1,69 @@ + + + + + Blender User + Blender 3.4.1 commit date:2022-12-19, commit time:17:00, hash:55485cb379f7 + + 2023-08-26T13:02:10 + 2023-08-26T13:02:10 + + Z_UP + + + + + + + 0 1 -1 0 1 1 0.001533925 0.9999988 -1 0.001533925 0.9999988 1 0.00306791 0.9999953 -1 0.00306791 0.9999953 1 0.004601895 0.9999894 -1 0.004601895 0.9999894 1 0.00613588 0.9999812 -1 0.00613588 0.9999812 1 0.007669806 0.9999706 -1 0.007669806 0.9999706 1 0.009203732 0.9999576 -1 0.009203732 0.9999576 1 0.01073765 0.9999424 -1 0.01073765 0.9999424 1 0.01227152 0.9999247 -1 0.01227152 0.9999247 1 0.01380538 0.9999047 -1 0.01380538 0.9999047 1 0.01533919 0.9998824 -1 0.01533919 0.9998824 1 0.01687294 0.9998577 -1 0.01687294 0.9998577 1 0.01840668 0.9998306 -1 0.01840668 0.9998306 1 0.01994037 0.9998012 -1 0.01994037 0.9998012 1 0.02147406 0.9997694 -1 0.02147406 0.9997694 1 0.02300763 0.9997353 -1 0.02300763 0.9997353 1 0.02454119 0.9996988 -1 0.02454119 0.9996988 1 0.0260747 0.99966 -1 0.0260747 0.99966 1 0.02760809 0.9996188 -1 0.02760809 0.9996188 1 0.02914148 0.9995753 -1 0.02914148 0.9995753 1 0.03067475 0.9995294 -1 0.03067475 0.9995294 1 0.03220802 0.9994812 -1 0.03220802 0.9994812 1 0.03374117 0.9994306 -1 0.03374117 0.9994306 1 0.0352742 0.9993777 -1 0.0352742 0.9993777 1 0.03680717 0.9993224 -1 0.03680717 0.9993224 1 0.03834009 0.9992648 -1 0.03834009 0.9992648 1 0.03987288 0.9992048 -1 0.03987288 0.9992048 1 0.04140561 0.9991424 -1 0.04140561 0.9991424 1 0.04293823 0.9990777 -1 0.04293823 0.9990777 1 0.04447072 0.9990107 -1 0.04447072 0.9990107 1 0.04600316 0.9989413 -1 0.04600316 0.9989413 1 0.04753547 0.9988695 -1 0.04753547 0.9988695 1 0.04906767 0.9987955 -1 0.04906767 0.9987955 1 0.05059975 0.998719 -1 0.05059975 0.998719 1 0.05213171 0.9986402 -1 0.05213171 0.9986402 1 0.05366349 0.9985591 -1 0.05366349 0.9985591 1 0.05519521 0.9984756 -1 0.05519521 0.9984756 1 0.05672681 0.9983897 -1 0.05672681 0.9983897 1 0.05825823 0.9983016 -1 0.05825823 0.9983016 1 0.05978953 0.998211 -1 0.05978953 0.998211 1 0.06132072 0.9981181 -1 0.06132072 0.9981181 1 0.06285172 0.9980229 -1 0.06285172 0.9980229 1 0.06438261 0.9979253 -1 0.06438261 0.9979253 1 0.06591331 0.9978253 -1 0.06591331 0.9978253 1 0.0674439 0.9977231 -1 0.0674439 0.9977231 1 0.06897431 0.9976184 -1 0.06897431 0.9976184 1 0.07050454 0.9975115 -1 0.07050454 0.9975115 1 0.07203465 0.9974021 -1 0.07203465 0.9974021 1 0.07356452 0.9972904 -1 0.07356452 0.9972904 1 0.07509428 0.9971764 -1 0.07509428 0.9971764 1 0.07662385 0.9970601 -1 0.07662385 0.9970601 1 0.07815325 0.9969413 -1 0.07815325 0.9969413 1 0.0796824 0.9968203 -1 0.0796824 0.9968203 1 0.08121144 0.9966969 -1 0.08121144 0.9966969 1 0.08274024 0.9965711 -1 0.08274024 0.9965711 1 0.08426886 0.996443 -1 0.08426886 0.996443 1 0.0857973 0.9963126 -1 0.0857973 0.9963126 1 0.08732551 0.9961798 -1 0.08732551 0.9961798 1 0.08885353 0.9960447 -1 0.08885353 0.9960447 1 0.09038132 0.9959073 -1 0.09038132 0.9959073 1 0.09190893 0.9957674 -1 0.09190893 0.9957674 1 0.0934363 0.9956253 -1 0.0934363 0.9956253 1 0.09496349 0.9954808 -1 0.09496349 0.9954808 1 0.09649044 0.9953339 -1 0.09649044 0.9953339 1 0.09801709 0.9951847 -1 0.09801709 0.9951847 1 0.09954357 0.9950332 -1 0.09954357 0.9950332 1 0.1010698 0.9948793 -1 0.1010698 0.9948793 1 0.1025959 0.9947232 -1 0.1025959 0.9947232 1 0.1041216 0.9945646 -1 0.1041216 0.9945646 1 0.1056472 0.9944037 -1 0.1056472 0.9944037 1 0.1071724 0.9942405 -1 0.1071724 0.9942405 1 0.1086974 0.9940749 -1 0.1086974 0.9940749 1 0.1102222 0.993907 -1 0.1102222 0.993907 1 0.1117467 0.9937368 -1 0.1117467 0.9937368 1 0.1132709 0.9935641 -1 0.1132709 0.9935641 1 0.1147949 0.9933892 -1 0.1147949 0.9933892 1 0.1163186 0.9932119 -1 0.1163186 0.9932119 1 0.117842 0.9930323 -1 0.117842 0.9930323 1 0.1193652 0.9928504 -1 0.1193652 0.9928504 1 0.1208881 0.9926661 -1 0.1208881 0.9926661 1 0.1224107 0.9924796 -1 0.1224107 0.9924796 1 0.123933 0.9922906 -1 0.123933 0.9922906 1 0.125455 0.9920993 -1 0.125455 0.9920993 1 0.1269767 0.9919057 -1 0.1269767 0.9919057 1 0.1284981 0.9917098 -1 0.1284981 0.9917098 1 0.1300192 0.9915115 -1 0.1300192 0.9915115 1 0.13154 0.9913108 -1 0.13154 0.9913108 1 0.1330605 0.991108 -1 0.1330605 0.991108 1 0.1345807 0.9909027 -1 0.1345807 0.9909027 1 0.1361005 0.990695 -1 0.1361005 0.990695 1 0.1376201 0.9904851 -1 0.1376201 0.9904851 1 0.1391393 0.9902728 -1 0.1391393 0.9902728 1 0.1406582 0.9900582 -1 0.1406582 0.9900582 1 0.1421768 0.9898413 -1 0.1421768 0.9898413 1 0.143695 0.989622 -1 0.143695 0.989622 1 0.1452129 0.9894005 -1 0.1452129 0.9894005 1 0.1467304 0.9891765 -1 0.1467304 0.9891765 1 0.1482477 0.9889503 -1 0.1482477 0.9889503 1 0.1497645 0.9887217 -1 0.1497645 0.9887217 1 0.151281 0.9884908 -1 0.151281 0.9884908 1 0.1527972 0.9882576 -1 0.1527972 0.9882576 1 0.154313 0.988022 -1 0.154313 0.988022 1 0.1558284 0.9877842 -1 0.1558284 0.9877842 1 0.1573435 0.987544 -1 0.1573435 0.987544 1 0.1588581 0.9873014 -1 0.1588581 0.9873014 1 0.1603724 0.9870566 -1 0.1603724 0.9870566 1 0.1618863 0.9868094 -1 0.1618863 0.9868094 1 0.1633999 0.9865599 -1 0.1633999 0.9865599 1 0.1649131 0.9863081 -1 0.1649131 0.9863081 1 0.1664259 0.986054 -1 0.1664259 0.986054 1 0.1679382 0.9857975 -1 0.1679382 0.9857975 1 0.1694503 0.9855387 -1 0.1694503 0.9855387 1 0.1709619 0.9852777 -1 0.1709619 0.9852777 1 0.1724731 0.9850143 -1 0.1724731 0.9850143 1 0.1739838 0.9847485 -1 0.1739838 0.9847485 1 0.1754943 0.9844805 -1 0.1754943 0.9844805 1 0.1770042 0.9842101 -1 0.1770042 0.9842101 1 0.1785138 0.9839375 -1 0.1785138 0.9839375 1 0.1800229 0.9836624 -1 0.1800229 0.9836624 1 0.1815316 0.9833851 -1 0.1815316 0.9833851 1 0.1830399 0.9831055 -1 0.1830399 0.9831055 1 0.1845477 0.9828236 -1 0.1845477 0.9828236 1 0.1860551 0.9825393 -1 0.1860551 0.9825393 1 0.1875621 0.9822527 -1 0.1875621 0.9822527 1 0.1890686 0.9819639 -1 0.1890686 0.9819639 1 0.1905747 0.9816727 -1 0.1905747 0.9816727 1 0.1920804 0.9813792 -1 0.1920804 0.9813792 1 0.1935856 0.9810834 -1 0.1935856 0.9810834 1 0.1950903 0.9807853 -1 0.1950903 0.9807853 1 0.1965946 0.9804849 -1 0.1965946 0.9804849 1 0.1980984 0.9801821 -1 0.1980984 0.9801821 1 0.1996017 0.9798771 -1 0.1996017 0.9798771 1 0.2011046 0.9795698 -1 0.2011046 0.9795698 1 0.202607 0.9792602 -1 0.202607 0.9792602 1 0.204109 0.9789482 -1 0.204109 0.9789482 1 0.2056104 0.9786339 -1 0.2056104 0.9786339 1 0.2071114 0.9783174 -1 0.2071114 0.9783174 1 0.2086118 0.9779985 -1 0.2086118 0.9779985 1 0.2101118 0.9776774 -1 0.2101118 0.9776774 1 0.2116113 0.9773539 -1 0.2116113 0.9773539 1 0.2131103 0.9770281 -1 0.2131103 0.9770281 1 0.2146088 0.9767001 -1 0.2146088 0.9767001 1 0.2161068 0.9763697 -1 0.2161068 0.9763697 1 0.2176042 0.9760371 -1 0.2176042 0.9760371 1 0.2191012 0.9757021 -1 0.2191012 0.9757021 1 0.2205977 0.9753649 -1 0.2205977 0.9753649 1 0.2220936 0.9750254 -1 0.2220936 0.9750254 1 0.223589 0.9746835 -1 0.223589 0.9746835 1 0.2250839 0.9743394 -1 0.2250839 0.9743394 1 0.2265782 0.973993 -1 0.2265782 0.973993 1 0.2280721 0.9736443 -1 0.2280721 0.9736443 1 0.2295653 0.9732933 -1 0.2295653 0.9732933 1 0.2310581 0.97294 -1 0.2310581 0.97294 1 0.2325503 0.9725844 -1 0.2325503 0.9725844 1 0.2340419 0.9722265 -1 0.2340419 0.9722265 1 0.235533 0.9718663 -1 0.235533 0.9718663 1 0.2370236 0.9715039 -1 0.2370236 0.9715039 1 0.2385136 0.9711391 -1 0.2385136 0.9711391 1 0.240003 0.9707722 -1 0.240003 0.9707722 1 0.2414919 0.9704028 -1 0.2414919 0.9704028 1 0.2429802 0.9700313 -1 0.2429802 0.9700313 1 0.2444679 0.9696574 -1 0.2444679 0.9696574 1 0.245955 0.9692813 -1 0.245955 0.9692813 1 0.2474416 0.9689028 -1 0.2474416 0.9689028 1 0.2489276 0.9685221 -1 0.2489276 0.9685221 1 0.250413 0.9681391 -1 0.250413 0.9681391 1 0.2518978 0.9677538 -1 0.2518978 0.9677538 1 0.253382 0.9673663 -1 0.253382 0.9673663 1 0.2548657 0.9669765 -1 0.2548657 0.9669765 1 0.2563487 0.9665844 -1 0.2563487 0.9665844 1 0.2578311 0.96619 -1 0.2578311 0.96619 1 0.2593129 0.9657934 -1 0.2593129 0.9657934 1 0.2607941 0.9653944 -1 0.2607941 0.9653944 1 0.2622747 0.9649932 -1 0.2622747 0.9649932 1 0.2637547 0.9645898 -1 0.2637547 0.9645898 1 0.2652341 0.9641841 -1 0.2652341 0.9641841 1 0.2667128 0.9637761 -1 0.2667128 0.9637761 1 0.2681909 0.9633658 -1 0.2681909 0.9633658 1 0.2696684 0.9629533 -1 0.2696684 0.9629533 1 0.2711452 0.9625385 -1 0.2711452 0.9625385 1 0.2726213 0.9621214 -1 0.2726213 0.9621214 1 0.2740969 0.9617021 -1 0.2740969 0.9617021 1 0.2755718 0.9612805 -1 0.2755718 0.9612805 1 0.2770461 0.9608566 -1 0.2770461 0.9608566 1 0.2785197 0.9604305 -1 0.2785197 0.9604305 1 0.2799926 0.9600021 -1 0.2799926 0.9600021 1 0.2814649 0.9595715 -1 0.2814649 0.9595715 1 0.2829366 0.9591386 -1 0.2829366 0.9591386 1 0.2844076 0.9587035 -1 0.2844076 0.9587035 1 0.2858778 0.9582661 -1 0.2858778 0.9582661 1 0.2873475 0.9578264 -1 0.2873475 0.9578264 1 0.2888164 0.9573845 -1 0.2888164 0.9573845 1 0.2902847 0.9569404 -1 0.2902847 0.9569404 1 0.2917523 0.9564939 -1 0.2917523 0.9564939 1 0.2932192 0.9560453 -1 0.2932192 0.9560453 1 0.2946854 0.9555943 -1 0.2946854 0.9555943 1 0.2961509 0.9551412 -1 0.2961509 0.9551412 1 0.2976157 0.9546858 -1 0.2976157 0.9546858 1 0.2990798 0.9542281 -1 0.2990798 0.9542281 1 0.3005433 0.9537682 -1 0.3005433 0.9537682 1 0.302006 0.953306 -1 0.302006 0.953306 1 0.3034679 0.9528416 -1 0.3034679 0.9528416 1 0.3049293 0.952375 -1 0.3049293 0.952375 1 0.3063898 0.9519062 -1 0.3063898 0.9519062 1 0.3078497 0.951435 -1 0.3078497 0.951435 1 0.3093088 0.9509617 -1 0.3093088 0.9509617 1 0.3107671 0.9504861 -1 0.3107671 0.9504861 1 0.3122248 0.9500082 -1 0.3122248 0.9500082 1 0.3136817 0.9495282 -1 0.3136817 0.9495282 1 0.3151379 0.9490459 -1 0.3151379 0.9490459 1 0.3165934 0.9485614 -1 0.3165934 0.9485614 1 0.3180481 0.9480746 -1 0.3180481 0.9480746 1 0.319502 0.9475856 -1 0.319502 0.9475856 1 0.3209552 0.9470944 -1 0.3209552 0.9470944 1 0.3224077 0.9466009 -1 0.3224077 0.9466009 1 0.3238593 0.9461053 -1 0.3238593 0.9461053 1 0.3253103 0.9456073 -1 0.3253103 0.9456073 1 0.3267605 0.9451072 -1 0.3267605 0.9451072 1 0.3282098 0.9446048 -1 0.3282098 0.9446048 1 0.3296585 0.9441003 -1 0.3296585 0.9441003 1 0.3311063 0.9435935 -1 0.3311063 0.9435935 1 0.3325534 0.9430844 -1 0.3325534 0.9430844 1 0.3339996 0.9425732 -1 0.3339996 0.9425732 1 0.3354452 0.9420598 -1 0.3354452 0.9420598 1 0.3368899 0.9415441 -1 0.3368899 0.9415441 1 0.3383337 0.9410262 -1 0.3383337 0.9410262 1 0.3397769 0.9405061 -1 0.3397769 0.9405061 1 0.3412192 0.9399837 -1 0.3412192 0.9399837 1 0.3426607 0.9394592 -1 0.3426607 0.9394592 1 0.3441014 0.9389325 -1 0.3441014 0.9389325 1 0.3455413 0.9384036 -1 0.3455413 0.9384036 1 0.3469804 0.9378724 -1 0.3469804 0.9378724 1 0.3484187 0.937339 -1 0.3484187 0.937339 1 0.3498561 0.9368035 -1 0.3498561 0.9368035 1 0.3512927 0.9362657 -1 0.3512927 0.9362657 1 0.3527286 0.9357257 -1 0.3527286 0.9357257 1 0.3541635 0.9351835 -1 0.3541635 0.9351835 1 0.3555977 0.9346391 -1 0.3555977 0.9346391 1 0.357031 0.9340925 -1 0.357031 0.9340925 1 0.3584634 0.9335438 -1 0.3584634 0.9335438 1 0.3598951 0.9329928 -1 0.3598951 0.9329928 1 0.3613258 0.9324396 -1 0.3613258 0.9324396 1 0.3627557 0.9318843 -1 0.3627557 0.9318843 1 0.3641848 0.9313267 -1 0.3641848 0.9313267 1 0.365613 0.9307669 -1 0.365613 0.9307669 1 0.3670403 0.930205 -1 0.3670403 0.930205 1 0.3684668 0.9296409 -1 0.3684668 0.9296409 1 0.3698924 0.9290746 -1 0.3698924 0.9290746 1 0.3713172 0.9285061 -1 0.3713172 0.9285061 1 0.3727411 0.9279354 -1 0.3727411 0.9279354 1 0.3741641 0.9273625 -1 0.3741641 0.9273625 1 0.3755862 0.9267875 -1 0.3755862 0.9267875 1 0.3770074 0.9262102 -1 0.3770074 0.9262102 1 0.3784278 0.9256308 -1 0.3784278 0.9256308 1 0.3798472 0.9250493 -1 0.3798472 0.9250493 1 0.3812658 0.9244655 -1 0.3812658 0.9244655 1 0.3826835 0.9238795 -1 0.3826835 0.9238795 1 0.3841002 0.9232914 -1 0.3841002 0.9232914 1 0.3855161 0.9227011 -1 0.3855161 0.9227011 1 0.386931 0.9221087 -1 0.386931 0.9221087 1 0.388345 0.921514 -1 0.388345 0.921514 1 0.3897582 0.9209172 -1 0.3897582 0.9209172 1 0.3911704 0.9203183 -1 0.3911704 0.9203183 1 0.3925817 0.9197171 -1 0.3925817 0.9197171 1 0.3939921 0.9191139 -1 0.3939921 0.9191139 1 0.3954015 0.9185084 -1 0.3954015 0.9185084 1 0.39681 0.9179008 -1 0.39681 0.9179008 1 0.3982176 0.917291 -1 0.3982176 0.917291 1 0.3996242 0.9166791 -1 0.3996242 0.9166791 1 0.4010299 0.916065 -1 0.4010299 0.916065 1 0.4024347 0.9154487 -1 0.4024347 0.9154487 1 0.4038385 0.9148303 -1 0.4038385 0.9148303 1 0.4052413 0.9142097 -1 0.4052413 0.9142097 1 0.4066432 0.913587 -1 0.4066432 0.913587 1 0.4080442 0.9129622 -1 0.4080442 0.9129622 1 0.4094442 0.9123352 -1 0.4094442 0.9123352 1 0.4108432 0.911706 -1 0.4108432 0.911706 1 0.4122412 0.9110748 -1 0.4122412 0.9110748 1 0.4136383 0.9104413 -1 0.4136383 0.9104413 1 0.4150344 0.9098057 -1 0.4150344 0.9098057 1 0.4164296 0.909168 -1 0.4164296 0.909168 1 0.4178237 0.9085281 -1 0.4178237 0.9085281 1 0.4192169 0.9078861 -1 0.4192169 0.9078861 1 0.4206091 0.907242 -1 0.4206091 0.907242 1 0.4220003 0.9065957 -1 0.4220003 0.9065957 1 0.4233905 0.9059473 -1 0.4233905 0.9059473 1 0.4247797 0.9052968 -1 0.4247797 0.9052968 1 0.4261679 0.9046441 -1 0.4261679 0.9046441 1 0.4275551 0.9039893 -1 0.4275551 0.9039893 1 0.4289413 0.9033324 -1 0.4289413 0.9033324 1 0.4303265 0.9026733 -1 0.4303265 0.9026733 1 0.4317107 0.9020121 -1 0.4317107 0.9020121 1 0.4330939 0.9013488 -1 0.4330939 0.9013488 1 0.434476 0.9006834 -1 0.434476 0.9006834 1 0.4358571 0.9000159 -1 0.4358571 0.9000159 1 0.4372372 0.8993462 -1 0.4372372 0.8993462 1 0.4386162 0.8986745 -1 0.4386162 0.8986745 1 0.4399943 0.8980006 -1 0.4399943 0.8980006 1 0.4413713 0.8973246 -1 0.4413713 0.8973246 1 0.4427472 0.8966464 -1 0.4427472 0.8966464 1 0.4441221 0.8959662 -1 0.4441221 0.8959662 1 0.445496 0.8952839 -1 0.445496 0.8952839 1 0.4468688 0.8945995 -1 0.4468688 0.8945995 1 0.4482406 0.893913 -1 0.4482406 0.893913 1 0.4496113 0.8932243 -1 0.4496113 0.8932243 1 0.450981 0.8925336 -1 0.450981 0.8925336 1 0.4523496 0.8918407 -1 0.4523496 0.8918407 1 0.4537171 0.8911458 -1 0.4537171 0.8911458 1 0.4550836 0.8904488 -1 0.4550836 0.8904488 1 0.456449 0.8897496 -1 0.456449 0.8897496 1 0.4578133 0.8890483 -1 0.4578133 0.8890483 1 0.4591765 0.888345 -1 0.4591765 0.888345 1 0.4605387 0.8876397 -1 0.4605387 0.8876397 1 0.4618998 0.8869321 -1 0.4618998 0.8869321 1 0.4632598 0.8862226 -1 0.4632598 0.8862226 1 0.4646187 0.8855109 -1 0.4646187 0.8855109 1 0.4659765 0.8847971 -1 0.4659765 0.8847971 1 0.4673332 0.8840813 -1 0.4673332 0.8840813 1 0.4686889 0.8833633 -1 0.4686889 0.8833633 1 0.4700433 0.8826434 -1 0.4700433 0.8826434 1 0.4713968 0.8819212 -1 0.4713968 0.8819212 1 0.4727491 0.8811971 -1 0.4727491 0.8811971 1 0.4741002 0.8804709 -1 0.4741002 0.8804709 1 0.4754503 0.8797426 -1 0.4754503 0.8797426 1 0.4767993 0.8790122 -1 0.4767993 0.8790122 1 0.478147 0.8782798 -1 0.478147 0.8782798 1 0.4794937 0.8775453 -1 0.4794937 0.8775453 1 0.4808393 0.8768087 -1 0.4808393 0.8768087 1 0.4821838 0.8760701 -1 0.4821838 0.8760701 1 0.4835271 0.8753294 -1 0.4835271 0.8753294 1 0.4848693 0.8745867 -1 0.4848693 0.8745867 1 0.4862103 0.8738418 -1 0.4862103 0.8738418 1 0.4875501 0.873095 -1 0.4875501 0.873095 1 0.4888889 0.8723461 -1 0.4888889 0.8723461 1 0.4902265 0.8715951 -1 0.4902265 0.8715951 1 0.4915629 0.870842 -1 0.4915629 0.870842 1 0.4928982 0.870087 -1 0.4928982 0.870087 1 0.4942323 0.8693299 -1 0.4942323 0.8693299 1 0.4955653 0.8685707 -1 0.4955653 0.8685707 1 0.4968971 0.8678095 -1 0.4968971 0.8678095 1 0.4982277 0.8670462 -1 0.4982277 0.8670462 1 0.4995571 0.866281 -1 0.4995571 0.866281 1 0.5008854 0.8655136 -1 0.5008854 0.8655136 1 0.5022125 0.8647443 -1 0.5022125 0.8647443 1 0.5035384 0.8639729 -1 0.5035384 0.8639729 1 0.5048632 0.8631994 -1 0.5048632 0.8631994 1 0.5061867 0.862424 -1 0.5061867 0.862424 1 0.507509 0.8616465 -1 0.507509 0.8616465 1 0.5088302 0.8608669 -1 0.5088302 0.8608669 1 0.5101501 0.8600854 -1 0.5101501 0.8600854 1 0.5114689 0.8593018 -1 0.5114689 0.8593018 1 0.5127865 0.8585162 -1 0.5127865 0.8585162 1 0.5141028 0.8577286 -1 0.5141028 0.8577286 1 0.5154179 0.856939 -1 0.5154179 0.856939 1 0.5167318 0.8561474 -1 0.5167318 0.8561474 1 0.5180445 0.8553537 -1 0.5180445 0.8553537 1 0.519356 0.854558 -1 0.519356 0.854558 1 0.5206663 0.8537603 -1 0.5206663 0.8537603 1 0.5219753 0.8529606 -1 0.5219753 0.8529606 1 0.5232831 0.8521589 -1 0.5232831 0.8521589 1 0.5245897 0.8513552 -1 0.5245897 0.8513552 1 0.5258951 0.8505495 -1 0.5258951 0.8505495 1 0.5271992 0.8497418 -1 0.5271992 0.8497418 1 0.5285021 0.848932 -1 0.5285021 0.848932 1 0.5298036 0.8481203 -1 0.5298036 0.8481203 1 0.531104 0.8473066 -1 0.531104 0.8473066 1 0.5324032 0.8464909 -1 0.5324032 0.8464909 1 0.533701 0.8456733 -1 0.533701 0.8456733 1 0.5349976 0.8448536 -1 0.5349976 0.8448536 1 0.536293 0.8440319 -1 0.536293 0.8440319 1 0.5375871 0.8432083 -1 0.5375871 0.8432083 1 0.5388799 0.8423826 -1 0.5388799 0.8423826 1 0.5401715 0.841555 -1 0.5401715 0.841555 1 0.5414618 0.8407254 -1 0.5414618 0.8407254 1 0.5427508 0.8398938 -1 0.5427508 0.8398938 1 0.5440385 0.8390603 -1 0.5440385 0.8390603 1 0.545325 0.8382247 -1 0.545325 0.8382247 1 0.5466102 0.8373872 -1 0.5466102 0.8373872 1 0.5478941 0.8365477 -1 0.5478941 0.8365477 1 0.5491767 0.8357062 -1 0.5491767 0.8357062 1 0.550458 0.8348628 -1 0.550458 0.8348628 1 0.551738 0.8340175 -1 0.551738 0.8340175 1 0.5530167 0.8331702 -1 0.5530167 0.8331702 1 0.5542941 0.8323209 -1 0.5542941 0.8323209 1 0.5555703 0.8314696 -1 0.5555703 0.8314696 1 0.5568451 0.8306164 -1 0.5568451 0.8306164 1 0.5581185 0.8297612 -1 0.5581185 0.8297612 1 0.5593907 0.8289041 -1 0.5593907 0.8289041 1 0.5606616 0.828045 -1 0.5606616 0.828045 1 0.5619311 0.827184 -1 0.5619311 0.827184 1 0.5631994 0.8263211 -1 0.5631994 0.8263211 1 0.5644662 0.8254562 -1 0.5644662 0.8254562 1 0.5657318 0.8245893 -1 0.5657318 0.8245893 1 0.5669961 0.8237205 -1 0.5669961 0.8237205 1 0.568259 0.8228498 -1 0.568259 0.8228498 1 0.5695205 0.8219771 -1 0.5695205 0.8219771 1 0.5707808 0.8211025 -1 0.5707808 0.8211025 1 0.5720396 0.820226 -1 0.5720396 0.820226 1 0.5732972 0.8193475 -1 0.5732972 0.8193475 1 0.5745534 0.8184671 -1 0.5745534 0.8184671 1 0.5758082 0.8175848 -1 0.5758082 0.8175848 1 0.5770617 0.8167006 -1 0.5770617 0.8167006 1 0.5783138 0.8158144 -1 0.5783138 0.8158144 1 0.5795646 0.8149263 -1 0.5795646 0.8149263 1 0.580814 0.8140363 -1 0.580814 0.8140363 1 0.582062 0.8131444 -1 0.582062 0.8131444 1 0.5833087 0.8122506 -1 0.5833087 0.8122506 1 0.584554 0.8113548 -1 0.584554 0.8113548 1 0.5857979 0.8104572 -1 0.5857979 0.8104572 1 0.5870404 0.8095577 -1 0.5870404 0.8095577 1 0.5882816 0.8086562 -1 0.5882816 0.8086562 1 0.5895213 0.8077529 -1 0.5895213 0.8077529 1 0.5907597 0.8068476 -1 0.5907597 0.8068476 1 0.5919967 0.8059404 -1 0.5919967 0.8059404 1 0.5932323 0.8050313 -1 0.5932323 0.8050313 1 0.5944665 0.8041204 -1 0.5944665 0.8041204 1 0.5956993 0.8032075 -1 0.5956993 0.8032075 1 0.5969308 0.8022928 -1 0.5969308 0.8022928 1 0.5981608 0.8013762 -1 0.5981608 0.8013762 1 0.5993893 0.8004577 -1 0.5993893 0.8004577 1 0.6006165 0.7995373 -1 0.6006165 0.7995373 1 0.6018423 0.798615 -1 0.6018423 0.798615 1 0.6030666 0.7976908 -1 0.6030666 0.7976908 1 0.6042895 0.7967648 -1 0.6042895 0.7967648 1 0.605511 0.7958369 -1 0.605511 0.7958369 1 0.6067311 0.7949072 -1 0.6067311 0.7949072 1 0.6079498 0.7939755 -1 0.6079498 0.7939755 1 0.609167 0.793042 -1 0.609167 0.793042 1 0.6103828 0.7921066 -1 0.6103828 0.7921066 1 0.6115972 0.7911694 -1 0.6115972 0.7911694 1 0.6128101 0.7902302 -1 0.6128101 0.7902302 1 0.6140216 0.7892892 -1 0.6140216 0.7892892 1 0.6152316 0.7883464 -1 0.6152316 0.7883464 1 0.6164402 0.7874017 -1 0.6164402 0.7874017 1 0.6176474 0.7864552 -1 0.6176474 0.7864552 1 0.618853 0.7855068 -1 0.618853 0.7855068 1 0.6200572 0.7845566 -1 0.6200572 0.7845566 1 0.62126 0.7836045 -1 0.62126 0.7836045 1 0.6224613 0.7826506 -1 0.6224613 0.7826506 1 0.6236611 0.7816948 -1 0.6236611 0.7816948 1 0.6248595 0.7807372 -1 0.6248595 0.7807372 1 0.6260564 0.7797778 -1 0.6260564 0.7797778 1 0.6272518 0.7788165 -1 0.6272518 0.7788165 1 0.6284458 0.7778534 -1 0.6284458 0.7778534 1 0.6296383 0.7768884 -1 0.6296383 0.7768884 1 0.6308293 0.7759217 -1 0.6308293 0.7759217 1 0.6320188 0.7749531 -1 0.6320188 0.7749531 1 0.6332068 0.7739827 -1 0.6332068 0.7739827 1 0.6343933 0.7730104 -1 0.6343933 0.7730104 1 0.6355783 0.7720364 -1 0.6355783 0.7720364 1 0.6367619 0.7710605 -1 0.6367619 0.7710605 1 0.6379439 0.7700828 -1 0.6379439 0.7700828 1 0.6391245 0.7691034 -1 0.6391245 0.7691034 1 0.6403035 0.768122 -1 0.6403035 0.768122 1 0.6414811 0.7671389 -1 0.6414811 0.7671389 1 0.6426571 0.766154 -1 0.6426571 0.766154 1 0.6438316 0.7651672 -1 0.6438316 0.7651672 1 0.6450046 0.7641788 -1 0.6450046 0.7641788 1 0.646176 0.7631884 -1 0.646176 0.7631884 1 0.647346 0.7621963 -1 0.647346 0.7621963 1 0.6485145 0.7612023 -1 0.6485145 0.7612023 1 0.6496813 0.7602066 -1 0.6496813 0.7602066 1 0.6508467 0.7592092 -1 0.6508467 0.7592092 1 0.6520106 0.7582099 -1 0.6520106 0.7582099 1 0.6531729 0.7572088 -1 0.6531729 0.7572088 1 0.6543336 0.756206 -1 0.6543336 0.756206 1 0.6554929 0.7552014 -1 0.6554929 0.7552014 1 0.6566506 0.754195 -1 0.6566506 0.754195 1 0.6578067 0.7531868 -1 0.6578067 0.7531868 1 0.6589613 0.7521768 -1 0.6589613 0.7521768 1 0.6601144 0.7511651 -1 0.6601144 0.7511651 1 0.6612659 0.7501516 -1 0.6612659 0.7501516 1 0.6624158 0.7491364 -1 0.6624158 0.7491364 1 0.6635642 0.7481194 -1 0.6635642 0.7481194 1 0.664711 0.7471006 -1 0.664711 0.7471006 1 0.6658563 0.7460801 -1 0.6658563 0.7460801 1 0.6669999 0.7450578 -1 0.6669999 0.7450578 1 0.6681421 0.7440337 -1 0.6681421 0.7440337 1 0.6692826 0.743008 -1 0.6692826 0.743008 1 0.6704216 0.7419804 -1 0.6704216 0.7419804 1 0.671559 0.7409511 -1 0.671559 0.7409511 1 0.6726948 0.7399201 -1 0.6726948 0.7399201 1 0.673829 0.7388873 -1 0.673829 0.7388873 1 0.6749617 0.7378528 -1 0.6749617 0.7378528 1 0.6760928 0.7368166 -1 0.6760928 0.7368166 1 0.6772222 0.7357786 -1 0.6772222 0.7357786 1 0.6783501 0.7347389 -1 0.6783501 0.7347389 1 0.6794763 0.7336974 -1 0.6794763 0.7336974 1 0.680601 0.7326543 -1 0.680601 0.7326543 1 0.6817241 0.7316094 -1 0.6817241 0.7316094 1 0.6828456 0.7305628 -1 0.6828456 0.7305628 1 0.6839655 0.7295144 -1 0.6839655 0.7295144 1 0.6850837 0.7284644 -1 0.6850837 0.7284644 1 0.6862003 0.7274127 -1 0.6862003 0.7274127 1 0.6873154 0.7263591 -1 0.6873154 0.7263591 1 0.6884288 0.725304 -1 0.6884288 0.725304 1 0.6895406 0.7242471 -1 0.6895406 0.7242471 1 0.6906507 0.7231885 -1 0.6906507 0.7231885 1 0.6917593 0.7221282 -1 0.6917593 0.7221282 1 0.6928662 0.7210662 -1 0.6928662 0.7210662 1 0.6939715 0.7200025 -1 0.6939715 0.7200025 1 0.6950752 0.7189371 -1 0.6950752 0.7189371 1 0.6961772 0.71787 -1 0.6961772 0.71787 1 0.6972776 0.7168012 -1 0.6972776 0.7168012 1 0.6983763 0.7157308 -1 0.6983763 0.7157308 1 0.6994734 0.7146587 -1 0.6994734 0.7146587 1 0.7005688 0.7135849 -1 0.7005688 0.7135849 1 0.7016626 0.7125094 -1 0.7016626 0.7125094 1 0.7027547 0.7114322 -1 0.7027547 0.7114322 1 0.7038453 0.7103533 -1 0.7038453 0.7103533 1 0.7049341 0.7092728 -1 0.7049341 0.7092728 1 0.7060213 0.7081906 -1 0.7060213 0.7081906 1 0.7071068 0.7071068 -1 0.7071068 0.7071068 1 0.7081906 0.7060213 -1 0.7081906 0.7060213 1 0.7092728 0.7049341 -1 0.7092728 0.7049341 1 0.7103533 0.7038453 -1 0.7103533 0.7038453 1 0.7114322 0.7027547 -1 0.7114322 0.7027547 1 0.7125094 0.7016626 -1 0.7125094 0.7016626 1 0.7135849 0.7005688 -1 0.7135849 0.7005688 1 0.7146587 0.6994734 -1 0.7146587 0.6994734 1 0.7157308 0.6983763 -1 0.7157308 0.6983763 1 0.7168012 0.6972776 -1 0.7168012 0.6972776 1 0.71787 0.6961772 -1 0.71787 0.6961772 1 0.7189371 0.6950752 -1 0.7189371 0.6950752 1 0.7200025 0.6939715 -1 0.7200025 0.6939715 1 0.7210662 0.6928662 -1 0.7210662 0.6928662 1 0.7221282 0.6917593 -1 0.7221282 0.6917593 1 0.7231885 0.6906507 -1 0.7231885 0.6906507 1 0.7242471 0.6895406 -1 0.7242471 0.6895406 1 0.725304 0.6884288 -1 0.725304 0.6884288 1 0.7263591 0.6873154 -1 0.7263591 0.6873154 1 0.7274127 0.6862003 -1 0.7274127 0.6862003 1 0.7284644 0.6850837 -1 0.7284644 0.6850837 1 0.7295144 0.6839655 -1 0.7295144 0.6839655 1 0.7305628 0.6828456 -1 0.7305628 0.6828456 1 0.7316094 0.6817241 -1 0.7316094 0.6817241 1 0.7326543 0.680601 -1 0.7326543 0.680601 1 0.7336974 0.6794763 -1 0.7336974 0.6794763 1 0.7347389 0.6783501 -1 0.7347389 0.6783501 1 0.7357786 0.6772222 -1 0.7357786 0.6772222 1 0.7368166 0.6760928 -1 0.7368166 0.6760928 1 0.7378528 0.6749617 -1 0.7378528 0.6749617 1 0.7388873 0.673829 -1 0.7388873 0.673829 1 0.7399201 0.6726948 -1 0.7399201 0.6726948 1 0.7409511 0.671559 -1 0.7409511 0.671559 1 0.7419804 0.6704216 -1 0.7419804 0.6704216 1 0.743008 0.6692826 -1 0.743008 0.6692826 1 0.7440337 0.6681421 -1 0.7440337 0.6681421 1 0.7450578 0.6669999 -1 0.7450578 0.6669999 1 0.7460801 0.6658563 -1 0.7460801 0.6658563 1 0.7471006 0.664711 -1 0.7471006 0.664711 1 0.7481194 0.6635642 -1 0.7481194 0.6635642 1 0.7491364 0.6624158 -1 0.7491364 0.6624158 1 0.7501516 0.6612659 -1 0.7501516 0.6612659 1 0.7511651 0.6601144 -1 0.7511651 0.6601144 1 0.7521768 0.6589613 -1 0.7521768 0.6589613 1 0.7531868 0.6578067 -1 0.7531868 0.6578067 1 0.754195 0.6566506 -1 0.754195 0.6566506 1 0.7552014 0.6554929 -1 0.7552014 0.6554929 1 0.756206 0.6543336 -1 0.756206 0.6543336 1 0.7572088 0.6531729 -1 0.7572088 0.6531729 1 0.7582099 0.6520106 -1 0.7582099 0.6520106 1 0.7592092 0.6508467 -1 0.7592092 0.6508467 1 0.7602066 0.6496813 -1 0.7602066 0.6496813 1 0.7612023 0.6485145 -1 0.7612023 0.6485145 1 0.7621963 0.647346 -1 0.7621963 0.647346 1 0.7631884 0.646176 -1 0.7631884 0.646176 1 0.7641788 0.6450046 -1 0.7641788 0.6450046 1 0.7651672 0.6438316 -1 0.7651672 0.6438316 1 0.766154 0.6426571 -1 0.766154 0.6426571 1 0.7671389 0.6414811 -1 0.7671389 0.6414811 1 0.768122 0.6403035 -1 0.768122 0.6403035 1 0.7691034 0.6391245 -1 0.7691034 0.6391245 1 0.7700828 0.6379439 -1 0.7700828 0.6379439 1 0.7710605 0.6367619 -1 0.7710605 0.6367619 1 0.7720364 0.6355783 -1 0.7720364 0.6355783 1 0.7730104 0.6343933 -1 0.7730104 0.6343933 1 0.7739827 0.6332068 -1 0.7739827 0.6332068 1 0.7749531 0.6320188 -1 0.7749531 0.6320188 1 0.7759217 0.6308293 -1 0.7759217 0.6308293 1 0.7768884 0.6296383 -1 0.7768884 0.6296383 1 0.7778534 0.6284458 -1 0.7778534 0.6284458 1 0.7788165 0.6272518 -1 0.7788165 0.6272518 1 0.7797778 0.6260564 -1 0.7797778 0.6260564 1 0.7807372 0.6248595 -1 0.7807372 0.6248595 1 0.7816948 0.6236611 -1 0.7816948 0.6236611 1 0.7826506 0.6224613 -1 0.7826506 0.6224613 1 0.7836045 0.62126 -1 0.7836045 0.62126 1 0.7845566 0.6200572 -1 0.7845566 0.6200572 1 0.7855068 0.618853 -1 0.7855068 0.618853 1 0.7864552 0.6176474 -1 0.7864552 0.6176474 1 0.7874017 0.6164402 -1 0.7874017 0.6164402 1 0.7883464 0.6152316 -1 0.7883464 0.6152316 1 0.7892892 0.6140216 -1 0.7892892 0.6140216 1 0.7902302 0.6128101 -1 0.7902302 0.6128101 1 0.7911694 0.6115972 -1 0.7911694 0.6115972 1 0.7921066 0.6103828 -1 0.7921066 0.6103828 1 0.793042 0.609167 -1 0.793042 0.609167 1 0.7939755 0.6079498 -1 0.7939755 0.6079498 1 0.7949072 0.6067311 -1 0.7949072 0.6067311 1 0.7958369 0.605511 -1 0.7958369 0.605511 1 0.7967648 0.6042895 -1 0.7967648 0.6042895 1 0.7976908 0.6030666 -1 0.7976908 0.6030666 1 0.798615 0.6018423 -1 0.798615 0.6018423 1 0.7995373 0.6006165 -1 0.7995373 0.6006165 1 0.8004577 0.5993893 -1 0.8004577 0.5993893 1 0.8013762 0.5981608 -1 0.8013762 0.5981608 1 0.8022928 0.5969308 -1 0.8022928 0.5969308 1 0.8032075 0.5956993 -1 0.8032075 0.5956993 1 0.8041204 0.5944665 -1 0.8041204 0.5944665 1 0.8050313 0.5932323 -1 0.8050313 0.5932323 1 0.8059404 0.5919967 -1 0.8059404 0.5919967 1 0.8068476 0.5907597 -1 0.8068476 0.5907597 1 0.8077529 0.5895213 -1 0.8077529 0.5895213 1 0.8086562 0.5882816 -1 0.8086562 0.5882816 1 0.8095577 0.5870404 -1 0.8095577 0.5870404 1 0.8104572 0.5857979 -1 0.8104572 0.5857979 1 0.8113548 0.584554 -1 0.8113548 0.584554 1 0.8122506 0.5833087 -1 0.8122506 0.5833087 1 0.8131444 0.582062 -1 0.8131444 0.582062 1 0.8140363 0.580814 -1 0.8140363 0.580814 1 0.8149263 0.5795646 -1 0.8149263 0.5795646 1 0.8158144 0.5783138 -1 0.8158144 0.5783138 1 0.8167006 0.5770617 -1 0.8167006 0.5770617 1 0.8175848 0.5758082 -1 0.8175848 0.5758082 1 0.8184671 0.5745534 -1 0.8184671 0.5745534 1 0.8193475 0.5732972 -1 0.8193475 0.5732972 1 0.820226 0.5720396 -1 0.820226 0.5720396 1 0.8211025 0.5707808 -1 0.8211025 0.5707808 1 0.8219771 0.5695205 -1 0.8219771 0.5695205 1 0.8228498 0.568259 -1 0.8228498 0.568259 1 0.8237205 0.5669961 -1 0.8237205 0.5669961 1 0.8245893 0.5657318 -1 0.8245893 0.5657318 1 0.8254562 0.5644662 -1 0.8254562 0.5644662 1 0.8263211 0.5631994 -1 0.8263211 0.5631994 1 0.827184 0.5619311 -1 0.827184 0.5619311 1 0.828045 0.5606616 -1 0.828045 0.5606616 1 0.8289041 0.5593907 -1 0.8289041 0.5593907 1 0.8297612 0.5581185 -1 0.8297612 0.5581185 1 0.8306164 0.5568451 -1 0.8306164 0.5568451 1 0.8314696 0.5555703 -1 0.8314696 0.5555703 1 0.8323209 0.5542941 -1 0.8323209 0.5542941 1 0.8331702 0.5530167 -1 0.8331702 0.5530167 1 0.8340175 0.551738 -1 0.8340175 0.551738 1 0.8348628 0.550458 -1 0.8348628 0.550458 1 0.8357062 0.5491767 -1 0.8357062 0.5491767 1 0.8365477 0.5478941 -1 0.8365477 0.5478941 1 0.8373872 0.5466102 -1 0.8373872 0.5466102 1 0.8382247 0.545325 -1 0.8382247 0.545325 1 0.8390603 0.5440385 -1 0.8390603 0.5440385 1 0.8398938 0.5427508 -1 0.8398938 0.5427508 1 0.8407254 0.5414618 -1 0.8407254 0.5414618 1 0.841555 0.5401715 -1 0.841555 0.5401715 1 0.8423826 0.5388799 -1 0.8423826 0.5388799 1 0.8432083 0.5375871 -1 0.8432083 0.5375871 1 0.8440319 0.536293 -1 0.8440319 0.536293 1 0.8448536 0.5349976 -1 0.8448536 0.5349976 1 0.8456733 0.533701 -1 0.8456733 0.533701 1 0.8464909 0.5324032 -1 0.8464909 0.5324032 1 0.8473066 0.531104 -1 0.8473066 0.531104 1 0.8481203 0.5298036 -1 0.8481203 0.5298036 1 0.848932 0.5285021 -1 0.848932 0.5285021 1 0.8497418 0.5271992 -1 0.8497418 0.5271992 1 0.8505495 0.5258951 -1 0.8505495 0.5258951 1 0.8513552 0.5245897 -1 0.8513552 0.5245897 1 0.8521589 0.5232831 -1 0.8521589 0.5232831 1 0.8529606 0.5219753 -1 0.8529606 0.5219753 1 0.8537603 0.5206663 -1 0.8537603 0.5206663 1 0.854558 0.519356 -1 0.854558 0.519356 1 0.8553537 0.5180445 -1 0.8553537 0.5180445 1 0.8561474 0.5167318 -1 0.8561474 0.5167318 1 0.856939 0.5154179 -1 0.856939 0.5154179 1 0.8577286 0.5141028 -1 0.8577286 0.5141028 1 0.8585162 0.5127865 -1 0.8585162 0.5127865 1 0.8593018 0.5114689 -1 0.8593018 0.5114689 1 0.8600854 0.5101501 -1 0.8600854 0.5101501 1 0.8608669 0.5088302 -1 0.8608669 0.5088302 1 0.8616465 0.507509 -1 0.8616465 0.507509 1 0.862424 0.5061867 -1 0.862424 0.5061867 1 0.8631994 0.5048632 -1 0.8631994 0.5048632 1 0.8639729 0.5035384 -1 0.8639729 0.5035384 1 0.8647443 0.5022125 -1 0.8647443 0.5022125 1 0.8655136 0.5008854 -1 0.8655136 0.5008854 1 0.866281 0.4995571 -1 0.866281 0.4995571 1 0.8670462 0.4982277 -1 0.8670462 0.4982277 1 0.8678095 0.4968971 -1 0.8678095 0.4968971 1 0.8685707 0.4955653 -1 0.8685707 0.4955653 1 0.8693299 0.4942323 -1 0.8693299 0.4942323 1 0.870087 0.4928982 -1 0.870087 0.4928982 1 0.870842 0.4915629 -1 0.870842 0.4915629 1 0.8715951 0.4902265 -1 0.8715951 0.4902265 1 0.8723461 0.4888889 -1 0.8723461 0.4888889 1 0.873095 0.4875501 -1 0.873095 0.4875501 1 0.8738418 0.4862103 -1 0.8738418 0.4862103 1 0.8745867 0.4848693 -1 0.8745867 0.4848693 1 0.8753294 0.4835271 -1 0.8753294 0.4835271 1 0.8760701 0.4821838 -1 0.8760701 0.4821838 1 0.8768087 0.4808393 -1 0.8768087 0.4808393 1 0.8775453 0.4794937 -1 0.8775453 0.4794937 1 0.8782798 0.478147 -1 0.8782798 0.478147 1 0.8790122 0.4767993 -1 0.8790122 0.4767993 1 0.8797426 0.4754503 -1 0.8797426 0.4754503 1 0.8804709 0.4741002 -1 0.8804709 0.4741002 1 0.8811971 0.4727491 -1 0.8811971 0.4727491 1 0.8819212 0.4713968 -1 0.8819212 0.4713968 1 0.8826434 0.4700433 -1 0.8826434 0.4700433 1 0.8833633 0.4686889 -1 0.8833633 0.4686889 1 0.8840813 0.4673332 -1 0.8840813 0.4673332 1 0.8847971 0.4659765 -1 0.8847971 0.4659765 1 0.8855109 0.4646187 -1 0.8855109 0.4646187 1 0.8862226 0.4632598 -1 0.8862226 0.4632598 1 0.8869321 0.4618998 -1 0.8869321 0.4618998 1 0.8876397 0.4605387 -1 0.8876397 0.4605387 1 0.888345 0.4591765 -1 0.888345 0.4591765 1 0.8890483 0.4578133 -1 0.8890483 0.4578133 1 0.8897496 0.456449 -1 0.8897496 0.456449 1 0.8904488 0.4550836 -1 0.8904488 0.4550836 1 0.8911458 0.4537171 -1 0.8911458 0.4537171 1 0.8918407 0.4523496 -1 0.8918407 0.4523496 1 0.8925336 0.450981 -1 0.8925336 0.450981 1 0.8932243 0.4496113 -1 0.8932243 0.4496113 1 0.893913 0.4482406 -1 0.893913 0.4482406 1 0.8945995 0.4468688 -1 0.8945995 0.4468688 1 0.8952839 0.445496 -1 0.8952839 0.445496 1 0.8959662 0.4441221 -1 0.8959662 0.4441221 1 0.8966464 0.4427472 -1 0.8966464 0.4427472 1 0.8973246 0.4413713 -1 0.8973246 0.4413713 1 0.8980006 0.4399943 -1 0.8980006 0.4399943 1 0.8986745 0.4386162 -1 0.8986745 0.4386162 1 0.8993462 0.4372372 -1 0.8993462 0.4372372 1 0.9000159 0.4358571 -1 0.9000159 0.4358571 1 0.9006834 0.434476 -1 0.9006834 0.434476 1 0.9013488 0.4330939 -1 0.9013488 0.4330939 1 0.9020121 0.4317107 -1 0.9020121 0.4317107 1 0.9026733 0.4303265 -1 0.9026733 0.4303265 1 0.9033324 0.4289413 -1 0.9033324 0.4289413 1 0.9039893 0.4275551 -1 0.9039893 0.4275551 1 0.9046441 0.4261679 -1 0.9046441 0.4261679 1 0.9052968 0.4247797 -1 0.9052968 0.4247797 1 0.9059473 0.4233905 -1 0.9059473 0.4233905 1 0.9065957 0.4220003 -1 0.9065957 0.4220003 1 0.907242 0.4206091 -1 0.907242 0.4206091 1 0.9078861 0.4192169 -1 0.9078861 0.4192169 1 0.9085281 0.4178237 -1 0.9085281 0.4178237 1 0.909168 0.4164296 -1 0.909168 0.4164296 1 0.9098057 0.4150344 -1 0.9098057 0.4150344 1 0.9104413 0.4136383 -1 0.9104413 0.4136383 1 0.9110748 0.4122412 -1 0.9110748 0.4122412 1 0.911706 0.4108432 -1 0.911706 0.4108432 1 0.9123352 0.4094442 -1 0.9123352 0.4094442 1 0.9129622 0.4080442 -1 0.9129622 0.4080442 1 0.913587 0.4066432 -1 0.913587 0.4066432 1 0.9142097 0.4052413 -1 0.9142097 0.4052413 1 0.9148303 0.4038385 -1 0.9148303 0.4038385 1 0.9154487 0.4024347 -1 0.9154487 0.4024347 1 0.916065 0.4010299 -1 0.916065 0.4010299 1 0.9166791 0.3996242 -1 0.9166791 0.3996242 1 0.917291 0.3982176 -1 0.917291 0.3982176 1 0.9179008 0.39681 -1 0.9179008 0.39681 1 0.9185084 0.3954015 -1 0.9185084 0.3954015 1 0.9191139 0.3939921 -1 0.9191139 0.3939921 1 0.9197171 0.3925817 -1 0.9197171 0.3925817 1 0.9203183 0.3911704 -1 0.9203183 0.3911704 1 0.9209172 0.3897582 -1 0.9209172 0.3897582 1 0.921514 0.388345 -1 0.921514 0.388345 1 0.9221087 0.386931 -1 0.9221087 0.386931 1 0.9227011 0.3855161 -1 0.9227011 0.3855161 1 0.9232914 0.3841002 -1 0.9232914 0.3841002 1 0.9238795 0.3826835 -1 0.9238795 0.3826835 1 0.9244655 0.3812658 -1 0.9244655 0.3812658 1 0.9250493 0.3798472 -1 0.9250493 0.3798472 1 0.9256308 0.3784278 -1 0.9256308 0.3784278 1 0.9262102 0.3770074 -1 0.9262102 0.3770074 1 0.9267875 0.3755862 -1 0.9267875 0.3755862 1 0.9273625 0.3741641 -1 0.9273625 0.3741641 1 0.9279354 0.3727411 -1 0.9279354 0.3727411 1 0.9285061 0.3713172 -1 0.9285061 0.3713172 1 0.9290746 0.3698924 -1 0.9290746 0.3698924 1 0.9296409 0.3684668 -1 0.9296409 0.3684668 1 0.930205 0.3670403 -1 0.930205 0.3670403 1 0.9307669 0.365613 -1 0.9307669 0.365613 1 0.9313267 0.3641848 -1 0.9313267 0.3641848 1 0.9318843 0.3627557 -1 0.9318843 0.3627557 1 0.9324396 0.3613258 -1 0.9324396 0.3613258 1 0.9329928 0.3598951 -1 0.9329928 0.3598951 1 0.9335438 0.3584634 -1 0.9335438 0.3584634 1 0.9340925 0.357031 -1 0.9340925 0.357031 1 0.9346391 0.3555977 -1 0.9346391 0.3555977 1 0.9351835 0.3541635 -1 0.9351835 0.3541635 1 0.9357257 0.3527286 -1 0.9357257 0.3527286 1 0.9362657 0.3512927 -1 0.9362657 0.3512927 1 0.9368035 0.3498561 -1 0.9368035 0.3498561 1 0.937339 0.3484187 -1 0.937339 0.3484187 1 0.9378724 0.3469804 -1 0.9378724 0.3469804 1 0.9384036 0.3455413 -1 0.9384036 0.3455413 1 0.9389325 0.3441014 -1 0.9389325 0.3441014 1 0.9394592 0.3426607 -1 0.9394592 0.3426607 1 0.9399837 0.3412192 -1 0.9399837 0.3412192 1 0.9405061 0.3397769 -1 0.9405061 0.3397769 1 0.9410262 0.3383337 -1 0.9410262 0.3383337 1 0.9415441 0.3368899 -1 0.9415441 0.3368899 1 0.9420598 0.3354452 -1 0.9420598 0.3354452 1 0.9425732 0.3339996 -1 0.9425732 0.3339996 1 0.9430844 0.3325534 -1 0.9430844 0.3325534 1 0.9435935 0.3311063 -1 0.9435935 0.3311063 1 0.9441003 0.3296585 -1 0.9441003 0.3296585 1 0.9446048 0.3282098 -1 0.9446048 0.3282098 1 0.9451072 0.3267605 -1 0.9451072 0.3267605 1 0.9456073 0.3253103 -1 0.9456073 0.3253103 1 0.9461053 0.3238593 -1 0.9461053 0.3238593 1 0.9466009 0.3224077 -1 0.9466009 0.3224077 1 0.9470944 0.3209552 -1 0.9470944 0.3209552 1 0.9475856 0.319502 -1 0.9475856 0.319502 1 0.9480746 0.3180481 -1 0.9480746 0.3180481 1 0.9485614 0.3165934 -1 0.9485614 0.3165934 1 0.9490459 0.3151379 -1 0.9490459 0.3151379 1 0.9495282 0.3136817 -1 0.9495282 0.3136817 1 0.9500082 0.3122248 -1 0.9500082 0.3122248 1 0.9504861 0.3107671 -1 0.9504861 0.3107671 1 0.9509617 0.3093088 -1 0.9509617 0.3093088 1 0.951435 0.3078497 -1 0.951435 0.3078497 1 0.9519062 0.3063898 -1 0.9519062 0.3063898 1 0.952375 0.3049293 -1 0.952375 0.3049293 1 0.9528416 0.3034679 -1 0.9528416 0.3034679 1 0.953306 0.302006 -1 0.953306 0.302006 1 0.9537682 0.3005433 -1 0.9537682 0.3005433 1 0.9542281 0.2990798 -1 0.9542281 0.2990798 1 0.9546858 0.2976157 -1 0.9546858 0.2976157 1 0.9551412 0.2961509 -1 0.9551412 0.2961509 1 0.9555943 0.2946854 -1 0.9555943 0.2946854 1 0.9560453 0.2932192 -1 0.9560453 0.2932192 1 0.9564939 0.2917523 -1 0.9564939 0.2917523 1 0.9569404 0.2902847 -1 0.9569404 0.2902847 1 0.9573845 0.2888164 -1 0.9573845 0.2888164 1 0.9578264 0.2873475 -1 0.9578264 0.2873475 1 0.9582661 0.2858778 -1 0.9582661 0.2858778 1 0.9587035 0.2844076 -1 0.9587035 0.2844076 1 0.9591386 0.2829366 -1 0.9591386 0.2829366 1 0.9595715 0.2814649 -1 0.9595715 0.2814649 1 0.9600021 0.2799926 -1 0.9600021 0.2799926 1 0.9604305 0.2785197 -1 0.9604305 0.2785197 1 0.9608566 0.2770461 -1 0.9608566 0.2770461 1 0.9612805 0.2755718 -1 0.9612805 0.2755718 1 0.9617021 0.2740969 -1 0.9617021 0.2740969 1 0.9621214 0.2726213 -1 0.9621214 0.2726213 1 0.9625385 0.2711452 -1 0.9625385 0.2711452 1 0.9629533 0.2696684 -1 0.9629533 0.2696684 1 0.9633658 0.2681909 -1 0.9633658 0.2681909 1 0.9637761 0.2667128 -1 0.9637761 0.2667128 1 0.9641841 0.2652341 -1 0.9641841 0.2652341 1 0.9645898 0.2637547 -1 0.9645898 0.2637547 1 0.9649932 0.2622747 -1 0.9649932 0.2622747 1 0.9653944 0.2607941 -1 0.9653944 0.2607941 1 0.9657934 0.2593129 -1 0.9657934 0.2593129 1 0.96619 0.2578311 -1 0.96619 0.2578311 1 0.9665844 0.2563487 -1 0.9665844 0.2563487 1 0.9669765 0.2548657 -1 0.9669765 0.2548657 1 0.9673663 0.253382 -1 0.9673663 0.253382 1 0.9677538 0.2518978 -1 0.9677538 0.2518978 1 0.9681391 0.250413 -1 0.9681391 0.250413 1 0.9685221 0.2489276 -1 0.9685221 0.2489276 1 0.9689028 0.2474416 -1 0.9689028 0.2474416 1 0.9692813 0.245955 -1 0.9692813 0.245955 1 0.9696574 0.2444679 -1 0.9696574 0.2444679 1 0.9700313 0.2429802 -1 0.9700313 0.2429802 1 0.9704028 0.2414919 -1 0.9704028 0.2414919 1 0.9707722 0.240003 -1 0.9707722 0.240003 1 0.9711391 0.2385136 -1 0.9711391 0.2385136 1 0.9715039 0.2370236 -1 0.9715039 0.2370236 1 0.9718663 0.235533 -1 0.9718663 0.235533 1 0.9722265 0.2340419 -1 0.9722265 0.2340419 1 0.9725844 0.2325503 -1 0.9725844 0.2325503 1 0.97294 0.2310581 -1 0.97294 0.2310581 1 0.9732933 0.2295653 -1 0.9732933 0.2295653 1 0.9736443 0.2280721 -1 0.9736443 0.2280721 1 0.973993 0.2265782 -1 0.973993 0.2265782 1 0.9743394 0.2250839 -1 0.9743394 0.2250839 1 0.9746835 0.223589 -1 0.9746835 0.223589 1 0.9750254 0.2220936 -1 0.9750254 0.2220936 1 0.9753649 0.2205977 -1 0.9753649 0.2205977 1 0.9757021 0.2191012 -1 0.9757021 0.2191012 1 0.9760371 0.2176042 -1 0.9760371 0.2176042 1 0.9763697 0.2161068 -1 0.9763697 0.2161068 1 0.9767001 0.2146088 -1 0.9767001 0.2146088 1 0.9770281 0.2131103 -1 0.9770281 0.2131103 1 0.9773539 0.2116113 -1 0.9773539 0.2116113 1 0.9776774 0.2101118 -1 0.9776774 0.2101118 1 0.9779985 0.2086118 -1 0.9779985 0.2086118 1 0.9783174 0.2071114 -1 0.9783174 0.2071114 1 0.9786339 0.2056104 -1 0.9786339 0.2056104 1 0.9789482 0.204109 -1 0.9789482 0.204109 1 0.9792602 0.202607 -1 0.9792602 0.202607 1 0.9795698 0.2011046 -1 0.9795698 0.2011046 1 0.9798771 0.1996017 -1 0.9798771 0.1996017 1 0.9801821 0.1980984 -1 0.9801821 0.1980984 1 0.9804849 0.1965946 -1 0.9804849 0.1965946 1 0.9807853 0.1950903 -1 0.9807853 0.1950903 1 0.9810834 0.1935856 -1 0.9810834 0.1935856 1 0.9813792 0.1920804 -1 0.9813792 0.1920804 1 0.9816727 0.1905747 -1 0.9816727 0.1905747 1 0.9819639 0.1890686 -1 0.9819639 0.1890686 1 0.9822527 0.1875621 -1 0.9822527 0.1875621 1 0.9825393 0.1860551 -1 0.9825393 0.1860551 1 0.9828236 0.1845477 -1 0.9828236 0.1845477 1 0.9831055 0.1830399 -1 0.9831055 0.1830399 1 0.9833851 0.1815316 -1 0.9833851 0.1815316 1 0.9836624 0.1800229 -1 0.9836624 0.1800229 1 0.9839375 0.1785138 -1 0.9839375 0.1785138 1 0.9842101 0.1770042 -1 0.9842101 0.1770042 1 0.9844805 0.1754943 -1 0.9844805 0.1754943 1 0.9847485 0.1739838 -1 0.9847485 0.1739838 1 0.9850143 0.1724731 -1 0.9850143 0.1724731 1 0.9852777 0.1709619 -1 0.9852777 0.1709619 1 0.9855387 0.1694503 -1 0.9855387 0.1694503 1 0.9857975 0.1679382 -1 0.9857975 0.1679382 1 0.986054 0.1664259 -1 0.986054 0.1664259 1 0.9863081 0.1649131 -1 0.9863081 0.1649131 1 0.9865599 0.1633999 -1 0.9865599 0.1633999 1 0.9868094 0.1618863 -1 0.9868094 0.1618863 1 0.9870566 0.1603724 -1 0.9870566 0.1603724 1 0.9873014 0.1588581 -1 0.9873014 0.1588581 1 0.987544 0.1573435 -1 0.987544 0.1573435 1 0.9877842 0.1558284 -1 0.9877842 0.1558284 1 0.988022 0.154313 -1 0.988022 0.154313 1 0.9882576 0.1527972 -1 0.9882576 0.1527972 1 0.9884908 0.151281 -1 0.9884908 0.151281 1 0.9887217 0.1497645 -1 0.9887217 0.1497645 1 0.9889503 0.1482477 -1 0.9889503 0.1482477 1 0.9891765 0.1467304 -1 0.9891765 0.1467304 1 0.9894005 0.1452129 -1 0.9894005 0.1452129 1 0.989622 0.143695 -1 0.989622 0.143695 1 0.9898413 0.1421768 -1 0.9898413 0.1421768 1 0.9900582 0.1406582 -1 0.9900582 0.1406582 1 0.9902728 0.1391393 -1 0.9902728 0.1391393 1 0.9904851 0.1376201 -1 0.9904851 0.1376201 1 0.990695 0.1361005 -1 0.990695 0.1361005 1 0.9909027 0.1345807 -1 0.9909027 0.1345807 1 0.991108 0.1330605 -1 0.991108 0.1330605 1 0.9913108 0.13154 -1 0.9913108 0.13154 1 0.9915115 0.1300192 -1 0.9915115 0.1300192 1 0.9917098 0.1284981 -1 0.9917098 0.1284981 1 0.9919057 0.1269767 -1 0.9919057 0.1269767 1 0.9920993 0.125455 -1 0.9920993 0.125455 1 0.9922906 0.123933 -1 0.9922906 0.123933 1 0.9924796 0.1224107 -1 0.9924796 0.1224107 1 0.9926661 0.1208881 -1 0.9926661 0.1208881 1 0.9928504 0.1193652 -1 0.9928504 0.1193652 1 0.9930323 0.117842 -1 0.9930323 0.117842 1 0.9932119 0.1163186 -1 0.9932119 0.1163186 1 0.9933892 0.1147949 -1 0.9933892 0.1147949 1 0.9935641 0.1132709 -1 0.9935641 0.1132709 1 0.9937368 0.1117467 -1 0.9937368 0.1117467 1 0.993907 0.1102222 -1 0.993907 0.1102222 1 0.9940749 0.1086974 -1 0.9940749 0.1086974 1 0.9942405 0.1071724 -1 0.9942405 0.1071724 1 0.9944037 0.1056472 -1 0.9944037 0.1056472 1 0.9945646 0.1041216 -1 0.9945646 0.1041216 1 0.9947232 0.1025959 -1 0.9947232 0.1025959 1 0.9948793 0.1010698 -1 0.9948793 0.1010698 1 0.9950332 0.09954357 -1 0.9950332 0.09954357 1 0.9951847 0.09801709 -1 0.9951847 0.09801709 1 0.9953339 0.09649044 -1 0.9953339 0.09649044 1 0.9954808 0.09496349 -1 0.9954808 0.09496349 1 0.9956253 0.0934363 -1 0.9956253 0.0934363 1 0.9957674 0.09190893 -1 0.9957674 0.09190893 1 0.9959073 0.09038132 -1 0.9959073 0.09038132 1 0.9960447 0.08885353 -1 0.9960447 0.08885353 1 0.9961798 0.08732551 -1 0.9961798 0.08732551 1 0.9963126 0.0857973 -1 0.9963126 0.0857973 1 0.996443 0.08426886 -1 0.996443 0.08426886 1 0.9965711 0.08274024 -1 0.9965711 0.08274024 1 0.9966969 0.08121144 -1 0.9966969 0.08121144 1 0.9968203 0.0796824 -1 0.9968203 0.0796824 1 0.9969413 0.07815325 -1 0.9969413 0.07815325 1 0.9970601 0.07662385 -1 0.9970601 0.07662385 1 0.9971764 0.07509428 -1 0.9971764 0.07509428 1 0.9972904 0.07356452 -1 0.9972904 0.07356452 1 0.9974021 0.07203465 -1 0.9974021 0.07203465 1 0.9975115 0.07050454 -1 0.9975115 0.07050454 1 0.9976184 0.06897431 -1 0.9976184 0.06897431 1 0.9977231 0.0674439 -1 0.9977231 0.0674439 1 0.9978253 0.06591331 -1 0.9978253 0.06591331 1 0.9979253 0.06438261 -1 0.9979253 0.06438261 1 0.9980229 0.06285172 -1 0.9980229 0.06285172 1 0.9981181 0.06132072 -1 0.9981181 0.06132072 1 0.998211 0.05978953 -1 0.998211 0.05978953 1 0.9983016 0.05825823 -1 0.9983016 0.05825823 1 0.9983897 0.05672681 -1 0.9983897 0.05672681 1 0.9984756 0.05519521 -1 0.9984756 0.05519521 1 0.9985591 0.05366349 -1 0.9985591 0.05366349 1 0.9986402 0.05213171 -1 0.9986402 0.05213171 1 0.998719 0.05059975 -1 0.998719 0.05059975 1 0.9987955 0.04906767 -1 0.9987955 0.04906767 1 0.9988695 0.04753547 -1 0.9988695 0.04753547 1 0.9989413 0.04600316 -1 0.9989413 0.04600316 1 0.9990107 0.04447072 -1 0.9990107 0.04447072 1 0.9990777 0.04293823 -1 0.9990777 0.04293823 1 0.9991424 0.04140561 -1 0.9991424 0.04140561 1 0.9992048 0.03987288 -1 0.9992048 0.03987288 1 0.9992648 0.03834009 -1 0.9992648 0.03834009 1 0.9993224 0.03680717 -1 0.9993224 0.03680717 1 0.9993777 0.0352742 -1 0.9993777 0.0352742 1 0.9994306 0.03374117 -1 0.9994306 0.03374117 1 0.9994812 0.03220802 -1 0.9994812 0.03220802 1 0.9995294 0.03067475 -1 0.9995294 0.03067475 1 0.9995753 0.02914148 -1 0.9995753 0.02914148 1 0.9996188 0.02760809 -1 0.9996188 0.02760809 1 0.99966 0.0260747 -1 0.99966 0.0260747 1 0.9996988 0.02454119 -1 0.9996988 0.02454119 1 0.9997353 0.02300763 -1 0.9997353 0.02300763 1 0.9997694 0.02147406 -1 0.9997694 0.02147406 1 0.9998012 0.01994037 -1 0.9998012 0.01994037 1 0.9998306 0.01840668 -1 0.9998306 0.01840668 1 0.9998577 0.01687294 -1 0.9998577 0.01687294 1 0.9998824 0.01533919 -1 0.9998824 0.01533919 1 0.9999047 0.01380538 -1 0.9999047 0.01380538 1 0.9999247 0.01227152 -1 0.9999247 0.01227152 1 0.9999424 0.01073765 -1 0.9999424 0.01073765 1 0.9999576 0.009203732 -1 0.9999576 0.009203732 1 0.9999706 0.007669806 -1 0.9999706 0.007669806 1 0.9999812 0.00613588 -1 0.9999812 0.00613588 1 0.9999894 0.004601895 -1 0.9999894 0.004601895 1 0.9999953 0.00306791 -1 0.9999953 0.00306791 1 0.9999988 0.001533925 -1 0.9999988 0.001533925 1 1 0 -1 1 0 1 0.9999988 -0.001533925 -1 0.9999988 -0.001533925 1 0.9999953 -0.00306791 -1 0.9999953 -0.00306791 1 0.9999894 -0.004601895 -1 0.9999894 -0.004601895 1 0.9999812 -0.00613588 -1 0.9999812 -0.00613588 1 0.9999706 -0.007669806 -1 0.9999706 -0.007669806 1 0.9999576 -0.009203732 -1 0.9999576 -0.009203732 1 0.9999424 -0.01073765 -1 0.9999424 -0.01073765 1 0.9999247 -0.01227152 -1 0.9999247 -0.01227152 1 0.9999047 -0.01380538 -1 0.9999047 -0.01380538 1 0.9998824 -0.01533919 -1 0.9998824 -0.01533919 1 0.9998577 -0.01687294 -1 0.9998577 -0.01687294 1 0.9998306 -0.01840668 -1 0.9998306 -0.01840668 1 0.9998012 -0.01994037 -1 0.9998012 -0.01994037 1 0.9997694 -0.02147406 -1 0.9997694 -0.02147406 1 0.9997353 -0.02300763 -1 0.9997353 -0.02300763 1 0.9996988 -0.02454119 -1 0.9996988 -0.02454119 1 0.99966 -0.0260747 -1 0.99966 -0.0260747 1 0.9996188 -0.02760809 -1 0.9996188 -0.02760809 1 0.9995753 -0.02914148 -1 0.9995753 -0.02914148 1 0.9995294 -0.03067475 -1 0.9995294 -0.03067475 1 0.9994812 -0.03220802 -1 0.9994812 -0.03220802 1 0.9994306 -0.03374117 -1 0.9994306 -0.03374117 1 0.9993777 -0.0352742 -1 0.9993777 -0.0352742 1 0.9993224 -0.03680717 -1 0.9993224 -0.03680717 1 0.9992648 -0.03834009 -1 0.9992648 -0.03834009 1 0.9992048 -0.03987288 -1 0.9992048 -0.03987288 1 0.9991424 -0.04140561 -1 0.9991424 -0.04140561 1 0.9990777 -0.04293823 -1 0.9990777 -0.04293823 1 0.9990107 -0.04447072 -1 0.9990107 -0.04447072 1 0.9989413 -0.04600316 -1 0.9989413 -0.04600316 1 0.9988695 -0.04753547 -1 0.9988695 -0.04753547 1 0.9987955 -0.04906767 -1 0.9987955 -0.04906767 1 0.998719 -0.05059975 -1 0.998719 -0.05059975 1 0.9986402 -0.05213171 -1 0.9986402 -0.05213171 1 0.9985591 -0.05366349 -1 0.9985591 -0.05366349 1 0.9984756 -0.05519521 -1 0.9984756 -0.05519521 1 0.9983897 -0.05672681 -1 0.9983897 -0.05672681 1 0.9983016 -0.05825823 -1 0.9983016 -0.05825823 1 0.998211 -0.05978953 -1 0.998211 -0.05978953 1 0.9981181 -0.06132072 -1 0.9981181 -0.06132072 1 0.9980229 -0.06285172 -1 0.9980229 -0.06285172 1 0.9979253 -0.06438261 -1 0.9979253 -0.06438261 1 0.9978253 -0.06591331 -1 0.9978253 -0.06591331 1 0.9977231 -0.0674439 -1 0.9977231 -0.0674439 1 0.9976184 -0.06897431 -1 0.9976184 -0.06897431 1 0.9975115 -0.07050454 -1 0.9975115 -0.07050454 1 0.9974021 -0.07203465 -1 0.9974021 -0.07203465 1 0.9972904 -0.07356452 -1 0.9972904 -0.07356452 1 0.9971764 -0.07509428 -1 0.9971764 -0.07509428 1 0.9970601 -0.07662385 -1 0.9970601 -0.07662385 1 0.9969413 -0.07815325 -1 0.9969413 -0.07815325 1 0.9968203 -0.0796824 -1 0.9968203 -0.0796824 1 0.9966969 -0.08121144 -1 0.9966969 -0.08121144 1 0.9965711 -0.08274024 -1 0.9965711 -0.08274024 1 0.996443 -0.08426886 -1 0.996443 -0.08426886 1 0.9963126 -0.0857973 -1 0.9963126 -0.0857973 1 0.9961798 -0.08732551 -1 0.9961798 -0.08732551 1 0.9960447 -0.08885353 -1 0.9960447 -0.08885353 1 0.9959073 -0.09038132 -1 0.9959073 -0.09038132 1 0.9957674 -0.09190893 -1 0.9957674 -0.09190893 1 0.9956253 -0.0934363 -1 0.9956253 -0.0934363 1 0.9954808 -0.09496349 -1 0.9954808 -0.09496349 1 0.9953339 -0.09649044 -1 0.9953339 -0.09649044 1 0.9951847 -0.09801709 -1 0.9951847 -0.09801709 1 0.9950332 -0.09954357 -1 0.9950332 -0.09954357 1 0.9948793 -0.1010698 -1 0.9948793 -0.1010698 1 0.9947232 -0.1025959 -1 0.9947232 -0.1025959 1 0.9945646 -0.1041216 -1 0.9945646 -0.1041216 1 0.9944037 -0.1056472 -1 0.9944037 -0.1056472 1 0.9942405 -0.1071724 -1 0.9942405 -0.1071724 1 0.9940749 -0.1086974 -1 0.9940749 -0.1086974 1 0.993907 -0.1102222 -1 0.993907 -0.1102222 1 0.9937368 -0.1117467 -1 0.9937368 -0.1117467 1 0.9935641 -0.1132709 -1 0.9935641 -0.1132709 1 0.9933892 -0.1147949 -1 0.9933892 -0.1147949 1 0.9932119 -0.1163186 -1 0.9932119 -0.1163186 1 0.9930323 -0.117842 -1 0.9930323 -0.117842 1 0.9928504 -0.1193652 -1 0.9928504 -0.1193652 1 0.9926661 -0.1208881 -1 0.9926661 -0.1208881 1 0.9924796 -0.1224107 -1 0.9924796 -0.1224107 1 0.9922906 -0.123933 -1 0.9922906 -0.123933 1 0.9920993 -0.125455 -1 0.9920993 -0.125455 1 0.9919057 -0.1269767 -1 0.9919057 -0.1269767 1 0.9917098 -0.1284981 -1 0.9917098 -0.1284981 1 0.9915115 -0.1300192 -1 0.9915115 -0.1300192 1 0.9913108 -0.13154 -1 0.9913108 -0.13154 1 0.991108 -0.1330605 -1 0.991108 -0.1330605 1 0.9909027 -0.1345807 -1 0.9909027 -0.1345807 1 0.990695 -0.1361005 -1 0.990695 -0.1361005 1 0.9904851 -0.1376201 -1 0.9904851 -0.1376201 1 0.9902728 -0.1391393 -1 0.9902728 -0.1391393 1 0.9900582 -0.1406582 -1 0.9900582 -0.1406582 1 0.9898413 -0.1421768 -1 0.9898413 -0.1421768 1 0.989622 -0.143695 -1 0.989622 -0.143695 1 0.9894005 -0.1452129 -1 0.9894005 -0.1452129 1 0.9891765 -0.1467304 -1 0.9891765 -0.1467304 1 0.9889503 -0.1482477 -1 0.9889503 -0.1482477 1 0.9887217 -0.1497645 -1 0.9887217 -0.1497645 1 0.9884908 -0.151281 -1 0.9884908 -0.151281 1 0.9882576 -0.1527972 -1 0.9882576 -0.1527972 1 0.988022 -0.154313 -1 0.988022 -0.154313 1 0.9877842 -0.1558284 -1 0.9877842 -0.1558284 1 0.987544 -0.1573435 -1 0.987544 -0.1573435 1 0.9873014 -0.1588581 -1 0.9873014 -0.1588581 1 0.9870566 -0.1603724 -1 0.9870566 -0.1603724 1 0.9868094 -0.1618863 -1 0.9868094 -0.1618863 1 0.9865599 -0.1633999 -1 0.9865599 -0.1633999 1 0.9863081 -0.1649131 -1 0.9863081 -0.1649131 1 0.986054 -0.1664259 -1 0.986054 -0.1664259 1 0.9857975 -0.1679382 -1 0.9857975 -0.1679382 1 0.9855387 -0.1694503 -1 0.9855387 -0.1694503 1 0.9852777 -0.1709619 -1 0.9852777 -0.1709619 1 0.9850143 -0.1724731 -1 0.9850143 -0.1724731 1 0.9847485 -0.1739838 -1 0.9847485 -0.1739838 1 0.9844805 -0.1754943 -1 0.9844805 -0.1754943 1 0.9842101 -0.1770042 -1 0.9842101 -0.1770042 1 0.9839375 -0.1785138 -1 0.9839375 -0.1785138 1 0.9836624 -0.1800229 -1 0.9836624 -0.1800229 1 0.9833851 -0.1815316 -1 0.9833851 -0.1815316 1 0.9831055 -0.1830399 -1 0.9831055 -0.1830399 1 0.9828236 -0.1845477 -1 0.9828236 -0.1845477 1 0.9825393 -0.1860551 -1 0.9825393 -0.1860551 1 0.9822527 -0.1875621 -1 0.9822527 -0.1875621 1 0.9819639 -0.1890686 -1 0.9819639 -0.1890686 1 0.9816727 -0.1905747 -1 0.9816727 -0.1905747 1 0.9813792 -0.1920804 -1 0.9813792 -0.1920804 1 0.9810834 -0.1935856 -1 0.9810834 -0.1935856 1 0.9807853 -0.1950903 -1 0.9807853 -0.1950903 1 0.9804849 -0.1965946 -1 0.9804849 -0.1965946 1 0.9801821 -0.1980984 -1 0.9801821 -0.1980984 1 0.9798771 -0.1996017 -1 0.9798771 -0.1996017 1 0.9795698 -0.2011046 -1 0.9795698 -0.2011046 1 0.9792602 -0.202607 -1 0.9792602 -0.202607 1 0.9789482 -0.204109 -1 0.9789482 -0.204109 1 0.9786339 -0.2056104 -1 0.9786339 -0.2056104 1 0.9783174 -0.2071114 -1 0.9783174 -0.2071114 1 0.9779985 -0.2086118 -1 0.9779985 -0.2086118 1 0.9776774 -0.2101118 -1 0.9776774 -0.2101118 1 0.9773539 -0.2116113 -1 0.9773539 -0.2116113 1 0.9770281 -0.2131103 -1 0.9770281 -0.2131103 1 0.9767001 -0.2146088 -1 0.9767001 -0.2146088 1 0.9763697 -0.2161068 -1 0.9763697 -0.2161068 1 0.9760371 -0.2176042 -1 0.9760371 -0.2176042 1 0.9757021 -0.2191012 -1 0.9757021 -0.2191012 1 0.9753649 -0.2205977 -1 0.9753649 -0.2205977 1 0.9750254 -0.2220936 -1 0.9750254 -0.2220936 1 0.9746835 -0.223589 -1 0.9746835 -0.223589 1 0.9743394 -0.2250839 -1 0.9743394 -0.2250839 1 0.973993 -0.2265782 -1 0.973993 -0.2265782 1 0.9736443 -0.2280721 -1 0.9736443 -0.2280721 1 0.9732933 -0.2295653 -1 0.9732933 -0.2295653 1 0.97294 -0.2310581 -1 0.97294 -0.2310581 1 0.9725844 -0.2325503 -1 0.9725844 -0.2325503 1 0.9722265 -0.2340419 -1 0.9722265 -0.2340419 1 0.9718663 -0.235533 -1 0.9718663 -0.235533 1 0.9715039 -0.2370236 -1 0.9715039 -0.2370236 1 0.9711391 -0.2385136 -1 0.9711391 -0.2385136 1 0.9707722 -0.240003 -1 0.9707722 -0.240003 1 0.9704028 -0.2414919 -1 0.9704028 -0.2414919 1 0.9700313 -0.2429802 -1 0.9700313 -0.2429802 1 0.9696574 -0.2444679 -1 0.9696574 -0.2444679 1 0.9692813 -0.245955 -1 0.9692813 -0.245955 1 0.9689028 -0.2474416 -1 0.9689028 -0.2474416 1 0.9685221 -0.2489276 -1 0.9685221 -0.2489276 1 0.9681391 -0.250413 -1 0.9681391 -0.250413 1 0.9677538 -0.2518978 -1 0.9677538 -0.2518978 1 0.9673663 -0.253382 -1 0.9673663 -0.253382 1 0.9669765 -0.2548657 -1 0.9669765 -0.2548657 1 0.9665844 -0.2563487 -1 0.9665844 -0.2563487 1 0.96619 -0.2578311 -1 0.96619 -0.2578311 1 0.9657934 -0.2593129 -1 0.9657934 -0.2593129 1 0.9653944 -0.2607941 -1 0.9653944 -0.2607941 1 0.9649932 -0.2622747 -1 0.9649932 -0.2622747 1 0.9645898 -0.2637547 -1 0.9645898 -0.2637547 1 0.9641841 -0.2652341 -1 0.9641841 -0.2652341 1 0.9637761 -0.2667128 -1 0.9637761 -0.2667128 1 0.9633658 -0.2681909 -1 0.9633658 -0.2681909 1 0.9629533 -0.2696684 -1 0.9629533 -0.2696684 1 0.9625385 -0.2711452 -1 0.9625385 -0.2711452 1 0.9621214 -0.2726213 -1 0.9621214 -0.2726213 1 0.9617021 -0.2740969 -1 0.9617021 -0.2740969 1 0.9612805 -0.2755718 -1 0.9612805 -0.2755718 1 0.9608566 -0.2770461 -1 0.9608566 -0.2770461 1 0.9604305 -0.2785197 -1 0.9604305 -0.2785197 1 0.9600021 -0.2799926 -1 0.9600021 -0.2799926 1 0.9595715 -0.2814649 -1 0.9595715 -0.2814649 1 0.9591386 -0.2829366 -1 0.9591386 -0.2829366 1 0.9587035 -0.2844076 -1 0.9587035 -0.2844076 1 0.9582661 -0.2858778 -1 0.9582661 -0.2858778 1 0.9578264 -0.2873475 -1 0.9578264 -0.2873475 1 0.9573845 -0.2888164 -1 0.9573845 -0.2888164 1 0.9569404 -0.2902847 -1 0.9569404 -0.2902847 1 0.9564939 -0.2917523 -1 0.9564939 -0.2917523 1 0.9560453 -0.2932192 -1 0.9560453 -0.2932192 1 0.9555943 -0.2946854 -1 0.9555943 -0.2946854 1 0.9551412 -0.2961509 -1 0.9551412 -0.2961509 1 0.9546858 -0.2976157 -1 0.9546858 -0.2976157 1 0.9542281 -0.2990798 -1 0.9542281 -0.2990798 1 0.9537682 -0.3005433 -1 0.9537682 -0.3005433 1 0.953306 -0.302006 -1 0.953306 -0.302006 1 0.9528416 -0.3034679 -1 0.9528416 -0.3034679 1 0.952375 -0.3049293 -1 0.952375 -0.3049293 1 0.9519062 -0.3063898 -1 0.9519062 -0.3063898 1 0.951435 -0.3078497 -1 0.951435 -0.3078497 1 0.9509617 -0.3093088 -1 0.9509617 -0.3093088 1 0.9504861 -0.3107671 -1 0.9504861 -0.3107671 1 0.9500082 -0.3122248 -1 0.9500082 -0.3122248 1 0.9495282 -0.3136817 -1 0.9495282 -0.3136817 1 0.9490459 -0.3151379 -1 0.9490459 -0.3151379 1 0.9485614 -0.3165934 -1 0.9485614 -0.3165934 1 0.9480746 -0.3180481 -1 0.9480746 -0.3180481 1 0.9475856 -0.319502 -1 0.9475856 -0.319502 1 0.9470944 -0.3209552 -1 0.9470944 -0.3209552 1 0.9466009 -0.3224077 -1 0.9466009 -0.3224077 1 0.9461053 -0.3238593 -1 0.9461053 -0.3238593 1 0.9456073 -0.3253103 -1 0.9456073 -0.3253103 1 0.9451072 -0.3267605 -1 0.9451072 -0.3267605 1 0.9446048 -0.3282098 -1 0.9446048 -0.3282098 1 0.9441003 -0.3296585 -1 0.9441003 -0.3296585 1 0.9435935 -0.3311063 -1 0.9435935 -0.3311063 1 0.9430844 -0.3325534 -1 0.9430844 -0.3325534 1 0.9425732 -0.3339996 -1 0.9425732 -0.3339996 1 0.9420598 -0.3354452 -1 0.9420598 -0.3354452 1 0.9415441 -0.3368899 -1 0.9415441 -0.3368899 1 0.9410262 -0.3383337 -1 0.9410262 -0.3383337 1 0.9405061 -0.3397769 -1 0.9405061 -0.3397769 1 0.9399837 -0.3412192 -1 0.9399837 -0.3412192 1 0.9394592 -0.3426607 -1 0.9394592 -0.3426607 1 0.9389325 -0.3441014 -1 0.9389325 -0.3441014 1 0.9384036 -0.3455413 -1 0.9384036 -0.3455413 1 0.9378724 -0.3469804 -1 0.9378724 -0.3469804 1 0.937339 -0.3484187 -1 0.937339 -0.3484187 1 0.9368035 -0.3498561 -1 0.9368035 -0.3498561 1 0.9362657 -0.3512927 -1 0.9362657 -0.3512927 1 0.9357257 -0.3527286 -1 0.9357257 -0.3527286 1 0.9351835 -0.3541635 -1 0.9351835 -0.3541635 1 0.9346391 -0.3555977 -1 0.9346391 -0.3555977 1 0.9340925 -0.357031 -1 0.9340925 -0.357031 1 0.9335438 -0.3584634 -1 0.9335438 -0.3584634 1 0.9329928 -0.3598951 -1 0.9329928 -0.3598951 1 0.9324396 -0.3613258 -1 0.9324396 -0.3613258 1 0.9318843 -0.3627557 -1 0.9318843 -0.3627557 1 0.9313267 -0.3641848 -1 0.9313267 -0.3641848 1 0.9307669 -0.365613 -1 0.9307669 -0.365613 1 0.930205 -0.3670403 -1 0.930205 -0.3670403 1 0.9296409 -0.3684668 -1 0.9296409 -0.3684668 1 0.9290746 -0.3698924 -1 0.9290746 -0.3698924 1 0.9285061 -0.3713172 -1 0.9285061 -0.3713172 1 0.9279354 -0.3727411 -1 0.9279354 -0.3727411 1 0.9273625 -0.3741641 -1 0.9273625 -0.3741641 1 0.9267875 -0.3755862 -1 0.9267875 -0.3755862 1 0.9262102 -0.3770074 -1 0.9262102 -0.3770074 1 0.9256308 -0.3784278 -1 0.9256308 -0.3784278 1 0.9250493 -0.3798472 -1 0.9250493 -0.3798472 1 0.9244655 -0.3812658 -1 0.9244655 -0.3812658 1 0.9238795 -0.3826835 -1 0.9238795 -0.3826835 1 0.9232914 -0.3841002 -1 0.9232914 -0.3841002 1 0.9227011 -0.3855161 -1 0.9227011 -0.3855161 1 0.9221087 -0.386931 -1 0.9221087 -0.386931 1 0.921514 -0.388345 -1 0.921514 -0.388345 1 0.9209172 -0.3897582 -1 0.9209172 -0.3897582 1 0.9203183 -0.3911704 -1 0.9203183 -0.3911704 1 0.9197171 -0.3925817 -1 0.9197171 -0.3925817 1 0.9191139 -0.3939921 -1 0.9191139 -0.3939921 1 0.9185084 -0.3954015 -1 0.9185084 -0.3954015 1 0.9179008 -0.39681 -1 0.9179008 -0.39681 1 0.917291 -0.3982176 -1 0.917291 -0.3982176 1 0.9166791 -0.3996242 -1 0.9166791 -0.3996242 1 0.916065 -0.4010299 -1 0.916065 -0.4010299 1 0.9154487 -0.4024347 -1 0.9154487 -0.4024347 1 0.9148303 -0.4038385 -1 0.9148303 -0.4038385 1 0.9142097 -0.4052413 -1 0.9142097 -0.4052413 1 0.913587 -0.4066432 -1 0.913587 -0.4066432 1 0.9129622 -0.4080442 -1 0.9129622 -0.4080442 1 0.9123352 -0.4094442 -1 0.9123352 -0.4094442 1 0.911706 -0.4108432 -1 0.911706 -0.4108432 1 0.9110748 -0.4122412 -1 0.9110748 -0.4122412 1 0.9104413 -0.4136383 -1 0.9104413 -0.4136383 1 0.9098057 -0.4150344 -1 0.9098057 -0.4150344 1 0.909168 -0.4164296 -1 0.909168 -0.4164296 1 0.9085281 -0.4178237 -1 0.9085281 -0.4178237 1 0.9078861 -0.4192169 -1 0.9078861 -0.4192169 1 0.907242 -0.4206091 -1 0.907242 -0.4206091 1 0.9065957 -0.4220003 -1 0.9065957 -0.4220003 1 0.9059473 -0.4233905 -1 0.9059473 -0.4233905 1 0.9052968 -0.4247797 -1 0.9052968 -0.4247797 1 0.9046441 -0.4261679 -1 0.9046441 -0.4261679 1 0.9039893 -0.4275551 -1 0.9039893 -0.4275551 1 0.9033324 -0.4289413 -1 0.9033324 -0.4289413 1 0.9026733 -0.4303265 -1 0.9026733 -0.4303265 1 0.9020121 -0.4317107 -1 0.9020121 -0.4317107 1 0.9013488 -0.4330939 -1 0.9013488 -0.4330939 1 0.9006834 -0.434476 -1 0.9006834 -0.434476 1 0.9000159 -0.4358571 -1 0.9000159 -0.4358571 1 0.8993462 -0.4372372 -1 0.8993462 -0.4372372 1 0.8986745 -0.4386162 -1 0.8986745 -0.4386162 1 0.8980006 -0.4399943 -1 0.8980006 -0.4399943 1 0.8973246 -0.4413713 -1 0.8973246 -0.4413713 1 0.8966464 -0.4427472 -1 0.8966464 -0.4427472 1 0.8959662 -0.4441221 -1 0.8959662 -0.4441221 1 0.8952839 -0.445496 -1 0.8952839 -0.445496 1 0.8945995 -0.4468688 -1 0.8945995 -0.4468688 1 0.893913 -0.4482406 -1 0.893913 -0.4482406 1 0.8932243 -0.4496113 -1 0.8932243 -0.4496113 1 0.8925336 -0.450981 -1 0.8925336 -0.450981 1 0.8918407 -0.4523496 -1 0.8918407 -0.4523496 1 0.8911458 -0.4537171 -1 0.8911458 -0.4537171 1 0.8904488 -0.4550836 -1 0.8904488 -0.4550836 1 0.8897496 -0.456449 -1 0.8897496 -0.456449 1 0.8890483 -0.4578133 -1 0.8890483 -0.4578133 1 0.888345 -0.4591765 -1 0.888345 -0.4591765 1 0.8876397 -0.4605387 -1 0.8876397 -0.4605387 1 0.8869321 -0.4618998 -1 0.8869321 -0.4618998 1 0.8862226 -0.4632598 -1 0.8862226 -0.4632598 1 0.8855109 -0.4646187 -1 0.8855109 -0.4646187 1 0.8847971 -0.4659765 -1 0.8847971 -0.4659765 1 0.8840813 -0.4673332 -1 0.8840813 -0.4673332 1 0.8833633 -0.4686889 -1 0.8833633 -0.4686889 1 0.8826434 -0.4700433 -1 0.8826434 -0.4700433 1 0.8819212 -0.4713968 -1 0.8819212 -0.4713968 1 0.8811971 -0.4727491 -1 0.8811971 -0.4727491 1 0.8804709 -0.4741002 -1 0.8804709 -0.4741002 1 0.8797426 -0.4754503 -1 0.8797426 -0.4754503 1 0.8790122 -0.4767993 -1 0.8790122 -0.4767993 1 0.8782798 -0.478147 -1 0.8782798 -0.478147 1 0.8775453 -0.4794937 -1 0.8775453 -0.4794937 1 0.8768087 -0.4808393 -1 0.8768087 -0.4808393 1 0.8760701 -0.4821838 -1 0.8760701 -0.4821838 1 0.8753294 -0.4835271 -1 0.8753294 -0.4835271 1 0.8745867 -0.4848693 -1 0.8745867 -0.4848693 1 0.8738418 -0.4862103 -1 0.8738418 -0.4862103 1 0.873095 -0.4875501 -1 0.873095 -0.4875501 1 0.8723461 -0.4888889 -1 0.8723461 -0.4888889 1 0.8715951 -0.4902265 -1 0.8715951 -0.4902265 1 0.870842 -0.4915629 -1 0.870842 -0.4915629 1 0.870087 -0.4928982 -1 0.870087 -0.4928982 1 0.8693299 -0.4942323 -1 0.8693299 -0.4942323 1 0.8685707 -0.4955653 -1 0.8685707 -0.4955653 1 0.8678095 -0.4968971 -1 0.8678095 -0.4968971 1 0.8670462 -0.4982277 -1 0.8670462 -0.4982277 1 0.866281 -0.4995571 -1 0.866281 -0.4995571 1 0.8655136 -0.5008854 -1 0.8655136 -0.5008854 1 0.8647443 -0.5022125 -1 0.8647443 -0.5022125 1 0.8639729 -0.5035384 -1 0.8639729 -0.5035384 1 0.8631994 -0.5048632 -1 0.8631994 -0.5048632 1 0.862424 -0.5061867 -1 0.862424 -0.5061867 1 0.8616465 -0.507509 -1 0.8616465 -0.507509 1 0.8608669 -0.5088302 -1 0.8608669 -0.5088302 1 0.8600854 -0.5101501 -1 0.8600854 -0.5101501 1 0.8593018 -0.5114689 -1 0.8593018 -0.5114689 1 0.8585162 -0.5127865 -1 0.8585162 -0.5127865 1 0.8577286 -0.5141028 -1 0.8577286 -0.5141028 1 0.856939 -0.5154179 -1 0.856939 -0.5154179 1 0.8561474 -0.5167318 -1 0.8561474 -0.5167318 1 0.8553537 -0.5180445 -1 0.8553537 -0.5180445 1 0.854558 -0.519356 -1 0.854558 -0.519356 1 0.8537603 -0.5206663 -1 0.8537603 -0.5206663 1 0.8529606 -0.5219753 -1 0.8529606 -0.5219753 1 0.8521589 -0.5232831 -1 0.8521589 -0.5232831 1 0.8513552 -0.5245897 -1 0.8513552 -0.5245897 1 0.8505495 -0.5258951 -1 0.8505495 -0.5258951 1 0.8497418 -0.5271992 -1 0.8497418 -0.5271992 1 0.848932 -0.5285021 -1 0.848932 -0.5285021 1 0.8481203 -0.5298036 -1 0.8481203 -0.5298036 1 0.8473066 -0.531104 -1 0.8473066 -0.531104 1 0.8464909 -0.5324032 -1 0.8464909 -0.5324032 1 0.8456733 -0.533701 -1 0.8456733 -0.533701 1 0.8448536 -0.5349976 -1 0.8448536 -0.5349976 1 0.8440319 -0.536293 -1 0.8440319 -0.536293 1 0.8432083 -0.5375871 -1 0.8432083 -0.5375871 1 0.8423826 -0.5388799 -1 0.8423826 -0.5388799 1 0.841555 -0.5401715 -1 0.841555 -0.5401715 1 0.8407254 -0.5414618 -1 0.8407254 -0.5414618 1 0.8398938 -0.5427508 -1 0.8398938 -0.5427508 1 0.8390603 -0.5440385 -1 0.8390603 -0.5440385 1 0.8382247 -0.545325 -1 0.8382247 -0.545325 1 0.8373872 -0.5466102 -1 0.8373872 -0.5466102 1 0.8365477 -0.5478941 -1 0.8365477 -0.5478941 1 0.8357062 -0.5491767 -1 0.8357062 -0.5491767 1 0.8348628 -0.550458 -1 0.8348628 -0.550458 1 0.8340175 -0.551738 -1 0.8340175 -0.551738 1 0.8331702 -0.5530167 -1 0.8331702 -0.5530167 1 0.8323209 -0.5542941 -1 0.8323209 -0.5542941 1 0.8314696 -0.5555703 -1 0.8314696 -0.5555703 1 0.8306164 -0.5568451 -1 0.8306164 -0.5568451 1 0.8297612 -0.5581185 -1 0.8297612 -0.5581185 1 0.8289041 -0.5593907 -1 0.8289041 -0.5593907 1 0.828045 -0.5606616 -1 0.828045 -0.5606616 1 0.827184 -0.5619311 -1 0.827184 -0.5619311 1 0.8263211 -0.5631994 -1 0.8263211 -0.5631994 1 0.8254562 -0.5644662 -1 0.8254562 -0.5644662 1 0.8245893 -0.5657318 -1 0.8245893 -0.5657318 1 0.8237205 -0.5669961 -1 0.8237205 -0.5669961 1 0.8228498 -0.568259 -1 0.8228498 -0.568259 1 0.8219771 -0.5695205 -1 0.8219771 -0.5695205 1 0.8211025 -0.5707808 -1 0.8211025 -0.5707808 1 0.820226 -0.5720396 -1 0.820226 -0.5720396 1 0.8193475 -0.5732972 -1 0.8193475 -0.5732972 1 0.8184671 -0.5745534 -1 0.8184671 -0.5745534 1 0.8175848 -0.5758082 -1 0.8175848 -0.5758082 1 0.8167006 -0.5770617 -1 0.8167006 -0.5770617 1 0.8158144 -0.5783138 -1 0.8158144 -0.5783138 1 0.8149263 -0.5795646 -1 0.8149263 -0.5795646 1 0.8140363 -0.580814 -1 0.8140363 -0.580814 1 0.8131444 -0.582062 -1 0.8131444 -0.582062 1 0.8122506 -0.5833087 -1 0.8122506 -0.5833087 1 0.8113548 -0.584554 -1 0.8113548 -0.584554 1 0.8104572 -0.5857979 -1 0.8104572 -0.5857979 1 0.8095577 -0.5870404 -1 0.8095577 -0.5870404 1 0.8086562 -0.5882816 -1 0.8086562 -0.5882816 1 0.8077529 -0.5895213 -1 0.8077529 -0.5895213 1 0.8068476 -0.5907597 -1 0.8068476 -0.5907597 1 0.8059404 -0.5919967 -1 0.8059404 -0.5919967 1 0.8050313 -0.5932323 -1 0.8050313 -0.5932323 1 0.8041204 -0.5944665 -1 0.8041204 -0.5944665 1 0.8032075 -0.5956993 -1 0.8032075 -0.5956993 1 0.8022928 -0.5969308 -1 0.8022928 -0.5969308 1 0.8013762 -0.5981608 -1 0.8013762 -0.5981608 1 0.8004577 -0.5993893 -1 0.8004577 -0.5993893 1 0.7995373 -0.6006165 -1 0.7995373 -0.6006165 1 0.798615 -0.6018423 -1 0.798615 -0.6018423 1 0.7976908 -0.6030666 -1 0.7976908 -0.6030666 1 0.7967648 -0.6042895 -1 0.7967648 -0.6042895 1 0.7958369 -0.605511 -1 0.7958369 -0.605511 1 0.7949072 -0.6067311 -1 0.7949072 -0.6067311 1 0.7939755 -0.6079498 -1 0.7939755 -0.6079498 1 0.793042 -0.609167 -1 0.793042 -0.609167 1 0.7921066 -0.6103828 -1 0.7921066 -0.6103828 1 0.7911694 -0.6115972 -1 0.7911694 -0.6115972 1 0.7902302 -0.6128101 -1 0.7902302 -0.6128101 1 0.7892892 -0.6140216 -1 0.7892892 -0.6140216 1 0.7883464 -0.6152316 -1 0.7883464 -0.6152316 1 0.7874017 -0.6164402 -1 0.7874017 -0.6164402 1 0.7864552 -0.6176474 -1 0.7864552 -0.6176474 1 0.7855068 -0.618853 -1 0.7855068 -0.618853 1 0.7845566 -0.6200572 -1 0.7845566 -0.6200572 1 0.7836045 -0.62126 -1 0.7836045 -0.62126 1 0.7826506 -0.6224613 -1 0.7826506 -0.6224613 1 0.7816948 -0.6236611 -1 0.7816948 -0.6236611 1 0.7807372 -0.6248595 -1 0.7807372 -0.6248595 1 0.7797778 -0.6260564 -1 0.7797778 -0.6260564 1 0.7788165 -0.6272518 -1 0.7788165 -0.6272518 1 0.7778534 -0.6284458 -1 0.7778534 -0.6284458 1 0.7768884 -0.6296383 -1 0.7768884 -0.6296383 1 0.7759217 -0.6308293 -1 0.7759217 -0.6308293 1 0.7749531 -0.6320188 -1 0.7749531 -0.6320188 1 0.7739827 -0.6332068 -1 0.7739827 -0.6332068 1 0.7730104 -0.6343933 -1 0.7730104 -0.6343933 1 0.7720364 -0.6355783 -1 0.7720364 -0.6355783 1 0.7710605 -0.6367619 -1 0.7710605 -0.6367619 1 0.7700828 -0.6379439 -1 0.7700828 -0.6379439 1 0.7691034 -0.6391245 -1 0.7691034 -0.6391245 1 0.768122 -0.6403035 -1 0.768122 -0.6403035 1 0.7671389 -0.6414811 -1 0.7671389 -0.6414811 1 0.766154 -0.6426571 -1 0.766154 -0.6426571 1 0.7651672 -0.6438316 -1 0.7651672 -0.6438316 1 0.7641788 -0.6450046 -1 0.7641788 -0.6450046 1 0.7631884 -0.646176 -1 0.7631884 -0.646176 1 0.7621963 -0.647346 -1 0.7621963 -0.647346 1 0.7612023 -0.6485145 -1 0.7612023 -0.6485145 1 0.7602066 -0.6496813 -1 0.7602066 -0.6496813 1 0.7592092 -0.6508467 -1 0.7592092 -0.6508467 1 0.7582099 -0.6520106 -1 0.7582099 -0.6520106 1 0.7572088 -0.6531729 -1 0.7572088 -0.6531729 1 0.756206 -0.6543336 -1 0.756206 -0.6543336 1 0.7552014 -0.6554929 -1 0.7552014 -0.6554929 1 0.754195 -0.6566506 -1 0.754195 -0.6566506 1 0.7531868 -0.6578067 -1 0.7531868 -0.6578067 1 0.7521768 -0.6589613 -1 0.7521768 -0.6589613 1 0.7511651 -0.6601144 -1 0.7511651 -0.6601144 1 0.7501516 -0.6612659 -1 0.7501516 -0.6612659 1 0.7491364 -0.6624158 -1 0.7491364 -0.6624158 1 0.7481194 -0.6635642 -1 0.7481194 -0.6635642 1 0.7471006 -0.664711 -1 0.7471006 -0.664711 1 0.7460801 -0.6658563 -1 0.7460801 -0.6658563 1 0.7450578 -0.6669999 -1 0.7450578 -0.6669999 1 0.7440337 -0.6681421 -1 0.7440337 -0.6681421 1 0.743008 -0.6692826 -1 0.743008 -0.6692826 1 0.7419804 -0.6704216 -1 0.7419804 -0.6704216 1 0.7409511 -0.671559 -1 0.7409511 -0.671559 1 0.7399201 -0.6726948 -1 0.7399201 -0.6726948 1 0.7388873 -0.673829 -1 0.7388873 -0.673829 1 0.7378528 -0.6749617 -1 0.7378528 -0.6749617 1 0.7368166 -0.6760928 -1 0.7368166 -0.6760928 1 0.7357786 -0.6772222 -1 0.7357786 -0.6772222 1 0.7347389 -0.6783501 -1 0.7347389 -0.6783501 1 0.7336974 -0.6794763 -1 0.7336974 -0.6794763 1 0.7326543 -0.680601 -1 0.7326543 -0.680601 1 0.7316094 -0.6817241 -1 0.7316094 -0.6817241 1 0.7305628 -0.6828456 -1 0.7305628 -0.6828456 1 0.7295144 -0.6839655 -1 0.7295144 -0.6839655 1 0.7284644 -0.6850837 -1 0.7284644 -0.6850837 1 0.7274127 -0.6862003 -1 0.7274127 -0.6862003 1 0.7263591 -0.6873154 -1 0.7263591 -0.6873154 1 0.725304 -0.6884288 -1 0.725304 -0.6884288 1 0.7242471 -0.6895406 -1 0.7242471 -0.6895406 1 0.7231885 -0.6906507 -1 0.7231885 -0.6906507 1 0.7221282 -0.6917593 -1 0.7221282 -0.6917593 1 0.7210662 -0.6928662 -1 0.7210662 -0.6928662 1 0.7200025 -0.6939715 -1 0.7200025 -0.6939715 1 0.7189371 -0.6950752 -1 0.7189371 -0.6950752 1 0.71787 -0.6961772 -1 0.71787 -0.6961772 1 0.7168012 -0.6972776 -1 0.7168012 -0.6972776 1 0.7157308 -0.6983763 -1 0.7157308 -0.6983763 1 0.7146587 -0.6994734 -1 0.7146587 -0.6994734 1 0.7135849 -0.7005688 -1 0.7135849 -0.7005688 1 0.7125094 -0.7016626 -1 0.7125094 -0.7016626 1 0.7114322 -0.7027547 -1 0.7114322 -0.7027547 1 0.7103533 -0.7038453 -1 0.7103533 -0.7038453 1 0.7092728 -0.7049341 -1 0.7092728 -0.7049341 1 0.7081906 -0.7060213 -1 0.7081906 -0.7060213 1 0.7071068 -0.7071068 -1 0.7071068 -0.7071068 1 0.7060213 -0.7081906 -1 0.7060213 -0.7081906 1 0.7049341 -0.7092728 -1 0.7049341 -0.7092728 1 0.7038453 -0.7103533 -1 0.7038453 -0.7103533 1 0.7027547 -0.7114322 -1 0.7027547 -0.7114322 1 0.7016626 -0.7125094 -1 0.7016626 -0.7125094 1 0.7005688 -0.7135849 -1 0.7005688 -0.7135849 1 0.6994734 -0.7146587 -1 0.6994734 -0.7146587 1 0.6983763 -0.7157308 -1 0.6983763 -0.7157308 1 0.6972776 -0.7168012 -1 0.6972776 -0.7168012 1 0.6961772 -0.71787 -1 0.6961772 -0.71787 1 0.6950752 -0.7189371 -1 0.6950752 -0.7189371 1 0.6939715 -0.7200025 -1 0.6939715 -0.7200025 1 0.6928662 -0.7210662 -1 0.6928662 -0.7210662 1 0.6917593 -0.7221282 -1 0.6917593 -0.7221282 1 0.6906507 -0.7231885 -1 0.6906507 -0.7231885 1 0.6895406 -0.7242471 -1 0.6895406 -0.7242471 1 0.6884288 -0.725304 -1 0.6884288 -0.725304 1 0.6873154 -0.7263591 -1 0.6873154 -0.7263591 1 0.6862003 -0.7274127 -1 0.6862003 -0.7274127 1 0.6850837 -0.7284644 -1 0.6850837 -0.7284644 1 0.6839655 -0.7295144 -1 0.6839655 -0.7295144 1 0.6828456 -0.7305628 -1 0.6828456 -0.7305628 1 0.6817241 -0.7316094 -1 0.6817241 -0.7316094 1 0.680601 -0.7326543 -1 0.680601 -0.7326543 1 0.6794763 -0.7336974 -1 0.6794763 -0.7336974 1 0.6783501 -0.7347389 -1 0.6783501 -0.7347389 1 0.6772222 -0.7357786 -1 0.6772222 -0.7357786 1 0.6760928 -0.7368166 -1 0.6760928 -0.7368166 1 0.6749617 -0.7378528 -1 0.6749617 -0.7378528 1 0.673829 -0.7388873 -1 0.673829 -0.7388873 1 0.6726948 -0.7399201 -1 0.6726948 -0.7399201 1 0.671559 -0.7409511 -1 0.671559 -0.7409511 1 0.6704216 -0.7419804 -1 0.6704216 -0.7419804 1 0.6692826 -0.743008 -1 0.6692826 -0.743008 1 0.6681421 -0.7440337 -1 0.6681421 -0.7440337 1 0.6669999 -0.7450578 -1 0.6669999 -0.7450578 1 0.6658563 -0.7460801 -1 0.6658563 -0.7460801 1 0.664711 -0.7471006 -1 0.664711 -0.7471006 1 0.6635642 -0.7481194 -1 0.6635642 -0.7481194 1 0.6624158 -0.7491364 -1 0.6624158 -0.7491364 1 0.6612659 -0.7501516 -1 0.6612659 -0.7501516 1 0.6601144 -0.7511651 -1 0.6601144 -0.7511651 1 0.6589613 -0.7521768 -1 0.6589613 -0.7521768 1 0.6578067 -0.7531868 -1 0.6578067 -0.7531868 1 0.6566506 -0.754195 -1 0.6566506 -0.754195 1 0.6554929 -0.7552014 -1 0.6554929 -0.7552014 1 0.6543336 -0.756206 -1 0.6543336 -0.756206 1 0.6531729 -0.7572088 -1 0.6531729 -0.7572088 1 0.6520106 -0.7582099 -1 0.6520106 -0.7582099 1 0.6508467 -0.7592092 -1 0.6508467 -0.7592092 1 0.6496813 -0.7602066 -1 0.6496813 -0.7602066 1 0.6485145 -0.7612023 -1 0.6485145 -0.7612023 1 0.647346 -0.7621963 -1 0.647346 -0.7621963 1 0.646176 -0.7631884 -1 0.646176 -0.7631884 1 0.6450046 -0.7641788 -1 0.6450046 -0.7641788 1 0.6438316 -0.7651672 -1 0.6438316 -0.7651672 1 0.6426571 -0.766154 -1 0.6426571 -0.766154 1 0.6414811 -0.7671389 -1 0.6414811 -0.7671389 1 0.6403035 -0.768122 -1 0.6403035 -0.768122 1 0.6391245 -0.7691034 -1 0.6391245 -0.7691034 1 0.6379439 -0.7700828 -1 0.6379439 -0.7700828 1 0.6367619 -0.7710605 -1 0.6367619 -0.7710605 1 0.6355783 -0.7720364 -1 0.6355783 -0.7720364 1 0.6343933 -0.7730104 -1 0.6343933 -0.7730104 1 0.6332068 -0.7739827 -1 0.6332068 -0.7739827 1 0.6320188 -0.7749531 -1 0.6320188 -0.7749531 1 0.6308293 -0.7759217 -1 0.6308293 -0.7759217 1 0.6296383 -0.7768884 -1 0.6296383 -0.7768884 1 0.6284458 -0.7778534 -1 0.6284458 -0.7778534 1 0.6272518 -0.7788165 -1 0.6272518 -0.7788165 1 0.6260564 -0.7797778 -1 0.6260564 -0.7797778 1 0.6248595 -0.7807372 -1 0.6248595 -0.7807372 1 0.6236611 -0.7816948 -1 0.6236611 -0.7816948 1 0.6224613 -0.7826506 -1 0.6224613 -0.7826506 1 0.62126 -0.7836045 -1 0.62126 -0.7836045 1 0.6200572 -0.7845566 -1 0.6200572 -0.7845566 1 0.618853 -0.7855068 -1 0.618853 -0.7855068 1 0.6176474 -0.7864552 -1 0.6176474 -0.7864552 1 0.6164402 -0.7874017 -1 0.6164402 -0.7874017 1 0.6152316 -0.7883464 -1 0.6152316 -0.7883464 1 0.6140216 -0.7892892 -1 0.6140216 -0.7892892 1 0.6128101 -0.7902302 -1 0.6128101 -0.7902302 1 0.6115972 -0.7911694 -1 0.6115972 -0.7911694 1 0.6103828 -0.7921066 -1 0.6103828 -0.7921066 1 0.609167 -0.793042 -1 0.609167 -0.793042 1 0.6079498 -0.7939755 -1 0.6079498 -0.7939755 1 0.6067311 -0.7949072 -1 0.6067311 -0.7949072 1 0.605511 -0.7958369 -1 0.605511 -0.7958369 1 0.6042895 -0.7967648 -1 0.6042895 -0.7967648 1 0.6030666 -0.7976908 -1 0.6030666 -0.7976908 1 0.6018423 -0.798615 -1 0.6018423 -0.798615 1 0.6006165 -0.7995373 -1 0.6006165 -0.7995373 1 0.5993893 -0.8004577 -1 0.5993893 -0.8004577 1 0.5981608 -0.8013762 -1 0.5981608 -0.8013762 1 0.5969308 -0.8022928 -1 0.5969308 -0.8022928 1 0.5956993 -0.8032075 -1 0.5956993 -0.8032075 1 0.5944665 -0.8041204 -1 0.5944665 -0.8041204 1 0.5932323 -0.8050313 -1 0.5932323 -0.8050313 1 0.5919967 -0.8059404 -1 0.5919967 -0.8059404 1 0.5907597 -0.8068476 -1 0.5907597 -0.8068476 1 0.5895213 -0.8077529 -1 0.5895213 -0.8077529 1 0.5882816 -0.8086562 -1 0.5882816 -0.8086562 1 0.5870404 -0.8095577 -1 0.5870404 -0.8095577 1 0.5857979 -0.8104572 -1 0.5857979 -0.8104572 1 0.584554 -0.8113548 -1 0.584554 -0.8113548 1 0.5833087 -0.8122506 -1 0.5833087 -0.8122506 1 0.582062 -0.8131444 -1 0.582062 -0.8131444 1 0.580814 -0.8140363 -1 0.580814 -0.8140363 1 0.5795646 -0.8149263 -1 0.5795646 -0.8149263 1 0.5783138 -0.8158144 -1 0.5783138 -0.8158144 1 0.5770617 -0.8167006 -1 0.5770617 -0.8167006 1 0.5758082 -0.8175848 -1 0.5758082 -0.8175848 1 0.5745534 -0.8184671 -1 0.5745534 -0.8184671 1 0.5732972 -0.8193475 -1 0.5732972 -0.8193475 1 0.5720396 -0.820226 -1 0.5720396 -0.820226 1 0.5707808 -0.8211025 -1 0.5707808 -0.8211025 1 0.5695205 -0.8219771 -1 0.5695205 -0.8219771 1 0.568259 -0.8228498 -1 0.568259 -0.8228498 1 0.5669961 -0.8237205 -1 0.5669961 -0.8237205 1 0.5657318 -0.8245893 -1 0.5657318 -0.8245893 1 0.5644662 -0.8254562 -1 0.5644662 -0.8254562 1 0.5631994 -0.8263211 -1 0.5631994 -0.8263211 1 0.5619311 -0.827184 -1 0.5619311 -0.827184 1 0.5606616 -0.828045 -1 0.5606616 -0.828045 1 0.5593907 -0.8289041 -1 0.5593907 -0.8289041 1 0.5581185 -0.8297612 -1 0.5581185 -0.8297612 1 0.5568451 -0.8306164 -1 0.5568451 -0.8306164 1 0.5555703 -0.8314696 -1 0.5555703 -0.8314696 1 0.5542941 -0.8323209 -1 0.5542941 -0.8323209 1 0.5530167 -0.8331702 -1 0.5530167 -0.8331702 1 0.551738 -0.8340175 -1 0.551738 -0.8340175 1 0.550458 -0.8348628 -1 0.550458 -0.8348628 1 0.5491767 -0.8357062 -1 0.5491767 -0.8357062 1 0.5478941 -0.8365477 -1 0.5478941 -0.8365477 1 0.5466102 -0.8373872 -1 0.5466102 -0.8373872 1 0.545325 -0.8382247 -1 0.545325 -0.8382247 1 0.5440385 -0.8390603 -1 0.5440385 -0.8390603 1 0.5427508 -0.8398938 -1 0.5427508 -0.8398938 1 0.5414618 -0.8407254 -1 0.5414618 -0.8407254 1 0.5401715 -0.841555 -1 0.5401715 -0.841555 1 0.5388799 -0.8423826 -1 0.5388799 -0.8423826 1 0.5375871 -0.8432083 -1 0.5375871 -0.8432083 1 0.536293 -0.8440319 -1 0.536293 -0.8440319 1 0.5349976 -0.8448536 -1 0.5349976 -0.8448536 1 0.533701 -0.8456733 -1 0.533701 -0.8456733 1 0.5324032 -0.8464909 -1 0.5324032 -0.8464909 1 0.531104 -0.8473066 -1 0.531104 -0.8473066 1 0.5298036 -0.8481203 -1 0.5298036 -0.8481203 1 0.5285021 -0.848932 -1 0.5285021 -0.848932 1 0.5271992 -0.8497418 -1 0.5271992 -0.8497418 1 0.5258951 -0.8505495 -1 0.5258951 -0.8505495 1 0.5245897 -0.8513552 -1 0.5245897 -0.8513552 1 0.5232831 -0.8521589 -1 0.5232831 -0.8521589 1 0.5219753 -0.8529606 -1 0.5219753 -0.8529606 1 0.5206663 -0.8537603 -1 0.5206663 -0.8537603 1 0.519356 -0.854558 -1 0.519356 -0.854558 1 0.5180445 -0.8553537 -1 0.5180445 -0.8553537 1 0.5167318 -0.8561474 -1 0.5167318 -0.8561474 1 0.5154179 -0.856939 -1 0.5154179 -0.856939 1 0.5141028 -0.8577286 -1 0.5141028 -0.8577286 1 0.5127865 -0.8585162 -1 0.5127865 -0.8585162 1 0.5114689 -0.8593018 -1 0.5114689 -0.8593018 1 0.5101501 -0.8600854 -1 0.5101501 -0.8600854 1 0.5088302 -0.8608669 -1 0.5088302 -0.8608669 1 0.507509 -0.8616465 -1 0.507509 -0.8616465 1 0.5061867 -0.862424 -1 0.5061867 -0.862424 1 0.5048632 -0.8631994 -1 0.5048632 -0.8631994 1 0.5035384 -0.8639729 -1 0.5035384 -0.8639729 1 0.5022125 -0.8647443 -1 0.5022125 -0.8647443 1 0.5008854 -0.8655136 -1 0.5008854 -0.8655136 1 0.4995571 -0.866281 -1 0.4995571 -0.866281 1 0.4982277 -0.8670462 -1 0.4982277 -0.8670462 1 0.4968971 -0.8678095 -1 0.4968971 -0.8678095 1 0.4955653 -0.8685707 -1 0.4955653 -0.8685707 1 0.4942323 -0.8693299 -1 0.4942323 -0.8693299 1 0.4928982 -0.870087 -1 0.4928982 -0.870087 1 0.4915629 -0.870842 -1 0.4915629 -0.870842 1 0.4902265 -0.8715951 -1 0.4902265 -0.8715951 1 0.4888889 -0.8723461 -1 0.4888889 -0.8723461 1 0.4875501 -0.873095 -1 0.4875501 -0.873095 1 0.4862103 -0.8738418 -1 0.4862103 -0.8738418 1 0.4848693 -0.8745867 -1 0.4848693 -0.8745867 1 0.4835271 -0.8753294 -1 0.4835271 -0.8753294 1 0.4821838 -0.8760701 -1 0.4821838 -0.8760701 1 0.4808393 -0.8768087 -1 0.4808393 -0.8768087 1 0.4794937 -0.8775453 -1 0.4794937 -0.8775453 1 0.478147 -0.8782798 -1 0.478147 -0.8782798 1 0.4767993 -0.8790122 -1 0.4767993 -0.8790122 1 0.4754503 -0.8797426 -1 0.4754503 -0.8797426 1 0.4741002 -0.8804709 -1 0.4741002 -0.8804709 1 0.4727491 -0.8811971 -1 0.4727491 -0.8811971 1 0.4713968 -0.8819212 -1 0.4713968 -0.8819212 1 0.4700433 -0.8826434 -1 0.4700433 -0.8826434 1 0.4686889 -0.8833633 -1 0.4686889 -0.8833633 1 0.4673332 -0.8840813 -1 0.4673332 -0.8840813 1 0.4659765 -0.8847971 -1 0.4659765 -0.8847971 1 0.4646187 -0.8855109 -1 0.4646187 -0.8855109 1 0.4632598 -0.8862226 -1 0.4632598 -0.8862226 1 0.4618998 -0.8869321 -1 0.4618998 -0.8869321 1 0.4605387 -0.8876397 -1 0.4605387 -0.8876397 1 0.4591765 -0.888345 -1 0.4591765 -0.888345 1 0.4578133 -0.8890483 -1 0.4578133 -0.8890483 1 0.456449 -0.8897496 -1 0.456449 -0.8897496 1 0.4550836 -0.8904488 -1 0.4550836 -0.8904488 1 0.4537171 -0.8911458 -1 0.4537171 -0.8911458 1 0.4523496 -0.8918407 -1 0.4523496 -0.8918407 1 0.450981 -0.8925336 -1 0.450981 -0.8925336 1 0.4496113 -0.8932243 -1 0.4496113 -0.8932243 1 0.4482406 -0.893913 -1 0.4482406 -0.893913 1 0.4468688 -0.8945995 -1 0.4468688 -0.8945995 1 0.445496 -0.8952839 -1 0.445496 -0.8952839 1 0.4441221 -0.8959662 -1 0.4441221 -0.8959662 1 0.4427472 -0.8966464 -1 0.4427472 -0.8966464 1 0.4413713 -0.8973246 -1 0.4413713 -0.8973246 1 0.4399943 -0.8980006 -1 0.4399943 -0.8980006 1 0.4386162 -0.8986745 -1 0.4386162 -0.8986745 1 0.4372372 -0.8993462 -1 0.4372372 -0.8993462 1 0.4358571 -0.9000159 -1 0.4358571 -0.9000159 1 0.434476 -0.9006834 -1 0.434476 -0.9006834 1 0.4330939 -0.9013488 -1 0.4330939 -0.9013488 1 0.4317107 -0.9020121 -1 0.4317107 -0.9020121 1 0.4303265 -0.9026733 -1 0.4303265 -0.9026733 1 0.4289413 -0.9033324 -1 0.4289413 -0.9033324 1 0.4275551 -0.9039893 -1 0.4275551 -0.9039893 1 0.4261679 -0.9046441 -1 0.4261679 -0.9046441 1 0.4247797 -0.9052968 -1 0.4247797 -0.9052968 1 0.4233905 -0.9059473 -1 0.4233905 -0.9059473 1 0.4220003 -0.9065957 -1 0.4220003 -0.9065957 1 0.4206091 -0.907242 -1 0.4206091 -0.907242 1 0.4192169 -0.9078861 -1 0.4192169 -0.9078861 1 0.4178237 -0.9085281 -1 0.4178237 -0.9085281 1 0.4164296 -0.909168 -1 0.4164296 -0.909168 1 0.4150344 -0.9098057 -1 0.4150344 -0.9098057 1 0.4136383 -0.9104413 -1 0.4136383 -0.9104413 1 0.4122412 -0.9110748 -1 0.4122412 -0.9110748 1 0.4108432 -0.911706 -1 0.4108432 -0.911706 1 0.4094442 -0.9123352 -1 0.4094442 -0.9123352 1 0.4080442 -0.9129622 -1 0.4080442 -0.9129622 1 0.4066432 -0.913587 -1 0.4066432 -0.913587 1 0.4052413 -0.9142097 -1 0.4052413 -0.9142097 1 0.4038385 -0.9148303 -1 0.4038385 -0.9148303 1 0.4024347 -0.9154487 -1 0.4024347 -0.9154487 1 0.4010299 -0.916065 -1 0.4010299 -0.916065 1 0.3996242 -0.9166791 -1 0.3996242 -0.9166791 1 0.3982176 -0.917291 -1 0.3982176 -0.917291 1 0.39681 -0.9179008 -1 0.39681 -0.9179008 1 0.3954015 -0.9185084 -1 0.3954015 -0.9185084 1 0.3939921 -0.9191139 -1 0.3939921 -0.9191139 1 0.3925817 -0.9197171 -1 0.3925817 -0.9197171 1 0.3911704 -0.9203183 -1 0.3911704 -0.9203183 1 0.3897582 -0.9209172 -1 0.3897582 -0.9209172 1 0.388345 -0.921514 -1 0.388345 -0.921514 1 0.386931 -0.9221087 -1 0.386931 -0.9221087 1 0.3855161 -0.9227011 -1 0.3855161 -0.9227011 1 0.3841002 -0.9232914 -1 0.3841002 -0.9232914 1 0.3826835 -0.9238795 -1 0.3826835 -0.9238795 1 0.3812658 -0.9244655 -1 0.3812658 -0.9244655 1 0.3798472 -0.9250493 -1 0.3798472 -0.9250493 1 0.3784278 -0.9256308 -1 0.3784278 -0.9256308 1 0.3770074 -0.9262102 -1 0.3770074 -0.9262102 1 0.3755862 -0.9267875 -1 0.3755862 -0.9267875 1 0.3741641 -0.9273625 -1 0.3741641 -0.9273625 1 0.3727411 -0.9279354 -1 0.3727411 -0.9279354 1 0.3713172 -0.9285061 -1 0.3713172 -0.9285061 1 0.3698924 -0.9290746 -1 0.3698924 -0.9290746 1 0.3684668 -0.9296409 -1 0.3684668 -0.9296409 1 0.3670403 -0.930205 -1 0.3670403 -0.930205 1 0.365613 -0.9307669 -1 0.365613 -0.9307669 1 0.3641848 -0.9313267 -1 0.3641848 -0.9313267 1 0.3627557 -0.9318843 -1 0.3627557 -0.9318843 1 0.3613258 -0.9324396 -1 0.3613258 -0.9324396 1 0.3598951 -0.9329928 -1 0.3598951 -0.9329928 1 0.3584634 -0.9335438 -1 0.3584634 -0.9335438 1 0.357031 -0.9340925 -1 0.357031 -0.9340925 1 0.3555977 -0.9346391 -1 0.3555977 -0.9346391 1 0.3541635 -0.9351835 -1 0.3541635 -0.9351835 1 0.3527286 -0.9357257 -1 0.3527286 -0.9357257 1 0.3512927 -0.9362657 -1 0.3512927 -0.9362657 1 0.3498561 -0.9368035 -1 0.3498561 -0.9368035 1 0.3484187 -0.937339 -1 0.3484187 -0.937339 1 0.3469804 -0.9378724 -1 0.3469804 -0.9378724 1 0.3455413 -0.9384036 -1 0.3455413 -0.9384036 1 0.3441014 -0.9389325 -1 0.3441014 -0.9389325 1 0.3426607 -0.9394592 -1 0.3426607 -0.9394592 1 0.3412192 -0.9399837 -1 0.3412192 -0.9399837 1 0.3397769 -0.9405061 -1 0.3397769 -0.9405061 1 0.3383337 -0.9410262 -1 0.3383337 -0.9410262 1 0.3368899 -0.9415441 -1 0.3368899 -0.9415441 1 0.3354452 -0.9420598 -1 0.3354452 -0.9420598 1 0.3339996 -0.9425732 -1 0.3339996 -0.9425732 1 0.3325534 -0.9430844 -1 0.3325534 -0.9430844 1 0.3311063 -0.9435935 -1 0.3311063 -0.9435935 1 0.3296585 -0.9441003 -1 0.3296585 -0.9441003 1 0.3282098 -0.9446048 -1 0.3282098 -0.9446048 1 0.3267605 -0.9451072 -1 0.3267605 -0.9451072 1 0.3253103 -0.9456073 -1 0.3253103 -0.9456073 1 0.3238593 -0.9461053 -1 0.3238593 -0.9461053 1 0.3224077 -0.9466009 -1 0.3224077 -0.9466009 1 0.3209552 -0.9470944 -1 0.3209552 -0.9470944 1 0.319502 -0.9475856 -1 0.319502 -0.9475856 1 0.3180481 -0.9480746 -1 0.3180481 -0.9480746 1 0.3165934 -0.9485614 -1 0.3165934 -0.9485614 1 0.3151379 -0.9490459 -1 0.3151379 -0.9490459 1 0.3136817 -0.9495282 -1 0.3136817 -0.9495282 1 0.3122248 -0.9500082 -1 0.3122248 -0.9500082 1 0.3107671 -0.9504861 -1 0.3107671 -0.9504861 1 0.3093088 -0.9509617 -1 0.3093088 -0.9509617 1 0.3078497 -0.951435 -1 0.3078497 -0.951435 1 0.3063898 -0.9519062 -1 0.3063898 -0.9519062 1 0.3049293 -0.952375 -1 0.3049293 -0.952375 1 0.3034679 -0.9528416 -1 0.3034679 -0.9528416 1 0.302006 -0.953306 -1 0.302006 -0.953306 1 0.3005433 -0.9537682 -1 0.3005433 -0.9537682 1 0.2990798 -0.9542281 -1 0.2990798 -0.9542281 1 0.2976157 -0.9546858 -1 0.2976157 -0.9546858 1 0.2961509 -0.9551412 -1 0.2961509 -0.9551412 1 0.2946854 -0.9555943 -1 0.2946854 -0.9555943 1 0.2932192 -0.9560453 -1 0.2932192 -0.9560453 1 0.2917523 -0.9564939 -1 0.2917523 -0.9564939 1 0.2902847 -0.9569404 -1 0.2902847 -0.9569404 1 0.2888164 -0.9573845 -1 0.2888164 -0.9573845 1 0.2873475 -0.9578264 -1 0.2873475 -0.9578264 1 0.2858778 -0.9582661 -1 0.2858778 -0.9582661 1 0.2844076 -0.9587035 -1 0.2844076 -0.9587035 1 0.2829366 -0.9591386 -1 0.2829366 -0.9591386 1 0.2814649 -0.9595715 -1 0.2814649 -0.9595715 1 0.2799926 -0.9600021 -1 0.2799926 -0.9600021 1 0.2785197 -0.9604305 -1 0.2785197 -0.9604305 1 0.2770461 -0.9608566 -1 0.2770461 -0.9608566 1 0.2755718 -0.9612805 -1 0.2755718 -0.9612805 1 0.2740969 -0.9617021 -1 0.2740969 -0.9617021 1 0.2726213 -0.9621214 -1 0.2726213 -0.9621214 1 0.2711452 -0.9625385 -1 0.2711452 -0.9625385 1 0.2696684 -0.9629533 -1 0.2696684 -0.9629533 1 0.2681909 -0.9633658 -1 0.2681909 -0.9633658 1 0.2667128 -0.9637761 -1 0.2667128 -0.9637761 1 0.2652341 -0.9641841 -1 0.2652341 -0.9641841 1 0.2637547 -0.9645898 -1 0.2637547 -0.9645898 1 0.2622747 -0.9649932 -1 0.2622747 -0.9649932 1 0.2607941 -0.9653944 -1 0.2607941 -0.9653944 1 0.2593129 -0.9657934 -1 0.2593129 -0.9657934 1 0.2578311 -0.96619 -1 0.2578311 -0.96619 1 0.2563487 -0.9665844 -1 0.2563487 -0.9665844 1 0.2548657 -0.9669765 -1 0.2548657 -0.9669765 1 0.253382 -0.9673663 -1 0.253382 -0.9673663 1 0.2518978 -0.9677538 -1 0.2518978 -0.9677538 1 0.250413 -0.9681391 -1 0.250413 -0.9681391 1 0.2489276 -0.9685221 -1 0.2489276 -0.9685221 1 0.2474416 -0.9689028 -1 0.2474416 -0.9689028 1 0.245955 -0.9692813 -1 0.245955 -0.9692813 1 0.2444679 -0.9696574 -1 0.2444679 -0.9696574 1 0.2429802 -0.9700313 -1 0.2429802 -0.9700313 1 0.2414919 -0.9704028 -1 0.2414919 -0.9704028 1 0.240003 -0.9707722 -1 0.240003 -0.9707722 1 0.2385136 -0.9711391 -1 0.2385136 -0.9711391 1 0.2370236 -0.9715039 -1 0.2370236 -0.9715039 1 0.235533 -0.9718663 -1 0.235533 -0.9718663 1 0.2340419 -0.9722265 -1 0.2340419 -0.9722265 1 0.2325503 -0.9725844 -1 0.2325503 -0.9725844 1 0.2310581 -0.97294 -1 0.2310581 -0.97294 1 0.2295653 -0.9732933 -1 0.2295653 -0.9732933 1 0.2280721 -0.9736443 -1 0.2280721 -0.9736443 1 0.2265782 -0.973993 -1 0.2265782 -0.973993 1 0.2250839 -0.9743394 -1 0.2250839 -0.9743394 1 0.223589 -0.9746835 -1 0.223589 -0.9746835 1 0.2220936 -0.9750254 -1 0.2220936 -0.9750254 1 0.2205977 -0.9753649 -1 0.2205977 -0.9753649 1 0.2191012 -0.9757021 -1 0.2191012 -0.9757021 1 0.2176042 -0.9760371 -1 0.2176042 -0.9760371 1 0.2161068 -0.9763697 -1 0.2161068 -0.9763697 1 0.2146088 -0.9767001 -1 0.2146088 -0.9767001 1 0.2131103 -0.9770281 -1 0.2131103 -0.9770281 1 0.2116113 -0.9773539 -1 0.2116113 -0.9773539 1 0.2101118 -0.9776774 -1 0.2101118 -0.9776774 1 0.2086118 -0.9779985 -1 0.2086118 -0.9779985 1 0.2071114 -0.9783174 -1 0.2071114 -0.9783174 1 0.2056104 -0.9786339 -1 0.2056104 -0.9786339 1 0.204109 -0.9789482 -1 0.204109 -0.9789482 1 0.202607 -0.9792602 -1 0.202607 -0.9792602 1 0.2011046 -0.9795698 -1 0.2011046 -0.9795698 1 0.1996017 -0.9798771 -1 0.1996017 -0.9798771 1 0.1980984 -0.9801821 -1 0.1980984 -0.9801821 1 0.1965946 -0.9804849 -1 0.1965946 -0.9804849 1 0.1950903 -0.9807853 -1 0.1950903 -0.9807853 1 0.1935856 -0.9810834 -1 0.1935856 -0.9810834 1 0.1920804 -0.9813792 -1 0.1920804 -0.9813792 1 0.1905747 -0.9816727 -1 0.1905747 -0.9816727 1 0.1890686 -0.9819639 -1 0.1890686 -0.9819639 1 0.1875621 -0.9822527 -1 0.1875621 -0.9822527 1 0.1860551 -0.9825393 -1 0.1860551 -0.9825393 1 0.1845477 -0.9828236 -1 0.1845477 -0.9828236 1 0.1830399 -0.9831055 -1 0.1830399 -0.9831055 1 0.1815316 -0.9833851 -1 0.1815316 -0.9833851 1 0.1800229 -0.9836624 -1 0.1800229 -0.9836624 1 0.1785138 -0.9839375 -1 0.1785138 -0.9839375 1 0.1770042 -0.9842101 -1 0.1770042 -0.9842101 1 0.1754943 -0.9844805 -1 0.1754943 -0.9844805 1 0.1739838 -0.9847485 -1 0.1739838 -0.9847485 1 0.1724731 -0.9850143 -1 0.1724731 -0.9850143 1 0.1709619 -0.9852777 -1 0.1709619 -0.9852777 1 0.1694503 -0.9855387 -1 0.1694503 -0.9855387 1 0.1679382 -0.9857975 -1 0.1679382 -0.9857975 1 0.1664259 -0.986054 -1 0.1664259 -0.986054 1 0.1649131 -0.9863081 -1 0.1649131 -0.9863081 1 0.1633999 -0.9865599 -1 0.1633999 -0.9865599 1 0.1618863 -0.9868094 -1 0.1618863 -0.9868094 1 0.1603724 -0.9870566 -1 0.1603724 -0.9870566 1 0.1588581 -0.9873014 -1 0.1588581 -0.9873014 1 0.1573435 -0.987544 -1 0.1573435 -0.987544 1 0.1558284 -0.9877842 -1 0.1558284 -0.9877842 1 0.154313 -0.988022 -1 0.154313 -0.988022 1 0.1527972 -0.9882576 -1 0.1527972 -0.9882576 1 0.151281 -0.9884908 -1 0.151281 -0.9884908 1 0.1497645 -0.9887217 -1 0.1497645 -0.9887217 1 0.1482477 -0.9889503 -1 0.1482477 -0.9889503 1 0.1467304 -0.9891765 -1 0.1467304 -0.9891765 1 0.1452129 -0.9894005 -1 0.1452129 -0.9894005 1 0.143695 -0.989622 -1 0.143695 -0.989622 1 0.1421768 -0.9898413 -1 0.1421768 -0.9898413 1 0.1406582 -0.9900582 -1 0.1406582 -0.9900582 1 0.1391393 -0.9902728 -1 0.1391393 -0.9902728 1 0.1376201 -0.9904851 -1 0.1376201 -0.9904851 1 0.1361005 -0.990695 -1 0.1361005 -0.990695 1 0.1345807 -0.9909027 -1 0.1345807 -0.9909027 1 0.1330605 -0.991108 -1 0.1330605 -0.991108 1 0.13154 -0.9913108 -1 0.13154 -0.9913108 1 0.1300192 -0.9915115 -1 0.1300192 -0.9915115 1 0.1284981 -0.9917098 -1 0.1284981 -0.9917098 1 0.1269767 -0.9919057 -1 0.1269767 -0.9919057 1 0.125455 -0.9920993 -1 0.125455 -0.9920993 1 0.123933 -0.9922906 -1 0.123933 -0.9922906 1 0.1224107 -0.9924796 -1 0.1224107 -0.9924796 1 0.1208881 -0.9926661 -1 0.1208881 -0.9926661 1 0.1193652 -0.9928504 -1 0.1193652 -0.9928504 1 0.117842 -0.9930323 -1 0.117842 -0.9930323 1 0.1163186 -0.9932119 -1 0.1163186 -0.9932119 1 0.1147949 -0.9933892 -1 0.1147949 -0.9933892 1 0.1132709 -0.9935641 -1 0.1132709 -0.9935641 1 0.1117467 -0.9937368 -1 0.1117467 -0.9937368 1 0.1102222 -0.993907 -1 0.1102222 -0.993907 1 0.1086974 -0.9940749 -1 0.1086974 -0.9940749 1 0.1071724 -0.9942405 -1 0.1071724 -0.9942405 1 0.1056472 -0.9944037 -1 0.1056472 -0.9944037 1 0.1041216 -0.9945646 -1 0.1041216 -0.9945646 1 0.1025959 -0.9947232 -1 0.1025959 -0.9947232 1 0.1010698 -0.9948793 -1 0.1010698 -0.9948793 1 0.09954357 -0.9950332 -1 0.09954357 -0.9950332 1 0.09801709 -0.9951847 -1 0.09801709 -0.9951847 1 0.09649044 -0.9953339 -1 0.09649044 -0.9953339 1 0.09496349 -0.9954808 -1 0.09496349 -0.9954808 1 0.0934363 -0.9956253 -1 0.0934363 -0.9956253 1 0.09190893 -0.9957674 -1 0.09190893 -0.9957674 1 0.09038132 -0.9959073 -1 0.09038132 -0.9959073 1 0.08885353 -0.9960447 -1 0.08885353 -0.9960447 1 0.08732551 -0.9961798 -1 0.08732551 -0.9961798 1 0.0857973 -0.9963126 -1 0.0857973 -0.9963126 1 0.08426886 -0.996443 -1 0.08426886 -0.996443 1 0.08274024 -0.9965711 -1 0.08274024 -0.9965711 1 0.08121144 -0.9966969 -1 0.08121144 -0.9966969 1 0.0796824 -0.9968203 -1 0.0796824 -0.9968203 1 0.07815325 -0.9969413 -1 0.07815325 -0.9969413 1 0.07662385 -0.9970601 -1 0.07662385 -0.9970601 1 0.07509428 -0.9971764 -1 0.07509428 -0.9971764 1 0.07356452 -0.9972904 -1 0.07356452 -0.9972904 1 0.07203465 -0.9974021 -1 0.07203465 -0.9974021 1 0.07050454 -0.9975115 -1 0.07050454 -0.9975115 1 0.06897431 -0.9976184 -1 0.06897431 -0.9976184 1 0.0674439 -0.9977231 -1 0.0674439 -0.9977231 1 0.06591331 -0.9978253 -1 0.06591331 -0.9978253 1 0.06438261 -0.9979253 -1 0.06438261 -0.9979253 1 0.06285172 -0.9980229 -1 0.06285172 -0.9980229 1 0.06132072 -0.9981181 -1 0.06132072 -0.9981181 1 0.05978953 -0.998211 -1 0.05978953 -0.998211 1 0.05825823 -0.9983016 -1 0.05825823 -0.9983016 1 0.05672681 -0.9983897 -1 0.05672681 -0.9983897 1 0.05519521 -0.9984756 -1 0.05519521 -0.9984756 1 0.05366349 -0.9985591 -1 0.05366349 -0.9985591 1 0.05213171 -0.9986402 -1 0.05213171 -0.9986402 1 0.05059975 -0.998719 -1 0.05059975 -0.998719 1 0.04906767 -0.9987955 -1 0.04906767 -0.9987955 1 0.04753547 -0.9988695 -1 0.04753547 -0.9988695 1 0.04600316 -0.9989413 -1 0.04600316 -0.9989413 1 0.04447072 -0.9990107 -1 0.04447072 -0.9990107 1 0.04293823 -0.9990777 -1 0.04293823 -0.9990777 1 0.04140561 -0.9991424 -1 0.04140561 -0.9991424 1 0.03987288 -0.9992048 -1 0.03987288 -0.9992048 1 0.03834009 -0.9992648 -1 0.03834009 -0.9992648 1 0.03680717 -0.9993224 -1 0.03680717 -0.9993224 1 0.0352742 -0.9993777 -1 0.0352742 -0.9993777 1 0.03374117 -0.9994306 -1 0.03374117 -0.9994306 1 0.03220802 -0.9994812 -1 0.03220802 -0.9994812 1 0.03067475 -0.9995294 -1 0.03067475 -0.9995294 1 0.02914148 -0.9995753 -1 0.02914148 -0.9995753 1 0.02760809 -0.9996188 -1 0.02760809 -0.9996188 1 0.0260747 -0.99966 -1 0.0260747 -0.99966 1 0.02454119 -0.9996988 -1 0.02454119 -0.9996988 1 0.02300763 -0.9997353 -1 0.02300763 -0.9997353 1 0.02147406 -0.9997694 -1 0.02147406 -0.9997694 1 0.01994037 -0.9998012 -1 0.01994037 -0.9998012 1 0.01840668 -0.9998306 -1 0.01840668 -0.9998306 1 0.01687294 -0.9998577 -1 0.01687294 -0.9998577 1 0.01533919 -0.9998824 -1 0.01533919 -0.9998824 1 0.01380538 -0.9999047 -1 0.01380538 -0.9999047 1 0.01227152 -0.9999247 -1 0.01227152 -0.9999247 1 0.01073765 -0.9999424 -1 0.01073765 -0.9999424 1 0.009203732 -0.9999576 -1 0.009203732 -0.9999576 1 0.007669806 -0.9999706 -1 0.007669806 -0.9999706 1 0.00613588 -0.9999812 -1 0.00613588 -0.9999812 1 0.004601895 -0.9999894 -1 0.004601895 -0.9999894 1 0.00306791 -0.9999953 -1 0.00306791 -0.9999953 1 0.001533925 -0.9999988 -1 0.001533925 -0.9999988 1 0 -1 -1 0 -1 1 -0.001533925 -0.9999988 -1 -0.001533925 -0.9999988 1 -0.00306791 -0.9999953 -1 -0.00306791 -0.9999953 1 -0.004601895 -0.9999894 -1 -0.004601895 -0.9999894 1 -0.00613588 -0.9999812 -1 -0.00613588 -0.9999812 1 -0.007669806 -0.9999706 -1 -0.007669806 -0.9999706 1 -0.009203732 -0.9999576 -1 -0.009203732 -0.9999576 1 -0.01073765 -0.9999424 -1 -0.01073765 -0.9999424 1 -0.01227152 -0.9999247 -1 -0.01227152 -0.9999247 1 -0.01380538 -0.9999047 -1 -0.01380538 -0.9999047 1 -0.01533919 -0.9998824 -1 -0.01533919 -0.9998824 1 -0.01687294 -0.9998577 -1 -0.01687294 -0.9998577 1 -0.01840668 -0.9998306 -1 -0.01840668 -0.9998306 1 -0.01994037 -0.9998012 -1 -0.01994037 -0.9998012 1 -0.02147406 -0.9997694 -1 -0.02147406 -0.9997694 1 -0.02300763 -0.9997353 -1 -0.02300763 -0.9997353 1 -0.02454119 -0.9996988 -1 -0.02454119 -0.9996988 1 -0.0260747 -0.99966 -1 -0.0260747 -0.99966 1 -0.02760809 -0.9996188 -1 -0.02760809 -0.9996188 1 -0.02914148 -0.9995753 -1 -0.02914148 -0.9995753 1 -0.03067475 -0.9995294 -1 -0.03067475 -0.9995294 1 -0.03220802 -0.9994812 -1 -0.03220802 -0.9994812 1 -0.03374117 -0.9994306 -1 -0.03374117 -0.9994306 1 -0.0352742 -0.9993777 -1 -0.0352742 -0.9993777 1 -0.03680717 -0.9993224 -1 -0.03680717 -0.9993224 1 -0.03834009 -0.9992648 -1 -0.03834009 -0.9992648 1 -0.03987288 -0.9992048 -1 -0.03987288 -0.9992048 1 -0.04140561 -0.9991424 -1 -0.04140561 -0.9991424 1 -0.04293823 -0.9990777 -1 -0.04293823 -0.9990777 1 -0.04447072 -0.9990107 -1 -0.04447072 -0.9990107 1 -0.04600316 -0.9989413 -1 -0.04600316 -0.9989413 1 -0.04753547 -0.9988695 -1 -0.04753547 -0.9988695 1 -0.04906767 -0.9987955 -1 -0.04906767 -0.9987955 1 -0.05059975 -0.998719 -1 -0.05059975 -0.998719 1 -0.05213171 -0.9986402 -1 -0.05213171 -0.9986402 1 -0.05366349 -0.9985591 -1 -0.05366349 -0.9985591 1 -0.05519521 -0.9984756 -1 -0.05519521 -0.9984756 1 -0.05672681 -0.9983897 -1 -0.05672681 -0.9983897 1 -0.05825823 -0.9983016 -1 -0.05825823 -0.9983016 1 -0.05978953 -0.998211 -1 -0.05978953 -0.998211 1 -0.06132072 -0.9981181 -1 -0.06132072 -0.9981181 1 -0.06285172 -0.9980229 -1 -0.06285172 -0.9980229 1 -0.06438261 -0.9979253 -1 -0.06438261 -0.9979253 1 -0.06591331 -0.9978253 -1 -0.06591331 -0.9978253 1 -0.0674439 -0.9977231 -1 -0.0674439 -0.9977231 1 -0.06897431 -0.9976184 -1 -0.06897431 -0.9976184 1 -0.07050454 -0.9975115 -1 -0.07050454 -0.9975115 1 -0.07203465 -0.9974021 -1 -0.07203465 -0.9974021 1 -0.07356452 -0.9972904 -1 -0.07356452 -0.9972904 1 -0.07509428 -0.9971764 -1 -0.07509428 -0.9971764 1 -0.07662385 -0.9970601 -1 -0.07662385 -0.9970601 1 -0.07815325 -0.9969413 -1 -0.07815325 -0.9969413 1 -0.0796824 -0.9968203 -1 -0.0796824 -0.9968203 1 -0.08121144 -0.9966969 -1 -0.08121144 -0.9966969 1 -0.08274024 -0.9965711 -1 -0.08274024 -0.9965711 1 -0.08426886 -0.996443 -1 -0.08426886 -0.996443 1 -0.0857973 -0.9963126 -1 -0.0857973 -0.9963126 1 -0.08732551 -0.9961798 -1 -0.08732551 -0.9961798 1 -0.08885353 -0.9960447 -1 -0.08885353 -0.9960447 1 -0.09038132 -0.9959073 -1 -0.09038132 -0.9959073 1 -0.09190893 -0.9957674 -1 -0.09190893 -0.9957674 1 -0.0934363 -0.9956253 -1 -0.0934363 -0.9956253 1 -0.09496349 -0.9954808 -1 -0.09496349 -0.9954808 1 -0.09649044 -0.9953339 -1 -0.09649044 -0.9953339 1 -0.09801709 -0.9951847 -1 -0.09801709 -0.9951847 1 -0.09954357 -0.9950332 -1 -0.09954357 -0.9950332 1 -0.1010698 -0.9948793 -1 -0.1010698 -0.9948793 1 -0.1025959 -0.9947232 -1 -0.1025959 -0.9947232 1 -0.1041216 -0.9945646 -1 -0.1041216 -0.9945646 1 -0.1056472 -0.9944037 -1 -0.1056472 -0.9944037 1 -0.1071724 -0.9942405 -1 -0.1071724 -0.9942405 1 -0.1086974 -0.9940749 -1 -0.1086974 -0.9940749 1 -0.1102222 -0.993907 -1 -0.1102222 -0.993907 1 -0.1117467 -0.9937368 -1 -0.1117467 -0.9937368 1 -0.1132709 -0.9935641 -1 -0.1132709 -0.9935641 1 -0.1147949 -0.9933892 -1 -0.1147949 -0.9933892 1 -0.1163186 -0.9932119 -1 -0.1163186 -0.9932119 1 -0.117842 -0.9930323 -1 -0.117842 -0.9930323 1 -0.1193652 -0.9928504 -1 -0.1193652 -0.9928504 1 -0.1208881 -0.9926661 -1 -0.1208881 -0.9926661 1 -0.1224107 -0.9924796 -1 -0.1224107 -0.9924796 1 -0.123933 -0.9922906 -1 -0.123933 -0.9922906 1 -0.125455 -0.9920993 -1 -0.125455 -0.9920993 1 -0.1269767 -0.9919057 -1 -0.1269767 -0.9919057 1 -0.1284981 -0.9917098 -1 -0.1284981 -0.9917098 1 -0.1300192 -0.9915115 -1 -0.1300192 -0.9915115 1 -0.13154 -0.9913108 -1 -0.13154 -0.9913108 1 -0.1330605 -0.991108 -1 -0.1330605 -0.991108 1 -0.1345807 -0.9909027 -1 -0.1345807 -0.9909027 1 -0.1361005 -0.990695 -1 -0.1361005 -0.990695 1 -0.1376201 -0.9904851 -1 -0.1376201 -0.9904851 1 -0.1391393 -0.9902728 -1 -0.1391393 -0.9902728 1 -0.1406582 -0.9900582 -1 -0.1406582 -0.9900582 1 -0.1421768 -0.9898413 -1 -0.1421768 -0.9898413 1 -0.143695 -0.989622 -1 -0.143695 -0.989622 1 -0.1452129 -0.9894005 -1 -0.1452129 -0.9894005 1 -0.1467304 -0.9891765 -1 -0.1467304 -0.9891765 1 -0.1482477 -0.9889503 -1 -0.1482477 -0.9889503 1 -0.1497645 -0.9887217 -1 -0.1497645 -0.9887217 1 -0.151281 -0.9884908 -1 -0.151281 -0.9884908 1 -0.1527972 -0.9882576 -1 -0.1527972 -0.9882576 1 -0.154313 -0.988022 -1 -0.154313 -0.988022 1 -0.1558284 -0.9877842 -1 -0.1558284 -0.9877842 1 -0.1573435 -0.987544 -1 -0.1573435 -0.987544 1 -0.1588581 -0.9873014 -1 -0.1588581 -0.9873014 1 -0.1603724 -0.9870566 -1 -0.1603724 -0.9870566 1 -0.1618863 -0.9868094 -1 -0.1618863 -0.9868094 1 -0.1633999 -0.9865599 -1 -0.1633999 -0.9865599 1 -0.1649131 -0.9863081 -1 -0.1649131 -0.9863081 1 -0.1664259 -0.986054 -1 -0.1664259 -0.986054 1 -0.1679382 -0.9857975 -1 -0.1679382 -0.9857975 1 -0.1694503 -0.9855387 -1 -0.1694503 -0.9855387 1 -0.1709619 -0.9852777 -1 -0.1709619 -0.9852777 1 -0.1724731 -0.9850143 -1 -0.1724731 -0.9850143 1 -0.1739838 -0.9847485 -1 -0.1739838 -0.9847485 1 -0.1754943 -0.9844805 -1 -0.1754943 -0.9844805 1 -0.1770042 -0.9842101 -1 -0.1770042 -0.9842101 1 -0.1785138 -0.9839375 -1 -0.1785138 -0.9839375 1 -0.1800229 -0.9836624 -1 -0.1800229 -0.9836624 1 -0.1815316 -0.9833851 -1 -0.1815316 -0.9833851 1 -0.1830399 -0.9831055 -1 -0.1830399 -0.9831055 1 -0.1845477 -0.9828236 -1 -0.1845477 -0.9828236 1 -0.1860551 -0.9825393 -1 -0.1860551 -0.9825393 1 -0.1875621 -0.9822527 -1 -0.1875621 -0.9822527 1 -0.1890686 -0.9819639 -1 -0.1890686 -0.9819639 1 -0.1905747 -0.9816727 -1 -0.1905747 -0.9816727 1 -0.1920804 -0.9813792 -1 -0.1920804 -0.9813792 1 -0.1935856 -0.9810834 -1 -0.1935856 -0.9810834 1 -0.1950903 -0.9807853 -1 -0.1950903 -0.9807853 1 -0.1965946 -0.9804849 -1 -0.1965946 -0.9804849 1 -0.1980984 -0.9801821 -1 -0.1980984 -0.9801821 1 -0.1996017 -0.9798771 -1 -0.1996017 -0.9798771 1 -0.2011046 -0.9795698 -1 -0.2011046 -0.9795698 1 -0.202607 -0.9792602 -1 -0.202607 -0.9792602 1 -0.204109 -0.9789482 -1 -0.204109 -0.9789482 1 -0.2056104 -0.9786339 -1 -0.2056104 -0.9786339 1 -0.2071114 -0.9783174 -1 -0.2071114 -0.9783174 1 -0.2086118 -0.9779985 -1 -0.2086118 -0.9779985 1 -0.2101118 -0.9776774 -1 -0.2101118 -0.9776774 1 -0.2116113 -0.9773539 -1 -0.2116113 -0.9773539 1 -0.2131103 -0.9770281 -1 -0.2131103 -0.9770281 1 -0.2146088 -0.9767001 -1 -0.2146088 -0.9767001 1 -0.2161068 -0.9763697 -1 -0.2161068 -0.9763697 1 -0.2176042 -0.9760371 -1 -0.2176042 -0.9760371 1 -0.2191012 -0.9757021 -1 -0.2191012 -0.9757021 1 -0.2205977 -0.9753649 -1 -0.2205977 -0.9753649 1 -0.2220936 -0.9750254 -1 -0.2220936 -0.9750254 1 -0.223589 -0.9746835 -1 -0.223589 -0.9746835 1 -0.2250839 -0.9743394 -1 -0.2250839 -0.9743394 1 -0.2265782 -0.973993 -1 -0.2265782 -0.973993 1 -0.2280721 -0.9736443 -1 -0.2280721 -0.9736443 1 -0.2295653 -0.9732933 -1 -0.2295653 -0.9732933 1 -0.2310581 -0.97294 -1 -0.2310581 -0.97294 1 -0.2325503 -0.9725844 -1 -0.2325503 -0.9725844 1 -0.2340419 -0.9722265 -1 -0.2340419 -0.9722265 1 -0.235533 -0.9718663 -1 -0.235533 -0.9718663 1 -0.2370236 -0.9715039 -1 -0.2370236 -0.9715039 1 -0.2385136 -0.9711391 -1 -0.2385136 -0.9711391 1 -0.240003 -0.9707722 -1 -0.240003 -0.9707722 1 -0.2414919 -0.9704028 -1 -0.2414919 -0.9704028 1 -0.2429802 -0.9700313 -1 -0.2429802 -0.9700313 1 -0.2444679 -0.9696574 -1 -0.2444679 -0.9696574 1 -0.245955 -0.9692813 -1 -0.245955 -0.9692813 1 -0.2474416 -0.9689028 -1 -0.2474416 -0.9689028 1 -0.2489276 -0.9685221 -1 -0.2489276 -0.9685221 1 -0.250413 -0.9681391 -1 -0.250413 -0.9681391 1 -0.2518978 -0.9677538 -1 -0.2518978 -0.9677538 1 -0.253382 -0.9673663 -1 -0.253382 -0.9673663 1 -0.2548657 -0.9669765 -1 -0.2548657 -0.9669765 1 -0.2563487 -0.9665844 -1 -0.2563487 -0.9665844 1 -0.2578311 -0.96619 -1 -0.2578311 -0.96619 1 -0.2593129 -0.9657934 -1 -0.2593129 -0.9657934 1 -0.2607941 -0.9653944 -1 -0.2607941 -0.9653944 1 -0.2622747 -0.9649932 -1 -0.2622747 -0.9649932 1 -0.2637547 -0.9645898 -1 -0.2637547 -0.9645898 1 -0.2652341 -0.9641841 -1 -0.2652341 -0.9641841 1 -0.2667128 -0.9637761 -1 -0.2667128 -0.9637761 1 -0.2681909 -0.9633658 -1 -0.2681909 -0.9633658 1 -0.2696684 -0.9629533 -1 -0.2696684 -0.9629533 1 -0.2711452 -0.9625385 -1 -0.2711452 -0.9625385 1 -0.2726213 -0.9621214 -1 -0.2726213 -0.9621214 1 -0.2740969 -0.9617021 -1 -0.2740969 -0.9617021 1 -0.2755718 -0.9612805 -1 -0.2755718 -0.9612805 1 -0.2770461 -0.9608566 -1 -0.2770461 -0.9608566 1 -0.2785197 -0.9604305 -1 -0.2785197 -0.9604305 1 -0.2799926 -0.9600021 -1 -0.2799926 -0.9600021 1 -0.2814649 -0.9595715 -1 -0.2814649 -0.9595715 1 -0.2829366 -0.9591386 -1 -0.2829366 -0.9591386 1 -0.2844076 -0.9587035 -1 -0.2844076 -0.9587035 1 -0.2858778 -0.9582661 -1 -0.2858778 -0.9582661 1 -0.2873475 -0.9578264 -1 -0.2873475 -0.9578264 1 -0.2888164 -0.9573845 -1 -0.2888164 -0.9573845 1 -0.2902847 -0.9569404 -1 -0.2902847 -0.9569404 1 -0.2917523 -0.9564939 -1 -0.2917523 -0.9564939 1 -0.2932192 -0.9560453 -1 -0.2932192 -0.9560453 1 -0.2946854 -0.9555943 -1 -0.2946854 -0.9555943 1 -0.2961509 -0.9551412 -1 -0.2961509 -0.9551412 1 -0.2976157 -0.9546858 -1 -0.2976157 -0.9546858 1 -0.2990798 -0.9542281 -1 -0.2990798 -0.9542281 1 -0.3005433 -0.9537682 -1 -0.3005433 -0.9537682 1 -0.302006 -0.953306 -1 -0.302006 -0.953306 1 -0.3034679 -0.9528416 -1 -0.3034679 -0.9528416 1 -0.3049293 -0.952375 -1 -0.3049293 -0.952375 1 -0.3063898 -0.9519062 -1 -0.3063898 -0.9519062 1 -0.3078497 -0.951435 -1 -0.3078497 -0.951435 1 -0.3093088 -0.9509617 -1 -0.3093088 -0.9509617 1 -0.3107671 -0.9504861 -1 -0.3107671 -0.9504861 1 -0.3122248 -0.9500082 -1 -0.3122248 -0.9500082 1 -0.3136817 -0.9495282 -1 -0.3136817 -0.9495282 1 -0.3151379 -0.9490459 -1 -0.3151379 -0.9490459 1 -0.3165934 -0.9485614 -1 -0.3165934 -0.9485614 1 -0.3180481 -0.9480746 -1 -0.3180481 -0.9480746 1 -0.319502 -0.9475856 -1 -0.319502 -0.9475856 1 -0.3209552 -0.9470944 -1 -0.3209552 -0.9470944 1 -0.3224077 -0.9466009 -1 -0.3224077 -0.9466009 1 -0.3238593 -0.9461053 -1 -0.3238593 -0.9461053 1 -0.3253103 -0.9456073 -1 -0.3253103 -0.9456073 1 -0.3267605 -0.9451072 -1 -0.3267605 -0.9451072 1 -0.3282098 -0.9446048 -1 -0.3282098 -0.9446048 1 -0.3296585 -0.9441003 -1 -0.3296585 -0.9441003 1 -0.3311063 -0.9435935 -1 -0.3311063 -0.9435935 1 -0.3325534 -0.9430844 -1 -0.3325534 -0.9430844 1 -0.3339996 -0.9425732 -1 -0.3339996 -0.9425732 1 -0.3354452 -0.9420598 -1 -0.3354452 -0.9420598 1 -0.3368899 -0.9415441 -1 -0.3368899 -0.9415441 1 -0.3383337 -0.9410262 -1 -0.3383337 -0.9410262 1 -0.3397769 -0.9405061 -1 -0.3397769 -0.9405061 1 -0.3412192 -0.9399837 -1 -0.3412192 -0.9399837 1 -0.3426607 -0.9394592 -1 -0.3426607 -0.9394592 1 -0.3441014 -0.9389325 -1 -0.3441014 -0.9389325 1 -0.3455413 -0.9384036 -1 -0.3455413 -0.9384036 1 -0.3469804 -0.9378724 -1 -0.3469804 -0.9378724 1 -0.3484187 -0.937339 -1 -0.3484187 -0.937339 1 -0.3498561 -0.9368035 -1 -0.3498561 -0.9368035 1 -0.3512927 -0.9362657 -1 -0.3512927 -0.9362657 1 -0.3527286 -0.9357257 -1 -0.3527286 -0.9357257 1 -0.3541635 -0.9351835 -1 -0.3541635 -0.9351835 1 -0.3555977 -0.9346391 -1 -0.3555977 -0.9346391 1 -0.357031 -0.9340925 -1 -0.357031 -0.9340925 1 -0.3584634 -0.9335438 -1 -0.3584634 -0.9335438 1 -0.3598951 -0.9329928 -1 -0.3598951 -0.9329928 1 -0.3613258 -0.9324396 -1 -0.3613258 -0.9324396 1 -0.3627557 -0.9318843 -1 -0.3627557 -0.9318843 1 -0.3641848 -0.9313267 -1 -0.3641848 -0.9313267 1 -0.365613 -0.9307669 -1 -0.365613 -0.9307669 1 -0.3670403 -0.930205 -1 -0.3670403 -0.930205 1 -0.3684668 -0.9296409 -1 -0.3684668 -0.9296409 1 -0.3698924 -0.9290746 -1 -0.3698924 -0.9290746 1 -0.3713172 -0.9285061 -1 -0.3713172 -0.9285061 1 -0.3727411 -0.9279354 -1 -0.3727411 -0.9279354 1 -0.3741641 -0.9273625 -1 -0.3741641 -0.9273625 1 -0.3755862 -0.9267875 -1 -0.3755862 -0.9267875 1 -0.3770074 -0.9262102 -1 -0.3770074 -0.9262102 1 -0.3784278 -0.9256308 -1 -0.3784278 -0.9256308 1 -0.3798472 -0.9250493 -1 -0.3798472 -0.9250493 1 -0.3812658 -0.9244655 -1 -0.3812658 -0.9244655 1 -0.3826835 -0.9238795 -1 -0.3826835 -0.9238795 1 -0.3841002 -0.9232914 -1 -0.3841002 -0.9232914 1 -0.3855161 -0.9227011 -1 -0.3855161 -0.9227011 1 -0.386931 -0.9221087 -1 -0.386931 -0.9221087 1 -0.388345 -0.921514 -1 -0.388345 -0.921514 1 -0.3897582 -0.9209172 -1 -0.3897582 -0.9209172 1 -0.3911704 -0.9203183 -1 -0.3911704 -0.9203183 1 -0.3925817 -0.9197171 -1 -0.3925817 -0.9197171 1 -0.3939921 -0.9191139 -1 -0.3939921 -0.9191139 1 -0.3954015 -0.9185084 -1 -0.3954015 -0.9185084 1 -0.39681 -0.9179008 -1 -0.39681 -0.9179008 1 -0.3982176 -0.917291 -1 -0.3982176 -0.917291 1 -0.3996242 -0.9166791 -1 -0.3996242 -0.9166791 1 -0.4010299 -0.916065 -1 -0.4010299 -0.916065 1 -0.4024347 -0.9154487 -1 -0.4024347 -0.9154487 1 -0.4038385 -0.9148303 -1 -0.4038385 -0.9148303 1 -0.4052413 -0.9142097 -1 -0.4052413 -0.9142097 1 -0.4066432 -0.913587 -1 -0.4066432 -0.913587 1 -0.4080442 -0.9129622 -1 -0.4080442 -0.9129622 1 -0.4094442 -0.9123352 -1 -0.4094442 -0.9123352 1 -0.4108432 -0.911706 -1 -0.4108432 -0.911706 1 -0.4122412 -0.9110748 -1 -0.4122412 -0.9110748 1 -0.4136383 -0.9104413 -1 -0.4136383 -0.9104413 1 -0.4150344 -0.9098057 -1 -0.4150344 -0.9098057 1 -0.4164296 -0.909168 -1 -0.4164296 -0.909168 1 -0.4178237 -0.9085281 -1 -0.4178237 -0.9085281 1 -0.4192169 -0.9078861 -1 -0.4192169 -0.9078861 1 -0.4206091 -0.907242 -1 -0.4206091 -0.907242 1 -0.4220003 -0.9065957 -1 -0.4220003 -0.9065957 1 -0.4233905 -0.9059473 -1 -0.4233905 -0.9059473 1 -0.4247797 -0.9052968 -1 -0.4247797 -0.9052968 1 -0.4261679 -0.9046441 -1 -0.4261679 -0.9046441 1 -0.4275551 -0.9039893 -1 -0.4275551 -0.9039893 1 -0.4289413 -0.9033324 -1 -0.4289413 -0.9033324 1 -0.4303265 -0.9026733 -1 -0.4303265 -0.9026733 1 -0.4317107 -0.9020121 -1 -0.4317107 -0.9020121 1 -0.4330939 -0.9013488 -1 -0.4330939 -0.9013488 1 -0.434476 -0.9006834 -1 -0.434476 -0.9006834 1 -0.4358571 -0.9000159 -1 -0.4358571 -0.9000159 1 -0.4372372 -0.8993462 -1 -0.4372372 -0.8993462 1 -0.4386162 -0.8986745 -1 -0.4386162 -0.8986745 1 -0.4399943 -0.8980006 -1 -0.4399943 -0.8980006 1 -0.4413713 -0.8973246 -1 -0.4413713 -0.8973246 1 -0.4427472 -0.8966464 -1 -0.4427472 -0.8966464 1 -0.4441221 -0.8959662 -1 -0.4441221 -0.8959662 1 -0.445496 -0.8952839 -1 -0.445496 -0.8952839 1 -0.4468688 -0.8945995 -1 -0.4468688 -0.8945995 1 -0.4482406 -0.893913 -1 -0.4482406 -0.893913 1 -0.4496113 -0.8932243 -1 -0.4496113 -0.8932243 1 -0.450981 -0.8925336 -1 -0.450981 -0.8925336 1 -0.4523496 -0.8918407 -1 -0.4523496 -0.8918407 1 -0.4537171 -0.8911458 -1 -0.4537171 -0.8911458 1 -0.4550836 -0.8904488 -1 -0.4550836 -0.8904488 1 -0.456449 -0.8897496 -1 -0.456449 -0.8897496 1 -0.4578133 -0.8890483 -1 -0.4578133 -0.8890483 1 -0.4591765 -0.888345 -1 -0.4591765 -0.888345 1 -0.4605387 -0.8876397 -1 -0.4605387 -0.8876397 1 -0.4618998 -0.8869321 -1 -0.4618998 -0.8869321 1 -0.4632598 -0.8862226 -1 -0.4632598 -0.8862226 1 -0.4646187 -0.8855109 -1 -0.4646187 -0.8855109 1 -0.4659765 -0.8847971 -1 -0.4659765 -0.8847971 1 -0.4673332 -0.8840813 -1 -0.4673332 -0.8840813 1 -0.4686889 -0.8833633 -1 -0.4686889 -0.8833633 1 -0.4700433 -0.8826434 -1 -0.4700433 -0.8826434 1 -0.4713968 -0.8819212 -1 -0.4713968 -0.8819212 1 -0.4727491 -0.8811971 -1 -0.4727491 -0.8811971 1 -0.4741002 -0.8804709 -1 -0.4741002 -0.8804709 1 -0.4754503 -0.8797426 -1 -0.4754503 -0.8797426 1 -0.4767993 -0.8790122 -1 -0.4767993 -0.8790122 1 -0.478147 -0.8782798 -1 -0.478147 -0.8782798 1 -0.4794937 -0.8775453 -1 -0.4794937 -0.8775453 1 -0.4808393 -0.8768087 -1 -0.4808393 -0.8768087 1 -0.4821838 -0.8760701 -1 -0.4821838 -0.8760701 1 -0.4835271 -0.8753294 -1 -0.4835271 -0.8753294 1 -0.4848693 -0.8745867 -1 -0.4848693 -0.8745867 1 -0.4862103 -0.8738418 -1 -0.4862103 -0.8738418 1 -0.4875501 -0.873095 -1 -0.4875501 -0.873095 1 -0.4888889 -0.8723461 -1 -0.4888889 -0.8723461 1 -0.4902265 -0.8715951 -1 -0.4902265 -0.8715951 1 -0.4915629 -0.870842 -1 -0.4915629 -0.870842 1 -0.4928982 -0.870087 -1 -0.4928982 -0.870087 1 -0.4942323 -0.8693299 -1 -0.4942323 -0.8693299 1 -0.4955653 -0.8685707 -1 -0.4955653 -0.8685707 1 -0.4968971 -0.8678095 -1 -0.4968971 -0.8678095 1 -0.4982277 -0.8670462 -1 -0.4982277 -0.8670462 1 -0.4995571 -0.866281 -1 -0.4995571 -0.866281 1 -0.5008854 -0.8655136 -1 -0.5008854 -0.8655136 1 -0.5022125 -0.8647443 -1 -0.5022125 -0.8647443 1 -0.5035384 -0.8639729 -1 -0.5035384 -0.8639729 1 -0.5048632 -0.8631994 -1 -0.5048632 -0.8631994 1 -0.5061867 -0.862424 -1 -0.5061867 -0.862424 1 -0.507509 -0.8616465 -1 -0.507509 -0.8616465 1 -0.5088302 -0.8608669 -1 -0.5088302 -0.8608669 1 -0.5101501 -0.8600854 -1 -0.5101501 -0.8600854 1 -0.5114689 -0.8593018 -1 -0.5114689 -0.8593018 1 -0.5127865 -0.8585162 -1 -0.5127865 -0.8585162 1 -0.5141028 -0.8577286 -1 -0.5141028 -0.8577286 1 -0.5154179 -0.856939 -1 -0.5154179 -0.856939 1 -0.5167318 -0.8561474 -1 -0.5167318 -0.8561474 1 -0.5180445 -0.8553537 -1 -0.5180445 -0.8553537 1 -0.519356 -0.854558 -1 -0.519356 -0.854558 1 -0.5206663 -0.8537603 -1 -0.5206663 -0.8537603 1 -0.5219753 -0.8529606 -1 -0.5219753 -0.8529606 1 -0.5232831 -0.8521589 -1 -0.5232831 -0.8521589 1 -0.5245897 -0.8513552 -1 -0.5245897 -0.8513552 1 -0.5258951 -0.8505495 -1 -0.5258951 -0.8505495 1 -0.5271992 -0.8497418 -1 -0.5271992 -0.8497418 1 -0.5285021 -0.848932 -1 -0.5285021 -0.848932 1 -0.5298036 -0.8481203 -1 -0.5298036 -0.8481203 1 -0.531104 -0.8473066 -1 -0.531104 -0.8473066 1 -0.5324032 -0.8464909 -1 -0.5324032 -0.8464909 1 -0.533701 -0.8456733 -1 -0.533701 -0.8456733 1 -0.5349976 -0.8448536 -1 -0.5349976 -0.8448536 1 -0.536293 -0.8440319 -1 -0.536293 -0.8440319 1 -0.5375871 -0.8432083 -1 -0.5375871 -0.8432083 1 -0.5388799 -0.8423826 -1 -0.5388799 -0.8423826 1 -0.5401715 -0.841555 -1 -0.5401715 -0.841555 1 -0.5414618 -0.8407254 -1 -0.5414618 -0.8407254 1 -0.5427508 -0.8398938 -1 -0.5427508 -0.8398938 1 -0.5440385 -0.8390603 -1 -0.5440385 -0.8390603 1 -0.545325 -0.8382247 -1 -0.545325 -0.8382247 1 -0.5466102 -0.8373872 -1 -0.5466102 -0.8373872 1 -0.5478941 -0.8365477 -1 -0.5478941 -0.8365477 1 -0.5491767 -0.8357062 -1 -0.5491767 -0.8357062 1 -0.550458 -0.8348628 -1 -0.550458 -0.8348628 1 -0.551738 -0.8340175 -1 -0.551738 -0.8340175 1 -0.5530167 -0.8331702 -1 -0.5530167 -0.8331702 1 -0.5542941 -0.8323209 -1 -0.5542941 -0.8323209 1 -0.5555703 -0.8314696 -1 -0.5555703 -0.8314696 1 -0.5568451 -0.8306164 -1 -0.5568451 -0.8306164 1 -0.5581185 -0.8297612 -1 -0.5581185 -0.8297612 1 -0.5593907 -0.8289041 -1 -0.5593907 -0.8289041 1 -0.5606616 -0.828045 -1 -0.5606616 -0.828045 1 -0.5619311 -0.827184 -1 -0.5619311 -0.827184 1 -0.5631994 -0.8263211 -1 -0.5631994 -0.8263211 1 -0.5644662 -0.8254562 -1 -0.5644662 -0.8254562 1 -0.5657318 -0.8245893 -1 -0.5657318 -0.8245893 1 -0.5669961 -0.8237205 -1 -0.5669961 -0.8237205 1 -0.568259 -0.8228498 -1 -0.568259 -0.8228498 1 -0.5695205 -0.8219771 -1 -0.5695205 -0.8219771 1 -0.5707808 -0.8211025 -1 -0.5707808 -0.8211025 1 -0.5720396 -0.820226 -1 -0.5720396 -0.820226 1 -0.5732972 -0.8193475 -1 -0.5732972 -0.8193475 1 -0.5745534 -0.8184671 -1 -0.5745534 -0.8184671 1 -0.5758082 -0.8175848 -1 -0.5758082 -0.8175848 1 -0.5770617 -0.8167006 -1 -0.5770617 -0.8167006 1 -0.5783138 -0.8158144 -1 -0.5783138 -0.8158144 1 -0.5795646 -0.8149263 -1 -0.5795646 -0.8149263 1 -0.580814 -0.8140363 -1 -0.580814 -0.8140363 1 -0.582062 -0.8131444 -1 -0.582062 -0.8131444 1 -0.5833087 -0.8122506 -1 -0.5833087 -0.8122506 1 -0.584554 -0.8113548 -1 -0.584554 -0.8113548 1 -0.5857979 -0.8104572 -1 -0.5857979 -0.8104572 1 -0.5870404 -0.8095577 -1 -0.5870404 -0.8095577 1 -0.5882816 -0.8086562 -1 -0.5882816 -0.8086562 1 -0.5895213 -0.8077529 -1 -0.5895213 -0.8077529 1 -0.5907597 -0.8068476 -1 -0.5907597 -0.8068476 1 -0.5919967 -0.8059404 -1 -0.5919967 -0.8059404 1 -0.5932323 -0.8050313 -1 -0.5932323 -0.8050313 1 -0.5944665 -0.8041204 -1 -0.5944665 -0.8041204 1 -0.5956993 -0.8032075 -1 -0.5956993 -0.8032075 1 -0.5969308 -0.8022928 -1 -0.5969308 -0.8022928 1 -0.5981608 -0.8013762 -1 -0.5981608 -0.8013762 1 -0.5993893 -0.8004577 -1 -0.5993893 -0.8004577 1 -0.6006165 -0.7995373 -1 -0.6006165 -0.7995373 1 -0.6018423 -0.798615 -1 -0.6018423 -0.798615 1 -0.6030666 -0.7976908 -1 -0.6030666 -0.7976908 1 -0.6042895 -0.7967648 -1 -0.6042895 -0.7967648 1 -0.605511 -0.7958369 -1 -0.605511 -0.7958369 1 -0.6067311 -0.7949072 -1 -0.6067311 -0.7949072 1 -0.6079498 -0.7939755 -1 -0.6079498 -0.7939755 1 -0.609167 -0.793042 -1 -0.609167 -0.793042 1 -0.6103828 -0.7921066 -1 -0.6103828 -0.7921066 1 -0.6115972 -0.7911694 -1 -0.6115972 -0.7911694 1 -0.6128101 -0.7902302 -1 -0.6128101 -0.7902302 1 -0.6140216 -0.7892892 -1 -0.6140216 -0.7892892 1 -0.6152316 -0.7883464 -1 -0.6152316 -0.7883464 1 -0.6164402 -0.7874017 -1 -0.6164402 -0.7874017 1 -0.6176474 -0.7864552 -1 -0.6176474 -0.7864552 1 -0.618853 -0.7855068 -1 -0.618853 -0.7855068 1 -0.6200572 -0.7845566 -1 -0.6200572 -0.7845566 1 -0.62126 -0.7836045 -1 -0.62126 -0.7836045 1 -0.6224613 -0.7826506 -1 -0.6224613 -0.7826506 1 -0.6236611 -0.7816948 -1 -0.6236611 -0.7816948 1 -0.6248595 -0.7807372 -1 -0.6248595 -0.7807372 1 -0.6260564 -0.7797778 -1 -0.6260564 -0.7797778 1 -0.6272518 -0.7788165 -1 -0.6272518 -0.7788165 1 -0.6284458 -0.7778534 -1 -0.6284458 -0.7778534 1 -0.6296383 -0.7768884 -1 -0.6296383 -0.7768884 1 -0.6308293 -0.7759217 -1 -0.6308293 -0.7759217 1 -0.6320188 -0.7749531 -1 -0.6320188 -0.7749531 1 -0.6332068 -0.7739827 -1 -0.6332068 -0.7739827 1 -0.6343933 -0.7730104 -1 -0.6343933 -0.7730104 1 -0.6355783 -0.7720364 -1 -0.6355783 -0.7720364 1 -0.6367619 -0.7710605 -1 -0.6367619 -0.7710605 1 -0.6379439 -0.7700828 -1 -0.6379439 -0.7700828 1 -0.6391245 -0.7691034 -1 -0.6391245 -0.7691034 1 -0.6403035 -0.768122 -1 -0.6403035 -0.768122 1 -0.6414811 -0.7671389 -1 -0.6414811 -0.7671389 1 -0.6426571 -0.766154 -1 -0.6426571 -0.766154 1 -0.6438316 -0.7651672 -1 -0.6438316 -0.7651672 1 -0.6450046 -0.7641788 -1 -0.6450046 -0.7641788 1 -0.646176 -0.7631884 -1 -0.646176 -0.7631884 1 -0.647346 -0.7621963 -1 -0.647346 -0.7621963 1 -0.6485145 -0.7612023 -1 -0.6485145 -0.7612023 1 -0.6496813 -0.7602066 -1 -0.6496813 -0.7602066 1 -0.6508467 -0.7592092 -1 -0.6508467 -0.7592092 1 -0.6520106 -0.7582099 -1 -0.6520106 -0.7582099 1 -0.6531729 -0.7572088 -1 -0.6531729 -0.7572088 1 -0.6543336 -0.756206 -1 -0.6543336 -0.756206 1 -0.6554929 -0.7552014 -1 -0.6554929 -0.7552014 1 -0.6566506 -0.754195 -1 -0.6566506 -0.754195 1 -0.6578067 -0.7531868 -1 -0.6578067 -0.7531868 1 -0.6589613 -0.7521768 -1 -0.6589613 -0.7521768 1 -0.6601144 -0.7511651 -1 -0.6601144 -0.7511651 1 -0.6612659 -0.7501516 -1 -0.6612659 -0.7501516 1 -0.6624158 -0.7491364 -1 -0.6624158 -0.7491364 1 -0.6635642 -0.7481194 -1 -0.6635642 -0.7481194 1 -0.664711 -0.7471006 -1 -0.664711 -0.7471006 1 -0.6658563 -0.7460801 -1 -0.6658563 -0.7460801 1 -0.6669999 -0.7450578 -1 -0.6669999 -0.7450578 1 -0.6681421 -0.7440337 -1 -0.6681421 -0.7440337 1 -0.6692826 -0.743008 -1 -0.6692826 -0.743008 1 -0.6704216 -0.7419804 -1 -0.6704216 -0.7419804 1 -0.671559 -0.7409511 -1 -0.671559 -0.7409511 1 -0.6726948 -0.7399201 -1 -0.6726948 -0.7399201 1 -0.673829 -0.7388873 -1 -0.673829 -0.7388873 1 -0.6749617 -0.7378528 -1 -0.6749617 -0.7378528 1 -0.6760928 -0.7368166 -1 -0.6760928 -0.7368166 1 -0.6772222 -0.7357786 -1 -0.6772222 -0.7357786 1 -0.6783501 -0.7347389 -1 -0.6783501 -0.7347389 1 -0.6794763 -0.7336974 -1 -0.6794763 -0.7336974 1 -0.680601 -0.7326543 -1 -0.680601 -0.7326543 1 -0.6817241 -0.7316094 -1 -0.6817241 -0.7316094 1 -0.6828456 -0.7305628 -1 -0.6828456 -0.7305628 1 -0.6839655 -0.7295144 -1 -0.6839655 -0.7295144 1 -0.6850837 -0.7284644 -1 -0.6850837 -0.7284644 1 -0.6862003 -0.7274127 -1 -0.6862003 -0.7274127 1 -0.6873154 -0.7263591 -1 -0.6873154 -0.7263591 1 -0.6884288 -0.725304 -1 -0.6884288 -0.725304 1 -0.6895406 -0.7242471 -1 -0.6895406 -0.7242471 1 -0.6906507 -0.7231885 -1 -0.6906507 -0.7231885 1 -0.6917593 -0.7221282 -1 -0.6917593 -0.7221282 1 -0.6928662 -0.7210662 -1 -0.6928662 -0.7210662 1 -0.6939715 -0.7200025 -1 -0.6939715 -0.7200025 1 -0.6950752 -0.7189371 -1 -0.6950752 -0.7189371 1 -0.6961772 -0.71787 -1 -0.6961772 -0.71787 1 -0.6972776 -0.7168012 -1 -0.6972776 -0.7168012 1 -0.6983763 -0.7157308 -1 -0.6983763 -0.7157308 1 -0.6994734 -0.7146587 -1 -0.6994734 -0.7146587 1 -0.7005688 -0.7135849 -1 -0.7005688 -0.7135849 1 -0.7016626 -0.7125094 -1 -0.7016626 -0.7125094 1 -0.7027547 -0.7114322 -1 -0.7027547 -0.7114322 1 -0.7038453 -0.7103533 -1 -0.7038453 -0.7103533 1 -0.7049341 -0.7092728 -1 -0.7049341 -0.7092728 1 -0.7060213 -0.7081906 -1 -0.7060213 -0.7081906 1 -0.7071068 -0.7071068 -1 -0.7071068 -0.7071068 1 -0.7081906 -0.7060213 -1 -0.7081906 -0.7060213 1 -0.7092728 -0.7049341 -1 -0.7092728 -0.7049341 1 -0.7103533 -0.7038453 -1 -0.7103533 -0.7038453 1 -0.7114322 -0.7027547 -1 -0.7114322 -0.7027547 1 -0.7125094 -0.7016626 -1 -0.7125094 -0.7016626 1 -0.7135849 -0.7005688 -1 -0.7135849 -0.7005688 1 -0.7146587 -0.6994734 -1 -0.7146587 -0.6994734 1 -0.7157308 -0.6983763 -1 -0.7157308 -0.6983763 1 -0.7168012 -0.6972776 -1 -0.7168012 -0.6972776 1 -0.71787 -0.6961772 -1 -0.71787 -0.6961772 1 -0.7189371 -0.6950752 -1 -0.7189371 -0.6950752 1 -0.7200025 -0.6939715 -1 -0.7200025 -0.6939715 1 -0.7210662 -0.6928662 -1 -0.7210662 -0.6928662 1 -0.7221282 -0.6917593 -1 -0.7221282 -0.6917593 1 -0.7231885 -0.6906507 -1 -0.7231885 -0.6906507 1 -0.7242471 -0.6895406 -1 -0.7242471 -0.6895406 1 -0.725304 -0.6884288 -1 -0.725304 -0.6884288 1 -0.7263591 -0.6873154 -1 -0.7263591 -0.6873154 1 -0.7274127 -0.6862003 -1 -0.7274127 -0.6862003 1 -0.7284644 -0.6850837 -1 -0.7284644 -0.6850837 1 -0.7295144 -0.6839655 -1 -0.7295144 -0.6839655 1 -0.7305628 -0.6828456 -1 -0.7305628 -0.6828456 1 -0.7316094 -0.6817241 -1 -0.7316094 -0.6817241 1 -0.7326543 -0.680601 -1 -0.7326543 -0.680601 1 -0.7336974 -0.6794763 -1 -0.7336974 -0.6794763 1 -0.7347389 -0.6783501 -1 -0.7347389 -0.6783501 1 -0.7357786 -0.6772222 -1 -0.7357786 -0.6772222 1 -0.7368166 -0.6760928 -1 -0.7368166 -0.6760928 1 -0.7378528 -0.6749617 -1 -0.7378528 -0.6749617 1 -0.7388873 -0.673829 -1 -0.7388873 -0.673829 1 -0.7399201 -0.6726948 -1 -0.7399201 -0.6726948 1 -0.7409511 -0.671559 -1 -0.7409511 -0.671559 1 -0.7419804 -0.6704216 -1 -0.7419804 -0.6704216 1 -0.743008 -0.6692826 -1 -0.743008 -0.6692826 1 -0.7440337 -0.6681421 -1 -0.7440337 -0.6681421 1 -0.7450578 -0.6669999 -1 -0.7450578 -0.6669999 1 -0.7460801 -0.6658563 -1 -0.7460801 -0.6658563 1 -0.7471006 -0.664711 -1 -0.7471006 -0.664711 1 -0.7481194 -0.6635642 -1 -0.7481194 -0.6635642 1 -0.7491364 -0.6624158 -1 -0.7491364 -0.6624158 1 -0.7501516 -0.6612659 -1 -0.7501516 -0.6612659 1 -0.7511651 -0.6601144 -1 -0.7511651 -0.6601144 1 -0.7521768 -0.6589613 -1 -0.7521768 -0.6589613 1 -0.7531868 -0.6578067 -1 -0.7531868 -0.6578067 1 -0.754195 -0.6566506 -1 -0.754195 -0.6566506 1 -0.7552014 -0.6554929 -1 -0.7552014 -0.6554929 1 -0.756206 -0.6543336 -1 -0.756206 -0.6543336 1 -0.7572088 -0.6531729 -1 -0.7572088 -0.6531729 1 -0.7582099 -0.6520106 -1 -0.7582099 -0.6520106 1 -0.7592092 -0.6508467 -1 -0.7592092 -0.6508467 1 -0.7602066 -0.6496813 -1 -0.7602066 -0.6496813 1 -0.7612023 -0.6485145 -1 -0.7612023 -0.6485145 1 -0.7621963 -0.647346 -1 -0.7621963 -0.647346 1 -0.7631884 -0.646176 -1 -0.7631884 -0.646176 1 -0.7641788 -0.6450046 -1 -0.7641788 -0.6450046 1 -0.7651672 -0.6438316 -1 -0.7651672 -0.6438316 1 -0.766154 -0.6426571 -1 -0.766154 -0.6426571 1 -0.7671389 -0.6414811 -1 -0.7671389 -0.6414811 1 -0.768122 -0.6403035 -1 -0.768122 -0.6403035 1 -0.7691034 -0.6391245 -1 -0.7691034 -0.6391245 1 -0.7700828 -0.6379439 -1 -0.7700828 -0.6379439 1 -0.7710605 -0.6367619 -1 -0.7710605 -0.6367619 1 -0.7720364 -0.6355783 -1 -0.7720364 -0.6355783 1 -0.7730104 -0.6343933 -1 -0.7730104 -0.6343933 1 -0.7739827 -0.6332068 -1 -0.7739827 -0.6332068 1 -0.7749531 -0.6320188 -1 -0.7749531 -0.6320188 1 -0.7759217 -0.6308293 -1 -0.7759217 -0.6308293 1 -0.7768884 -0.6296383 -1 -0.7768884 -0.6296383 1 -0.7778534 -0.6284458 -1 -0.7778534 -0.6284458 1 -0.7788165 -0.6272518 -1 -0.7788165 -0.6272518 1 -0.7797778 -0.6260564 -1 -0.7797778 -0.6260564 1 -0.7807372 -0.6248595 -1 -0.7807372 -0.6248595 1 -0.7816948 -0.6236611 -1 -0.7816948 -0.6236611 1 -0.7826506 -0.6224613 -1 -0.7826506 -0.6224613 1 -0.7836045 -0.62126 -1 -0.7836045 -0.62126 1 -0.7845566 -0.6200572 -1 -0.7845566 -0.6200572 1 -0.7855068 -0.618853 -1 -0.7855068 -0.618853 1 -0.7864552 -0.6176474 -1 -0.7864552 -0.6176474 1 -0.7874017 -0.6164402 -1 -0.7874017 -0.6164402 1 -0.7883464 -0.6152316 -1 -0.7883464 -0.6152316 1 -0.7892892 -0.6140216 -1 -0.7892892 -0.6140216 1 -0.7902302 -0.6128101 -1 -0.7902302 -0.6128101 1 -0.7911694 -0.6115972 -1 -0.7911694 -0.6115972 1 -0.7921066 -0.6103828 -1 -0.7921066 -0.6103828 1 -0.793042 -0.609167 -1 -0.793042 -0.609167 1 -0.7939755 -0.6079498 -1 -0.7939755 -0.6079498 1 -0.7949072 -0.6067311 -1 -0.7949072 -0.6067311 1 -0.7958369 -0.605511 -1 -0.7958369 -0.605511 1 -0.7967648 -0.6042895 -1 -0.7967648 -0.6042895 1 -0.7976908 -0.6030666 -1 -0.7976908 -0.6030666 1 -0.798615 -0.6018423 -1 -0.798615 -0.6018423 1 -0.7995373 -0.6006165 -1 -0.7995373 -0.6006165 1 -0.8004577 -0.5993893 -1 -0.8004577 -0.5993893 1 -0.8013762 -0.5981608 -1 -0.8013762 -0.5981608 1 -0.8022928 -0.5969308 -1 -0.8022928 -0.5969308 1 -0.8032075 -0.5956993 -1 -0.8032075 -0.5956993 1 -0.8041204 -0.5944665 -1 -0.8041204 -0.5944665 1 -0.8050313 -0.5932323 -1 -0.8050313 -0.5932323 1 -0.8059404 -0.5919967 -1 -0.8059404 -0.5919967 1 -0.8068476 -0.5907597 -1 -0.8068476 -0.5907597 1 -0.8077529 -0.5895213 -1 -0.8077529 -0.5895213 1 -0.8086562 -0.5882816 -1 -0.8086562 -0.5882816 1 -0.8095577 -0.5870404 -1 -0.8095577 -0.5870404 1 -0.8104572 -0.5857979 -1 -0.8104572 -0.5857979 1 -0.8113548 -0.584554 -1 -0.8113548 -0.584554 1 -0.8122506 -0.5833087 -1 -0.8122506 -0.5833087 1 -0.8131444 -0.582062 -1 -0.8131444 -0.582062 1 -0.8140363 -0.580814 -1 -0.8140363 -0.580814 1 -0.8149263 -0.5795646 -1 -0.8149263 -0.5795646 1 -0.8158144 -0.5783138 -1 -0.8158144 -0.5783138 1 -0.8167006 -0.5770617 -1 -0.8167006 -0.5770617 1 -0.8175848 -0.5758082 -1 -0.8175848 -0.5758082 1 -0.8184671 -0.5745534 -1 -0.8184671 -0.5745534 1 -0.8193475 -0.5732972 -1 -0.8193475 -0.5732972 1 -0.820226 -0.5720396 -1 -0.820226 -0.5720396 1 -0.8211025 -0.5707808 -1 -0.8211025 -0.5707808 1 -0.8219771 -0.5695205 -1 -0.8219771 -0.5695205 1 -0.8228498 -0.568259 -1 -0.8228498 -0.568259 1 -0.8237205 -0.5669961 -1 -0.8237205 -0.5669961 1 -0.8245893 -0.5657318 -1 -0.8245893 -0.5657318 1 -0.8254562 -0.5644662 -1 -0.8254562 -0.5644662 1 -0.8263211 -0.5631994 -1 -0.8263211 -0.5631994 1 -0.827184 -0.5619311 -1 -0.827184 -0.5619311 1 -0.828045 -0.5606616 -1 -0.828045 -0.5606616 1 -0.8289041 -0.5593907 -1 -0.8289041 -0.5593907 1 -0.8297612 -0.5581185 -1 -0.8297612 -0.5581185 1 -0.8306164 -0.5568451 -1 -0.8306164 -0.5568451 1 -0.8314696 -0.5555703 -1 -0.8314696 -0.5555703 1 -0.8323209 -0.5542941 -1 -0.8323209 -0.5542941 1 -0.8331702 -0.5530167 -1 -0.8331702 -0.5530167 1 -0.8340175 -0.551738 -1 -0.8340175 -0.551738 1 -0.8348628 -0.550458 -1 -0.8348628 -0.550458 1 -0.8357062 -0.5491767 -1 -0.8357062 -0.5491767 1 -0.8365477 -0.5478941 -1 -0.8365477 -0.5478941 1 -0.8373872 -0.5466102 -1 -0.8373872 -0.5466102 1 -0.8382247 -0.545325 -1 -0.8382247 -0.545325 1 -0.8390603 -0.5440385 -1 -0.8390603 -0.5440385 1 -0.8398938 -0.5427508 -1 -0.8398938 -0.5427508 1 -0.8407254 -0.5414618 -1 -0.8407254 -0.5414618 1 -0.841555 -0.5401715 -1 -0.841555 -0.5401715 1 -0.8423826 -0.5388799 -1 -0.8423826 -0.5388799 1 -0.8432083 -0.5375871 -1 -0.8432083 -0.5375871 1 -0.8440319 -0.536293 -1 -0.8440319 -0.536293 1 -0.8448536 -0.5349976 -1 -0.8448536 -0.5349976 1 -0.8456733 -0.533701 -1 -0.8456733 -0.533701 1 -0.8464909 -0.5324032 -1 -0.8464909 -0.5324032 1 -0.8473066 -0.531104 -1 -0.8473066 -0.531104 1 -0.8481203 -0.5298036 -1 -0.8481203 -0.5298036 1 -0.848932 -0.5285021 -1 -0.848932 -0.5285021 1 -0.8497418 -0.5271992 -1 -0.8497418 -0.5271992 1 -0.8505495 -0.5258951 -1 -0.8505495 -0.5258951 1 -0.8513552 -0.5245897 -1 -0.8513552 -0.5245897 1 -0.8521589 -0.5232831 -1 -0.8521589 -0.5232831 1 -0.8529606 -0.5219753 -1 -0.8529606 -0.5219753 1 -0.8537603 -0.5206663 -1 -0.8537603 -0.5206663 1 -0.854558 -0.519356 -1 -0.854558 -0.519356 1 -0.8553537 -0.5180445 -1 -0.8553537 -0.5180445 1 -0.8561474 -0.5167318 -1 -0.8561474 -0.5167318 1 -0.856939 -0.5154179 -1 -0.856939 -0.5154179 1 -0.8577286 -0.5141028 -1 -0.8577286 -0.5141028 1 -0.8585162 -0.5127865 -1 -0.8585162 -0.5127865 1 -0.8593018 -0.5114689 -1 -0.8593018 -0.5114689 1 -0.8600854 -0.5101501 -1 -0.8600854 -0.5101501 1 -0.8608669 -0.5088302 -1 -0.8608669 -0.5088302 1 -0.8616465 -0.507509 -1 -0.8616465 -0.507509 1 -0.862424 -0.5061867 -1 -0.862424 -0.5061867 1 -0.8631994 -0.5048632 -1 -0.8631994 -0.5048632 1 -0.8639729 -0.5035384 -1 -0.8639729 -0.5035384 1 -0.8647443 -0.5022125 -1 -0.8647443 -0.5022125 1 -0.8655136 -0.5008854 -1 -0.8655136 -0.5008854 1 -0.866281 -0.4995571 -1 -0.866281 -0.4995571 1 -0.8670462 -0.4982277 -1 -0.8670462 -0.4982277 1 -0.8678095 -0.4968971 -1 -0.8678095 -0.4968971 1 -0.8685707 -0.4955653 -1 -0.8685707 -0.4955653 1 -0.8693299 -0.4942323 -1 -0.8693299 -0.4942323 1 -0.870087 -0.4928982 -1 -0.870087 -0.4928982 1 -0.870842 -0.4915629 -1 -0.870842 -0.4915629 1 -0.8715951 -0.4902265 -1 -0.8715951 -0.4902265 1 -0.8723461 -0.4888889 -1 -0.8723461 -0.4888889 1 -0.873095 -0.4875501 -1 -0.873095 -0.4875501 1 -0.8738418 -0.4862103 -1 -0.8738418 -0.4862103 1 -0.8745867 -0.4848693 -1 -0.8745867 -0.4848693 1 -0.8753294 -0.4835271 -1 -0.8753294 -0.4835271 1 -0.8760701 -0.4821838 -1 -0.8760701 -0.4821838 1 -0.8768087 -0.4808393 -1 -0.8768087 -0.4808393 1 -0.8775453 -0.4794937 -1 -0.8775453 -0.4794937 1 -0.8782798 -0.478147 -1 -0.8782798 -0.478147 1 -0.8790122 -0.4767993 -1 -0.8790122 -0.4767993 1 -0.8797426 -0.4754503 -1 -0.8797426 -0.4754503 1 -0.8804709 -0.4741002 -1 -0.8804709 -0.4741002 1 -0.8811971 -0.4727491 -1 -0.8811971 -0.4727491 1 -0.8819212 -0.4713968 -1 -0.8819212 -0.4713968 1 -0.8826434 -0.4700433 -1 -0.8826434 -0.4700433 1 -0.8833633 -0.4686889 -1 -0.8833633 -0.4686889 1 -0.8840813 -0.4673332 -1 -0.8840813 -0.4673332 1 -0.8847971 -0.4659765 -1 -0.8847971 -0.4659765 1 -0.8855109 -0.4646187 -1 -0.8855109 -0.4646187 1 -0.8862226 -0.4632598 -1 -0.8862226 -0.4632598 1 -0.8869321 -0.4618998 -1 -0.8869321 -0.4618998 1 -0.8876397 -0.4605387 -1 -0.8876397 -0.4605387 1 -0.888345 -0.4591765 -1 -0.888345 -0.4591765 1 -0.8890483 -0.4578133 -1 -0.8890483 -0.4578133 1 -0.8897496 -0.456449 -1 -0.8897496 -0.456449 1 -0.8904488 -0.4550836 -1 -0.8904488 -0.4550836 1 -0.8911458 -0.4537171 -1 -0.8911458 -0.4537171 1 -0.8918407 -0.4523496 -1 -0.8918407 -0.4523496 1 -0.8925336 -0.450981 -1 -0.8925336 -0.450981 1 -0.8932243 -0.4496113 -1 -0.8932243 -0.4496113 1 -0.893913 -0.4482406 -1 -0.893913 -0.4482406 1 -0.8945995 -0.4468688 -1 -0.8945995 -0.4468688 1 -0.8952839 -0.445496 -1 -0.8952839 -0.445496 1 -0.8959662 -0.4441221 -1 -0.8959662 -0.4441221 1 -0.8966464 -0.4427472 -1 -0.8966464 -0.4427472 1 -0.8973246 -0.4413713 -1 -0.8973246 -0.4413713 1 -0.8980006 -0.4399943 -1 -0.8980006 -0.4399943 1 -0.8986745 -0.4386162 -1 -0.8986745 -0.4386162 1 -0.8993462 -0.4372372 -1 -0.8993462 -0.4372372 1 -0.9000159 -0.4358571 -1 -0.9000159 -0.4358571 1 -0.9006834 -0.434476 -1 -0.9006834 -0.434476 1 -0.9013488 -0.4330939 -1 -0.9013488 -0.4330939 1 -0.9020121 -0.4317107 -1 -0.9020121 -0.4317107 1 -0.9026733 -0.4303265 -1 -0.9026733 -0.4303265 1 -0.9033324 -0.4289413 -1 -0.9033324 -0.4289413 1 -0.9039893 -0.4275551 -1 -0.9039893 -0.4275551 1 -0.9046441 -0.4261679 -1 -0.9046441 -0.4261679 1 -0.9052968 -0.4247797 -1 -0.9052968 -0.4247797 1 -0.9059473 -0.4233905 -1 -0.9059473 -0.4233905 1 -0.9065957 -0.4220003 -1 -0.9065957 -0.4220003 1 -0.907242 -0.4206091 -1 -0.907242 -0.4206091 1 -0.9078861 -0.4192169 -1 -0.9078861 -0.4192169 1 -0.9085281 -0.4178237 -1 -0.9085281 -0.4178237 1 -0.909168 -0.4164296 -1 -0.909168 -0.4164296 1 -0.9098057 -0.4150344 -1 -0.9098057 -0.4150344 1 -0.9104413 -0.4136383 -1 -0.9104413 -0.4136383 1 -0.9110748 -0.4122412 -1 -0.9110748 -0.4122412 1 -0.911706 -0.4108432 -1 -0.911706 -0.4108432 1 -0.9123352 -0.4094442 -1 -0.9123352 -0.4094442 1 -0.9129622 -0.4080442 -1 -0.9129622 -0.4080442 1 -0.913587 -0.4066432 -1 -0.913587 -0.4066432 1 -0.9142097 -0.4052413 -1 -0.9142097 -0.4052413 1 -0.9148303 -0.4038385 -1 -0.9148303 -0.4038385 1 -0.9154487 -0.4024347 -1 -0.9154487 -0.4024347 1 -0.916065 -0.4010299 -1 -0.916065 -0.4010299 1 -0.9166791 -0.3996242 -1 -0.9166791 -0.3996242 1 -0.917291 -0.3982176 -1 -0.917291 -0.3982176 1 -0.9179008 -0.39681 -1 -0.9179008 -0.39681 1 -0.9185084 -0.3954015 -1 -0.9185084 -0.3954015 1 -0.9191139 -0.3939921 -1 -0.9191139 -0.3939921 1 -0.9197171 -0.3925817 -1 -0.9197171 -0.3925817 1 -0.9203183 -0.3911704 -1 -0.9203183 -0.3911704 1 -0.9209172 -0.3897582 -1 -0.9209172 -0.3897582 1 -0.921514 -0.388345 -1 -0.921514 -0.388345 1 -0.9221087 -0.386931 -1 -0.9221087 -0.386931 1 -0.9227011 -0.3855161 -1 -0.9227011 -0.3855161 1 -0.9232914 -0.3841002 -1 -0.9232914 -0.3841002 1 -0.9238795 -0.3826835 -1 -0.9238795 -0.3826835 1 -0.9244655 -0.3812658 -1 -0.9244655 -0.3812658 1 -0.9250493 -0.3798472 -1 -0.9250493 -0.3798472 1 -0.9256308 -0.3784278 -1 -0.9256308 -0.3784278 1 -0.9262102 -0.3770074 -1 -0.9262102 -0.3770074 1 -0.9267875 -0.3755862 -1 -0.9267875 -0.3755862 1 -0.9273625 -0.3741641 -1 -0.9273625 -0.3741641 1 -0.9279354 -0.3727411 -1 -0.9279354 -0.3727411 1 -0.9285061 -0.3713172 -1 -0.9285061 -0.3713172 1 -0.9290746 -0.3698924 -1 -0.9290746 -0.3698924 1 -0.9296409 -0.3684668 -1 -0.9296409 -0.3684668 1 -0.930205 -0.3670403 -1 -0.930205 -0.3670403 1 -0.9307669 -0.365613 -1 -0.9307669 -0.365613 1 -0.9313267 -0.3641848 -1 -0.9313267 -0.3641848 1 -0.9318843 -0.3627557 -1 -0.9318843 -0.3627557 1 -0.9324396 -0.3613258 -1 -0.9324396 -0.3613258 1 -0.9329928 -0.3598951 -1 -0.9329928 -0.3598951 1 -0.9335438 -0.3584634 -1 -0.9335438 -0.3584634 1 -0.9340925 -0.357031 -1 -0.9340925 -0.357031 1 -0.9346391 -0.3555977 -1 -0.9346391 -0.3555977 1 -0.9351835 -0.3541635 -1 -0.9351835 -0.3541635 1 -0.9357257 -0.3527286 -1 -0.9357257 -0.3527286 1 -0.9362657 -0.3512927 -1 -0.9362657 -0.3512927 1 -0.9368035 -0.3498561 -1 -0.9368035 -0.3498561 1 -0.937339 -0.3484187 -1 -0.937339 -0.3484187 1 -0.9378724 -0.3469804 -1 -0.9378724 -0.3469804 1 -0.9384036 -0.3455413 -1 -0.9384036 -0.3455413 1 -0.9389325 -0.3441014 -1 -0.9389325 -0.3441014 1 -0.9394592 -0.3426607 -1 -0.9394592 -0.3426607 1 -0.9399837 -0.3412192 -1 -0.9399837 -0.3412192 1 -0.9405061 -0.3397769 -1 -0.9405061 -0.3397769 1 -0.9410262 -0.3383337 -1 -0.9410262 -0.3383337 1 -0.9415441 -0.3368899 -1 -0.9415441 -0.3368899 1 -0.9420598 -0.3354452 -1 -0.9420598 -0.3354452 1 -0.9425732 -0.3339996 -1 -0.9425732 -0.3339996 1 -0.9430844 -0.3325534 -1 -0.9430844 -0.3325534 1 -0.9435935 -0.3311063 -1 -0.9435935 -0.3311063 1 -0.9441003 -0.3296585 -1 -0.9441003 -0.3296585 1 -0.9446048 -0.3282098 -1 -0.9446048 -0.3282098 1 -0.9451072 -0.3267605 -1 -0.9451072 -0.3267605 1 -0.9456073 -0.3253103 -1 -0.9456073 -0.3253103 1 -0.9461053 -0.3238593 -1 -0.9461053 -0.3238593 1 -0.9466009 -0.3224077 -1 -0.9466009 -0.3224077 1 -0.9470944 -0.3209552 -1 -0.9470944 -0.3209552 1 -0.9475856 -0.319502 -1 -0.9475856 -0.319502 1 -0.9480746 -0.3180481 -1 -0.9480746 -0.3180481 1 -0.9485614 -0.3165934 -1 -0.9485614 -0.3165934 1 -0.9490459 -0.3151379 -1 -0.9490459 -0.3151379 1 -0.9495282 -0.3136817 -1 -0.9495282 -0.3136817 1 -0.9500082 -0.3122248 -1 -0.9500082 -0.3122248 1 -0.9504861 -0.3107671 -1 -0.9504861 -0.3107671 1 -0.9509617 -0.3093088 -1 -0.9509617 -0.3093088 1 -0.951435 -0.3078497 -1 -0.951435 -0.3078497 1 -0.9519062 -0.3063898 -1 -0.9519062 -0.3063898 1 -0.952375 -0.3049293 -1 -0.952375 -0.3049293 1 -0.9528416 -0.3034679 -1 -0.9528416 -0.3034679 1 -0.953306 -0.302006 -1 -0.953306 -0.302006 1 -0.9537682 -0.3005433 -1 -0.9537682 -0.3005433 1 -0.9542281 -0.2990798 -1 -0.9542281 -0.2990798 1 -0.9546858 -0.2976157 -1 -0.9546858 -0.2976157 1 -0.9551412 -0.2961509 -1 -0.9551412 -0.2961509 1 -0.9555943 -0.2946854 -1 -0.9555943 -0.2946854 1 -0.9560453 -0.2932192 -1 -0.9560453 -0.2932192 1 -0.9564939 -0.2917523 -1 -0.9564939 -0.2917523 1 -0.9569404 -0.2902847 -1 -0.9569404 -0.2902847 1 -0.9573845 -0.2888164 -1 -0.9573845 -0.2888164 1 -0.9578264 -0.2873475 -1 -0.9578264 -0.2873475 1 -0.9582661 -0.2858778 -1 -0.9582661 -0.2858778 1 -0.9587035 -0.2844076 -1 -0.9587035 -0.2844076 1 -0.9591386 -0.2829366 -1 -0.9591386 -0.2829366 1 -0.9595715 -0.2814649 -1 -0.9595715 -0.2814649 1 -0.9600021 -0.2799926 -1 -0.9600021 -0.2799926 1 -0.9604305 -0.2785197 -1 -0.9604305 -0.2785197 1 -0.9608566 -0.2770461 -1 -0.9608566 -0.2770461 1 -0.9612805 -0.2755718 -1 -0.9612805 -0.2755718 1 -0.9617021 -0.2740969 -1 -0.9617021 -0.2740969 1 -0.9621214 -0.2726213 -1 -0.9621214 -0.2726213 1 -0.9625385 -0.2711452 -1 -0.9625385 -0.2711452 1 -0.9629533 -0.2696684 -1 -0.9629533 -0.2696684 1 -0.9633658 -0.2681909 -1 -0.9633658 -0.2681909 1 -0.9637761 -0.2667128 -1 -0.9637761 -0.2667128 1 -0.9641841 -0.2652341 -1 -0.9641841 -0.2652341 1 -0.9645898 -0.2637547 -1 -0.9645898 -0.2637547 1 -0.9649932 -0.2622747 -1 -0.9649932 -0.2622747 1 -0.9653944 -0.2607941 -1 -0.9653944 -0.2607941 1 -0.9657934 -0.2593129 -1 -0.9657934 -0.2593129 1 -0.96619 -0.2578311 -1 -0.96619 -0.2578311 1 -0.9665844 -0.2563487 -1 -0.9665844 -0.2563487 1 -0.9669765 -0.2548657 -1 -0.9669765 -0.2548657 1 -0.9673663 -0.253382 -1 -0.9673663 -0.253382 1 -0.9677538 -0.2518978 -1 -0.9677538 -0.2518978 1 -0.9681391 -0.250413 -1 -0.9681391 -0.250413 1 -0.9685221 -0.2489276 -1 -0.9685221 -0.2489276 1 -0.9689028 -0.2474416 -1 -0.9689028 -0.2474416 1 -0.9692813 -0.245955 -1 -0.9692813 -0.245955 1 -0.9696574 -0.2444679 -1 -0.9696574 -0.2444679 1 -0.9700313 -0.2429802 -1 -0.9700313 -0.2429802 1 -0.9704028 -0.2414919 -1 -0.9704028 -0.2414919 1 -0.9707722 -0.240003 -1 -0.9707722 -0.240003 1 -0.9711391 -0.2385136 -1 -0.9711391 -0.2385136 1 -0.9715039 -0.2370236 -1 -0.9715039 -0.2370236 1 -0.9718663 -0.235533 -1 -0.9718663 -0.235533 1 -0.9722265 -0.2340419 -1 -0.9722265 -0.2340419 1 -0.9725844 -0.2325503 -1 -0.9725844 -0.2325503 1 -0.97294 -0.2310581 -1 -0.97294 -0.2310581 1 -0.9732933 -0.2295653 -1 -0.9732933 -0.2295653 1 -0.9736443 -0.2280721 -1 -0.9736443 -0.2280721 1 -0.973993 -0.2265782 -1 -0.973993 -0.2265782 1 -0.9743394 -0.2250839 -1 -0.9743394 -0.2250839 1 -0.9746835 -0.223589 -1 -0.9746835 -0.223589 1 -0.9750254 -0.2220936 -1 -0.9750254 -0.2220936 1 -0.9753649 -0.2205977 -1 -0.9753649 -0.2205977 1 -0.9757021 -0.2191012 -1 -0.9757021 -0.2191012 1 -0.9760371 -0.2176042 -1 -0.9760371 -0.2176042 1 -0.9763697 -0.2161068 -1 -0.9763697 -0.2161068 1 -0.9767001 -0.2146088 -1 -0.9767001 -0.2146088 1 -0.9770281 -0.2131103 -1 -0.9770281 -0.2131103 1 -0.9773539 -0.2116113 -1 -0.9773539 -0.2116113 1 -0.9776774 -0.2101118 -1 -0.9776774 -0.2101118 1 -0.9779985 -0.2086118 -1 -0.9779985 -0.2086118 1 -0.9783174 -0.2071114 -1 -0.9783174 -0.2071114 1 -0.9786339 -0.2056104 -1 -0.9786339 -0.2056104 1 -0.9789482 -0.204109 -1 -0.9789482 -0.204109 1 -0.9792602 -0.202607 -1 -0.9792602 -0.202607 1 -0.9795698 -0.2011046 -1 -0.9795698 -0.2011046 1 -0.9798771 -0.1996017 -1 -0.9798771 -0.1996017 1 -0.9801821 -0.1980984 -1 -0.9801821 -0.1980984 1 -0.9804849 -0.1965946 -1 -0.9804849 -0.1965946 1 -0.9807853 -0.1950903 -1 -0.9807853 -0.1950903 1 -0.9810834 -0.1935856 -1 -0.9810834 -0.1935856 1 -0.9813792 -0.1920804 -1 -0.9813792 -0.1920804 1 -0.9816727 -0.1905747 -1 -0.9816727 -0.1905747 1 -0.9819639 -0.1890686 -1 -0.9819639 -0.1890686 1 -0.9822527 -0.1875621 -1 -0.9822527 -0.1875621 1 -0.9825393 -0.1860551 -1 -0.9825393 -0.1860551 1 -0.9828236 -0.1845477 -1 -0.9828236 -0.1845477 1 -0.9831055 -0.1830399 -1 -0.9831055 -0.1830399 1 -0.9833851 -0.1815316 -1 -0.9833851 -0.1815316 1 -0.9836624 -0.1800229 -1 -0.9836624 -0.1800229 1 -0.9839375 -0.1785138 -1 -0.9839375 -0.1785138 1 -0.9842101 -0.1770042 -1 -0.9842101 -0.1770042 1 -0.9844805 -0.1754943 -1 -0.9844805 -0.1754943 1 -0.9847485 -0.1739838 -1 -0.9847485 -0.1739838 1 -0.9850143 -0.1724731 -1 -0.9850143 -0.1724731 1 -0.9852777 -0.1709619 -1 -0.9852777 -0.1709619 1 -0.9855387 -0.1694503 -1 -0.9855387 -0.1694503 1 -0.9857975 -0.1679382 -1 -0.9857975 -0.1679382 1 -0.986054 -0.1664259 -1 -0.986054 -0.1664259 1 -0.9863081 -0.1649131 -1 -0.9863081 -0.1649131 1 -0.9865599 -0.1633999 -1 -0.9865599 -0.1633999 1 -0.9868094 -0.1618863 -1 -0.9868094 -0.1618863 1 -0.9870566 -0.1603724 -1 -0.9870566 -0.1603724 1 -0.9873014 -0.1588581 -1 -0.9873014 -0.1588581 1 -0.987544 -0.1573435 -1 -0.987544 -0.1573435 1 -0.9877842 -0.1558284 -1 -0.9877842 -0.1558284 1 -0.988022 -0.154313 -1 -0.988022 -0.154313 1 -0.9882576 -0.1527972 -1 -0.9882576 -0.1527972 1 -0.9884908 -0.151281 -1 -0.9884908 -0.151281 1 -0.9887217 -0.1497645 -1 -0.9887217 -0.1497645 1 -0.9889503 -0.1482477 -1 -0.9889503 -0.1482477 1 -0.9891765 -0.1467304 -1 -0.9891765 -0.1467304 1 -0.9894005 -0.1452129 -1 -0.9894005 -0.1452129 1 -0.989622 -0.143695 -1 -0.989622 -0.143695 1 -0.9898413 -0.1421768 -1 -0.9898413 -0.1421768 1 -0.9900582 -0.1406582 -1 -0.9900582 -0.1406582 1 -0.9902728 -0.1391393 -1 -0.9902728 -0.1391393 1 -0.9904851 -0.1376201 -1 -0.9904851 -0.1376201 1 -0.990695 -0.1361005 -1 -0.990695 -0.1361005 1 -0.9909027 -0.1345807 -1 -0.9909027 -0.1345807 1 -0.991108 -0.1330605 -1 -0.991108 -0.1330605 1 -0.9913108 -0.13154 -1 -0.9913108 -0.13154 1 -0.9915115 -0.1300192 -1 -0.9915115 -0.1300192 1 -0.9917098 -0.1284981 -1 -0.9917098 -0.1284981 1 -0.9919057 -0.1269767 -1 -0.9919057 -0.1269767 1 -0.9920993 -0.125455 -1 -0.9920993 -0.125455 1 -0.9922906 -0.123933 -1 -0.9922906 -0.123933 1 -0.9924796 -0.1224107 -1 -0.9924796 -0.1224107 1 -0.9926661 -0.1208881 -1 -0.9926661 -0.1208881 1 -0.9928504 -0.1193652 -1 -0.9928504 -0.1193652 1 -0.9930323 -0.117842 -1 -0.9930323 -0.117842 1 -0.9932119 -0.1163186 -1 -0.9932119 -0.1163186 1 -0.9933892 -0.1147949 -1 -0.9933892 -0.1147949 1 -0.9935641 -0.1132709 -1 -0.9935641 -0.1132709 1 -0.9937368 -0.1117467 -1 -0.9937368 -0.1117467 1 -0.993907 -0.1102222 -1 -0.993907 -0.1102222 1 -0.9940749 -0.1086974 -1 -0.9940749 -0.1086974 1 -0.9942405 -0.1071724 -1 -0.9942405 -0.1071724 1 -0.9944037 -0.1056472 -1 -0.9944037 -0.1056472 1 -0.9945646 -0.1041216 -1 -0.9945646 -0.1041216 1 -0.9947232 -0.1025959 -1 -0.9947232 -0.1025959 1 -0.9948793 -0.1010698 -1 -0.9948793 -0.1010698 1 -0.9950332 -0.09954357 -1 -0.9950332 -0.09954357 1 -0.9951847 -0.09801709 -1 -0.9951847 -0.09801709 1 -0.9953339 -0.09649044 -1 -0.9953339 -0.09649044 1 -0.9954808 -0.09496349 -1 -0.9954808 -0.09496349 1 -0.9956253 -0.0934363 -1 -0.9956253 -0.0934363 1 -0.9957674 -0.09190893 -1 -0.9957674 -0.09190893 1 -0.9959073 -0.09038132 -1 -0.9959073 -0.09038132 1 -0.9960447 -0.08885353 -1 -0.9960447 -0.08885353 1 -0.9961798 -0.08732551 -1 -0.9961798 -0.08732551 1 -0.9963126 -0.0857973 -1 -0.9963126 -0.0857973 1 -0.996443 -0.08426886 -1 -0.996443 -0.08426886 1 -0.9965711 -0.08274024 -1 -0.9965711 -0.08274024 1 -0.9966969 -0.08121144 -1 -0.9966969 -0.08121144 1 -0.9968203 -0.0796824 -1 -0.9968203 -0.0796824 1 -0.9969413 -0.07815325 -1 -0.9969413 -0.07815325 1 -0.9970601 -0.07662385 -1 -0.9970601 -0.07662385 1 -0.9971764 -0.07509428 -1 -0.9971764 -0.07509428 1 -0.9972904 -0.07356452 -1 -0.9972904 -0.07356452 1 -0.9974021 -0.07203465 -1 -0.9974021 -0.07203465 1 -0.9975115 -0.07050454 -1 -0.9975115 -0.07050454 1 -0.9976184 -0.06897431 -1 -0.9976184 -0.06897431 1 -0.9977231 -0.0674439 -1 -0.9977231 -0.0674439 1 -0.9978253 -0.06591331 -1 -0.9978253 -0.06591331 1 -0.9979253 -0.06438261 -1 -0.9979253 -0.06438261 1 -0.9980229 -0.06285172 -1 -0.9980229 -0.06285172 1 -0.9981181 -0.06132072 -1 -0.9981181 -0.06132072 1 -0.998211 -0.05978953 -1 -0.998211 -0.05978953 1 -0.9983016 -0.05825823 -1 -0.9983016 -0.05825823 1 -0.9983897 -0.05672681 -1 -0.9983897 -0.05672681 1 -0.9984756 -0.05519521 -1 -0.9984756 -0.05519521 1 -0.9985591 -0.05366349 -1 -0.9985591 -0.05366349 1 -0.9986402 -0.05213171 -1 -0.9986402 -0.05213171 1 -0.998719 -0.05059975 -1 -0.998719 -0.05059975 1 -0.9987955 -0.04906767 -1 -0.9987955 -0.04906767 1 -0.9988695 -0.04753547 -1 -0.9988695 -0.04753547 1 -0.9989413 -0.04600316 -1 -0.9989413 -0.04600316 1 -0.9990107 -0.04447072 -1 -0.9990107 -0.04447072 1 -0.9990777 -0.04293823 -1 -0.9990777 -0.04293823 1 -0.9991424 -0.04140561 -1 -0.9991424 -0.04140561 1 -0.9992048 -0.03987288 -1 -0.9992048 -0.03987288 1 -0.9992648 -0.03834009 -1 -0.9992648 -0.03834009 1 -0.9993224 -0.03680717 -1 -0.9993224 -0.03680717 1 -0.9993777 -0.0352742 -1 -0.9993777 -0.0352742 1 -0.9994306 -0.03374117 -1 -0.9994306 -0.03374117 1 -0.9994812 -0.03220802 -1 -0.9994812 -0.03220802 1 -0.9995294 -0.03067475 -1 -0.9995294 -0.03067475 1 -0.9995753 -0.02914148 -1 -0.9995753 -0.02914148 1 -0.9996188 -0.02760809 -1 -0.9996188 -0.02760809 1 -0.99966 -0.0260747 -1 -0.99966 -0.0260747 1 -0.9996988 -0.02454119 -1 -0.9996988 -0.02454119 1 -0.9997353 -0.02300763 -1 -0.9997353 -0.02300763 1 -0.9997694 -0.02147406 -1 -0.9997694 -0.02147406 1 -0.9998012 -0.01994037 -1 -0.9998012 -0.01994037 1 -0.9998306 -0.01840668 -1 -0.9998306 -0.01840668 1 -0.9998577 -0.01687294 -1 -0.9998577 -0.01687294 1 -0.9998824 -0.01533919 -1 -0.9998824 -0.01533919 1 -0.9999047 -0.01380538 -1 -0.9999047 -0.01380538 1 -0.9999247 -0.01227152 -1 -0.9999247 -0.01227152 1 -0.9999424 -0.01073765 -1 -0.9999424 -0.01073765 1 -0.9999576 -0.009203732 -1 -0.9999576 -0.009203732 1 -0.9999706 -0.007669806 -1 -0.9999706 -0.007669806 1 -0.9999812 -0.00613588 -1 -0.9999812 -0.00613588 1 -0.9999894 -0.004601895 -1 -0.9999894 -0.004601895 1 -0.9999953 -0.00306791 -1 -0.9999953 -0.00306791 1 -0.9999988 -0.001533925 -1 -0.9999988 -0.001533925 1 -1 0 -1 -1 0 1 -0.9999988 0.001533925 -1 -0.9999988 0.001533925 1 -0.9999953 0.00306791 -1 -0.9999953 0.00306791 1 -0.9999894 0.004601895 -1 -0.9999894 0.004601895 1 -0.9999812 0.00613588 -1 -0.9999812 0.00613588 1 -0.9999706 0.007669806 -1 -0.9999706 0.007669806 1 -0.9999576 0.009203732 -1 -0.9999576 0.009203732 1 -0.9999424 0.01073765 -1 -0.9999424 0.01073765 1 -0.9999247 0.01227152 -1 -0.9999247 0.01227152 1 -0.9999047 0.01380538 -1 -0.9999047 0.01380538 1 -0.9998824 0.01533919 -1 -0.9998824 0.01533919 1 -0.9998577 0.01687294 -1 -0.9998577 0.01687294 1 -0.9998306 0.01840668 -1 -0.9998306 0.01840668 1 -0.9998012 0.01994037 -1 -0.9998012 0.01994037 1 -0.9997694 0.02147406 -1 -0.9997694 0.02147406 1 -0.9997353 0.02300763 -1 -0.9997353 0.02300763 1 -0.9996988 0.02454119 -1 -0.9996988 0.02454119 1 -0.99966 0.0260747 -1 -0.99966 0.0260747 1 -0.9996188 0.02760809 -1 -0.9996188 0.02760809 1 -0.9995753 0.02914148 -1 -0.9995753 0.02914148 1 -0.9995294 0.03067475 -1 -0.9995294 0.03067475 1 -0.9994812 0.03220802 -1 -0.9994812 0.03220802 1 -0.9994306 0.03374117 -1 -0.9994306 0.03374117 1 -0.9993777 0.0352742 -1 -0.9993777 0.0352742 1 -0.9993224 0.03680717 -1 -0.9993224 0.03680717 1 -0.9992648 0.03834009 -1 -0.9992648 0.03834009 1 -0.9992048 0.03987288 -1 -0.9992048 0.03987288 1 -0.9991424 0.04140561 -1 -0.9991424 0.04140561 1 -0.9990777 0.04293823 -1 -0.9990777 0.04293823 1 -0.9990107 0.04447072 -1 -0.9990107 0.04447072 1 -0.9989413 0.04600316 -1 -0.9989413 0.04600316 1 -0.9988695 0.04753547 -1 -0.9988695 0.04753547 1 -0.9987955 0.04906767 -1 -0.9987955 0.04906767 1 -0.998719 0.05059975 -1 -0.998719 0.05059975 1 -0.9986402 0.05213171 -1 -0.9986402 0.05213171 1 -0.9985591 0.05366349 -1 -0.9985591 0.05366349 1 -0.9984756 0.05519521 -1 -0.9984756 0.05519521 1 -0.9983897 0.05672681 -1 -0.9983897 0.05672681 1 -0.9983016 0.05825823 -1 -0.9983016 0.05825823 1 -0.998211 0.05978953 -1 -0.998211 0.05978953 1 -0.9981181 0.06132072 -1 -0.9981181 0.06132072 1 -0.9980229 0.06285172 -1 -0.9980229 0.06285172 1 -0.9979253 0.06438261 -1 -0.9979253 0.06438261 1 -0.9978253 0.06591331 -1 -0.9978253 0.06591331 1 -0.9977231 0.0674439 -1 -0.9977231 0.0674439 1 -0.9976184 0.06897431 -1 -0.9976184 0.06897431 1 -0.9975115 0.07050454 -1 -0.9975115 0.07050454 1 -0.9974021 0.07203465 -1 -0.9974021 0.07203465 1 -0.9972904 0.07356452 -1 -0.9972904 0.07356452 1 -0.9971764 0.07509428 -1 -0.9971764 0.07509428 1 -0.9970601 0.07662385 -1 -0.9970601 0.07662385 1 -0.9969413 0.07815325 -1 -0.9969413 0.07815325 1 -0.9968203 0.0796824 -1 -0.9968203 0.0796824 1 -0.9966969 0.08121144 -1 -0.9966969 0.08121144 1 -0.9965711 0.08274024 -1 -0.9965711 0.08274024 1 -0.996443 0.08426886 -1 -0.996443 0.08426886 1 -0.9963126 0.0857973 -1 -0.9963126 0.0857973 1 -0.9961798 0.08732551 -1 -0.9961798 0.08732551 1 -0.9960447 0.08885353 -1 -0.9960447 0.08885353 1 -0.9959073 0.09038132 -1 -0.9959073 0.09038132 1 -0.9957674 0.09190893 -1 -0.9957674 0.09190893 1 -0.9956253 0.0934363 -1 -0.9956253 0.0934363 1 -0.9954808 0.09496349 -1 -0.9954808 0.09496349 1 -0.9953339 0.09649044 -1 -0.9953339 0.09649044 1 -0.9951847 0.09801709 -1 -0.9951847 0.09801709 1 -0.9950332 0.09954357 -1 -0.9950332 0.09954357 1 -0.9948793 0.1010698 -1 -0.9948793 0.1010698 1 -0.9947232 0.1025959 -1 -0.9947232 0.1025959 1 -0.9945646 0.1041216 -1 -0.9945646 0.1041216 1 -0.9944037 0.1056472 -1 -0.9944037 0.1056472 1 -0.9942405 0.1071724 -1 -0.9942405 0.1071724 1 -0.9940749 0.1086974 -1 -0.9940749 0.1086974 1 -0.993907 0.1102222 -1 -0.993907 0.1102222 1 -0.9937368 0.1117467 -1 -0.9937368 0.1117467 1 -0.9935641 0.1132709 -1 -0.9935641 0.1132709 1 -0.9933892 0.1147949 -1 -0.9933892 0.1147949 1 -0.9932119 0.1163186 -1 -0.9932119 0.1163186 1 -0.9930323 0.117842 -1 -0.9930323 0.117842 1 -0.9928504 0.1193652 -1 -0.9928504 0.1193652 1 -0.9926661 0.1208881 -1 -0.9926661 0.1208881 1 -0.9924796 0.1224107 -1 -0.9924796 0.1224107 1 -0.9922906 0.123933 -1 -0.9922906 0.123933 1 -0.9920993 0.125455 -1 -0.9920993 0.125455 1 -0.9919057 0.1269767 -1 -0.9919057 0.1269767 1 -0.9917098 0.1284981 -1 -0.9917098 0.1284981 1 -0.9915115 0.1300192 -1 -0.9915115 0.1300192 1 -0.9913108 0.13154 -1 -0.9913108 0.13154 1 -0.991108 0.1330605 -1 -0.991108 0.1330605 1 -0.9909027 0.1345807 -1 -0.9909027 0.1345807 1 -0.990695 0.1361005 -1 -0.990695 0.1361005 1 -0.9904851 0.1376201 -1 -0.9904851 0.1376201 1 -0.9902728 0.1391393 -1 -0.9902728 0.1391393 1 -0.9900582 0.1406582 -1 -0.9900582 0.1406582 1 -0.9898413 0.1421768 -1 -0.9898413 0.1421768 1 -0.989622 0.143695 -1 -0.989622 0.143695 1 -0.9894005 0.1452129 -1 -0.9894005 0.1452129 1 -0.9891765 0.1467304 -1 -0.9891765 0.1467304 1 -0.9889503 0.1482477 -1 -0.9889503 0.1482477 1 -0.9887217 0.1497645 -1 -0.9887217 0.1497645 1 -0.9884908 0.151281 -1 -0.9884908 0.151281 1 -0.9882576 0.1527972 -1 -0.9882576 0.1527972 1 -0.988022 0.154313 -1 -0.988022 0.154313 1 -0.9877842 0.1558284 -1 -0.9877842 0.1558284 1 -0.987544 0.1573435 -1 -0.987544 0.1573435 1 -0.9873014 0.1588581 -1 -0.9873014 0.1588581 1 -0.9870566 0.1603724 -1 -0.9870566 0.1603724 1 -0.9868094 0.1618863 -1 -0.9868094 0.1618863 1 -0.9865599 0.1633999 -1 -0.9865599 0.1633999 1 -0.9863081 0.1649131 -1 -0.9863081 0.1649131 1 -0.986054 0.1664259 -1 -0.986054 0.1664259 1 -0.9857975 0.1679382 -1 -0.9857975 0.1679382 1 -0.9855387 0.1694503 -1 -0.9855387 0.1694503 1 -0.9852777 0.1709619 -1 -0.9852777 0.1709619 1 -0.9850143 0.1724731 -1 -0.9850143 0.1724731 1 -0.9847485 0.1739838 -1 -0.9847485 0.1739838 1 -0.9844805 0.1754943 -1 -0.9844805 0.1754943 1 -0.9842101 0.1770042 -1 -0.9842101 0.1770042 1 -0.9839375 0.1785138 -1 -0.9839375 0.1785138 1 -0.9836624 0.1800229 -1 -0.9836624 0.1800229 1 -0.9833851 0.1815316 -1 -0.9833851 0.1815316 1 -0.9831055 0.1830399 -1 -0.9831055 0.1830399 1 -0.9828236 0.1845477 -1 -0.9828236 0.1845477 1 -0.9825393 0.1860551 -1 -0.9825393 0.1860551 1 -0.9822527 0.1875621 -1 -0.9822527 0.1875621 1 -0.9819639 0.1890686 -1 -0.9819639 0.1890686 1 -0.9816727 0.1905747 -1 -0.9816727 0.1905747 1 -0.9813792 0.1920804 -1 -0.9813792 0.1920804 1 -0.9810834 0.1935856 -1 -0.9810834 0.1935856 1 -0.9807853 0.1950903 -1 -0.9807853 0.1950903 1 -0.9804849 0.1965946 -1 -0.9804849 0.1965946 1 -0.9801821 0.1980984 -1 -0.9801821 0.1980984 1 -0.9798771 0.1996017 -1 -0.9798771 0.1996017 1 -0.9795698 0.2011046 -1 -0.9795698 0.2011046 1 -0.9792602 0.202607 -1 -0.9792602 0.202607 1 -0.9789482 0.204109 -1 -0.9789482 0.204109 1 -0.9786339 0.2056104 -1 -0.9786339 0.2056104 1 -0.9783174 0.2071114 -1 -0.9783174 0.2071114 1 -0.9779985 0.2086118 -1 -0.9779985 0.2086118 1 -0.9776774 0.2101118 -1 -0.9776774 0.2101118 1 -0.9773539 0.2116113 -1 -0.9773539 0.2116113 1 -0.9770281 0.2131103 -1 -0.9770281 0.2131103 1 -0.9767001 0.2146088 -1 -0.9767001 0.2146088 1 -0.9763697 0.2161068 -1 -0.9763697 0.2161068 1 -0.9760371 0.2176042 -1 -0.9760371 0.2176042 1 -0.9757021 0.2191012 -1 -0.9757021 0.2191012 1 -0.9753649 0.2205977 -1 -0.9753649 0.2205977 1 -0.9750254 0.2220936 -1 -0.9750254 0.2220936 1 -0.9746835 0.223589 -1 -0.9746835 0.223589 1 -0.9743394 0.2250839 -1 -0.9743394 0.2250839 1 -0.973993 0.2265782 -1 -0.973993 0.2265782 1 -0.9736443 0.2280721 -1 -0.9736443 0.2280721 1 -0.9732933 0.2295653 -1 -0.9732933 0.2295653 1 -0.97294 0.2310581 -1 -0.97294 0.2310581 1 -0.9725844 0.2325503 -1 -0.9725844 0.2325503 1 -0.9722265 0.2340419 -1 -0.9722265 0.2340419 1 -0.9718663 0.235533 -1 -0.9718663 0.235533 1 -0.9715039 0.2370236 -1 -0.9715039 0.2370236 1 -0.9711391 0.2385136 -1 -0.9711391 0.2385136 1 -0.9707722 0.240003 -1 -0.9707722 0.240003 1 -0.9704028 0.2414919 -1 -0.9704028 0.2414919 1 -0.9700313 0.2429802 -1 -0.9700313 0.2429802 1 -0.9696574 0.2444679 -1 -0.9696574 0.2444679 1 -0.9692813 0.245955 -1 -0.9692813 0.245955 1 -0.9689028 0.2474416 -1 -0.9689028 0.2474416 1 -0.9685221 0.2489276 -1 -0.9685221 0.2489276 1 -0.9681391 0.250413 -1 -0.9681391 0.250413 1 -0.9677538 0.2518978 -1 -0.9677538 0.2518978 1 -0.9673663 0.253382 -1 -0.9673663 0.253382 1 -0.9669765 0.2548657 -1 -0.9669765 0.2548657 1 -0.9665844 0.2563487 -1 -0.9665844 0.2563487 1 -0.96619 0.2578311 -1 -0.96619 0.2578311 1 -0.9657934 0.2593129 -1 -0.9657934 0.2593129 1 -0.9653944 0.2607941 -1 -0.9653944 0.2607941 1 -0.9649932 0.2622747 -1 -0.9649932 0.2622747 1 -0.9645898 0.2637547 -1 -0.9645898 0.2637547 1 -0.9641841 0.2652341 -1 -0.9641841 0.2652341 1 -0.9637761 0.2667128 -1 -0.9637761 0.2667128 1 -0.9633658 0.2681909 -1 -0.9633658 0.2681909 1 -0.9629533 0.2696684 -1 -0.9629533 0.2696684 1 -0.9625385 0.2711452 -1 -0.9625385 0.2711452 1 -0.9621214 0.2726213 -1 -0.9621214 0.2726213 1 -0.9617021 0.2740969 -1 -0.9617021 0.2740969 1 -0.9612805 0.2755718 -1 -0.9612805 0.2755718 1 -0.9608566 0.2770461 -1 -0.9608566 0.2770461 1 -0.9604305 0.2785197 -1 -0.9604305 0.2785197 1 -0.9600021 0.2799926 -1 -0.9600021 0.2799926 1 -0.9595715 0.2814649 -1 -0.9595715 0.2814649 1 -0.9591386 0.2829366 -1 -0.9591386 0.2829366 1 -0.9587035 0.2844076 -1 -0.9587035 0.2844076 1 -0.9582661 0.2858778 -1 -0.9582661 0.2858778 1 -0.9578264 0.2873475 -1 -0.9578264 0.2873475 1 -0.9573845 0.2888164 -1 -0.9573845 0.2888164 1 -0.9569404 0.2902847 -1 -0.9569404 0.2902847 1 -0.9564939 0.2917523 -1 -0.9564939 0.2917523 1 -0.9560453 0.2932192 -1 -0.9560453 0.2932192 1 -0.9555943 0.2946854 -1 -0.9555943 0.2946854 1 -0.9551412 0.2961509 -1 -0.9551412 0.2961509 1 -0.9546858 0.2976157 -1 -0.9546858 0.2976157 1 -0.9542281 0.2990798 -1 -0.9542281 0.2990798 1 -0.9537682 0.3005433 -1 -0.9537682 0.3005433 1 -0.953306 0.302006 -1 -0.953306 0.302006 1 -0.9528416 0.3034679 -1 -0.9528416 0.3034679 1 -0.952375 0.3049293 -1 -0.952375 0.3049293 1 -0.9519062 0.3063898 -1 -0.9519062 0.3063898 1 -0.951435 0.3078497 -1 -0.951435 0.3078497 1 -0.9509617 0.3093088 -1 -0.9509617 0.3093088 1 -0.9504861 0.3107671 -1 -0.9504861 0.3107671 1 -0.9500082 0.3122248 -1 -0.9500082 0.3122248 1 -0.9495282 0.3136817 -1 -0.9495282 0.3136817 1 -0.9490459 0.3151379 -1 -0.9490459 0.3151379 1 -0.9485614 0.3165934 -1 -0.9485614 0.3165934 1 -0.9480746 0.3180481 -1 -0.9480746 0.3180481 1 -0.9475856 0.319502 -1 -0.9475856 0.319502 1 -0.9470944 0.3209552 -1 -0.9470944 0.3209552 1 -0.9466009 0.3224077 -1 -0.9466009 0.3224077 1 -0.9461053 0.3238593 -1 -0.9461053 0.3238593 1 -0.9456073 0.3253103 -1 -0.9456073 0.3253103 1 -0.9451072 0.3267605 -1 -0.9451072 0.3267605 1 -0.9446048 0.3282098 -1 -0.9446048 0.3282098 1 -0.9441003 0.3296585 -1 -0.9441003 0.3296585 1 -0.9435935 0.3311063 -1 -0.9435935 0.3311063 1 -0.9430844 0.3325534 -1 -0.9430844 0.3325534 1 -0.9425732 0.3339996 -1 -0.9425732 0.3339996 1 -0.9420598 0.3354452 -1 -0.9420598 0.3354452 1 -0.9415441 0.3368899 -1 -0.9415441 0.3368899 1 -0.9410262 0.3383337 -1 -0.9410262 0.3383337 1 -0.9405061 0.3397769 -1 -0.9405061 0.3397769 1 -0.9399837 0.3412192 -1 -0.9399837 0.3412192 1 -0.9394592 0.3426607 -1 -0.9394592 0.3426607 1 -0.9389325 0.3441014 -1 -0.9389325 0.3441014 1 -0.9384036 0.3455413 -1 -0.9384036 0.3455413 1 -0.9378724 0.3469804 -1 -0.9378724 0.3469804 1 -0.937339 0.3484187 -1 -0.937339 0.3484187 1 -0.9368035 0.3498561 -1 -0.9368035 0.3498561 1 -0.9362657 0.3512927 -1 -0.9362657 0.3512927 1 -0.9357257 0.3527286 -1 -0.9357257 0.3527286 1 -0.9351835 0.3541635 -1 -0.9351835 0.3541635 1 -0.9346391 0.3555977 -1 -0.9346391 0.3555977 1 -0.9340925 0.357031 -1 -0.9340925 0.357031 1 -0.9335438 0.3584634 -1 -0.9335438 0.3584634 1 -0.9329928 0.3598951 -1 -0.9329928 0.3598951 1 -0.9324396 0.3613258 -1 -0.9324396 0.3613258 1 -0.9318843 0.3627557 -1 -0.9318843 0.3627557 1 -0.9313267 0.3641848 -1 -0.9313267 0.3641848 1 -0.9307669 0.365613 -1 -0.9307669 0.365613 1 -0.930205 0.3670403 -1 -0.930205 0.3670403 1 -0.9296409 0.3684668 -1 -0.9296409 0.3684668 1 -0.9290746 0.3698924 -1 -0.9290746 0.3698924 1 -0.9285061 0.3713172 -1 -0.9285061 0.3713172 1 -0.9279354 0.3727411 -1 -0.9279354 0.3727411 1 -0.9273625 0.3741641 -1 -0.9273625 0.3741641 1 -0.9267875 0.3755862 -1 -0.9267875 0.3755862 1 -0.9262102 0.3770074 -1 -0.9262102 0.3770074 1 -0.9256308 0.3784278 -1 -0.9256308 0.3784278 1 -0.9250493 0.3798472 -1 -0.9250493 0.3798472 1 -0.9244655 0.3812658 -1 -0.9244655 0.3812658 1 -0.9238795 0.3826835 -1 -0.9238795 0.3826835 1 -0.9232914 0.3841002 -1 -0.9232914 0.3841002 1 -0.9227011 0.3855161 -1 -0.9227011 0.3855161 1 -0.9221087 0.386931 -1 -0.9221087 0.386931 1 -0.921514 0.388345 -1 -0.921514 0.388345 1 -0.9209172 0.3897582 -1 -0.9209172 0.3897582 1 -0.9203183 0.3911704 -1 -0.9203183 0.3911704 1 -0.9197171 0.3925817 -1 -0.9197171 0.3925817 1 -0.9191139 0.3939921 -1 -0.9191139 0.3939921 1 -0.9185084 0.3954015 -1 -0.9185084 0.3954015 1 -0.9179008 0.39681 -1 -0.9179008 0.39681 1 -0.917291 0.3982176 -1 -0.917291 0.3982176 1 -0.9166791 0.3996242 -1 -0.9166791 0.3996242 1 -0.916065 0.4010299 -1 -0.916065 0.4010299 1 -0.9154487 0.4024347 -1 -0.9154487 0.4024347 1 -0.9148303 0.4038385 -1 -0.9148303 0.4038385 1 -0.9142097 0.4052413 -1 -0.9142097 0.4052413 1 -0.913587 0.4066432 -1 -0.913587 0.4066432 1 -0.9129622 0.4080442 -1 -0.9129622 0.4080442 1 -0.9123352 0.4094442 -1 -0.9123352 0.4094442 1 -0.911706 0.4108432 -1 -0.911706 0.4108432 1 -0.9110748 0.4122412 -1 -0.9110748 0.4122412 1 -0.9104413 0.4136383 -1 -0.9104413 0.4136383 1 -0.9098057 0.4150344 -1 -0.9098057 0.4150344 1 -0.909168 0.4164296 -1 -0.909168 0.4164296 1 -0.9085281 0.4178237 -1 -0.9085281 0.4178237 1 -0.9078861 0.4192169 -1 -0.9078861 0.4192169 1 -0.907242 0.4206091 -1 -0.907242 0.4206091 1 -0.9065957 0.4220003 -1 -0.9065957 0.4220003 1 -0.9059473 0.4233905 -1 -0.9059473 0.4233905 1 -0.9052968 0.4247797 -1 -0.9052968 0.4247797 1 -0.9046441 0.4261679 -1 -0.9046441 0.4261679 1 -0.9039893 0.4275551 -1 -0.9039893 0.4275551 1 -0.9033324 0.4289413 -1 -0.9033324 0.4289413 1 -0.9026733 0.4303265 -1 -0.9026733 0.4303265 1 -0.9020121 0.4317107 -1 -0.9020121 0.4317107 1 -0.9013488 0.4330939 -1 -0.9013488 0.4330939 1 -0.9006834 0.434476 -1 -0.9006834 0.434476 1 -0.9000159 0.4358571 -1 -0.9000159 0.4358571 1 -0.8993462 0.4372372 -1 -0.8993462 0.4372372 1 -0.8986745 0.4386162 -1 -0.8986745 0.4386162 1 -0.8980006 0.4399943 -1 -0.8980006 0.4399943 1 -0.8973246 0.4413713 -1 -0.8973246 0.4413713 1 -0.8966464 0.4427472 -1 -0.8966464 0.4427472 1 -0.8959662 0.4441221 -1 -0.8959662 0.4441221 1 -0.8952839 0.445496 -1 -0.8952839 0.445496 1 -0.8945995 0.4468688 -1 -0.8945995 0.4468688 1 -0.893913 0.4482406 -1 -0.893913 0.4482406 1 -0.8932243 0.4496113 -1 -0.8932243 0.4496113 1 -0.8925336 0.450981 -1 -0.8925336 0.450981 1 -0.8918407 0.4523496 -1 -0.8918407 0.4523496 1 -0.8911458 0.4537171 -1 -0.8911458 0.4537171 1 -0.8904488 0.4550836 -1 -0.8904488 0.4550836 1 -0.8897496 0.456449 -1 -0.8897496 0.456449 1 -0.8890483 0.4578133 -1 -0.8890483 0.4578133 1 -0.888345 0.4591765 -1 -0.888345 0.4591765 1 -0.8876397 0.4605387 -1 -0.8876397 0.4605387 1 -0.8869321 0.4618998 -1 -0.8869321 0.4618998 1 -0.8862226 0.4632598 -1 -0.8862226 0.4632598 1 -0.8855109 0.4646187 -1 -0.8855109 0.4646187 1 -0.8847971 0.4659765 -1 -0.8847971 0.4659765 1 -0.8840813 0.4673332 -1 -0.8840813 0.4673332 1 -0.8833633 0.4686889 -1 -0.8833633 0.4686889 1 -0.8826434 0.4700433 -1 -0.8826434 0.4700433 1 -0.8819212 0.4713968 -1 -0.8819212 0.4713968 1 -0.8811971 0.4727491 -1 -0.8811971 0.4727491 1 -0.8804709 0.4741002 -1 -0.8804709 0.4741002 1 -0.8797426 0.4754503 -1 -0.8797426 0.4754503 1 -0.8790122 0.4767993 -1 -0.8790122 0.4767993 1 -0.8782798 0.478147 -1 -0.8782798 0.478147 1 -0.8775453 0.4794937 -1 -0.8775453 0.4794937 1 -0.8768087 0.4808393 -1 -0.8768087 0.4808393 1 -0.8760701 0.4821838 -1 -0.8760701 0.4821838 1 -0.8753294 0.4835271 -1 -0.8753294 0.4835271 1 -0.8745867 0.4848693 -1 -0.8745867 0.4848693 1 -0.8738418 0.4862103 -1 -0.8738418 0.4862103 1 -0.873095 0.4875501 -1 -0.873095 0.4875501 1 -0.8723461 0.4888889 -1 -0.8723461 0.4888889 1 -0.8715951 0.4902265 -1 -0.8715951 0.4902265 1 -0.870842 0.4915629 -1 -0.870842 0.4915629 1 -0.870087 0.4928982 -1 -0.870087 0.4928982 1 -0.8693299 0.4942323 -1 -0.8693299 0.4942323 1 -0.8685707 0.4955653 -1 -0.8685707 0.4955653 1 -0.8678095 0.4968971 -1 -0.8678095 0.4968971 1 -0.8670462 0.4982277 -1 -0.8670462 0.4982277 1 -0.866281 0.4995571 -1 -0.866281 0.4995571 1 -0.8655136 0.5008854 -1 -0.8655136 0.5008854 1 -0.8647443 0.5022125 -1 -0.8647443 0.5022125 1 -0.8639729 0.5035384 -1 -0.8639729 0.5035384 1 -0.8631994 0.5048632 -1 -0.8631994 0.5048632 1 -0.862424 0.5061867 -1 -0.862424 0.5061867 1 -0.8616465 0.507509 -1 -0.8616465 0.507509 1 -0.8608669 0.5088302 -1 -0.8608669 0.5088302 1 -0.8600854 0.5101501 -1 -0.8600854 0.5101501 1 -0.8593018 0.5114689 -1 -0.8593018 0.5114689 1 -0.8585162 0.5127865 -1 -0.8585162 0.5127865 1 -0.8577286 0.5141028 -1 -0.8577286 0.5141028 1 -0.856939 0.5154179 -1 -0.856939 0.5154179 1 -0.8561474 0.5167318 -1 -0.8561474 0.5167318 1 -0.8553537 0.5180445 -1 -0.8553537 0.5180445 1 -0.854558 0.519356 -1 -0.854558 0.519356 1 -0.8537603 0.5206663 -1 -0.8537603 0.5206663 1 -0.8529606 0.5219753 -1 -0.8529606 0.5219753 1 -0.8521589 0.5232831 -1 -0.8521589 0.5232831 1 -0.8513552 0.5245897 -1 -0.8513552 0.5245897 1 -0.8505495 0.5258951 -1 -0.8505495 0.5258951 1 -0.8497418 0.5271992 -1 -0.8497418 0.5271992 1 -0.848932 0.5285021 -1 -0.848932 0.5285021 1 -0.8481203 0.5298036 -1 -0.8481203 0.5298036 1 -0.8473066 0.531104 -1 -0.8473066 0.531104 1 -0.8464909 0.5324032 -1 -0.8464909 0.5324032 1 -0.8456733 0.533701 -1 -0.8456733 0.533701 1 -0.8448536 0.5349976 -1 -0.8448536 0.5349976 1 -0.8440319 0.536293 -1 -0.8440319 0.536293 1 -0.8432083 0.5375871 -1 -0.8432083 0.5375871 1 -0.8423826 0.5388799 -1 -0.8423826 0.5388799 1 -0.841555 0.5401715 -1 -0.841555 0.5401715 1 -0.8407254 0.5414618 -1 -0.8407254 0.5414618 1 -0.8398938 0.5427508 -1 -0.8398938 0.5427508 1 -0.8390603 0.5440385 -1 -0.8390603 0.5440385 1 -0.8382247 0.545325 -1 -0.8382247 0.545325 1 -0.8373872 0.5466102 -1 -0.8373872 0.5466102 1 -0.8365477 0.5478941 -1 -0.8365477 0.5478941 1 -0.8357062 0.5491767 -1 -0.8357062 0.5491767 1 -0.8348628 0.550458 -1 -0.8348628 0.550458 1 -0.8340175 0.551738 -1 -0.8340175 0.551738 1 -0.8331702 0.5530167 -1 -0.8331702 0.5530167 1 -0.8323209 0.5542941 -1 -0.8323209 0.5542941 1 -0.8314696 0.5555703 -1 -0.8314696 0.5555703 1 -0.8306164 0.5568451 -1 -0.8306164 0.5568451 1 -0.8297612 0.5581185 -1 -0.8297612 0.5581185 1 -0.8289041 0.5593907 -1 -0.8289041 0.5593907 1 -0.828045 0.5606616 -1 -0.828045 0.5606616 1 -0.827184 0.5619311 -1 -0.827184 0.5619311 1 -0.8263211 0.5631994 -1 -0.8263211 0.5631994 1 -0.8254562 0.5644662 -1 -0.8254562 0.5644662 1 -0.8245893 0.5657318 -1 -0.8245893 0.5657318 1 -0.8237205 0.5669961 -1 -0.8237205 0.5669961 1 -0.8228498 0.568259 -1 -0.8228498 0.568259 1 -0.8219771 0.5695205 -1 -0.8219771 0.5695205 1 -0.8211025 0.5707808 -1 -0.8211025 0.5707808 1 -0.820226 0.5720396 -1 -0.820226 0.5720396 1 -0.8193475 0.5732972 -1 -0.8193475 0.5732972 1 -0.8184671 0.5745534 -1 -0.8184671 0.5745534 1 -0.8175848 0.5758082 -1 -0.8175848 0.5758082 1 -0.8167006 0.5770617 -1 -0.8167006 0.5770617 1 -0.8158144 0.5783138 -1 -0.8158144 0.5783138 1 -0.8149263 0.5795646 -1 -0.8149263 0.5795646 1 -0.8140363 0.580814 -1 -0.8140363 0.580814 1 -0.8131444 0.582062 -1 -0.8131444 0.582062 1 -0.8122506 0.5833087 -1 -0.8122506 0.5833087 1 -0.8113548 0.584554 -1 -0.8113548 0.584554 1 -0.8104572 0.5857979 -1 -0.8104572 0.5857979 1 -0.8095577 0.5870404 -1 -0.8095577 0.5870404 1 -0.8086562 0.5882816 -1 -0.8086562 0.5882816 1 -0.8077529 0.5895213 -1 -0.8077529 0.5895213 1 -0.8068476 0.5907597 -1 -0.8068476 0.5907597 1 -0.8059404 0.5919967 -1 -0.8059404 0.5919967 1 -0.8050313 0.5932323 -1 -0.8050313 0.5932323 1 -0.8041204 0.5944665 -1 -0.8041204 0.5944665 1 -0.8032075 0.5956993 -1 -0.8032075 0.5956993 1 -0.8022928 0.5969308 -1 -0.8022928 0.5969308 1 -0.8013762 0.5981608 -1 -0.8013762 0.5981608 1 -0.8004577 0.5993893 -1 -0.8004577 0.5993893 1 -0.7995373 0.6006165 -1 -0.7995373 0.6006165 1 -0.798615 0.6018423 -1 -0.798615 0.6018423 1 -0.7976908 0.6030666 -1 -0.7976908 0.6030666 1 -0.7967648 0.6042895 -1 -0.7967648 0.6042895 1 -0.7958369 0.605511 -1 -0.7958369 0.605511 1 -0.7949072 0.6067311 -1 -0.7949072 0.6067311 1 -0.7939755 0.6079498 -1 -0.7939755 0.6079498 1 -0.793042 0.609167 -1 -0.793042 0.609167 1 -0.7921066 0.6103828 -1 -0.7921066 0.6103828 1 -0.7911694 0.6115972 -1 -0.7911694 0.6115972 1 -0.7902302 0.6128101 -1 -0.7902302 0.6128101 1 -0.7892892 0.6140216 -1 -0.7892892 0.6140216 1 -0.7883464 0.6152316 -1 -0.7883464 0.6152316 1 -0.7874017 0.6164402 -1 -0.7874017 0.6164402 1 -0.7864552 0.6176474 -1 -0.7864552 0.6176474 1 -0.7855068 0.618853 -1 -0.7855068 0.618853 1 -0.7845566 0.6200572 -1 -0.7845566 0.6200572 1 -0.7836045 0.62126 -1 -0.7836045 0.62126 1 -0.7826506 0.6224613 -1 -0.7826506 0.6224613 1 -0.7816948 0.6236611 -1 -0.7816948 0.6236611 1 -0.7807372 0.6248595 -1 -0.7807372 0.6248595 1 -0.7797778 0.6260564 -1 -0.7797778 0.6260564 1 -0.7788165 0.6272518 -1 -0.7788165 0.6272518 1 -0.7778534 0.6284458 -1 -0.7778534 0.6284458 1 -0.7768884 0.6296383 -1 -0.7768884 0.6296383 1 -0.7759217 0.6308293 -1 -0.7759217 0.6308293 1 -0.7749531 0.6320188 -1 -0.7749531 0.6320188 1 -0.7739827 0.6332068 -1 -0.7739827 0.6332068 1 -0.7730104 0.6343933 -1 -0.7730104 0.6343933 1 -0.7720364 0.6355783 -1 -0.7720364 0.6355783 1 -0.7710605 0.6367619 -1 -0.7710605 0.6367619 1 -0.7700828 0.6379439 -1 -0.7700828 0.6379439 1 -0.7691034 0.6391245 -1 -0.7691034 0.6391245 1 -0.768122 0.6403035 -1 -0.768122 0.6403035 1 -0.7671389 0.6414811 -1 -0.7671389 0.6414811 1 -0.766154 0.6426571 -1 -0.766154 0.6426571 1 -0.7651672 0.6438316 -1 -0.7651672 0.6438316 1 -0.7641788 0.6450046 -1 -0.7641788 0.6450046 1 -0.7631884 0.646176 -1 -0.7631884 0.646176 1 -0.7621963 0.647346 -1 -0.7621963 0.647346 1 -0.7612023 0.6485145 -1 -0.7612023 0.6485145 1 -0.7602066 0.6496813 -1 -0.7602066 0.6496813 1 -0.7592092 0.6508467 -1 -0.7592092 0.6508467 1 -0.7582099 0.6520106 -1 -0.7582099 0.6520106 1 -0.7572088 0.6531729 -1 -0.7572088 0.6531729 1 -0.756206 0.6543336 -1 -0.756206 0.6543336 1 -0.7552014 0.6554929 -1 -0.7552014 0.6554929 1 -0.754195 0.6566506 -1 -0.754195 0.6566506 1 -0.7531868 0.6578067 -1 -0.7531868 0.6578067 1 -0.7521768 0.6589613 -1 -0.7521768 0.6589613 1 -0.7511651 0.6601144 -1 -0.7511651 0.6601144 1 -0.7501516 0.6612659 -1 -0.7501516 0.6612659 1 -0.7491364 0.6624158 -1 -0.7491364 0.6624158 1 -0.7481194 0.6635642 -1 -0.7481194 0.6635642 1 -0.7471006 0.664711 -1 -0.7471006 0.664711 1 -0.7460801 0.6658563 -1 -0.7460801 0.6658563 1 -0.7450578 0.6669999 -1 -0.7450578 0.6669999 1 -0.7440337 0.6681421 -1 -0.7440337 0.6681421 1 -0.743008 0.6692826 -1 -0.743008 0.6692826 1 -0.7419804 0.6704216 -1 -0.7419804 0.6704216 1 -0.7409511 0.671559 -1 -0.7409511 0.671559 1 -0.7399201 0.6726948 -1 -0.7399201 0.6726948 1 -0.7388873 0.673829 -1 -0.7388873 0.673829 1 -0.7378528 0.6749617 -1 -0.7378528 0.6749617 1 -0.7368166 0.6760928 -1 -0.7368166 0.6760928 1 -0.7357786 0.6772222 -1 -0.7357786 0.6772222 1 -0.7347389 0.6783501 -1 -0.7347389 0.6783501 1 -0.7336974 0.6794763 -1 -0.7336974 0.6794763 1 -0.7326543 0.680601 -1 -0.7326543 0.680601 1 -0.7316094 0.6817241 -1 -0.7316094 0.6817241 1 -0.7305628 0.6828456 -1 -0.7305628 0.6828456 1 -0.7295144 0.6839655 -1 -0.7295144 0.6839655 1 -0.7284644 0.6850837 -1 -0.7284644 0.6850837 1 -0.7274127 0.6862003 -1 -0.7274127 0.6862003 1 -0.7263591 0.6873154 -1 -0.7263591 0.6873154 1 -0.725304 0.6884288 -1 -0.725304 0.6884288 1 -0.7242471 0.6895406 -1 -0.7242471 0.6895406 1 -0.7231885 0.6906507 -1 -0.7231885 0.6906507 1 -0.7221282 0.6917593 -1 -0.7221282 0.6917593 1 -0.7210662 0.6928662 -1 -0.7210662 0.6928662 1 -0.7200025 0.6939715 -1 -0.7200025 0.6939715 1 -0.7189371 0.6950752 -1 -0.7189371 0.6950752 1 -0.71787 0.6961772 -1 -0.71787 0.6961772 1 -0.7168012 0.6972776 -1 -0.7168012 0.6972776 1 -0.7157308 0.6983763 -1 -0.7157308 0.6983763 1 -0.7146587 0.6994734 -1 -0.7146587 0.6994734 1 -0.7135849 0.7005688 -1 -0.7135849 0.7005688 1 -0.7125094 0.7016626 -1 -0.7125094 0.7016626 1 -0.7114322 0.7027547 -1 -0.7114322 0.7027547 1 -0.7103533 0.7038453 -1 -0.7103533 0.7038453 1 -0.7092728 0.7049341 -1 -0.7092728 0.7049341 1 -0.7081906 0.7060213 -1 -0.7081906 0.7060213 1 -0.7071068 0.7071068 -1 -0.7071068 0.7071068 1 -0.7060213 0.7081906 -1 -0.7060213 0.7081906 1 -0.7049341 0.7092728 -1 -0.7049341 0.7092728 1 -0.7038453 0.7103533 -1 -0.7038453 0.7103533 1 -0.7027547 0.7114322 -1 -0.7027547 0.7114322 1 -0.7016626 0.7125094 -1 -0.7016626 0.7125094 1 -0.7005688 0.7135849 -1 -0.7005688 0.7135849 1 -0.6994734 0.7146587 -1 -0.6994734 0.7146587 1 -0.6983763 0.7157308 -1 -0.6983763 0.7157308 1 -0.6972776 0.7168012 -1 -0.6972776 0.7168012 1 -0.6961772 0.71787 -1 -0.6961772 0.71787 1 -0.6950752 0.7189371 -1 -0.6950752 0.7189371 1 -0.6939715 0.7200025 -1 -0.6939715 0.7200025 1 -0.6928662 0.7210662 -1 -0.6928662 0.7210662 1 -0.6917593 0.7221282 -1 -0.6917593 0.7221282 1 -0.6906507 0.7231885 -1 -0.6906507 0.7231885 1 -0.6895406 0.7242471 -1 -0.6895406 0.7242471 1 -0.6884288 0.725304 -1 -0.6884288 0.725304 1 -0.6873154 0.7263591 -1 -0.6873154 0.7263591 1 -0.6862003 0.7274127 -1 -0.6862003 0.7274127 1 -0.6850837 0.7284644 -1 -0.6850837 0.7284644 1 -0.6839655 0.7295144 -1 -0.6839655 0.7295144 1 -0.6828456 0.7305628 -1 -0.6828456 0.7305628 1 -0.6817241 0.7316094 -1 -0.6817241 0.7316094 1 -0.680601 0.7326543 -1 -0.680601 0.7326543 1 -0.6794763 0.7336974 -1 -0.6794763 0.7336974 1 -0.6783501 0.7347389 -1 -0.6783501 0.7347389 1 -0.6772222 0.7357786 -1 -0.6772222 0.7357786 1 -0.6760928 0.7368166 -1 -0.6760928 0.7368166 1 -0.6749617 0.7378528 -1 -0.6749617 0.7378528 1 -0.673829 0.7388873 -1 -0.673829 0.7388873 1 -0.6726948 0.7399201 -1 -0.6726948 0.7399201 1 -0.671559 0.7409511 -1 -0.671559 0.7409511 1 -0.6704216 0.7419804 -1 -0.6704216 0.7419804 1 -0.6692826 0.743008 -1 -0.6692826 0.743008 1 -0.6681421 0.7440337 -1 -0.6681421 0.7440337 1 -0.6669999 0.7450578 -1 -0.6669999 0.7450578 1 -0.6658563 0.7460801 -1 -0.6658563 0.7460801 1 -0.664711 0.7471006 -1 -0.664711 0.7471006 1 -0.6635642 0.7481194 -1 -0.6635642 0.7481194 1 -0.6624158 0.7491364 -1 -0.6624158 0.7491364 1 -0.6612659 0.7501516 -1 -0.6612659 0.7501516 1 -0.6601144 0.7511651 -1 -0.6601144 0.7511651 1 -0.6589613 0.7521768 -1 -0.6589613 0.7521768 1 -0.6578067 0.7531868 -1 -0.6578067 0.7531868 1 -0.6566506 0.754195 -1 -0.6566506 0.754195 1 -0.6554929 0.7552014 -1 -0.6554929 0.7552014 1 -0.6543336 0.756206 -1 -0.6543336 0.756206 1 -0.6531729 0.7572088 -1 -0.6531729 0.7572088 1 -0.6520106 0.7582099 -1 -0.6520106 0.7582099 1 -0.6508467 0.7592092 -1 -0.6508467 0.7592092 1 -0.6496813 0.7602066 -1 -0.6496813 0.7602066 1 -0.6485145 0.7612023 -1 -0.6485145 0.7612023 1 -0.647346 0.7621963 -1 -0.647346 0.7621963 1 -0.646176 0.7631884 -1 -0.646176 0.7631884 1 -0.6450046 0.7641788 -1 -0.6450046 0.7641788 1 -0.6438316 0.7651672 -1 -0.6438316 0.7651672 1 -0.6426571 0.766154 -1 -0.6426571 0.766154 1 -0.6414811 0.7671389 -1 -0.6414811 0.7671389 1 -0.6403035 0.768122 -1 -0.6403035 0.768122 1 -0.6391245 0.7691034 -1 -0.6391245 0.7691034 1 -0.6379439 0.7700828 -1 -0.6379439 0.7700828 1 -0.6367619 0.7710605 -1 -0.6367619 0.7710605 1 -0.6355783 0.7720364 -1 -0.6355783 0.7720364 1 -0.6343933 0.7730104 -1 -0.6343933 0.7730104 1 -0.6332068 0.7739827 -1 -0.6332068 0.7739827 1 -0.6320188 0.7749531 -1 -0.6320188 0.7749531 1 -0.6308293 0.7759217 -1 -0.6308293 0.7759217 1 -0.6296383 0.7768884 -1 -0.6296383 0.7768884 1 -0.6284458 0.7778534 -1 -0.6284458 0.7778534 1 -0.6272518 0.7788165 -1 -0.6272518 0.7788165 1 -0.6260564 0.7797778 -1 -0.6260564 0.7797778 1 -0.6248595 0.7807372 -1 -0.6248595 0.7807372 1 -0.6236611 0.7816948 -1 -0.6236611 0.7816948 1 -0.6224613 0.7826506 -1 -0.6224613 0.7826506 1 -0.62126 0.7836045 -1 -0.62126 0.7836045 1 -0.6200572 0.7845566 -1 -0.6200572 0.7845566 1 -0.618853 0.7855068 -1 -0.618853 0.7855068 1 -0.6176474 0.7864552 -1 -0.6176474 0.7864552 1 -0.6164402 0.7874017 -1 -0.6164402 0.7874017 1 -0.6152316 0.7883464 -1 -0.6152316 0.7883464 1 -0.6140216 0.7892892 -1 -0.6140216 0.7892892 1 -0.6128101 0.7902302 -1 -0.6128101 0.7902302 1 -0.6115972 0.7911694 -1 -0.6115972 0.7911694 1 -0.6103828 0.7921066 -1 -0.6103828 0.7921066 1 -0.609167 0.793042 -1 -0.609167 0.793042 1 -0.6079498 0.7939755 -1 -0.6079498 0.7939755 1 -0.6067311 0.7949072 -1 -0.6067311 0.7949072 1 -0.605511 0.7958369 -1 -0.605511 0.7958369 1 -0.6042895 0.7967648 -1 -0.6042895 0.7967648 1 -0.6030666 0.7976908 -1 -0.6030666 0.7976908 1 -0.6018423 0.798615 -1 -0.6018423 0.798615 1 -0.6006165 0.7995373 -1 -0.6006165 0.7995373 1 -0.5993893 0.8004577 -1 -0.5993893 0.8004577 1 -0.5981608 0.8013762 -1 -0.5981608 0.8013762 1 -0.5969308 0.8022928 -1 -0.5969308 0.8022928 1 -0.5956993 0.8032075 -1 -0.5956993 0.8032075 1 -0.5944665 0.8041204 -1 -0.5944665 0.8041204 1 -0.5932323 0.8050313 -1 -0.5932323 0.8050313 1 -0.5919967 0.8059404 -1 -0.5919967 0.8059404 1 -0.5907597 0.8068476 -1 -0.5907597 0.8068476 1 -0.5895213 0.8077529 -1 -0.5895213 0.8077529 1 -0.5882816 0.8086562 -1 -0.5882816 0.8086562 1 -0.5870404 0.8095577 -1 -0.5870404 0.8095577 1 -0.5857979 0.8104572 -1 -0.5857979 0.8104572 1 -0.584554 0.8113548 -1 -0.584554 0.8113548 1 -0.5833087 0.8122506 -1 -0.5833087 0.8122506 1 -0.582062 0.8131444 -1 -0.582062 0.8131444 1 -0.580814 0.8140363 -1 -0.580814 0.8140363 1 -0.5795646 0.8149263 -1 -0.5795646 0.8149263 1 -0.5783138 0.8158144 -1 -0.5783138 0.8158144 1 -0.5770617 0.8167006 -1 -0.5770617 0.8167006 1 -0.5758082 0.8175848 -1 -0.5758082 0.8175848 1 -0.5745534 0.8184671 -1 -0.5745534 0.8184671 1 -0.5732972 0.8193475 -1 -0.5732972 0.8193475 1 -0.5720396 0.820226 -1 -0.5720396 0.820226 1 -0.5707808 0.8211025 -1 -0.5707808 0.8211025 1 -0.5695205 0.8219771 -1 -0.5695205 0.8219771 1 -0.568259 0.8228498 -1 -0.568259 0.8228498 1 -0.5669961 0.8237205 -1 -0.5669961 0.8237205 1 -0.5657318 0.8245893 -1 -0.5657318 0.8245893 1 -0.5644662 0.8254562 -1 -0.5644662 0.8254562 1 -0.5631994 0.8263211 -1 -0.5631994 0.8263211 1 -0.5619311 0.827184 -1 -0.5619311 0.827184 1 -0.5606616 0.828045 -1 -0.5606616 0.828045 1 -0.5593907 0.8289041 -1 -0.5593907 0.8289041 1 -0.5581185 0.8297612 -1 -0.5581185 0.8297612 1 -0.5568451 0.8306164 -1 -0.5568451 0.8306164 1 -0.5555703 0.8314696 -1 -0.5555703 0.8314696 1 -0.5542941 0.8323209 -1 -0.5542941 0.8323209 1 -0.5530167 0.8331702 -1 -0.5530167 0.8331702 1 -0.551738 0.8340175 -1 -0.551738 0.8340175 1 -0.550458 0.8348628 -1 -0.550458 0.8348628 1 -0.5491767 0.8357062 -1 -0.5491767 0.8357062 1 -0.5478941 0.8365477 -1 -0.5478941 0.8365477 1 -0.5466102 0.8373872 -1 -0.5466102 0.8373872 1 -0.545325 0.8382247 -1 -0.545325 0.8382247 1 -0.5440385 0.8390603 -1 -0.5440385 0.8390603 1 -0.5427508 0.8398938 -1 -0.5427508 0.8398938 1 -0.5414618 0.8407254 -1 -0.5414618 0.8407254 1 -0.5401715 0.841555 -1 -0.5401715 0.841555 1 -0.5388799 0.8423826 -1 -0.5388799 0.8423826 1 -0.5375871 0.8432083 -1 -0.5375871 0.8432083 1 -0.536293 0.8440319 -1 -0.536293 0.8440319 1 -0.5349976 0.8448536 -1 -0.5349976 0.8448536 1 -0.533701 0.8456733 -1 -0.533701 0.8456733 1 -0.5324032 0.8464909 -1 -0.5324032 0.8464909 1 -0.531104 0.8473066 -1 -0.531104 0.8473066 1 -0.5298036 0.8481203 -1 -0.5298036 0.8481203 1 -0.5285021 0.848932 -1 -0.5285021 0.848932 1 -0.5271992 0.8497418 -1 -0.5271992 0.8497418 1 -0.5258951 0.8505495 -1 -0.5258951 0.8505495 1 -0.5245897 0.8513552 -1 -0.5245897 0.8513552 1 -0.5232831 0.8521589 -1 -0.5232831 0.8521589 1 -0.5219753 0.8529606 -1 -0.5219753 0.8529606 1 -0.5206663 0.8537603 -1 -0.5206663 0.8537603 1 -0.519356 0.854558 -1 -0.519356 0.854558 1 -0.5180445 0.8553537 -1 -0.5180445 0.8553537 1 -0.5167318 0.8561474 -1 -0.5167318 0.8561474 1 -0.5154179 0.856939 -1 -0.5154179 0.856939 1 -0.5141028 0.8577286 -1 -0.5141028 0.8577286 1 -0.5127865 0.8585162 -1 -0.5127865 0.8585162 1 -0.5114689 0.8593018 -1 -0.5114689 0.8593018 1 -0.5101501 0.8600854 -1 -0.5101501 0.8600854 1 -0.5088302 0.8608669 -1 -0.5088302 0.8608669 1 -0.507509 0.8616465 -1 -0.507509 0.8616465 1 -0.5061867 0.862424 -1 -0.5061867 0.862424 1 -0.5048632 0.8631994 -1 -0.5048632 0.8631994 1 -0.5035384 0.8639729 -1 -0.5035384 0.8639729 1 -0.5022125 0.8647443 -1 -0.5022125 0.8647443 1 -0.5008854 0.8655136 -1 -0.5008854 0.8655136 1 -0.4995571 0.866281 -1 -0.4995571 0.866281 1 -0.4982277 0.8670462 -1 -0.4982277 0.8670462 1 -0.4968971 0.8678095 -1 -0.4968971 0.8678095 1 -0.4955653 0.8685707 -1 -0.4955653 0.8685707 1 -0.4942323 0.8693299 -1 -0.4942323 0.8693299 1 -0.4928982 0.870087 -1 -0.4928982 0.870087 1 -0.4915629 0.870842 -1 -0.4915629 0.870842 1 -0.4902265 0.8715951 -1 -0.4902265 0.8715951 1 -0.4888889 0.8723461 -1 -0.4888889 0.8723461 1 -0.4875501 0.873095 -1 -0.4875501 0.873095 1 -0.4862103 0.8738418 -1 -0.4862103 0.8738418 1 -0.4848693 0.8745867 -1 -0.4848693 0.8745867 1 -0.4835271 0.8753294 -1 -0.4835271 0.8753294 1 -0.4821838 0.8760701 -1 -0.4821838 0.8760701 1 -0.4808393 0.8768087 -1 -0.4808393 0.8768087 1 -0.4794937 0.8775453 -1 -0.4794937 0.8775453 1 -0.478147 0.8782798 -1 -0.478147 0.8782798 1 -0.4767993 0.8790122 -1 -0.4767993 0.8790122 1 -0.4754503 0.8797426 -1 -0.4754503 0.8797426 1 -0.4741002 0.8804709 -1 -0.4741002 0.8804709 1 -0.4727491 0.8811971 -1 -0.4727491 0.8811971 1 -0.4713968 0.8819212 -1 -0.4713968 0.8819212 1 -0.4700433 0.8826434 -1 -0.4700433 0.8826434 1 -0.4686889 0.8833633 -1 -0.4686889 0.8833633 1 -0.4673332 0.8840813 -1 -0.4673332 0.8840813 1 -0.4659765 0.8847971 -1 -0.4659765 0.8847971 1 -0.4646187 0.8855109 -1 -0.4646187 0.8855109 1 -0.4632598 0.8862226 -1 -0.4632598 0.8862226 1 -0.4618998 0.8869321 -1 -0.4618998 0.8869321 1 -0.4605387 0.8876397 -1 -0.4605387 0.8876397 1 -0.4591765 0.888345 -1 -0.4591765 0.888345 1 -0.4578133 0.8890483 -1 -0.4578133 0.8890483 1 -0.456449 0.8897496 -1 -0.456449 0.8897496 1 -0.4550836 0.8904488 -1 -0.4550836 0.8904488 1 -0.4537171 0.8911458 -1 -0.4537171 0.8911458 1 -0.4523496 0.8918407 -1 -0.4523496 0.8918407 1 -0.450981 0.8925336 -1 -0.450981 0.8925336 1 -0.4496113 0.8932243 -1 -0.4496113 0.8932243 1 -0.4482406 0.893913 -1 -0.4482406 0.893913 1 -0.4468688 0.8945995 -1 -0.4468688 0.8945995 1 -0.445496 0.8952839 -1 -0.445496 0.8952839 1 -0.4441221 0.8959662 -1 -0.4441221 0.8959662 1 -0.4427472 0.8966464 -1 -0.4427472 0.8966464 1 -0.4413713 0.8973246 -1 -0.4413713 0.8973246 1 -0.4399943 0.8980006 -1 -0.4399943 0.8980006 1 -0.4386162 0.8986745 -1 -0.4386162 0.8986745 1 -0.4372372 0.8993462 -1 -0.4372372 0.8993462 1 -0.4358571 0.9000159 -1 -0.4358571 0.9000159 1 -0.434476 0.9006834 -1 -0.434476 0.9006834 1 -0.4330939 0.9013488 -1 -0.4330939 0.9013488 1 -0.4317107 0.9020121 -1 -0.4317107 0.9020121 1 -0.4303265 0.9026733 -1 -0.4303265 0.9026733 1 -0.4289413 0.9033324 -1 -0.4289413 0.9033324 1 -0.4275551 0.9039893 -1 -0.4275551 0.9039893 1 -0.4261679 0.9046441 -1 -0.4261679 0.9046441 1 -0.4247797 0.9052968 -1 -0.4247797 0.9052968 1 -0.4233905 0.9059473 -1 -0.4233905 0.9059473 1 -0.4220003 0.9065957 -1 -0.4220003 0.9065957 1 -0.4206091 0.907242 -1 -0.4206091 0.907242 1 -0.4192169 0.9078861 -1 -0.4192169 0.9078861 1 -0.4178237 0.9085281 -1 -0.4178237 0.9085281 1 -0.4164296 0.909168 -1 -0.4164296 0.909168 1 -0.4150344 0.9098057 -1 -0.4150344 0.9098057 1 -0.4136383 0.9104413 -1 -0.4136383 0.9104413 1 -0.4122412 0.9110748 -1 -0.4122412 0.9110748 1 -0.4108432 0.911706 -1 -0.4108432 0.911706 1 -0.4094442 0.9123352 -1 -0.4094442 0.9123352 1 -0.4080442 0.9129622 -1 -0.4080442 0.9129622 1 -0.4066432 0.913587 -1 -0.4066432 0.913587 1 -0.4052413 0.9142097 -1 -0.4052413 0.9142097 1 -0.4038385 0.9148303 -1 -0.4038385 0.9148303 1 -0.4024347 0.9154487 -1 -0.4024347 0.9154487 1 -0.4010299 0.916065 -1 -0.4010299 0.916065 1 -0.3996242 0.9166791 -1 -0.3996242 0.9166791 1 -0.3982176 0.917291 -1 -0.3982176 0.917291 1 -0.39681 0.9179008 -1 -0.39681 0.9179008 1 -0.3954015 0.9185084 -1 -0.3954015 0.9185084 1 -0.3939921 0.9191139 -1 -0.3939921 0.9191139 1 -0.3925817 0.9197171 -1 -0.3925817 0.9197171 1 -0.3911704 0.9203183 -1 -0.3911704 0.9203183 1 -0.3897582 0.9209172 -1 -0.3897582 0.9209172 1 -0.388345 0.921514 -1 -0.388345 0.921514 1 -0.386931 0.9221087 -1 -0.386931 0.9221087 1 -0.3855161 0.9227011 -1 -0.3855161 0.9227011 1 -0.3841002 0.9232914 -1 -0.3841002 0.9232914 1 -0.3826835 0.9238795 -1 -0.3826835 0.9238795 1 -0.3812658 0.9244655 -1 -0.3812658 0.9244655 1 -0.3798472 0.9250493 -1 -0.3798472 0.9250493 1 -0.3784278 0.9256308 -1 -0.3784278 0.9256308 1 -0.3770074 0.9262102 -1 -0.3770074 0.9262102 1 -0.3755862 0.9267875 -1 -0.3755862 0.9267875 1 -0.3741641 0.9273625 -1 -0.3741641 0.9273625 1 -0.3727411 0.9279354 -1 -0.3727411 0.9279354 1 -0.3713172 0.9285061 -1 -0.3713172 0.9285061 1 -0.3698924 0.9290746 -1 -0.3698924 0.9290746 1 -0.3684668 0.9296409 -1 -0.3684668 0.9296409 1 -0.3670403 0.930205 -1 -0.3670403 0.930205 1 -0.365613 0.9307669 -1 -0.365613 0.9307669 1 -0.3641848 0.9313267 -1 -0.3641848 0.9313267 1 -0.3627557 0.9318843 -1 -0.3627557 0.9318843 1 -0.3613258 0.9324396 -1 -0.3613258 0.9324396 1 -0.3598951 0.9329928 -1 -0.3598951 0.9329928 1 -0.3584634 0.9335438 -1 -0.3584634 0.9335438 1 -0.357031 0.9340925 -1 -0.357031 0.9340925 1 -0.3555977 0.9346391 -1 -0.3555977 0.9346391 1 -0.3541635 0.9351835 -1 -0.3541635 0.9351835 1 -0.3527286 0.9357257 -1 -0.3527286 0.9357257 1 -0.3512927 0.9362657 -1 -0.3512927 0.9362657 1 -0.3498561 0.9368035 -1 -0.3498561 0.9368035 1 -0.3484187 0.937339 -1 -0.3484187 0.937339 1 -0.3469804 0.9378724 -1 -0.3469804 0.9378724 1 -0.3455413 0.9384036 -1 -0.3455413 0.9384036 1 -0.3441014 0.9389325 -1 -0.3441014 0.9389325 1 -0.3426607 0.9394592 -1 -0.3426607 0.9394592 1 -0.3412192 0.9399837 -1 -0.3412192 0.9399837 1 -0.3397769 0.9405061 -1 -0.3397769 0.9405061 1 -0.3383337 0.9410262 -1 -0.3383337 0.9410262 1 -0.3368899 0.9415441 -1 -0.3368899 0.9415441 1 -0.3354452 0.9420598 -1 -0.3354452 0.9420598 1 -0.3339996 0.9425732 -1 -0.3339996 0.9425732 1 -0.3325534 0.9430844 -1 -0.3325534 0.9430844 1 -0.3311063 0.9435935 -1 -0.3311063 0.9435935 1 -0.3296585 0.9441003 -1 -0.3296585 0.9441003 1 -0.3282098 0.9446048 -1 -0.3282098 0.9446048 1 -0.3267605 0.9451072 -1 -0.3267605 0.9451072 1 -0.3253103 0.9456073 -1 -0.3253103 0.9456073 1 -0.3238593 0.9461053 -1 -0.3238593 0.9461053 1 -0.3224077 0.9466009 -1 -0.3224077 0.9466009 1 -0.3209552 0.9470944 -1 -0.3209552 0.9470944 1 -0.319502 0.9475856 -1 -0.319502 0.9475856 1 -0.3180481 0.9480746 -1 -0.3180481 0.9480746 1 -0.3165934 0.9485614 -1 -0.3165934 0.9485614 1 -0.3151379 0.9490459 -1 -0.3151379 0.9490459 1 -0.3136817 0.9495282 -1 -0.3136817 0.9495282 1 -0.3122248 0.9500082 -1 -0.3122248 0.9500082 1 -0.3107671 0.9504861 -1 -0.3107671 0.9504861 1 -0.3093088 0.9509617 -1 -0.3093088 0.9509617 1 -0.3078497 0.951435 -1 -0.3078497 0.951435 1 -0.3063898 0.9519062 -1 -0.3063898 0.9519062 1 -0.3049293 0.952375 -1 -0.3049293 0.952375 1 -0.3034679 0.9528416 -1 -0.3034679 0.9528416 1 -0.302006 0.953306 -1 -0.302006 0.953306 1 -0.3005433 0.9537682 -1 -0.3005433 0.9537682 1 -0.2990798 0.9542281 -1 -0.2990798 0.9542281 1 -0.2976157 0.9546858 -1 -0.2976157 0.9546858 1 -0.2961509 0.9551412 -1 -0.2961509 0.9551412 1 -0.2946854 0.9555943 -1 -0.2946854 0.9555943 1 -0.2932192 0.9560453 -1 -0.2932192 0.9560453 1 -0.2917523 0.9564939 -1 -0.2917523 0.9564939 1 -0.2902847 0.9569404 -1 -0.2902847 0.9569404 1 -0.2888164 0.9573845 -1 -0.2888164 0.9573845 1 -0.2873475 0.9578264 -1 -0.2873475 0.9578264 1 -0.2858778 0.9582661 -1 -0.2858778 0.9582661 1 -0.2844076 0.9587035 -1 -0.2844076 0.9587035 1 -0.2829366 0.9591386 -1 -0.2829366 0.9591386 1 -0.2814649 0.9595715 -1 -0.2814649 0.9595715 1 -0.2799926 0.9600021 -1 -0.2799926 0.9600021 1 -0.2785197 0.9604305 -1 -0.2785197 0.9604305 1 -0.2770461 0.9608566 -1 -0.2770461 0.9608566 1 -0.2755718 0.9612805 -1 -0.2755718 0.9612805 1 -0.2740969 0.9617021 -1 -0.2740969 0.9617021 1 -0.2726213 0.9621214 -1 -0.2726213 0.9621214 1 -0.2711452 0.9625385 -1 -0.2711452 0.9625385 1 -0.2696684 0.9629533 -1 -0.2696684 0.9629533 1 -0.2681909 0.9633658 -1 -0.2681909 0.9633658 1 -0.2667128 0.9637761 -1 -0.2667128 0.9637761 1 -0.2652341 0.9641841 -1 -0.2652341 0.9641841 1 -0.2637547 0.9645898 -1 -0.2637547 0.9645898 1 -0.2622747 0.9649932 -1 -0.2622747 0.9649932 1 -0.2607941 0.9653944 -1 -0.2607941 0.9653944 1 -0.2593129 0.9657934 -1 -0.2593129 0.9657934 1 -0.2578311 0.96619 -1 -0.2578311 0.96619 1 -0.2563487 0.9665844 -1 -0.2563487 0.9665844 1 -0.2548657 0.9669765 -1 -0.2548657 0.9669765 1 -0.253382 0.9673663 -1 -0.253382 0.9673663 1 -0.2518978 0.9677538 -1 -0.2518978 0.9677538 1 -0.250413 0.9681391 -1 -0.250413 0.9681391 1 -0.2489276 0.9685221 -1 -0.2489276 0.9685221 1 -0.2474416 0.9689028 -1 -0.2474416 0.9689028 1 -0.245955 0.9692813 -1 -0.245955 0.9692813 1 -0.2444679 0.9696574 -1 -0.2444679 0.9696574 1 -0.2429802 0.9700313 -1 -0.2429802 0.9700313 1 -0.2414919 0.9704028 -1 -0.2414919 0.9704028 1 -0.240003 0.9707722 -1 -0.240003 0.9707722 1 -0.2385136 0.9711391 -1 -0.2385136 0.9711391 1 -0.2370236 0.9715039 -1 -0.2370236 0.9715039 1 -0.235533 0.9718663 -1 -0.235533 0.9718663 1 -0.2340419 0.9722265 -1 -0.2340419 0.9722265 1 -0.2325503 0.9725844 -1 -0.2325503 0.9725844 1 -0.2310581 0.97294 -1 -0.2310581 0.97294 1 -0.2295653 0.9732933 -1 -0.2295653 0.9732933 1 -0.2280721 0.9736443 -1 -0.2280721 0.9736443 1 -0.2265782 0.973993 -1 -0.2265782 0.973993 1 -0.2250839 0.9743394 -1 -0.2250839 0.9743394 1 -0.223589 0.9746835 -1 -0.223589 0.9746835 1 -0.2220936 0.9750254 -1 -0.2220936 0.9750254 1 -0.2205977 0.9753649 -1 -0.2205977 0.9753649 1 -0.2191012 0.9757021 -1 -0.2191012 0.9757021 1 -0.2176042 0.9760371 -1 -0.2176042 0.9760371 1 -0.2161068 0.9763697 -1 -0.2161068 0.9763697 1 -0.2146088 0.9767001 -1 -0.2146088 0.9767001 1 -0.2131103 0.9770281 -1 -0.2131103 0.9770281 1 -0.2116113 0.9773539 -1 -0.2116113 0.9773539 1 -0.2101118 0.9776774 -1 -0.2101118 0.9776774 1 -0.2086118 0.9779985 -1 -0.2086118 0.9779985 1 -0.2071114 0.9783174 -1 -0.2071114 0.9783174 1 -0.2056104 0.9786339 -1 -0.2056104 0.9786339 1 -0.204109 0.9789482 -1 -0.204109 0.9789482 1 -0.202607 0.9792602 -1 -0.202607 0.9792602 1 -0.2011046 0.9795698 -1 -0.2011046 0.9795698 1 -0.1996017 0.9798771 -1 -0.1996017 0.9798771 1 -0.1980984 0.9801821 -1 -0.1980984 0.9801821 1 -0.1965946 0.9804849 -1 -0.1965946 0.9804849 1 -0.1950903 0.9807853 -1 -0.1950903 0.9807853 1 -0.1935856 0.9810834 -1 -0.1935856 0.9810834 1 -0.1920804 0.9813792 -1 -0.1920804 0.9813792 1 -0.1905747 0.9816727 -1 -0.1905747 0.9816727 1 -0.1890686 0.9819639 -1 -0.1890686 0.9819639 1 -0.1875621 0.9822527 -1 -0.1875621 0.9822527 1 -0.1860551 0.9825393 -1 -0.1860551 0.9825393 1 -0.1845477 0.9828236 -1 -0.1845477 0.9828236 1 -0.1830399 0.9831055 -1 -0.1830399 0.9831055 1 -0.1815316 0.9833851 -1 -0.1815316 0.9833851 1 -0.1800229 0.9836624 -1 -0.1800229 0.9836624 1 -0.1785138 0.9839375 -1 -0.1785138 0.9839375 1 -0.1770042 0.9842101 -1 -0.1770042 0.9842101 1 -0.1754943 0.9844805 -1 -0.1754943 0.9844805 1 -0.1739838 0.9847485 -1 -0.1739838 0.9847485 1 -0.1724731 0.9850143 -1 -0.1724731 0.9850143 1 -0.1709619 0.9852777 -1 -0.1709619 0.9852777 1 -0.1694503 0.9855387 -1 -0.1694503 0.9855387 1 -0.1679382 0.9857975 -1 -0.1679382 0.9857975 1 -0.1664259 0.986054 -1 -0.1664259 0.986054 1 -0.1649131 0.9863081 -1 -0.1649131 0.9863081 1 -0.1633999 0.9865599 -1 -0.1633999 0.9865599 1 -0.1618863 0.9868094 -1 -0.1618863 0.9868094 1 -0.1603724 0.9870566 -1 -0.1603724 0.9870566 1 -0.1588581 0.9873014 -1 -0.1588581 0.9873014 1 -0.1573435 0.987544 -1 -0.1573435 0.987544 1 -0.1558284 0.9877842 -1 -0.1558284 0.9877842 1 -0.154313 0.988022 -1 -0.154313 0.988022 1 -0.1527972 0.9882576 -1 -0.1527972 0.9882576 1 -0.151281 0.9884908 -1 -0.151281 0.9884908 1 -0.1497645 0.9887217 -1 -0.1497645 0.9887217 1 -0.1482477 0.9889503 -1 -0.1482477 0.9889503 1 -0.1467304 0.9891765 -1 -0.1467304 0.9891765 1 -0.1452129 0.9894005 -1 -0.1452129 0.9894005 1 -0.143695 0.989622 -1 -0.143695 0.989622 1 -0.1421768 0.9898413 -1 -0.1421768 0.9898413 1 -0.1406582 0.9900582 -1 -0.1406582 0.9900582 1 -0.1391393 0.9902728 -1 -0.1391393 0.9902728 1 -0.1376201 0.9904851 -1 -0.1376201 0.9904851 1 -0.1361005 0.990695 -1 -0.1361005 0.990695 1 -0.1345807 0.9909027 -1 -0.1345807 0.9909027 1 -0.1330605 0.991108 -1 -0.1330605 0.991108 1 -0.13154 0.9913108 -1 -0.13154 0.9913108 1 -0.1300192 0.9915115 -1 -0.1300192 0.9915115 1 -0.1284981 0.9917098 -1 -0.1284981 0.9917098 1 -0.1269767 0.9919057 -1 -0.1269767 0.9919057 1 -0.125455 0.9920993 -1 -0.125455 0.9920993 1 -0.123933 0.9922906 -1 -0.123933 0.9922906 1 -0.1224107 0.9924796 -1 -0.1224107 0.9924796 1 -0.1208881 0.9926661 -1 -0.1208881 0.9926661 1 -0.1193652 0.9928504 -1 -0.1193652 0.9928504 1 -0.117842 0.9930323 -1 -0.117842 0.9930323 1 -0.1163186 0.9932119 -1 -0.1163186 0.9932119 1 -0.1147949 0.9933892 -1 -0.1147949 0.9933892 1 -0.1132709 0.9935641 -1 -0.1132709 0.9935641 1 -0.1117467 0.9937368 -1 -0.1117467 0.9937368 1 -0.1102222 0.993907 -1 -0.1102222 0.993907 1 -0.1086974 0.9940749 -1 -0.1086974 0.9940749 1 -0.1071724 0.9942405 -1 -0.1071724 0.9942405 1 -0.1056472 0.9944037 -1 -0.1056472 0.9944037 1 -0.1041216 0.9945646 -1 -0.1041216 0.9945646 1 -0.1025959 0.9947232 -1 -0.1025959 0.9947232 1 -0.1010698 0.9948793 -1 -0.1010698 0.9948793 1 -0.09954357 0.9950332 -1 -0.09954357 0.9950332 1 -0.09801709 0.9951847 -1 -0.09801709 0.9951847 1 -0.09649044 0.9953339 -1 -0.09649044 0.9953339 1 -0.09496349 0.9954808 -1 -0.09496349 0.9954808 1 -0.0934363 0.9956253 -1 -0.0934363 0.9956253 1 -0.09190893 0.9957674 -1 -0.09190893 0.9957674 1 -0.09038132 0.9959073 -1 -0.09038132 0.9959073 1 -0.08885353 0.9960447 -1 -0.08885353 0.9960447 1 -0.08732551 0.9961798 -1 -0.08732551 0.9961798 1 -0.0857973 0.9963126 -1 -0.0857973 0.9963126 1 -0.08426886 0.996443 -1 -0.08426886 0.996443 1 -0.08274024 0.9965711 -1 -0.08274024 0.9965711 1 -0.08121144 0.9966969 -1 -0.08121144 0.9966969 1 -0.0796824 0.9968203 -1 -0.0796824 0.9968203 1 -0.07815325 0.9969413 -1 -0.07815325 0.9969413 1 -0.07662385 0.9970601 -1 -0.07662385 0.9970601 1 -0.07509428 0.9971764 -1 -0.07509428 0.9971764 1 -0.07356452 0.9972904 -1 -0.07356452 0.9972904 1 -0.07203465 0.9974021 -1 -0.07203465 0.9974021 1 -0.07050454 0.9975115 -1 -0.07050454 0.9975115 1 -0.06897431 0.9976184 -1 -0.06897431 0.9976184 1 -0.0674439 0.9977231 -1 -0.0674439 0.9977231 1 -0.06591331 0.9978253 -1 -0.06591331 0.9978253 1 -0.06438261 0.9979253 -1 -0.06438261 0.9979253 1 -0.06285172 0.9980229 -1 -0.06285172 0.9980229 1 -0.06132072 0.9981181 -1 -0.06132072 0.9981181 1 -0.05978953 0.998211 -1 -0.05978953 0.998211 1 -0.05825823 0.9983016 -1 -0.05825823 0.9983016 1 -0.05672681 0.9983897 -1 -0.05672681 0.9983897 1 -0.05519521 0.9984756 -1 -0.05519521 0.9984756 1 -0.05366349 0.9985591 -1 -0.05366349 0.9985591 1 -0.05213171 0.9986402 -1 -0.05213171 0.9986402 1 -0.05059975 0.998719 -1 -0.05059975 0.998719 1 -0.04906767 0.9987955 -1 -0.04906767 0.9987955 1 -0.04753547 0.9988695 -1 -0.04753547 0.9988695 1 -0.04600316 0.9989413 -1 -0.04600316 0.9989413 1 -0.04447072 0.9990107 -1 -0.04447072 0.9990107 1 -0.04293823 0.9990777 -1 -0.04293823 0.9990777 1 -0.04140561 0.9991424 -1 -0.04140561 0.9991424 1 -0.03987288 0.9992048 -1 -0.03987288 0.9992048 1 -0.03834009 0.9992648 -1 -0.03834009 0.9992648 1 -0.03680717 0.9993224 -1 -0.03680717 0.9993224 1 -0.0352742 0.9993777 -1 -0.0352742 0.9993777 1 -0.03374117 0.9994306 -1 -0.03374117 0.9994306 1 -0.03220802 0.9994812 -1 -0.03220802 0.9994812 1 -0.03067475 0.9995294 -1 -0.03067475 0.9995294 1 -0.02914148 0.9995753 -1 -0.02914148 0.9995753 1 -0.02760809 0.9996188 -1 -0.02760809 0.9996188 1 -0.0260747 0.99966 -1 -0.0260747 0.99966 1 -0.02454119 0.9996988 -1 -0.02454119 0.9996988 1 -0.02300763 0.9997353 -1 -0.02300763 0.9997353 1 -0.02147406 0.9997694 -1 -0.02147406 0.9997694 1 -0.01994037 0.9998012 -1 -0.01994037 0.9998012 1 -0.01840668 0.9998306 -1 -0.01840668 0.9998306 1 -0.01687294 0.9998577 -1 -0.01687294 0.9998577 1 -0.01533919 0.9998824 -1 -0.01533919 0.9998824 1 -0.01380538 0.9999047 -1 -0.01380538 0.9999047 1 -0.01227152 0.9999247 -1 -0.01227152 0.9999247 1 -0.01073765 0.9999424 -1 -0.01073765 0.9999424 1 -0.009203732 0.9999576 -1 -0.009203732 0.9999576 1 -0.007669806 0.9999706 -1 -0.007669806 0.9999706 1 -0.00613588 0.9999812 -1 -0.00613588 0.9999812 1 -0.004601895 0.9999894 -1 -0.004601895 0.9999894 1 -0.00306791 0.9999953 -1 -0.00306791 0.9999953 1 -0.001533925 0.9999988 -1 -0.001533925 0.9999988 1 + + + + + + + + + + 7.77124e-4 0.9999997 0 0.002292513 0.9999974 0 0.003846704 0.9999927 0 0.005362153 0.9999857 0 0.006877541 0.9999763 0 0.008470654 0.9999642 0 0.00994718 0.9999506 0 0.01150143 0.999934 0 0.01305562 0.9999148 0 0.01457101 0.9998939 0 0.01608639 0.9998706 0 0.01764065 0.9998445 0 0.01919496 0.9998158 0 0.02071028 0.9997856 0 0.02222579 0.9997531 0 0.02377992 0.9997172 0 0.02529537 0.9996801 0 0.02684962 0.9996396 0 0.02836495 0.9995977 0 0.0299192 0.9995524 0 0.03143459 0.9995059 0 0.03298896 0.9994558 0 0.03450441 0.9994046 0 0.03605842 0.9993497 0 0.03753513 0.9992954 0 0.03912812 0.9992343 0 0.04064339 0.9991738 0 0.04215902 0.999111 0 0.04371309 0.9990442 0 0.04522871 0.9989767 0 0.04678261 0.9989051 0 0.04829823 0.998833 0 0.04981356 0.9987586 0 0.05136775 0.9986798 0 0.05292207 0.9985986 0 0.05443751 0.9985172 0 0.05595284 0.9984334 0 0.05746835 0.9983474 0 0.05902266 0.9982568 0 0.06057655 0.9981636 0 0.06209248 0.9980705 0 0.06360709 0.9979751 0 0.06516176 0.9978748 0 0.06667697 0.9977747 0 0.06819266 0.9976722 0 0.06974685 0.9975647 0 0.07126224 0.9974576 0 0.07281678 0.9973453 0 0.07433182 0.9972336 0 0.07584738 0.9971196 0 0.07740139 0.997 0 0.0789166 0.9968813 0 0.08043241 0.9967601 0 0.08198583 0.9966335 0 0.08350205 0.9965076 0 0.08501732 0.9963796 0 0.08657175 0.9962457 0 0.08808743 0.9961128 0 0.08960205 0.9959778 0 0.09115672 0.9958366 0 0.09267175 0.9956968 0 0.09418743 0.9955545 0 0.09574145 0.9954063 0 0.09725767 0.9952592 0 0.0987727 0.9951101 0 0.100326 0.9949547 0 0.101804 0.9948046 0 0.1033568 0.9946444 0 0.1049113 0.9944816 0 0.1063887 0.9943246 0 0.1079427 0.9941572 0 0.109458 0.9939915 0 0.1109731 0.9938235 0 0.1125274 0.9936487 0 0.114043 0.9934759 0 0.1155583 0.9933007 0 0.1170746 0.9931232 0 0.1185894 0.9929434 0 0.1201434 0.9927566 0 0.1216205 0.9925767 0 0.1231738 0.9923852 0 0.1247293 0.9921909 0 0.1262032 0.9920045 0 0.127721 0.9918102 0 0.1292769 0.9916086 0 0.1307892 0.9914102 0 0.1322655 0.9912143 0 0.1338204 0.9910057 0 0.135375 0.9907944 0 0.136853 0.9905914 0 0.1383662 0.9903812 0 0.1399198 0.9901629 0 0.1413968 0.989953 0 0.1429497 0.98973 0 0.1444289 0.9895153 0 0.1459839 0.989287 0 0.1474977 0.9890625 0 0.1490139 0.9888351 0 0.150489 0.9886118 0 0.1520455 0.9883735 0 0.1535578 0.9881398 0 0.1550756 0.9879027 0 0.156593 0.9876633 0 0.1581041 0.9874225 0 0.1596209 0.9871784 0 0.1611373 0.986932 0 0.1626155 0.9866896 0 0.1641659 0.9864329 0 0.1656842 0.9861789 0 0.1671614 0.9859296 0 0.1687136 0.9856652 0 0.1701899 0.9854114 0 0.1717068 0.9851481 0 0.1732611 0.984876 0 0.1747362 0.9846154 0 0.1762552 0.9843445 0 0.1777296 0.9840794 0 0.179282 0.9837978 0 0.1807965 0.9835206 0 0.1822764 0.9832474 0 0.18379 0.9829656 0 0.1853031 0.9826815 0 0.1868228 0.9823937 0 0.1882975 0.9821121 0 0.1898128 0.9818203 0 0.1913278 0.9815262 0 0.1928421 0.9812299 0 0.1943561 0.9809311 0 0.1958321 0.9806375 0 0.1973527 0.9803326 0 0.1988278 0.9800345 0 0.2003399 0.9797266 0 0.201859 0.9794147 0 0.2033739 0.9791012 0 0.2048471 0.978794 0 0.2063649 0.9784751 0 0.2078822 0.9781539 0 0.2093539 0.97784 0 0.2108702 0.9775141 0 0.212349 0.977194 0 0.2138643 0.9768634 0 0.2153421 0.9765387 0 0.2168564 0.9762036 0 0.2183701 0.9758661 0 0.2198464 0.9755345 0 0.2213264 0.9751999 0 0.2228385 0.9748555 0 0.2243586 0.9745067 0 0.2258327 0.9741661 0 0.2273107 0.9738223 0 0.2288249 0.9734676 0 0.2302974 0.9731203 0 0.2318149 0.97276 0 0.233295 0.972406 0 0.234807 0.972042 0 0.2362449 0.9716935 0 0.2377969 0.971315 0 0.2392383 0.9709609 0 0.2407524 0.9705866 0 0.2422294 0.9702191 0 0.2437468 0.969839 0 0.2451815 0.9694772 0 0.2466979 0.9690924 0 0.2482089 0.9687066 0 0.2496559 0.9683346 0 0.2511658 0.9679441 0 0.2526338 0.967562 0 0.2541203 0.9671727 0 0.2555967 0.9667836 0 0.2571088 0.9663825 0 0.2585477 0.9659986 0 0.2600682 0.9655903 0 0.2615422 0.9651921 0 0.2630155 0.9647916 0 0.2644981 0.9643862 0 0.2659701 0.9639813 0 0.2674515 0.9635714 0 0.2689222 0.9631619 0 0.2704023 0.9627474 0 0.2718819 0.9623307 0 0.2733866 0.9619043 0 0.2748289 0.9614932 0 0.2763065 0.9610697 0 0.2777835 0.9606438 0 0.2792599 0.9602156 0 0.2806997 0.9597957 0 0.2822105 0.9593526 0 0.2836848 0.9589177 0 0.2851227 0.958491 0 0.2865957 0.9580517 0 0.2880893 0.9576036 0 0.2895501 0.9571629 0 0.2910317 0.9567134 0 0.2924771 0.9562725 0 0.2939821 0.955811 0 0.2953907 0.9553766 0 0.2968941 0.9549104 0 0.298348 0.9544572 0 0.2998145 0.9539976 0 0.3012913 0.9535322 0 0.3027321 0.9530758 0 0.3041962 0.9526095 0 0.3056469 0.9521449 0 0.3071208 0.9516705 0 0.3086054 0.9511902 0 0.3100313 0.9507264 0 0.3115029 0.9502453 0 0.3129503 0.9497696 0 0.3143854 0.9492955 0 0.3158547 0.9488075 0 0.317335 0.9483136 0 0.3187795 0.947829 0 0.3202116 0.9473461 0 0.3216896 0.9468452 0 0.323132 0.9463539 0 0.3245965 0.9458526 0 0.3260493 0.9453528 0 0.3274896 0.9448549 0 0.328929 0.9443547 0 0.3303902 0.9438445 0 0.3318281 0.9433399 0 0.3332774 0.9428288 0 0.3347138 0.9423199 0 0.3361838 0.9417964 0 0.3376309 0.9412787 0 0.3390648 0.9407631 0 0.340498 0.9402453 0 0.3419302 0.9397253 0 0.3433742 0.9391987 0 0.3448049 0.9386744 0 0.3462815 0.9381307 0 0.3476889 0.93761 0 0.3491171 0.9370792 0 0.3506039 0.9365239 0 0.3519962 0.9360014 0 0.3534346 0.9354593 0 0.354906 0.934902 0 0.3563088 0.9343684 0 0.3577237 0.9338276 0 0.3591796 0.9332685 0 0.3606267 0.9327102 0 0.3620262 0.932168 0 0.3635055 0.9315922 0 0.3648901 0.9310507 0 0.3663339 0.9304835 0 0.3677433 0.9299274 0 0.3691721 0.9293611 0 0.3706134 0.9287872 0 0.3720538 0.9282112 0 0.3734465 0.9276517 0 0.3748517 0.9270849 0 0.3763093 0.9264942 0 0.3777264 0.9259173 0 0.3791291 0.9253439 0 0.3805505 0.9247602 0 0.3819846 0.9241688 0 0.3833984 0.9235832 0 0.3847975 0.9230011 0 0.3862288 0.922403 0 0.3876401 0.9218109 0 0.3890556 0.9212143 0 0.390465 0.9206178 0 0.3918597 0.9200251 0 0.3932533 0.9194303 0 0.394707 0.918807 0 0.3961316 0.9181938 0 0.3975039 0.9176005 0 0.3988938 0.9169973 0 0.4003296 0.9163712 0 0.4017318 0.9157574 0 0.4031331 0.9151414 0 0.404566 0.9145088 0 0.405933 0.9139029 0 0.4073459 0.913274 0 0.4087614 0.9126414 0 0.4101256 0.9120291 0 0.4115211 0.9114002 0 0.4129626 0.910748 0 0.414324 0.9101295 0 0.4157487 0.9094795 0 0.417123 0.9088501 0 0.4185136 0.9082106 0 0.4198859 0.9075769 0 0.4213066 0.9069184 0 0.4227089 0.9062656 0 0.4240784 0.9056255 0 0.4254789 0.9049684 0 0.4268466 0.9043241 0 0.4282618 0.9036548 0 0.4296274 0.9030063 0 0.4310238 0.9023407 0 0.4323875 0.901688 0 0.4337969 0.9010106 0 0.4351587 0.9003538 0 0.4365509 0.8996796 0 0.4379106 0.8990185 0 0.4393161 0.8983327 0 0.4407051 0.897652 0 0.4420617 0.8969846 0 0.4434173 0.8963153 0 0.4448028 0.8956286 0 0.4461875 0.8949396 0 0.4475555 0.8942562 0 0.448938 0.8935629 0 0.4503039 0.8928754 0 0.4516688 0.8921858 0 0.4530169 0.8915019 0 0.4543955 0.8908001 0 0.4557881 0.8900884 0 0.4571329 0.8893985 0 0.4584925 0.8886983 0 0.4598362 0.8880038 0 0.4612243 0.8872836 0 0.4625806 0.8865773 0 0.4639518 0.8858604 0 0.4653059 0.8851499 0 0.466659 0.8844373 0 0.4680269 0.8837142 0 0.4693635 0.883005 0 0.4707274 0.8822788 0 0.4720618 0.8815655 0 0.4734416 0.8808253 0 0.4747716 0.8801091 0 0.4761029 0.8793896 0 0.4774794 0.878643 0 0.4788385 0.8779031 0 0.4801801 0.8771699 0 0.481507 0.8764423 0 0.4828627 0.8756961 0 0.4841873 0.8749644 0 0.4855406 0.8742141 0 0.4868631 0.8734783 0 0.4882141 0.872724 0 0.4895508 0.8719748 0 0.4908995 0.8712164 0 0.4922173 0.8704724 0 0.4935674 0.8697076 0 0.4949124 0.868943 0 0.4962269 0.868193 0 0.4975736 0.8674219 0 0.4988858 0.8666679 0 0.5002259 0.865895 0 0.5015692 0.8651176 0 0.5028609 0.8643674 0 0.5041851 0.8635957 0 0.505542 0.862802 0 0.5068299 0.8620461 0 0.5081794 0.8612512 0 0.5095041 0.8604682 0 0.5107883 0.8597065 0 0.5121396 0.8589023 0 0.5134554 0.8581163 0 0.51477 0.8573284 0 0.5160549 0.8565555 0 0.51743 0.8557257 0 0.518678 0.8549698 0 0.5200222 0.8541529 0 0.5213305 0.8533548 0 0.5226094 0.8525722 0 0.52395 0.8517491 0 0.5252546 0.8509451 0 0.5265646 0.8501351 0 0.5278319 0.8493489 0 0.5291395 0.8485349 0 0.5304739 0.8477013 0 0.5317442 0.8469051 0 0.5330482 0.8460848 0 0.5343438 0.8452673 0 0.5356732 0.8444254 0 0.5369459 0.8436168 0 0.5382023 0.8428158 0 0.5395002 0.8419856 0 0.5408244 0.8411356 0 0.5421198 0.8403013 0 0.5433512 0.8395056 0 0.5446715 0.8386495 0 0.5459632 0.8378092 0 0.5472536 0.8369669 0 0.5485699 0.8361048 0 0.5498306 0.8352763 0 0.5510902 0.8344458 0 0.5523667 0.8336012 0 0.5536865 0.8327252 0 0.5549334 0.8318949 0 0.5561878 0.8310567 0 0.5575307 0.8301565 0 0.5587466 0.8293384 0 0.560024 0.8284765 0 0.5613095 0.827606 0 0.5625842 0.8267401 0 0.5638576 0.825872 0 0.5651032 0.8250204 0 0.5663738 0.8241485 0 0.5676431 0.8232749 0 0.5688948 0.8224104 0 0.5701875 0.8215146 0 0.5714265 0.8206533 0 0.5726641 0.8197901 0 0.5739004 0.8189252 0 0.5751979 0.8180144 0 0.5764315 0.8171455 0 0.5777263 0.8162307 0 0.5789313 0.8153765 0 0.5801866 0.8144837 0 0.5814514 0.8135812 0 0.5826781 0.8127031 0 0.5839403 0.8117967 0 0.5851643 0.8109149 0 0.5864351 0.8099963 0 0.5876703 0.8091005 0 0.5889132 0.8081964 0 0.5901569 0.8072886 0 0.5913738 0.8063977 0 0.5926263 0.8054776 0 0.5938524 0.8045741 0 0.5951021 0.8036502 0 0.5963132 0.8027518 0 0.5975353 0.8018427 0 0.5987808 0.800913 0 0.6000249 0.7999814 0 0.6012054 0.7990946 0 0.602484 0.798131 0 0.6036617 0.7972406 0 0.6049128 0.7962917 0 0.6061123 0.7953792 0 0.6073477 0.7944362 0 0.6085572 0.79351 0 0.6097652 0.7925821 0 0.6109719 0.7916523 0 0.6122391 0.7906728 0 0.6134052 0.7897683 0 0.6146075 0.7888331 0 0.6158461 0.7878664 0 0.6170456 0.7869274 0 0.6182677 0.7859677 0 0.619454 0.7850329 0 0.6206592 0.7840805 0 0.6218668 0.7831231 0 0.6230589 0.782175 0 0.6242496 0.7812251 0 0.6254767 0.7802429 0 0.6266407 0.7793084 0 0.6278504 0.778334 0 0.6290495 0.7773653 0 0.6302093 0.7764253 0 0.6314524 0.7754147 0 0.6326091 0.7744712 0 0.6338026 0.7734948 0 0.6350178 0.7724975 0 0.6361702 0.7715488 0 0.6373443 0.7705792 0 0.6385319 0.7695955 0 0.6397027 0.7686223 0 0.6408874 0.767635 0 0.6420705 0.7666456 0 0.643275 0.7656352 0 0.6443942 0.7646936 0 0.6455956 0.7636795 0 0.6467344 0.7627154 0 0.6479327 0.7616977 0 0.6490842 0.7607166 0 0.6502569 0.7597145 0 0.651428 0.7587106 0 0.6525976 0.7577048 0 0.6537656 0.7566972 0 0.6549099 0.7557071 0 0.6560969 0.7546766 0 0.6572383 0.753683 0 0.6584221 0.752649 0 0.6595603 0.7516517 0 0.6606971 0.7506526 0 0.6618543 0.7496326 0 0.6630098 0.7486108 0 0.664142 0.7476065 0 0.6652943 0.7465813 0 0.6664234 0.7455735 0 0.6675725 0.7445448 0 0.668677 0.7435531 0 0.6698616 0.742486 0 0.6710059 0.741452 0 0.6721273 0.7404357 0 0.6732857 0.7393825 0 0.6744039 0.7383627 0 0.6755205 0.7373412 0 0.6766954 0.7362632 0 0.6777877 0.7352577 0 0.6789205 0.7342118 0 0.6800099 0.733203 0 0.6811394 0.7321538 0 0.6823031 0.7310695 0 0.6834084 0.7300363 0 0.684551 0.7289651 0 0.6856325 0.7279479 0 0.6867924 0.7268537 0 0.6878708 0.7258332 0 0.6889864 0.7247744 0 0.6901023 0.7237119 0 0.6911759 0.7226866 0 0.6923255 0.7215853 0 0.6934162 0.7205374 0 0.694485 0.7195073 0 0.6956499 0.718381 0 0.6967155 0.7173476 0 0.6978182 0.7162749 0 0.6989194 0.7152005 0 0.700019 0.7141243 0 0.7010979 0.7130652 0 0.7022329 0.7119473 0 0.7033084 0.710885 0 0.7043817 0.7098215 0 0.705473 0.7087369 0 0.7065626 0.7076506 0 0.7076506 0.7065626 0 0.7087369 0.705473 0 0.7098022 0.7044011 0 0.7108656 0.703328 0 0.7119665 0.7022135 0 0.7130461 0.7011173 0 0.7141049 0.7000388 0 0.7152199 0.6988996 0 0.7162555 0.6978381 0 0.7173482 0.6967149 0 0.7183804 0.6956505 0 0.7194885 0.6945044 0 0.7205187 0.6934356 0 0.7215845 0.6923264 0 0.7226874 0.691175 0 0.7236739 0.6901421 0 0.7247734 0.6889874 0 0.7258527 0.6878503 0 0.7268526 0.6867935 0 0.7279285 0.6856531 0 0.7290026 0.684511 0 0.7300363 0.6834084 0 0.731107 0.6822629 0 0.7321165 0.6811795 0 0.7331656 0.6800501 0 0.7342132 0.678919 0 0.7352949 0.6777474 0 0.7362616 0.676697 0 0.7373219 0.6755416 0 0.7383804 0.6743845 0 0.7393807 0.6732876 0 0.7404357 0.6721273 0 0.7414502 0.6710079 0 0.7424666 0.669883 0 0.7435163 0.6687179 0 0.7445641 0.667551 0 0.7455929 0.6664018 0 0.7465813 0.6652943 0 0.7476065 0.664142 0 0.7486086 0.6630123 0 0.7496303 0.6618568 0 0.7506504 0.6606997 0 0.7516686 0.6595411 0 0.7526465 0.6584249 0 0.7536998 0.657219 0 0.7547126 0.6560556 0 0.7557237 0.6548906 0 0.756678 0.6537878 0 0.7576856 0.6526198 0 0.7586914 0.6514503 0 0.7596953 0.6502793 0 0.760681 0.6491259 0 0.7616814 0.6479518 0 0.7627182 0.646731 0 0.7636988 0.6455729 0 0.7646936 0.6443942 0 0.7656322 0.6432787 0 0.7666456 0.6420705 0 0.767635 0.6408874 0 0.7686066 0.6397219 0 0.7695763 0.6385549 0 0.7705602 0.6373673 0 0.7715488 0.6361702 0 0.7725133 0.6349988 0 0.7735296 0.6337603 0 0.7744903 0.6325859 0 0.7754337 0.631429 0 0.7764063 0.6302327 0 0.7773463 0.629073 0 0.7783151 0.627874 0 0.7793273 0.6266171 0 0.780262 0.625453 0 0.7812251 0.6242496 0 0.7821939 0.6230351 0 0.7831231 0.6218668 0 0.7840656 0.6206781 0 0.7850668 0.6194112 0 0.7859677 0.6182677 0 0.7869423 0.6170268 0 0.7878477 0.6158702 0 0.7888184 0.6146264 0 0.7897496 0.6134294 0 0.7906874 0.6122202 0 0.7916523 0.6109719 0 0.7925489 0.6098084 0 0.79351 0.6085572 0 0.7944175 0.6073723 0 0.7953978 0.6060877 0 0.7962872 0.6049187 0 0.7972265 0.6036804 0 0.7981264 0.60249 0 0.7990993 0.6011993 0 0.7999953 0.6000062 0 0.800913 0.5987808 0 0.8018427 0.5975353 0 0.8027704 0.5962883 0 0.8036453 0.5951086 0 0.8045927 0.5938271 0 0.8054776 0.5926263 0 0.8063977 0.5913738 0 0.8073021 0.5901384 0 0.8081914 0.5889201 0 0.8090821 0.5876957 0 0.8099912 0.5864422 0 0.8109149 0.5851643 0 0.8117967 0.5839403 0 0.8127031 0.5826781 0 0.8135812 0.5814514 0 0.8144837 0.5801866 0 0.8153948 0.5789054 0 0.8162437 0.577708 0 0.8171273 0.5764575 0 0.8180455 0.5751537 0 0.8189252 0.5739004 0 0.8197901 0.5726641 0 0.8206533 0.5714265 0 0.8215272 0.5701693 0 0.822423 0.5688766 0 0.823293 0.5676168 0 0.8241609 0.5663557 0 0.8250509 0.5650586 0 0.8258664 0.563866 0 0.8267524 0.5625662 0 0.8276003 0.561318 0 0.8284945 0.5599973 0 0.8293384 0.5587466 0 0.8301685 0.5575127 0 0.8310567 0.5561878 0 0.8318949 0.5549334 0 0.8327192 0.5536955 0 0.8336012 0.5523667 0 0.8344458 0.5510902 0 0.835288 0.5498127 0 0.8361165 0.5485521 0 0.8369669 0.5472536 0 0.8377915 0.5459904 0 0.838638 0.5446892 0 0.8394941 0.5433689 0 0.8403013 0.5421198 0 0.8411419 0.5408146 0 0.8419919 0.5394903 0 0.8428044 0.5382199 0 0.8436279 0.5369283 0 0.8444366 0.5356556 0 0.8452562 0.5343614 0 0.8460848 0.5330482 0 0.8468877 0.5317721 0 0.8477122 0.5304564 0 0.848524 0.5291569 0 0.8493555 0.5278213 0 0.8501633 0.5265192 0 0.8509451 0.5252546 0 0.8517597 0.5239327 0 0.8525722 0.5226094 0 0.8533722 0.5213023 0 0.8541701 0.5199939 0 0.854987 0.5186496 0 0.8557361 0.5174128 0 0.8565384 0.5160834 0 0.8573284 0.51477 0 0.8581163 0.5134554 0 0.8589125 0.5121224 0 0.8596964 0.5108054 0 0.8604784 0.5094872 0 0.8612342 0.5082082 0 0.8620361 0.5068469 0 0.8628119 0.5055251 0 0.8635957 0.5041851 0 0.8643575 0.5028778 0 0.8651273 0.5015524 0 0.8658901 0.5002342 0 0.8666895 0.4988482 0 0.8674435 0.497536 0 0.8682049 0.4962059 0 0.8689644 0.4948747 0 0.8697124 0.4935591 0 0.8704677 0.4922257 0 0.8712116 0.4909077 0 0.8719915 0.4895213 0 0.8727359 0.4881927 0 0.8734737 0.4868714 0 0.8742141 0.4855406 0 0.874948 0.4842171 0 0.8756797 0.4828925 0 0.8764423 0.481507 0 0.8771699 0.4801801 0 0.8779238 0.4788004 0 0.8786475 0.4774713 0 0.8794059 0.4760729 0 0.880121 0.4747497 0 0.8808296 0.4734335 0 0.8815817 0.4720317 0 0.8822906 0.4707052 0 0.8829933 0.4693859 0 0.8837024 0.4680493 0 0.8844373 0.466659 0 0.8851382 0.4653285 0 0.8858604 0.4639518 0 0.8865614 0.4626112 0 0.8872877 0.4612163 0 0.8880038 0.4598362 0 0.8886943 0.4585005 0 0.8894143 0.4571022 0 0.8900924 0.4557802 0 0.8908001 0.4543955 0 0.8915137 0.4529939 0 0.8921898 0.451661 0 0.892891 0.4502729 0 0.8935629 0.448938 0 0.8942601 0.4475477 0 0.894955 0.4461564 0 0.8956169 0.4448263 0 0.8963116 0.4434251 0 0.8969655 0.4421007 0 0.8976558 0.4406974 0 0.8983364 0.4393084 0 0.8990185 0.4379106 0 0.8996606 0.43659 0 0.9003728 0.4351196 0 0.9010144 0.4337894 0 0.901688 0.4323875 0 0.9023522 0.4309996 0 0.9029877 0.4296666 0 0.9036548 0.4282618 0 0.9043391 0.4268148 0 0.9049684 0.4254789 0 0.905629 0.424071 0 0.906277 0.4226844 0 0.9069001 0.4213459 0 0.9075769 0.4198859 0 0.9082254 0.4184815 0 0.908832 0.4171624 0 0.9094762 0.4157561 0 0.9101441 0.4142918 0 0.910748 0.4129626 0 0.9113824 0.4115607 0 0.9120437 0.4100933 0 0.9126414 0.4087614 0 0.9132628 0.4073711 0 0.9139174 0.4059005 0 0.9145088 0.404566 0 0.9151271 0.4031657 0 0.9157717 0.4016993 0 0.916357 0.4003622 0 0.9169941 0.3989009 0 0.9175975 0.397511 0 0.9182079 0.3960988 0 0.9188101 0.3946999 0 0.9194412 0.3932275 0 0.9200081 0.3918995 0 0.9206318 0.3904321 0 0.9211975 0.3890956 0 0.9218109 0.3876401 0 0.922403 0.3862288 0 0.9229902 0.3848237 0 0.9235969 0.3833652 0 0.9241522 0.3820246 0 0.9247602 0.3805505 0 0.925333 0.3791555 0 0.9259309 0.3776931 0 0.9264779 0.3763495 0 0.9270713 0.3748851 0 0.9276652 0.373413 0 0.9282004 0.3720806 0 0.92879 0.3706067 0 0.9293477 0.3692057 0 0.9299274 0.3677433 0 0.9304835 0.3663339 0 0.9310348 0.3649303 0 0.9316079 0.3634652 0 0.9321836 0.3619859 0 0.9326972 0.3606605 0 0.9332685 0.3591796 0 0.9338276 0.3577237 0 0.9343684 0.3563088 0 0.934902 0.354906 0 0.9354568 0.353441 0 0.9359886 0.3520302 0 0.9365391 0.3505634 0 0.9370896 0.3490893 0 0.93761 0.3476889 0 0.9381307 0.3462815 0 0.9386721 0.3448112 0 0.9391862 0.3434085 0 0.9397231 0.3419365 0 0.9402351 0.3405261 0 0.9407653 0.3390586 0 0.9412685 0.3376591 0 0.9417964 0.3361838 0 0.942322 0.3347076 0 0.9428433 0.3332368 0 0.9433399 0.3318281 0 0.9438566 0.3303557 0 0.9443689 0.3288884 0 0.9448569 0.3274835 0 0.9453668 0.3260086 0 0.9458526 0.3245965 0 0.9463539 0.323132 0 0.9468334 0.3217244 0 0.9473343 0.3202465 0 0.947829 0.3187795 0 0.9483 0.3173757 0 0.9487941 0.3158956 0 0.9492838 0.3144204 0 0.9497696 0.3129503 0 0.9502337 0.311538 0 0.950713 0.3100721 0 0.951192 0.3085997 0 0.9516724 0.3071151 0 0.9521449 0.3056469 0 0.9525964 0.3042371 0 0.9530663 0.3027618 0 0.9535322 0.3012913 0 0.9539976 0.2998145 0 0.954459 0.2983425 0 0.9548994 0.2969295 0 0.9553766 0.2953907 0 0.955811 0.2939821 0 0.9562634 0.2925073 0 0.9567134 0.2910317 0 0.9571629 0.2895501 0 0.9576036 0.2880893 0 0.9580501 0.286601 0 0.9584895 0.285128 0 0.958907 0.2837205 0 0.959342 0.2822462 0 0.9597957 0.2806997 0 0.960226 0.279224 0 0.9606527 0.2777528 0 0.9610815 0.2762655 0 0.961502 0.2747981 0 0.9619043 0.2733866 0 0.9623219 0.2719128 0 0.9627374 0.2704384 0 0.9631519 0.2689583 0 0.9635614 0.2674875 0 0.9639714 0.2660062 0 0.9643778 0.2645292 0 0.9647818 0.2630516 0 0.9651823 0.2615784 0 0.9655818 0.2600996 0 0.9659986 0.2585477 0 0.9663909 0.2570773 0 0.9667836 0.2555967 0 0.9671727 0.2541203 0 0.9675607 0.2526386 0 0.9679441 0.2511658 0 0.9683259 0.2496899 0 0.968706 0.2482113 0 0.9691018 0.2466614 0 0.9694766 0.2451838 0 0.9698298 0.2437834 0 0.9702191 0.2422294 0 0.9705871 0.2407501 0 0.9709694 0.2392039 0 0.9713144 0.2377991 0 0.9716935 0.2362449 0 0.972051 0.2347703 0 0.972406 0.233295 0 0.97276 0.2318149 0 0.9731111 0.2303364 0 0.973459 0.2288617 0 0.9738228 0.2273085 0 0.9741661 0.2258327 0 0.9745072 0.2243564 0 0.974847 0.2228754 0 0.9751999 0.2213264 0 0.9755345 0.2198464 0 0.9758656 0.2183722 0 0.9761953 0.2168934 0 0.9765387 0.2153421 0 0.9768634 0.2138643 0 0.977202 0.2123119 0 0.9775217 0.2108351 0 0.9778396 0.209356 0 0.9781539 0.2078822 0 0.9784673 0.2064021 0 0.9787936 0.2048491 0 0.9791012 0.2033739 0 0.9794227 0.2018198 0 0.9797261 0.2003418 0 0.980042 0.1987905 0 0.9803401 0.1973153 0 0.9806371 0.1958341 0 0.9809308 0.1943579 0 0.9812222 0.1928814 0 0.9815262 0.1913278 0 0.9818131 0.1898503 0 0.9821124 0.1882957 0 0.9823937 0.1868228 0 0.9826885 0.1852656 0 0.9829656 0.18379 0 0.9832543 0.1822388 0 0.9835276 0.1807589 0 0.9837978 0.179282 0 0.9840797 0.1777278 0 0.9843448 0.1762536 0 0.984609 0.1747722 0 0.9848697 0.1732971 0 0.9851547 0.1716691 0 0.9854114 0.1701899 0 0.9856655 0.168712 0 0.9859299 0.1671597 0 0.9861789 0.1656842 0 0.9864391 0.164128 0 0.9866836 0.1626517 0 0.9869258 0.1611751 0 0.9871784 0.1596209 0 0.9874162 0.1581435 0 0.9876635 0.1565915 0 0.987897 0.155112 0 0.9881395 0.1535592 0 0.988368 0.152082 0 0.9886173 0.1504525 0 0.9888408 0.148976 0 0.9890627 0.1474963 0 0.9892926 0.1459459 0 0.9895097 0.144467 0 0.9897242 0.1429892 0 0.9899582 0.1413601 0 0.990168 0.1398831 0 0.9903759 0.1384043 0 0.9905917 0.1368517 0 0.9907944 0.135375 0 0.9910057 0.1338204 0 0.9912142 0.1322668 0 0.9914102 0.1307892 0 0.9916038 0.1293138 0 0.9918153 0.1276816 0 0.9920043 0.1262044 0 0.9921909 0.1247287 0 0.9923852 0.1231738 0 0.9925767 0.1216205 0 0.9927567 0.1201428 0 0.9929434 0.1185894 0 0.9931278 0.1170357 0 0.9933007 0.1155583 0 0.9934804 0.1140041 0 0.9936487 0.1125274 0 0.9938235 0.1109731 0 0.9939957 0.1094197 0 0.9941572 0.1079427 0 0.9943247 0.1063882 0 0.9944816 0.1049118 0 0.9946443 0.1033573 0 0.9948046 0.1018036 0 0.9949547 0.100326 0 0.9951101 0.0987727 0 0.9952631 0.09721869 0 0.9954063 0.09574145 0 0.9955545 0.09418743 0 0.9957003 0.09263318 0 0.9958366 0.09115672 0 0.9959776 0.08960247 0 0.9961163 0.08804845 0 0.9962457 0.08657175 0 0.9963796 0.08501732 0 0.9965109 0.08346349 0 0.9966335 0.08198624 0 0.9967601 0.08043241 0 0.9968843 0.0788784 0 0.997 0.07740139 0 0.9971196 0.07584738 0 0.9972366 0.07429319 0 0.9973455 0.07281643 0 0.9974576 0.07126224 0 0.9975675 0.06970816 0 0.9976696 0.06823134 0 0.9977747 0.06667727 0 0.9978722 0.06520044 0 0.9979775 0.06356871 0 0.9980705 0.06209236 0 0.9981659 0.06053787 0 0.9982544 0.05906122 0 0.9983496 0.05742961 0 0.9984334 0.05595296 0 0.9985194 0.05439877 0 0.9985986 0.05292207 0 0.9986798 0.05136775 0 0.9987586 0.04981368 0 0.9988349 0.04825949 0 0.9989051 0.04678273 0 0.9989767 0.0452286 0 0.9990459 0.0436744 0 0.9991094 0.04219782 0 0.9991738 0.04064351 0 0.9992328 0.03916692 0 0.9992954 0.03753513 0 0.9993497 0.03605842 0 0.9994046 0.03450441 0 0.9994544 0.03302764 0 0.9995071 0.03139579 0 0.9995524 0.02991926 0 0.9995977 0.02836495 0 0.9996406 0.02681082 0 0.999679 0.02533417 0 0.9997172 0.02377992 0 0.9997531 0.02222573 0 0.9997847 0.02074915 0 0.9998158 0.01919496 0 0.9998445 0.0176407 0 0.9998707 0.01608645 0 0.9998933 0.01460987 0 0.9999148 0.01305568 0 0.999934 0.01150143 0 0.9999506 0.00994718 0 0.9999641 0.008470594 0 0.9999761 0.006916344 0 0.9999857 0.005362153 0 0.9999925 0.003885567 0 0.9999976 0.002253651 0 0.9999997 7.77124e-4 0 0.9999997 -7.77124e-4 0 0.9999974 -0.002331316 0 0.9999929 -0.003807902 0 0.9999857 -0.005362153 0 0.9999767 -0.006838679 0 0.9999641 -0.008470594 0 0.9999506 -0.00994718 0 0.999934 -0.01150143 0 0.9999148 -0.01305568 0 0.9998945 -0.0145322 0 0.9998707 -0.01608645 0 0.9998445 -0.0176407 0 0.9998158 -0.01919496 0 0.9997864 -0.02067148 0 0.9997531 -0.02222573 0 0.9997172 -0.02377992 0 0.9996811 -0.02525651 0 0.9996384 -0.02688843 0 0.9995977 -0.02836495 0 0.9995524 -0.02991926 0 0.9995047 -0.03147339 0 0.9994571 -0.03295004 0 0.9994046 -0.03450441 0 0.9993497 -0.03605842 0 0.9992954 -0.03753513 0 0.9992358 -0.03908932 0 0.9991738 -0.04064351 0 0.9991126 -0.04212021 0 0.9990425 -0.04375201 0 0.9989767 -0.0452286 0 0.9989051 -0.04678273 0 0.9988312 -0.04833704 0 0.9987586 -0.04981368 0 0.9986798 -0.05136775 0 0.9985986 -0.05292207 0 0.9985151 -0.05447626 0 0.9984334 -0.05595296 0 0.9983451 -0.05750703 0 0.998259 -0.0589838 0 0.9981613 -0.0606153 0 0.9980705 -0.06209236 0 0.9979726 -0.06364607 0 0.9978773 -0.06512308 0 0.9977747 -0.06667727 0 0.9976749 -0.06815397 0 0.9975621 -0.06978553 0 0.9974576 -0.07126224 0 0.9973455 -0.07281643 0 0.9972308 -0.07437044 0 0.9971196 -0.07584738 0 0.997 -0.07740139 0 0.9968782 -0.07895565 0 0.9967601 -0.08043241 0 0.9966335 -0.08198624 0 0.9965044 -0.08354067 0 0.9963796 -0.08501732 0 0.9962457 -0.08657175 0 0.9961094 -0.08812552 0 0.9959776 -0.08960247 0 0.9958366 -0.09115672 0 0.9956932 -0.09271025 0 0.9955545 -0.09418743 0 0.9954063 -0.09574145 0 0.9952555 -0.0972957 0 0.9951101 -0.0987727 0 0.9949547 -0.100326 0 0.9948046 -0.1018036 0 0.9946443 -0.1033573 0 0.9944816 -0.1049118 0 0.9943247 -0.1063882 0 0.9941572 -0.1079427 0 0.9939873 -0.1094964 0 0.9938235 -0.1109731 0 0.9936487 -0.1125274 0 0.9934716 -0.1140808 0 0.9933007 -0.1155583 0 0.9931188 -0.1171123 0 0.9929434 -0.1185894 0 0.9927567 -0.1201428 0 0.9925767 -0.1216205 0 0.9923852 -0.1231738 0 0.9921909 -0.1247287 0 0.9920043 -0.1262044 0 0.9918054 -0.127758 0 0.9916138 -0.1292374 0 0.9914102 -0.1307892 0 0.9912142 -0.1322668 0 0.9910057 -0.1338204 0 0.9907944 -0.135375 0 0.9905917 -0.1368517 0 0.9903864 -0.1383281 0 0.9901574 -0.1399592 0 0.9899474 -0.1414363 0 0.9897353 -0.1429131 0 0.9895207 -0.1443909 0 0.9892814 -0.146022 0 0.9890627 -0.1474963 0 0.9888294 -0.149052 0 0.9886057 -0.1505284 0 0.9883796 -0.152006 0 0.9881395 -0.1535592 0 0.9879088 -0.1550362 0 0.9876635 -0.1565915 0 0.9874283 -0.1580678 0 0.9871784 -0.1596209 0 0.9869382 -0.1610994 0 0.986696 -0.1625761 0 0.9864265 -0.1642037 0 0.9861789 -0.1656842 0 0.9859299 -0.1671597 0 0.9856655 -0.168712 0 0.9854114 -0.1701899 0 0.9851415 -0.1717445 0 0.984883 -0.1732217 0 0.9846224 -0.1746968 0 0.9843448 -0.1762536 0 0.9840797 -0.1777278 0 0.9837978 -0.179282 0 0.9835137 -0.1808341 0 0.9832404 -0.1823139 0 0.9829656 -0.18379 0 0.9826744 -0.1853406 0 0.9823937 -0.1868228 0 0.9821124 -0.1882957 0 0.9818276 -0.1897754 0 0.9815262 -0.1913278 0 0.9812368 -0.1928066 0 0.9809308 -0.1943579 0 0.9806371 -0.1958341 0 0.9803251 -0.19739 0 0.9800269 -0.1988651 0 0.9797261 -0.2003418 0 0.9794074 -0.2018944 0 0.9791012 -0.2033739 0 0.9787936 -0.2048491 0 0.978483 -0.2063277 0 0.9781539 -0.2078822 0 0.9778396 -0.209356 0 0.9775056 -0.2109094 0 0.9771859 -0.2123861 0 0.9768634 -0.2138643 0 0.9765387 -0.2153421 0 0.9762118 -0.2168194 0 0.9758656 -0.2183722 0 0.9755345 -0.2198464 0 0.9751999 -0.2213264 0 0.9748638 -0.2228016 0 0.9745072 -0.2243564 0 0.9741661 -0.2258327 0 0.9738228 -0.2273085 0 0.9734764 -0.2287881 0 0.9731285 -0.2302628 0 0.97276 -0.2318149 0 0.972406 -0.233295 0 0.9720332 -0.2348437 0 0.9716935 -0.2362449 0 0.9713144 -0.2377991 0 0.9709514 -0.2392772 0 0.9705871 -0.2407501 0 0.9702191 -0.2422294 0 0.9698482 -0.2437103 0 0.9694766 -0.2451838 0 0.9690832 -0.2467343 0 0.968706 -0.2482113 0 0.9683446 -0.2496171 0 0.9679441 -0.2511658 0 0.9675607 -0.2526386 0 0.9671727 -0.2541203 0 0.9667836 -0.2555967 0 0.9663716 -0.2571499 0 0.9659986 -0.2585477 0 0.9656013 -0.2600271 0 0.9652019 -0.261506 0 0.9648016 -0.2629793 0 0.9643975 -0.2644569 0 0.9639912 -0.265934 0 0.9635814 -0.2674154 0 0.963172 -0.2688862 0 0.9627576 -0.2703663 0 0.9623423 -0.2718408 0 0.9619043 -0.2733866 0 0.9614815 -0.27487 0 0.9610608 -0.2763373 0 0.9606319 -0.2778245 0 0.9602051 -0.2792957 0 0.9597957 -0.2806997 0 0.9593631 -0.2821748 0 0.9589282 -0.2836491 0 0.9584895 -0.285128 0 0.9580501 -0.286601 0 0.9576036 -0.2880893 0 0.9571629 -0.2895501 0 0.9567134 -0.2910317 0 0.9562851 -0.2924362 0 0.955811 -0.2939821 0 0.9553766 -0.2953907 0 0.9549215 -0.2968587 0 0.954459 -0.2983425 0 0.9539976 -0.2998145 0 0.9535322 -0.3012913 0 0.9530887 -0.3026912 0 0.952619 -0.3041666 0 0.9521449 -0.3056469 0 0.9516724 -0.3071151 0 0.951192 -0.3085997 0 0.950736 -0.3100019 0 0.9502568 -0.3114678 0 0.9497696 -0.3129503 0 0.949307 -0.3143504 0 0.9488173 -0.3158255 0 0.9483233 -0.3173059 0 0.947829 -0.3187795 0 0.9473578 -0.3201767 0 0.946857 -0.3216547 0 0.9463539 -0.323132 0 0.9458526 -0.3245965 0 0.9453429 -0.3260781 0 0.9448569 -0.3274835 0 0.9443448 -0.3289577 0 0.9438323 -0.3304249 0 0.9433399 -0.3318281 0 0.9428188 -0.3333058 0 0.942322 -0.3347076 0 0.9417964 -0.3361838 0 0.9412932 -0.3375902 0 0.9407653 -0.3390586 0 0.9402601 -0.3404574 0 0.9397231 -0.3419365 0 0.9392113 -0.34334 0 0.9386721 -0.3448112 0 0.9381307 -0.3462815 0 0.93761 -0.3476889 0 0.9370641 -0.3491575 0 0.9365136 -0.3506316 0 0.9360143 -0.3519622 0 0.9354568 -0.353441 0 0.934902 -0.354906 0 0.9343684 -0.3563088 0 0.9338276 -0.3577237 0 0.9332685 -0.3591796 0 0.9327234 -0.3605929 0 0.9321574 -0.3620534 0 0.9315815 -0.3635326 0 0.9310612 -0.364863 0 0.9304835 -0.3663339 0 0.9299274 -0.3677433 0 0.9293743 -0.3691385 0 0.92879 -0.3706067 0 0.9282273 -0.3720136 0 0.9276382 -0.3734799 0 0.9270983 -0.3748183 0 0.9265049 -0.3762828 0 0.9259037 -0.3777597 0 0.9253602 -0.3790889 0 0.9247602 -0.3805505 0 0.9241797 -0.3819583 0 0.9235693 -0.3834314 0 0.9230177 -0.3847575 0 0.922403 -0.3862288 0 0.9218109 -0.3876401 0 0.9212254 -0.3890296 0 0.9206039 -0.390498 0 0.920036 -0.3918337 0 0.9194132 -0.3932932 0 0.9188101 -0.3946999 0 0.9181797 -0.3961644 0 0.9175975 -0.397511 0 0.9169941 -0.3989009 0 0.9163855 -0.4002969 0 0.9157432 -0.4017645 0 0.9151557 -0.4031006 0 0.9145088 -0.404566 0 0.9138885 -0.4059655 0 0.9132917 -0.4073063 0 0.9126414 -0.4087614 0 0.9120146 -0.4101579 0 0.9114116 -0.4114962 0 0.910748 -0.4129626 0 0.9101148 -0.4143561 0 0.9094762 -0.4157561 0 0.9088614 -0.4170982 0 0.9081959 -0.4185456 0 0.9075769 -0.4198859 0 0.9069298 -0.421282 0 0.9062471 -0.4227483 0 0.905629 -0.424071 0 0.9049684 -0.4254789 0 0.9043091 -0.4268783 0 0.9036548 -0.4282618 0 0.9030178 -0.4296032 0 0.9023219 -0.4310629 0 0.901688 -0.4323875 0 0.9010144 -0.4337894 0 0.9003423 -0.4351826 0 0.8996912 -0.4365271 0 0.8990185 -0.4379106 0 0.8983364 -0.4393084 0 0.8976558 -0.4406974 0 0.8969963 -0.4420381 0 0.8963116 -0.4434251 0 0.895648 -0.444764 0 0.8949241 -0.4462186 0 0.8942601 -0.4475477 0 0.8935629 -0.448938 0 0.8928598 -0.4503349 0 0.8921898 -0.451661 0 0.8914822 -0.4530556 0 0.8908001 -0.4543955 0 0.8900924 -0.4557802 0 0.8893826 -0.4571636 0 0.8886943 -0.4585005 0 0.8880038 -0.4598362 0 0.8872877 -0.4612163 0 0.8865932 -0.4625501 0 0.8858604 -0.4639518 0 0.8851702 -0.4652675 0 0.8844373 -0.466659 0 0.8837345 -0.4679886 0 0.8830254 -0.4693252 0 0.8822584 -0.4707657 0 0.8815494 -0.472092 0 0.8808296 -0.4734335 0 0.8800885 -0.4748099 0 0.8793734 -0.4761329 0 0.8786475 -0.4774713 0 0.8778911 -0.4788603 0 0.8771699 -0.4801801 0 0.8764423 -0.481507 0 0.8757125 -0.4828329 0 0.8749808 -0.4841576 0 0.8742141 -0.4855406 0 0.8734737 -0.4868714 0 0.8727027 -0.4882519 0 0.8719582 -0.4895803 0 0.8712116 -0.4909077 0 0.8704677 -0.4922257 0 0.8697124 -0.4935591 0 0.8689309 -0.4949334 0 0.8681714 -0.4962645 0 0.8674098 -0.4975944 0 0.8666559 -0.4989066 0 0.8658901 -0.5002342 0 0.8651273 -0.5015524 0 0.8643575 -0.5028778 0 0.8635957 -0.5041851 0 0.8628119 -0.5055251 0 0.8620361 -0.5068469 0 0.8612682 -0.5081506 0 0.8604784 -0.5094872 0 0.8596964 -0.5108054 0 0.8589125 -0.5121224 0 0.8581163 -0.5134554 0 0.8573284 -0.51477 0 0.8565727 -0.5160264 0 0.8557361 -0.5174128 0 0.8549525 -0.5187064 0 0.8541356 -0.5200505 0 0.8533376 -0.5213589 0 0.8525722 -0.5226094 0 0.8517597 -0.5239327 0 0.8509451 -0.5252546 0 0.8501285 -0.5265753 0 0.8493207 -0.5278773 0 0.848524 -0.5291569 0 0.8477122 -0.5304564 0 0.8469225 -0.5317163 0 0.8460848 -0.5330482 0 0.8452562 -0.5343614 0 0.8444366 -0.5356556 0 0.8436279 -0.5369283 0 0.8428044 -0.5382199 0 0.8419566 -0.5395454 0 0.8411066 -0.5408695 0 0.8403013 -0.5421198 0 0.8394941 -0.5433689 0 0.838638 -0.5446892 0 0.8378269 -0.5459359 0 0.8369669 -0.5472536 0 0.8361165 -0.5485521 0 0.835288 -0.5498127 0 0.8344458 -0.5510902 0 0.8336012 -0.5523667 0 0.8327551 -0.5536416 0 0.8318949 -0.5549334 0 0.8310567 -0.5561878 0 0.8301685 -0.5575127 0 0.8293384 -0.5587466 0 0.8284585 -0.5600507 0 0.8276364 -0.5612648 0 0.8267524 -0.5625662 0 0.8259025 -0.563813 0 0.8250147 -0.5651115 0 0.8241609 -0.5663557 0 0.8232567 -0.5676694 0 0.822423 -0.5688766 0 0.8215272 -0.5701693 0 0.8206533 -0.5714265 0 0.8197901 -0.5726641 0 0.8189252 -0.5739004 0 0.8180089 -0.5752056 0 0.8171639 -0.5764056 0 0.8162437 -0.577708 0 0.8153581 -0.5789571 0 0.8144837 -0.5801866 0 0.8135812 -0.5814514 0 0.8127031 -0.5826781 0 0.8117967 -0.5839403 0 0.8109149 -0.5851643 0 0.8100281 -0.5863912 0 0.8091191 -0.5876449 0 0.8082283 -0.5888693 0 0.8073021 -0.5901384 0 0.8063977 -0.5913738 0 0.8054776 -0.5926263 0 0.8045556 -0.5938775 0 0.8036825 -0.5950584 0 0.8027333 -0.5963383 0 0.8018427 -0.5975353 0 0.800913 -0.5987808 0 0.7999953 -0.6000062 0 0.7990618 -0.6012489 0 0.7981638 -0.6024405 0 0.7972265 -0.6036804 0 0.7963247 -0.6048695 0 0.7953605 -0.6061369 0 0.7944549 -0.6073232 0 0.79351 -0.6085572 0 0.7925865 -0.6097596 0 0.7916523 -0.6109719 0 0.7906874 -0.6122202 0 0.7897872 -0.6133809 0 0.7888184 -0.6146264 0 0.7878854 -0.615822 0 0.7869423 -0.6170268 0 0.7859677 -0.6182677 0 0.7850291 -0.6194591 0 0.7840656 -0.6206781 0 0.7831231 -0.6218668 0 0.7821561 -0.6230827 0 0.7812251 -0.6242496 0 0.780224 -0.6255003 0 0.7792894 -0.6266643 0 0.7783531 -0.6278269 0 0.7773843 -0.6290261 0 0.7764444 -0.6301859 0 0.7753957 -0.6314758 0 0.7744522 -0.6326325 0 0.7734915 -0.6338068 0 0.7725133 -0.6349988 0 0.7715488 -0.6361702 0 0.7705984 -0.6373212 0 0.7696145 -0.6385088 0 0.7686066 -0.6397219 0 0.767635 -0.6408874 0 0.7666456 -0.6420705 0 0.7656705 -0.6432331 0 0.7646936 -0.6443942 0 0.7636604 -0.6456183 0 0.7626799 -0.6467761 0 0.7616814 -0.6479518 0 0.7607195 -0.6490809 0 0.7597336 -0.6502344 0 0.7587298 -0.6514056 0 0.757724 -0.6525752 0 0.7567165 -0.6537433 0 0.7557237 -0.6548906 0 0.7546741 -0.6560999 0 0.7536998 -0.657219 0 0.752685 -0.6583808 0 0.7516686 -0.6595411 0 0.7506889 -0.6606559 0 0.7496689 -0.6618131 0 0.7486472 -0.6629687 0 0.7476065 -0.664142 0 0.7465813 -0.6652943 0 0.7455542 -0.666445 0 0.7445255 -0.667594 0 0.743555 -0.6686749 0 0.7425054 -0.6698402 0 0.7414889 -0.6709653 0 0.7404357 -0.6721273 0 0.7394194 -0.6732451 0 0.7383804 -0.6743845 0 0.7373606 -0.6754994 0 0.7363004 -0.6766549 0 0.7352561 -0.6777893 0 0.7341745 -0.6789609 0 0.7332044 -0.6800084 0 0.7321552 -0.6811379 0 0.7310682 -0.6823044 0 0.7300363 -0.6834084 0 0.7289639 -0.6845523 0 0.7279673 -0.685612 0 0.7268914 -0.6867524 0 0.7258139 -0.6878913 0 0.7248122 -0.6889466 0 0.7237128 -0.6901014 0 0.7226486 -0.6912156 0 0.7216234 -0.6922859 0 0.7205187 -0.6934356 0 0.7194885 -0.6945044 0 0.7184192 -0.6956104 0 0.7173094 -0.6967549 0 0.7162944 -0.6977983 0 0.7151811 -0.6989393 0 0.7141437 -0.6999992 0 0.7130461 -0.7011173 0 0.7119665 -0.7022135 0 0.7109044 -0.7032887 0 0.7098022 -0.7044011 0 0.7087369 -0.705473 0 0.7076506 -0.7065626 0 0.7065626 -0.7076506 0 0.705473 -0.7087369 0 0.7044205 -0.7097829 0 0.7033084 -0.710885 0 0.702194 -0.7119856 0 0.7011367 -0.713027 0 0.700019 -0.7141243 0 0.6989194 -0.7152005 0 0.6978182 -0.7162749 0 0.6967543 -0.7173099 0 0.6956111 -0.7184186 0 0.6945238 -0.7194698 0 0.6934551 -0.7205 0 0.6922867 -0.7216225 0 0.6912147 -0.7226495 0 0.6901412 -0.7236748 0 0.6889476 -0.7248112 0 0.6878708 -0.7258332 0 0.6867536 -0.7268903 0 0.6856325 -0.7279479 0 0.6845122 -0.7290014 0 0.6834084 -0.7300363 0 0.6822643 -0.7311057 0 0.6811781 -0.7321178 0 0.6800486 -0.7331671 0 0.6789593 -0.734176 0 0.677749 -0.7352934 0 0.6766566 -0.7362987 0 0.6755205 -0.7373412 0 0.6743652 -0.738398 0 0.673247 -0.7394177 0 0.6721273 -0.7404357 0 0.6709673 -0.741487 0 0.6698616 -0.742486 0 0.6687157 -0.7435182 0 0.6675725 -0.7445448 0 0.6664234 -0.7455735 0 0.6652943 -0.7465813 0 0.664142 -0.7476065 0 0.6629712 -0.748645 0 0.6618157 -0.7496666 0 0.6606585 -0.7506865 0 0.6595218 -0.7516855 0 0.6583836 -0.7526826 0 0.6571998 -0.7537165 0 0.6560585 -0.7547101 0 0.6548714 -0.7557405 0 0.6537656 -0.7566972 0 0.6525976 -0.7577048 0 0.651428 -0.7587106 0 0.6502569 -0.7597145 0 0.6491226 -0.7606839 0 0.647971 -0.7616651 0 0.6467728 -0.7626827 0 0.6455956 -0.7636795 0 0.6443942 -0.7646936 0 0.6432368 -0.7656674 0 0.6420705 -0.7666456 0 0.6408874 -0.767635 0 0.639741 -0.7685906 0 0.6385319 -0.7695955 0 0.6373443 -0.7705792 0 0.6361702 -0.7715488 0 0.6349797 -0.7725288 0 0.6337645 -0.7735261 0 0.6326091 -0.7744712 0 0.6314524 -0.7754147 0 0.6302093 -0.7764253 0 0.6290495 -0.7773653 0 0.6278504 -0.778334 0 0.6266407 -0.7793084 0 0.6254767 -0.7802429 0 0.6242496 -0.7812251 0 0.6230589 -0.782175 0 0.6218668 -0.7831231 0 0.620697 -0.7840505 0 0.6194162 -0.7850628 0 0.6182677 -0.7859677 0 0.6170079 -0.786957 0 0.6158461 -0.7878664 0 0.6146452 -0.7888037 0 0.6134052 -0.7897683 0 0.6122015 -0.7907019 0 0.6109719 -0.7916523 0 0.6098028 -0.7925532 0 0.6085572 -0.79351 0 0.6073477 -0.7944362 0 0.6061123 -0.7953792 0 0.6048754 -0.7963201 0 0.6036991 -0.7972123 0 0.6024466 -0.7981592 0 0.6012428 -0.7990666 0 0.5999876 -0.8000093 0 0.5987808 -0.800913 0 0.5975353 -0.8018427 0 0.5963132 -0.8027518 0 0.5950649 -0.8036776 0 0.5938524 -0.8045741 0 0.5926263 -0.8054776 0 0.5913738 -0.8063977 0 0.5901198 -0.8073157 0 0.5888762 -0.8082234 0 0.5876703 -0.8091005 0 0.5863982 -0.810023 0 0.5851643 -0.8109149 0 0.5839403 -0.8117967 0 0.5826781 -0.8127031 0 0.5814514 -0.8135812 0 0.5801866 -0.8144837 0 0.5789313 -0.8153765 0 0.5776896 -0.8162566 0 0.5764315 -0.8171455 0 0.5751613 -0.8180401 0 0.5739004 -0.8189252 0 0.5726641 -0.8197901 0 0.5714265 -0.8206533 0 0.5701512 -0.8215399 0 0.5688584 -0.8224356 0 0.5676431 -0.8232749 0 0.5663375 -0.8241735 0 0.5650669 -0.8250452 0 0.5638214 -0.8258968 0 0.5625481 -0.8267646 0 0.5612734 -0.8276306 0 0.560024 -0.8284765 0 0.5587466 -0.8293384 0 0.5574946 -0.8301805 0 0.5561878 -0.8310567 0 0.5549334 -0.8318949 0 0.5536507 -0.8327491 0 0.5523667 -0.8336012 0 0.5510902 -0.8344458 0 0.5497949 -0.8352997 0 0.5485342 -0.8361281 0 0.5472536 -0.8369669 0 0.5459632 -0.8378092 0 0.544707 -0.8386265 0 0.5433866 -0.8394826 0 0.5421198 -0.8403013 0 0.5408598 -0.8411129 0 0.5395355 -0.8419629 0 0.5382376 -0.8427933 0 0.5369107 -0.8436391 0 0.535638 -0.8444477 0 0.534379 -0.8452451 0 0.5330482 -0.8460848 0 0.5317442 -0.8469051 0 0.530439 -0.8477233 0 0.5291743 -0.8485131 0 0.5278667 -0.8493273 0 0.5265299 -0.8501566 0 0.5252546 -0.8509451 0 0.5239154 -0.8517704 0 0.5226094 -0.8525722 0 0.5213305 -0.8533548 0 0.5200222 -0.8541529 0 0.518678 -0.8549698 0 0.5173955 -0.8557464 0 0.5160549 -0.8565555 0 0.51477 -0.8573284 0 0.5134554 -0.8581163 0 0.5121054 -0.8589227 0 0.5108224 -0.8596862 0 0.5094701 -0.8604885 0 0.5081794 -0.8612512 0 0.5068639 -0.8620262 0 0.5055081 -0.8628219 0 0.5041851 -0.8635957 0 0.5028946 -0.8643478 0 0.5015355 -0.8651371 0 0.5002427 -0.8658853 0 0.498869 -0.8666775 0 0.4975569 -0.8674314 0 0.4962435 -0.8681834 0 0.4948956 -0.8689524 0 0.4935507 -0.869717 0 0.4922339 -0.870463 0 0.490916 -0.871207 0 0.4895508 -0.8719748 0 0.4882306 -0.8727147 0 0.4868796 -0.8734691 0 0.4855406 -0.8742141 0 0.4841873 -0.8749644 0 0.4828627 -0.8756961 0 0.481507 -0.8764423 0 0.4801801 -0.8771699 0 0.4788222 -0.8779119 0 0.4774631 -0.8786518 0 0.4761029 -0.8793896 0 0.4747879 -0.8801004 0 0.4734254 -0.8808339 0 0.4720618 -0.8815655 0 0.4707435 -0.8822701 0 0.4693475 -0.8830136 0 0.4680109 -0.8837228 0 0.466659 -0.8844373 0 0.46529 -0.8851583 0 0.4639518 -0.8858604 0 0.4625806 -0.8865773 0 0.4612084 -0.8872919 0 0.4598362 -0.8880038 0 0.4585083 -0.8886902 0 0.4571329 -0.8893985 0 0.4557722 -0.8900964 0 0.4543955 -0.8908001 0 0.4530326 -0.8914939 0 0.4516531 -0.8921937 0 0.4503039 -0.8928754 0 0.448938 -0.8935629 0 0.44754 -0.8942641 0 0.4461875 -0.8949396 0 0.4447873 -0.8956363 0 0.4434328 -0.8963078 0 0.4420772 -0.8969771 0 0.4406897 -0.8976595 0 0.4393008 -0.8983402 0 0.4379106 -0.8990185 0 0.4365662 -0.8996722 0 0.4351435 -0.9003611 0 0.4337818 -0.9010181 0 0.4323875 -0.901688 0 0.4310389 -0.9023334 0 0.4296424 -0.9029991 0 0.4282618 -0.9036548 0 0.4268466 -0.9043241 0 0.4254789 -0.9049684 0 0.4240636 -0.9056326 0 0.4227238 -0.9062586 0 0.4213213 -0.9069114 0 0.4198859 -0.9075769 0 0.4185136 -0.9082106 0 0.4171377 -0.9088433 0 0.4157634 -0.9094728 0 0.414324 -0.9101295 0 0.4129626 -0.910748 0 0.4115357 -0.9113937 0 0.4101256 -0.9120291 0 0.4087614 -0.9126414 0 0.4073315 -0.9132804 0 0.405933 -0.9139029 0 0.404566 -0.9145088 0 0.4031331 -0.9151414 0 0.4017318 -0.9157574 0 0.4003296 -0.9163712 0 0.398908 -0.9169911 0 0.397518 -0.9175944 0 0.3961316 -0.9181938 0 0.3946929 -0.9188131 0 0.3932673 -0.9194242 0 0.3918737 -0.9200191 0 0.390465 -0.9206178 0 0.3890696 -0.9212085 0 0.3876401 -0.9218109 0 0.3862288 -0.922403 0 0.3847837 -0.9230068 0 0.3833984 -0.9235832 0 0.3819983 -0.9241631 0 0.3805505 -0.9247602 0 0.3791154 -0.9253494 0 0.3777264 -0.9259173 0 0.3763229 -0.9264886 0 0.3748517 -0.9270849 0 0.3734465 -0.9276517 0 0.3720404 -0.9282166 0 0.3706001 -0.9287927 0 0.3691721 -0.9293611 0 0.3677433 -0.9299274 0 0.3663339 -0.9304835 0 0.3649033 -0.9310455 0 0.3634923 -0.9315972 0 0.3620131 -0.932173 0 0.3606267 -0.9327102 0 0.3591796 -0.9332685 0 0.3577237 -0.9338276 0 0.3563088 -0.9343684 0 0.354906 -0.934902 0 0.3534474 -0.9354545 0 0.3519962 -0.9360014 0 0.3505911 -0.9365286 0 0.3491297 -0.9370744 0 0.3476889 -0.93761 0 0.3462815 -0.9381307 0 0.3448175 -0.9386698 0 0.3433742 -0.9391987 0 0.3419427 -0.9397209 0 0.3404855 -0.9402499 0 0.3390524 -0.9407675 0 0.3376185 -0.9412831 0 0.3361838 -0.9417964 0 0.3347015 -0.9423242 0 0.3332652 -0.9428332 0 0.3318281 -0.9433399 0 0.3303902 -0.9438445 0 0.328917 -0.9443589 0 0.3274775 -0.944859 0 0.3260374 -0.945357 0 0.3245965 -0.9458526 0 0.323132 -0.9463539 0 0.3216896 -0.9468452 0 0.3202116 -0.9473461 0 0.3187795 -0.947829 0 0.3173466 -0.9483096 0 0.3158664 -0.9488038 0 0.3143854 -0.9492955 0 0.3129503 -0.9497696 0 0.3115029 -0.9502453 0 0.3100427 -0.9507227 0 0.3085941 -0.9511939 0 0.3071095 -0.9516743 0 0.3056469 -0.9521449 0 0.3042075 -0.9526059 0 0.3027209 -0.9530794 0 0.3012913 -0.9535322 0 0.2998145 -0.9539976 0 0.2983369 -0.9544607 0 0.2968941 -0.9549104 0 0.2953907 -0.9553766 0 0.2939821 -0.955811 0 0.2924663 -0.9562758 0 0.2910317 -0.9567134 0 0.2895501 -0.9571629 0 0.2880893 -0.9576036 0 0.2866063 -0.9580485 0 0.2851333 -0.9584879 0 0.2836848 -0.9589177 0 0.2822105 -0.9593526 0 0.2806997 -0.9597957 0 0.2792599 -0.9602156 0 0.2777939 -0.9606408 0 0.2762962 -0.9610726 0 0.2748392 -0.9614902 0 0.2733866 -0.9619043 0 0.2718718 -0.9623335 0 0.2704023 -0.9627474 0 0.2689222 -0.9631619 0 0.2674515 -0.9635714 0 0.2659701 -0.9639813 0 0.2644881 -0.964389 0 0.2630155 -0.9647916 0 0.2615422 -0.9651921 0 0.2600585 -0.9655929 0 0.2585477 -0.9659986 0 0.2571185 -0.96638 0 0.2555967 -0.9667836 0 0.2541203 -0.9671727 0 0.2526434 -0.9675595 0 0.2511658 -0.9679441 0 0.2496512 -0.9683359 0 0.2482136 -0.9687054 0 0.2466979 -0.9690924 0 0.2451861 -0.9694761 0 0.2437468 -0.969839 0 0.2422294 -0.9702191 0 0.2407479 -0.9705877 0 0.2392428 -0.9709599 0 0.2378014 -0.9713139 0 0.2362449 -0.9716935 0 0.234807 -0.972042 0 0.233295 -0.972406 0 0.2318149 -0.97276 0 0.2303017 -0.9731193 0 0.2288249 -0.9734676 0 0.2273064 -0.9738233 0 0.2258327 -0.9741661 0 0.2243543 -0.9745077 0 0.2228385 -0.9748555 0 0.2213264 -0.9751999 0 0.2198464 -0.9755345 0 0.2183743 -0.9758651 0 0.2168564 -0.9762036 0 0.2153421 -0.9765387 0 0.2138643 -0.9768634 0 0.212349 -0.977194 0 0.2108743 -0.9775133 0 0.2093579 -0.9778391 0 0.2078822 -0.9781539 0 0.2063649 -0.9784751 0 0.204851 -0.9787932 0 0.2033739 -0.9791012 0 0.2018552 -0.9794155 0 0.2003437 -0.9797258 0 0.1988278 -0.9800345 0 0.1973527 -0.9803326 0 0.1958359 -0.9806368 0 0.1943598 -0.9809304 0 0.1928458 -0.9812291 0 0.1913278 -0.9815262 0 0.1898128 -0.9818203 0 0.1882939 -0.9821128 0 0.1868228 -0.9823937 0 0.1853031 -0.9826815 0 0.18379 -0.9829656 0 0.1822764 -0.9832474 0 0.1807965 -0.9835206 0 0.179282 -0.9837978 0 0.1777262 -0.98408 0 0.1762519 -0.9843451 0 0.1747328 -0.9846159 0 0.1732577 -0.9848766 0 0.1717068 -0.9851481 0 0.1701899 -0.9854114 0 0.1687104 -0.9856657 0 0.1671581 -0.9859302 0 0.1656842 -0.9861789 0 0.1641659 -0.9864329 0 0.1626124 -0.9866901 0 0.1611373 -0.986932 0 0.1596209 -0.9871784 0 0.1581072 -0.987422 0 0.1565901 -0.9876638 0 0.1550726 -0.9879032 0 0.1535607 -0.9881393 0 0.1520426 -0.988374 0 0.1504919 -0.9886113 0 0.1490139 -0.9888351 0 0.1474949 -0.9890629 0 0.1459839 -0.989287 0 0.1444289 -0.9895153 0 0.1429525 -0.9897296 0 0.1413996 -0.9899526 0 0.1399224 -0.9901625 0 0.1383662 -0.9903812 0 0.1368504 -0.9905918 0 0.135375 -0.9907944 0 0.1338204 -0.9910057 0 0.132268 -0.991214 0 0.1307892 -0.9914102 0 0.1292744 -0.9916089 0 0.1277186 -0.9918105 0 0.1262056 -0.9920041 0 0.1247281 -0.992191 0 0.1231738 -0.9923852 0 0.1216205 -0.9925767 0 0.1201422 -0.9927567 0 0.1185894 -0.9929434 0 0.1170734 -0.9931233 0 0.1155583 -0.9933007 0 0.1140419 -0.993476 0 0.1125274 -0.9936487 0 0.1109731 -0.9938235 0 0.109458 -0.9939915 0 0.1079427 -0.9941572 0 0.1063877 -0.9943248 0 0.1049124 -0.9944816 0 0.1033578 -0.9946443 0 0.1018031 -0.9948046 0 0.100326 -0.9949547 0 0.0987727 -0.9951101 0 0.09725672 -0.9952594 0 0.09574145 -0.9954063 0 0.09418743 -0.9955545 0 0.09267175 -0.9956968 0 0.09115672 -0.9958366 0 0.08960288 -0.9959776 0 0.08808654 -0.9961129 0 0.08657175 -0.9962457 0 0.08501732 -0.9963796 0 0.08350205 -0.9965076 0 0.08198666 -0.9966335 0 0.08043241 -0.9967601 0 0.07891738 -0.9968813 0 0.07740139 -0.997 0 0.07584738 -0.9971196 0 0.07433182 -0.9972336 0 0.07281607 -0.9973455 0 0.07126224 -0.9974576 0 0.06974685 -0.9975647 0 0.06819266 -0.9976722 0 0.06667762 -0.9977747 0 0.06516176 -0.9978748 0 0.06360769 -0.997975 0 0.06209218 -0.9980705 0 0.06057655 -0.9981636 0 0.05902236 -0.9982568 0 0.05746835 -0.9983474 0 0.05595314 -0.9984334 0 0.05443751 -0.9985172 0 0.05292207 -0.9985986 0 0.05136775 -0.9986798 0 0.0498138 -0.9987586 0 0.04829823 -0.998833 0 0.04678285 -0.9989051 0 0.04522854 -0.9989767 0 0.04371333 -0.9990442 0 0.04215902 -0.999111 0 0.04064363 -0.9991738 0 0.03912812 -0.9992343 0 0.03753513 -0.9992954 0 0.03605842 -0.9993497 0 0.03450441 -0.9994046 0 0.03298878 -0.9994558 0 0.03143459 -0.9995059 0 0.02991926 -0.9995524 0 0.02836501 -0.9995976 0 0.02684962 -0.9996396 0 0.02529537 -0.9996801 0 0.02377998 -0.9997172 0 0.02222573 -0.9997531 0 0.02071028 -0.9997856 0 0.01919496 -0.9998158 0 0.0176407 -0.9998445 0 0.01608645 -0.9998707 0 0.01457107 -0.9998939 0 0.01305568 -0.9999148 0 0.01150143 -0.999934 0 0.00994718 -0.9999506 0 0.008470594 -0.9999641 0 0.006877541 -0.9999763 0 0.005362153 -0.9999856 0 0.003846704 -0.9999927 0 0.002292513 -0.9999974 0 7.77124e-4 -0.9999997 0 -7.77124e-4 -0.9999997 0 -0.002292513 -0.9999974 0 -0.003846704 -0.9999927 0 -0.005362153 -0.9999857 0 -0.006877541 -0.9999763 0 -0.008470654 -0.9999642 0 -0.00994718 -0.9999506 0 -0.01150143 -0.999934 0 -0.01305562 -0.9999148 0 -0.01457101 -0.9998939 0 -0.01608639 -0.9998706 0 -0.01764065 -0.9998445 0 -0.01919496 -0.9998158 0 -0.02071028 -0.9997856 0 -0.02222579 -0.9997531 0 -0.02377992 -0.9997172 0 -0.02529537 -0.9996801 0 -0.02684962 -0.9996396 0 -0.02836495 -0.9995977 0 -0.0299192 -0.9995524 0 -0.03143459 -0.9995059 0 -0.03298896 -0.9994558 0 -0.03450441 -0.9994046 0 -0.03605842 -0.9993497 0 -0.03753513 -0.9992954 0 -0.03912812 -0.9992343 0 -0.04064339 -0.9991738 0 -0.04215902 -0.999111 0 -0.04371309 -0.9990442 0 -0.04522871 -0.9989767 0 -0.04678261 -0.9989051 0 -0.04829823 -0.998833 0 -0.04981356 -0.9987586 0 -0.05136775 -0.9986798 0 -0.05292207 -0.9985986 0 -0.05443751 -0.9985172 0 -0.05595284 -0.9984334 0 -0.05746835 -0.9983474 0 -0.05902266 -0.9982568 0 -0.06057655 -0.9981636 0 -0.06209248 -0.9980705 0 -0.06360709 -0.9979751 0 -0.06516176 -0.9978748 0 -0.06667697 -0.9977747 0 -0.06819266 -0.9976722 0 -0.06974685 -0.9975647 0 -0.07126224 -0.9974576 0 -0.07281678 -0.9973453 0 -0.07433182 -0.9972336 0 -0.07584738 -0.9971196 0 -0.07740139 -0.997 0 -0.0789166 -0.9968813 0 -0.08043241 -0.9967601 0 -0.08198583 -0.9966335 0 -0.08350205 -0.9965076 0 -0.08501732 -0.9963796 0 -0.08657175 -0.9962457 0 -0.08808743 -0.9961128 0 -0.08960205 -0.9959778 0 -0.09115672 -0.9958366 0 -0.09267175 -0.9956968 0 -0.09418743 -0.9955545 0 -0.09574145 -0.9954063 0 -0.09725767 -0.9952592 0 -0.0987727 -0.9951101 0 -0.100326 -0.9949547 0 -0.101804 -0.9948046 0 -0.1033568 -0.9946444 0 -0.1049113 -0.9944816 0 -0.1063887 -0.9943246 0 -0.1079427 -0.9941572 0 -0.109458 -0.9939915 0 -0.1109731 -0.9938235 0 -0.1125274 -0.9936487 0 -0.114043 -0.9934759 0 -0.1155583 -0.9933007 0 -0.1170746 -0.9931232 0 -0.1185894 -0.9929434 0 -0.1201434 -0.9927566 0 -0.1216205 -0.9925767 0 -0.1231738 -0.9923852 0 -0.1247293 -0.9921909 0 -0.1262032 -0.9920045 0 -0.127721 -0.9918102 0 -0.1292769 -0.9916086 0 -0.1307892 -0.9914102 0 -0.1322655 -0.9912143 0 -0.1338204 -0.9910057 0 -0.135375 -0.9907944 0 -0.136853 -0.9905914 0 -0.1383662 -0.9903812 0 -0.1399198 -0.9901629 0 -0.1413968 -0.989953 0 -0.1429497 -0.98973 0 -0.1444289 -0.9895153 0 -0.1459839 -0.989287 0 -0.1474977 -0.9890625 0 -0.1490139 -0.9888351 0 -0.150489 -0.9886118 0 -0.1520455 -0.9883735 0 -0.1535578 -0.9881398 0 -0.1550756 -0.9879027 0 -0.156593 -0.9876633 0 -0.1581041 -0.9874225 0 -0.1596209 -0.9871784 0 -0.1611373 -0.986932 0 -0.1626155 -0.9866896 0 -0.1641659 -0.9864329 0 -0.1656842 -0.9861789 0 -0.1671614 -0.9859296 0 -0.1687136 -0.9856652 0 -0.1701899 -0.9854114 0 -0.1717068 -0.9851481 0 -0.1732611 -0.984876 0 -0.1747362 -0.9846154 0 -0.1762552 -0.9843445 0 -0.1777296 -0.9840794 0 -0.179282 -0.9837978 0 -0.1807965 -0.9835206 0 -0.1822764 -0.9832474 0 -0.18379 -0.9829656 0 -0.1853031 -0.9826815 0 -0.1868228 -0.9823937 0 -0.1882975 -0.9821121 0 -0.1898128 -0.9818203 0 -0.1913278 -0.9815262 0 -0.1928421 -0.9812299 0 -0.1943561 -0.9809311 0 -0.1958321 -0.9806375 0 -0.1973527 -0.9803326 0 -0.1988278 -0.9800345 0 -0.2003399 -0.9797266 0 -0.201859 -0.9794147 0 -0.2033739 -0.9791012 0 -0.2048471 -0.978794 0 -0.2063649 -0.9784751 0 -0.2078822 -0.9781539 0 -0.2093539 -0.97784 0 -0.2108702 -0.9775141 0 -0.212349 -0.977194 0 -0.2138643 -0.9768634 0 -0.2153421 -0.9765387 0 -0.2168564 -0.9762036 0 -0.2183701 -0.9758661 0 -0.2198464 -0.9755345 0 -0.2213264 -0.9751999 0 -0.2228385 -0.9748555 0 -0.2243586 -0.9745067 0 -0.2258327 -0.9741661 0 -0.2273107 -0.9738223 0 -0.2288249 -0.9734676 0 -0.2302974 -0.9731203 0 -0.2318149 -0.97276 0 -0.233295 -0.972406 0 -0.234807 -0.972042 0 -0.2362449 -0.9716935 0 -0.2377969 -0.971315 0 -0.2392383 -0.9709609 0 -0.2407524 -0.9705866 0 -0.2422294 -0.9702191 0 -0.2437468 -0.969839 0 -0.2451815 -0.9694772 0 -0.2466979 -0.9690924 0 -0.2482089 -0.9687066 0 -0.2496559 -0.9683346 0 -0.2511658 -0.9679441 0 -0.2526338 -0.967562 0 -0.2541203 -0.9671727 0 -0.2555967 -0.9667836 0 -0.2571088 -0.9663825 0 -0.2585477 -0.9659986 0 -0.2600682 -0.9655903 0 -0.2615422 -0.9651921 0 -0.2630155 -0.9647916 0 -0.2644981 -0.9643862 0 -0.2659701 -0.9639813 0 -0.2674515 -0.9635714 0 -0.2689222 -0.9631619 0 -0.2704023 -0.9627474 0 -0.2718819 -0.9623307 0 -0.2733866 -0.9619043 0 -0.2748289 -0.9614932 0 -0.2763065 -0.9610697 0 -0.2777835 -0.9606438 0 -0.2792599 -0.9602156 0 -0.2806997 -0.9597957 0 -0.2822105 -0.9593526 0 -0.2836848 -0.9589177 0 -0.2851227 -0.958491 0 -0.2865957 -0.9580517 0 -0.2880893 -0.9576036 0 -0.2895501 -0.9571629 0 -0.2910317 -0.9567134 0 -0.2924771 -0.9562725 0 -0.2939821 -0.955811 0 -0.2953907 -0.9553766 0 -0.2968941 -0.9549104 0 -0.298348 -0.9544572 0 -0.2998145 -0.9539976 0 -0.3012913 -0.9535322 0 -0.3027321 -0.9530758 0 -0.3041962 -0.9526095 0 -0.3056469 -0.9521449 0 -0.3071208 -0.9516705 0 -0.3086054 -0.9511902 0 -0.3100313 -0.9507264 0 -0.3115029 -0.9502453 0 -0.3129503 -0.9497696 0 -0.3143854 -0.9492955 0 -0.3158547 -0.9488075 0 -0.317335 -0.9483136 0 -0.3187795 -0.947829 0 -0.3202116 -0.9473461 0 -0.3216896 -0.9468452 0 -0.323132 -0.9463539 0 -0.3245965 -0.9458526 0 -0.3260493 -0.9453528 0 -0.3274896 -0.9448549 0 -0.328929 -0.9443547 0 -0.3303902 -0.9438445 0 -0.3318281 -0.9433399 0 -0.3332774 -0.9428288 0 -0.3347138 -0.9423199 0 -0.3361838 -0.9417964 0 -0.3376309 -0.9412787 0 -0.3390648 -0.9407631 0 -0.340498 -0.9402453 0 -0.3419302 -0.9397253 0 -0.3433742 -0.9391987 0 -0.3448049 -0.9386744 0 -0.3462815 -0.9381307 0 -0.3476889 -0.93761 0 -0.3491171 -0.9370792 0 -0.3506039 -0.9365239 0 -0.3519962 -0.9360014 0 -0.3534346 -0.9354593 0 -0.354906 -0.934902 0 -0.3563088 -0.9343684 0 -0.3577237 -0.9338276 0 -0.3591796 -0.9332685 0 -0.3606267 -0.9327102 0 -0.3620262 -0.932168 0 -0.3635055 -0.9315922 0 -0.3648901 -0.9310507 0 -0.3663339 -0.9304835 0 -0.3677433 -0.9299274 0 -0.3691721 -0.9293611 0 -0.3706134 -0.9287872 0 -0.3720538 -0.9282112 0 -0.3734465 -0.9276517 0 -0.3748517 -0.9270849 0 -0.3763093 -0.9264942 0 -0.3777264 -0.9259173 0 -0.3791291 -0.9253439 0 -0.3805505 -0.9247602 0 -0.3819846 -0.9241688 0 -0.3833984 -0.9235832 0 -0.3847975 -0.9230011 0 -0.3862288 -0.922403 0 -0.3876401 -0.9218109 0 -0.3890556 -0.9212143 0 -0.390465 -0.9206178 0 -0.3918597 -0.9200251 0 -0.3932533 -0.9194303 0 -0.394707 -0.918807 0 -0.3961316 -0.9181938 0 -0.3975039 -0.9176005 0 -0.3988938 -0.9169973 0 -0.4003296 -0.9163712 0 -0.4017318 -0.9157574 0 -0.4031331 -0.9151414 0 -0.404566 -0.9145088 0 -0.405933 -0.9139029 0 -0.4073459 -0.913274 0 -0.4087614 -0.9126414 0 -0.4101256 -0.9120291 0 -0.4115211 -0.9114002 0 -0.4129626 -0.910748 0 -0.414324 -0.9101295 0 -0.4157487 -0.9094795 0 -0.417123 -0.9088501 0 -0.4185136 -0.9082106 0 -0.4198859 -0.9075769 0 -0.4213066 -0.9069184 0 -0.4227089 -0.9062656 0 -0.4240784 -0.9056255 0 -0.4254789 -0.9049684 0 -0.4268466 -0.9043241 0 -0.4282618 -0.9036548 0 -0.4296274 -0.9030063 0 -0.4310238 -0.9023407 0 -0.4323875 -0.901688 0 -0.4337969 -0.9010106 0 -0.4351587 -0.9003538 0 -0.4365509 -0.8996796 0 -0.4379106 -0.8990185 0 -0.4393161 -0.8983327 0 -0.4407051 -0.897652 0 -0.4420617 -0.8969846 0 -0.4434173 -0.8963153 0 -0.4448028 -0.8956286 0 -0.4461875 -0.8949396 0 -0.4475555 -0.8942562 0 -0.448938 -0.8935629 0 -0.4503039 -0.8928754 0 -0.4516688 -0.8921858 0 -0.4530169 -0.8915019 0 -0.4543955 -0.8908001 0 -0.4557881 -0.8900884 0 -0.4571329 -0.8893985 0 -0.4584925 -0.8886983 0 -0.4598362 -0.8880038 0 -0.4612243 -0.8872836 0 -0.4625806 -0.8865773 0 -0.4639518 -0.8858604 0 -0.4653059 -0.8851499 0 -0.466659 -0.8844373 0 -0.4680269 -0.8837142 0 -0.4693635 -0.883005 0 -0.4707274 -0.8822788 0 -0.4720618 -0.8815655 0 -0.4734416 -0.8808253 0 -0.4747716 -0.8801091 0 -0.4761029 -0.8793896 0 -0.4774794 -0.878643 0 -0.4788385 -0.8779031 0 -0.4801801 -0.8771699 0 -0.481507 -0.8764423 0 -0.4828627 -0.8756961 0 -0.4841873 -0.8749644 0 -0.4855406 -0.8742141 0 -0.4868631 -0.8734783 0 -0.4882141 -0.872724 0 -0.4895508 -0.8719748 0 -0.4908995 -0.8712164 0 -0.4922173 -0.8704724 0 -0.4935674 -0.8697076 0 -0.4949124 -0.868943 0 -0.4962269 -0.868193 0 -0.4975736 -0.8674219 0 -0.4988858 -0.8666679 0 -0.5002259 -0.865895 0 -0.5015692 -0.8651176 0 -0.5028609 -0.8643674 0 -0.5041851 -0.8635957 0 -0.505542 -0.862802 0 -0.5068299 -0.8620461 0 -0.5081794 -0.8612512 0 -0.5095041 -0.8604682 0 -0.5107883 -0.8597065 0 -0.5121396 -0.8589023 0 -0.5134554 -0.8581163 0 -0.51477 -0.8573284 0 -0.5160549 -0.8565555 0 -0.51743 -0.8557257 0 -0.518678 -0.8549698 0 -0.5200222 -0.8541529 0 -0.5213305 -0.8533548 0 -0.5226094 -0.8525722 0 -0.52395 -0.8517491 0 -0.5252546 -0.8509451 0 -0.5265646 -0.8501351 0 -0.5278319 -0.8493489 0 -0.5291395 -0.8485349 0 -0.5304739 -0.8477013 0 -0.5317442 -0.8469051 0 -0.5330482 -0.8460848 0 -0.5343438 -0.8452673 0 -0.5356732 -0.8444254 0 -0.5369459 -0.8436168 0 -0.5382023 -0.8428158 0 -0.5395002 -0.8419856 0 -0.5408244 -0.8411356 0 -0.5421198 -0.8403013 0 -0.5433512 -0.8395056 0 -0.5446715 -0.8386495 0 -0.5459632 -0.8378092 0 -0.5472536 -0.8369669 0 -0.5485699 -0.8361048 0 -0.5498306 -0.8352763 0 -0.5510902 -0.8344458 0 -0.5523667 -0.8336012 0 -0.5536865 -0.8327252 0 -0.5549334 -0.8318949 0 -0.5561878 -0.8310567 0 -0.5575307 -0.8301565 0 -0.5587466 -0.8293384 0 -0.560024 -0.8284765 0 -0.5613095 -0.827606 0 -0.5625842 -0.8267401 0 -0.5638576 -0.825872 0 -0.5651032 -0.8250204 0 -0.5663738 -0.8241485 0 -0.5676431 -0.8232749 0 -0.5688948 -0.8224104 0 -0.5701875 -0.8215146 0 -0.5714265 -0.8206533 0 -0.5726641 -0.8197901 0 -0.5739004 -0.8189252 0 -0.5751979 -0.8180144 0 -0.5764315 -0.8171455 0 -0.5777263 -0.8162307 0 -0.5789313 -0.8153765 0 -0.5801866 -0.8144837 0 -0.5814514 -0.8135812 0 -0.5826781 -0.8127031 0 -0.5839403 -0.8117967 0 -0.5851643 -0.8109149 0 -0.5864351 -0.8099963 0 -0.5876703 -0.8091005 0 -0.5889132 -0.8081964 0 -0.5901569 -0.8072886 0 -0.5913738 -0.8063977 0 -0.5926263 -0.8054776 0 -0.5938524 -0.8045741 0 -0.5951021 -0.8036502 0 -0.5963132 -0.8027518 0 -0.5975353 -0.8018427 0 -0.5987808 -0.800913 0 -0.6000249 -0.7999814 0 -0.6012054 -0.7990946 0 -0.602484 -0.798131 0 -0.6036617 -0.7972406 0 -0.6049128 -0.7962917 0 -0.6061123 -0.7953792 0 -0.6073477 -0.7944362 0 -0.6085572 -0.79351 0 -0.6097652 -0.7925821 0 -0.6109719 -0.7916523 0 -0.6122391 -0.7906728 0 -0.6134052 -0.7897683 0 -0.6146075 -0.7888331 0 -0.6158461 -0.7878664 0 -0.6170456 -0.7869274 0 -0.6182677 -0.7859677 0 -0.619454 -0.7850329 0 -0.6206592 -0.7840805 0 -0.6218668 -0.7831231 0 -0.6230589 -0.782175 0 -0.6242496 -0.7812251 0 -0.6254767 -0.7802429 0 -0.6266407 -0.7793084 0 -0.6278504 -0.778334 0 -0.6290495 -0.7773653 0 -0.6302093 -0.7764253 0 -0.6314524 -0.7754147 0 -0.6326091 -0.7744712 0 -0.6338026 -0.7734948 0 -0.6350178 -0.7724975 0 -0.6361702 -0.7715488 0 -0.6373443 -0.7705792 0 -0.6385319 -0.7695955 0 -0.6397027 -0.7686223 0 -0.6408874 -0.767635 0 -0.6420705 -0.7666456 0 -0.643275 -0.7656352 0 -0.6443942 -0.7646936 0 -0.6455956 -0.7636795 0 -0.6467344 -0.7627154 0 -0.6479327 -0.7616977 0 -0.6490842 -0.7607166 0 -0.6502569 -0.7597145 0 -0.651428 -0.7587106 0 -0.6525976 -0.7577048 0 -0.6537656 -0.7566972 0 -0.6549099 -0.7557071 0 -0.6560969 -0.7546766 0 -0.6572383 -0.753683 0 -0.6584221 -0.752649 0 -0.6595603 -0.7516517 0 -0.6606971 -0.7506526 0 -0.6618543 -0.7496326 0 -0.6630098 -0.7486108 0 -0.664142 -0.7476065 0 -0.6652943 -0.7465813 0 -0.6664234 -0.7455735 0 -0.6675725 -0.7445448 0 -0.668677 -0.7435531 0 -0.6698616 -0.742486 0 -0.6710059 -0.741452 0 -0.6721273 -0.7404357 0 -0.6732857 -0.7393825 0 -0.6744039 -0.7383627 0 -0.6755205 -0.7373412 0 -0.6766954 -0.7362632 0 -0.6777877 -0.7352577 0 -0.6789205 -0.7342118 0 -0.6800099 -0.733203 0 -0.6811394 -0.7321538 0 -0.6823031 -0.7310695 0 -0.6834084 -0.7300363 0 -0.684551 -0.7289651 0 -0.6856325 -0.7279479 0 -0.6867924 -0.7268537 0 -0.6878708 -0.7258332 0 -0.6889864 -0.7247744 0 -0.6901023 -0.7237119 0 -0.6911759 -0.7226866 0 -0.6923255 -0.7215853 0 -0.6934162 -0.7205374 0 -0.694485 -0.7195073 0 -0.6956499 -0.718381 0 -0.6967155 -0.7173476 0 -0.6978182 -0.7162749 0 -0.6989194 -0.7152005 0 -0.700019 -0.7141243 0 -0.7010979 -0.7130652 0 -0.7022329 -0.7119473 0 -0.7033084 -0.710885 0 -0.7043817 -0.7098215 0 -0.705473 -0.7087369 0 -0.7065626 -0.7076506 0 -0.7076506 -0.7065626 0 -0.7087369 -0.705473 0 -0.7098022 -0.7044011 0 -0.7108656 -0.703328 0 -0.7119665 -0.7022135 0 -0.7130461 -0.7011173 0 -0.7141049 -0.7000388 0 -0.7152199 -0.6988996 0 -0.7162555 -0.6978381 0 -0.7173482 -0.6967149 0 -0.7183804 -0.6956505 0 -0.7194885 -0.6945044 0 -0.7205187 -0.6934356 0 -0.7215845 -0.6923264 0 -0.7226874 -0.691175 0 -0.7236739 -0.6901421 0 -0.7247734 -0.6889874 0 -0.7258527 -0.6878503 0 -0.7268526 -0.6867935 0 -0.7279285 -0.6856531 0 -0.7290026 -0.684511 0 -0.7300363 -0.6834084 0 -0.731107 -0.6822629 0 -0.7321165 -0.6811795 0 -0.7331656 -0.6800501 0 -0.7342132 -0.678919 0 -0.7352949 -0.6777474 0 -0.7362616 -0.676697 0 -0.7373219 -0.6755416 0 -0.7383804 -0.6743845 0 -0.7393807 -0.6732876 0 -0.7404357 -0.6721273 0 -0.7414502 -0.6710079 0 -0.7424666 -0.669883 0 -0.7435163 -0.6687179 0 -0.7445641 -0.667551 0 -0.7455929 -0.6664018 0 -0.7465813 -0.6652943 0 -0.7476065 -0.664142 0 -0.7486086 -0.6630123 0 -0.7496303 -0.6618568 0 -0.7506504 -0.6606997 0 -0.7516686 -0.6595411 0 -0.7526465 -0.6584249 0 -0.7536998 -0.657219 0 -0.7547126 -0.6560556 0 -0.7557237 -0.6548906 0 -0.756678 -0.6537878 0 -0.7576856 -0.6526198 0 -0.7586914 -0.6514503 0 -0.7596953 -0.6502793 0 -0.760681 -0.6491259 0 -0.7616814 -0.6479518 0 -0.7627182 -0.646731 0 -0.7636988 -0.6455729 0 -0.7646936 -0.6443942 0 -0.7656322 -0.6432787 0 -0.7666456 -0.6420705 0 -0.767635 -0.6408874 0 -0.7686066 -0.6397219 0 -0.7695763 -0.6385549 0 -0.7705602 -0.6373673 0 -0.7715488 -0.6361702 0 -0.7725133 -0.6349988 0 -0.7735296 -0.6337603 0 -0.7744903 -0.6325859 0 -0.7754337 -0.631429 0 -0.7764063 -0.6302327 0 -0.7773463 -0.629073 0 -0.7783151 -0.627874 0 -0.7793273 -0.6266171 0 -0.780262 -0.625453 0 -0.7812251 -0.6242496 0 -0.7821939 -0.6230351 0 -0.7831231 -0.6218668 0 -0.7840656 -0.6206781 0 -0.7850668 -0.6194112 0 -0.7859677 -0.6182677 0 -0.7869423 -0.6170268 0 -0.7878477 -0.6158702 0 -0.7888184 -0.6146264 0 -0.7897496 -0.6134294 0 -0.7906874 -0.6122202 0 -0.7916523 -0.6109719 0 -0.7925489 -0.6098084 0 -0.79351 -0.6085572 0 -0.7944175 -0.6073723 0 -0.7953978 -0.6060877 0 -0.7962872 -0.6049187 0 -0.7972265 -0.6036804 0 -0.7981264 -0.60249 0 -0.7990993 -0.6011993 0 -0.7999953 -0.6000062 0 -0.800913 -0.5987808 0 -0.8018427 -0.5975353 0 -0.8027704 -0.5962883 0 -0.8036453 -0.5951086 0 -0.8045927 -0.5938271 0 -0.8054776 -0.5926263 0 -0.8063977 -0.5913738 0 -0.8073021 -0.5901384 0 -0.8081914 -0.5889201 0 -0.8090821 -0.5876957 0 -0.8099912 -0.5864422 0 -0.8109149 -0.5851643 0 -0.8117967 -0.5839403 0 -0.8127031 -0.5826781 0 -0.8135812 -0.5814514 0 -0.8144837 -0.5801866 0 -0.8153948 -0.5789054 0 -0.8162437 -0.577708 0 -0.8171273 -0.5764575 0 -0.8180455 -0.5751537 0 -0.8189252 -0.5739004 0 -0.8197901 -0.5726641 0 -0.8206533 -0.5714265 0 -0.8215272 -0.5701693 0 -0.822423 -0.5688766 0 -0.823293 -0.5676168 0 -0.8241609 -0.5663557 0 -0.8250509 -0.5650586 0 -0.8258664 -0.563866 0 -0.8267524 -0.5625662 0 -0.8276003 -0.561318 0 -0.8284945 -0.5599973 0 -0.8293384 -0.5587466 0 -0.8301685 -0.5575127 0 -0.8310567 -0.5561878 0 -0.8318949 -0.5549334 0 -0.8327192 -0.5536955 0 -0.8336012 -0.5523667 0 -0.8344458 -0.5510902 0 -0.835288 -0.5498127 0 -0.8361165 -0.5485521 0 -0.8369669 -0.5472536 0 -0.8377915 -0.5459904 0 -0.838638 -0.5446892 0 -0.8394941 -0.5433689 0 -0.8403013 -0.5421198 0 -0.8411419 -0.5408146 0 -0.8419919 -0.5394903 0 -0.8428044 -0.5382199 0 -0.8436279 -0.5369283 0 -0.8444366 -0.5356556 0 -0.8452562 -0.5343614 0 -0.8460848 -0.5330482 0 -0.8468877 -0.5317721 0 -0.8477122 -0.5304564 0 -0.848524 -0.5291569 0 -0.8493555 -0.5278213 0 -0.8501633 -0.5265192 0 -0.8509451 -0.5252546 0 -0.8517597 -0.5239327 0 -0.8525722 -0.5226094 0 -0.8533722 -0.5213023 0 -0.8541701 -0.5199939 0 -0.854987 -0.5186496 0 -0.8557361 -0.5174128 0 -0.8565384 -0.5160834 0 -0.8573284 -0.51477 0 -0.8581163 -0.5134554 0 -0.8589125 -0.5121224 0 -0.8596964 -0.5108054 0 -0.8604784 -0.5094872 0 -0.8612342 -0.5082082 0 -0.8620361 -0.5068469 0 -0.8628119 -0.5055251 0 -0.8635957 -0.5041851 0 -0.8643575 -0.5028778 0 -0.8651273 -0.5015524 0 -0.8658901 -0.5002342 0 -0.8666895 -0.4988482 0 -0.8674435 -0.497536 0 -0.8682049 -0.4962059 0 -0.8689644 -0.4948747 0 -0.8697124 -0.4935591 0 -0.8704677 -0.4922257 0 -0.8712116 -0.4909077 0 -0.8719915 -0.4895213 0 -0.8727359 -0.4881927 0 -0.8734737 -0.4868714 0 -0.8742141 -0.4855406 0 -0.874948 -0.4842171 0 -0.8756797 -0.4828925 0 -0.8764423 -0.481507 0 -0.8771699 -0.4801801 0 -0.8779238 -0.4788004 0 -0.8786475 -0.4774713 0 -0.8794059 -0.4760729 0 -0.880121 -0.4747497 0 -0.8808296 -0.4734335 0 -0.8815817 -0.4720317 0 -0.8822906 -0.4707052 0 -0.8829933 -0.4693859 0 -0.8837024 -0.4680493 0 -0.8844373 -0.466659 0 -0.8851382 -0.4653285 0 -0.8858604 -0.4639518 0 -0.8865614 -0.4626112 0 -0.8872877 -0.4612163 0 -0.8880038 -0.4598362 0 -0.8886943 -0.4585005 0 -0.8894143 -0.4571022 0 -0.8900924 -0.4557802 0 -0.8908001 -0.4543955 0 -0.8915137 -0.4529939 0 -0.8921898 -0.451661 0 -0.892891 -0.4502729 0 -0.8935629 -0.448938 0 -0.8942601 -0.4475477 0 -0.894955 -0.4461564 0 -0.8956169 -0.4448263 0 -0.8963116 -0.4434251 0 -0.8969655 -0.4421007 0 -0.8976558 -0.4406974 0 -0.8983364 -0.4393084 0 -0.8990185 -0.4379106 0 -0.8996606 -0.43659 0 -0.9003728 -0.4351196 0 -0.9010144 -0.4337894 0 -0.901688 -0.4323875 0 -0.9023522 -0.4309996 0 -0.9029877 -0.4296666 0 -0.9036548 -0.4282618 0 -0.9043391 -0.4268148 0 -0.9049684 -0.4254789 0 -0.905629 -0.424071 0 -0.906277 -0.4226844 0 -0.9069001 -0.4213459 0 -0.9075769 -0.4198859 0 -0.9082254 -0.4184815 0 -0.908832 -0.4171624 0 -0.9094762 -0.4157561 0 -0.9101441 -0.4142918 0 -0.910748 -0.4129626 0 -0.9113824 -0.4115607 0 -0.9120437 -0.4100933 0 -0.9126414 -0.4087614 0 -0.9132628 -0.4073711 0 -0.9139174 -0.4059005 0 -0.9145088 -0.404566 0 -0.9151271 -0.4031657 0 -0.9157717 -0.4016993 0 -0.916357 -0.4003622 0 -0.9169941 -0.3989009 0 -0.9175975 -0.397511 0 -0.9182079 -0.3960988 0 -0.9188101 -0.3946999 0 -0.9194412 -0.3932275 0 -0.9200081 -0.3918995 0 -0.9206318 -0.3904321 0 -0.9211975 -0.3890956 0 -0.9218109 -0.3876401 0 -0.922403 -0.3862288 0 -0.9229902 -0.3848237 0 -0.9235969 -0.3833652 0 -0.9241522 -0.3820246 0 -0.9247602 -0.3805505 0 -0.925333 -0.3791555 0 -0.9259309 -0.3776931 0 -0.9264779 -0.3763495 0 -0.9270713 -0.3748851 0 -0.9276652 -0.373413 0 -0.9282004 -0.3720806 0 -0.92879 -0.3706067 0 -0.9293477 -0.3692057 0 -0.9299274 -0.3677433 0 -0.9304835 -0.3663339 0 -0.9310348 -0.3649303 0 -0.9316079 -0.3634652 0 -0.9321836 -0.3619859 0 -0.9326972 -0.3606605 0 -0.9332685 -0.3591796 0 -0.9338276 -0.3577237 0 -0.9343684 -0.3563088 0 -0.934902 -0.354906 0 -0.9354568 -0.353441 0 -0.9359886 -0.3520302 0 -0.9365391 -0.3505634 0 -0.9370896 -0.3490893 0 -0.93761 -0.3476889 0 -0.9381307 -0.3462815 0 -0.9386721 -0.3448112 0 -0.9391862 -0.3434085 0 -0.9397231 -0.3419365 0 -0.9402351 -0.3405261 0 -0.9407653 -0.3390586 0 -0.9412685 -0.3376591 0 -0.9417964 -0.3361838 0 -0.942322 -0.3347076 0 -0.9428433 -0.3332368 0 -0.9433399 -0.3318281 0 -0.9438566 -0.3303557 0 -0.9443689 -0.3288884 0 -0.9448569 -0.3274835 0 -0.9453668 -0.3260086 0 -0.9458526 -0.3245965 0 -0.9463539 -0.323132 0 -0.9468334 -0.3217244 0 -0.9473343 -0.3202465 0 -0.947829 -0.3187795 0 -0.9483 -0.3173757 0 -0.9487941 -0.3158956 0 -0.9492838 -0.3144204 0 -0.9497696 -0.3129503 0 -0.9502337 -0.311538 0 -0.950713 -0.3100721 0 -0.951192 -0.3085997 0 -0.9516724 -0.3071151 0 -0.9521449 -0.3056469 0 -0.9525964 -0.3042371 0 -0.9530663 -0.3027618 0 -0.9535322 -0.3012913 0 -0.9539976 -0.2998145 0 -0.954459 -0.2983425 0 -0.9548994 -0.2969295 0 -0.9553766 -0.2953907 0 -0.955811 -0.2939821 0 -0.9562634 -0.2925073 0 -0.9567134 -0.2910317 0 -0.9571629 -0.2895501 0 -0.9576036 -0.2880893 0 -0.9580501 -0.286601 0 -0.9584895 -0.285128 0 -0.958907 -0.2837205 0 -0.959342 -0.2822462 0 -0.9597957 -0.2806997 0 -0.960226 -0.279224 0 -0.9606527 -0.2777528 0 -0.9610815 -0.2762655 0 -0.961502 -0.2747981 0 -0.9619043 -0.2733866 0 -0.9623219 -0.2719128 0 -0.9627374 -0.2704384 0 -0.9631519 -0.2689583 0 -0.9635614 -0.2674875 0 -0.9639714 -0.2660062 0 -0.9643778 -0.2645292 0 -0.9647818 -0.2630516 0 -0.9651823 -0.2615784 0 -0.9655818 -0.2600996 0 -0.9659986 -0.2585477 0 -0.9663909 -0.2570773 0 -0.9667836 -0.2555967 0 -0.9671727 -0.2541203 0 -0.9675607 -0.2526386 0 -0.9679441 -0.2511658 0 -0.9683259 -0.2496899 0 -0.968706 -0.2482113 0 -0.9691018 -0.2466614 0 -0.9694766 -0.2451838 0 -0.9698298 -0.2437834 0 -0.9702191 -0.2422294 0 -0.9705871 -0.2407501 0 -0.9709694 -0.2392039 0 -0.9713144 -0.2377991 0 -0.9716935 -0.2362449 0 -0.972051 -0.2347703 0 -0.972406 -0.233295 0 -0.97276 -0.2318149 0 -0.9731111 -0.2303364 0 -0.973459 -0.2288617 0 -0.9738228 -0.2273085 0 -0.9741661 -0.2258327 0 -0.9745072 -0.2243564 0 -0.974847 -0.2228754 0 -0.9751999 -0.2213264 0 -0.9755345 -0.2198464 0 -0.9758656 -0.2183722 0 -0.9761953 -0.2168934 0 -0.9765387 -0.2153421 0 -0.9768634 -0.2138643 0 -0.977202 -0.2123119 0 -0.9775217 -0.2108351 0 -0.9778396 -0.209356 0 -0.9781539 -0.2078822 0 -0.9784673 -0.2064021 0 -0.9787936 -0.2048491 0 -0.9791012 -0.2033739 0 -0.9794227 -0.2018198 0 -0.9797261 -0.2003418 0 -0.980042 -0.1987905 0 -0.9803401 -0.1973153 0 -0.9806371 -0.1958341 0 -0.9809308 -0.1943579 0 -0.9812222 -0.1928814 0 -0.9815262 -0.1913278 0 -0.9818131 -0.1898503 0 -0.9821124 -0.1882957 0 -0.9823937 -0.1868228 0 -0.9826885 -0.1852656 0 -0.9829656 -0.18379 0 -0.9832543 -0.1822388 0 -0.9835276 -0.1807589 0 -0.9837978 -0.179282 0 -0.9840797 -0.1777278 0 -0.9843448 -0.1762536 0 -0.984609 -0.1747722 0 -0.9848697 -0.1732971 0 -0.9851547 -0.1716691 0 -0.9854114 -0.1701899 0 -0.9856655 -0.168712 0 -0.9859299 -0.1671597 0 -0.9861789 -0.1656842 0 -0.9864391 -0.164128 0 -0.9866836 -0.1626517 0 -0.9869258 -0.1611751 0 -0.9871784 -0.1596209 0 -0.9874162 -0.1581435 0 -0.9876635 -0.1565915 0 -0.987897 -0.155112 0 -0.9881395 -0.1535592 0 -0.988368 -0.152082 0 -0.9886173 -0.1504525 0 -0.9888408 -0.148976 0 -0.9890627 -0.1474963 0 -0.9892926 -0.1459459 0 -0.9895097 -0.144467 0 -0.9897242 -0.1429892 0 -0.9899582 -0.1413601 0 -0.990168 -0.1398831 0 -0.9903759 -0.1384043 0 -0.9905917 -0.1368517 0 -0.9907944 -0.135375 0 -0.9910057 -0.1338204 0 -0.9912142 -0.1322668 0 -0.9914102 -0.1307892 0 -0.9916038 -0.1293138 0 -0.9918153 -0.1276816 0 -0.9920043 -0.1262044 0 -0.9921909 -0.1247287 0 -0.9923852 -0.1231738 0 -0.9925767 -0.1216205 0 -0.9927567 -0.1201428 0 -0.9929434 -0.1185894 0 -0.9931278 -0.1170357 0 -0.9933007 -0.1155583 0 -0.9934804 -0.1140041 0 -0.9936487 -0.1125274 0 -0.9938235 -0.1109731 0 -0.9939957 -0.1094197 0 -0.9941572 -0.1079427 0 -0.9943247 -0.1063882 0 -0.9944816 -0.1049118 0 -0.9946443 -0.1033573 0 -0.9948046 -0.1018036 0 -0.9949547 -0.100326 0 -0.9951101 -0.0987727 0 -0.9952631 -0.09721869 0 -0.9954063 -0.09574145 0 -0.9955545 -0.09418743 0 -0.9957003 -0.09263318 0 -0.9958366 -0.09115672 0 -0.9959776 -0.08960247 0 -0.9961163 -0.08804845 0 -0.9962457 -0.08657175 0 -0.9963796 -0.08501732 0 -0.9965109 -0.08346349 0 -0.9966335 -0.08198624 0 -0.9967601 -0.08043241 0 -0.9968843 -0.0788784 0 -0.997 -0.07740139 0 -0.9971196 -0.07584738 0 -0.9972366 -0.07429319 0 -0.9973455 -0.07281643 0 -0.9974576 -0.07126224 0 -0.9975675 -0.06970816 0 -0.9976696 -0.06823134 0 -0.9977747 -0.06667727 0 -0.9978722 -0.06520044 0 -0.9979775 -0.06356871 0 -0.9980705 -0.06209236 0 -0.9981659 -0.06053787 0 -0.9982544 -0.05906122 0 -0.9983496 -0.05742961 0 -0.9984334 -0.05595296 0 -0.9985194 -0.05439877 0 -0.9985986 -0.05292207 0 -0.9986798 -0.05136775 0 -0.9987586 -0.04981368 0 -0.9988349 -0.04825949 0 -0.9989051 -0.04678273 0 -0.9989767 -0.0452286 0 -0.9990459 -0.0436744 0 -0.9991094 -0.04219782 0 -0.9991738 -0.04064351 0 -0.9992328 -0.03916692 0 -0.9992954 -0.03753513 0 -0.9993497 -0.03605842 0 -0.9994046 -0.03450441 0 -0.9994544 -0.03302764 0 -0.9995071 -0.03139579 0 -0.9995524 -0.02991926 0 -0.9995977 -0.02836495 0 -0.9996406 -0.02681082 0 -0.999679 -0.02533417 0 -0.9997172 -0.02377992 0 -0.9997531 -0.02222573 0 -0.9997847 -0.02074915 0 -0.9998158 -0.01919496 0 -0.9998445 -0.0176407 0 -0.9998707 -0.01608645 0 -0.9998933 -0.01460987 0 -0.9999148 -0.01305568 0 -0.999934 -0.01150143 0 -0.9999506 -0.00994718 0 -0.9999641 -0.008470594 0 -0.9999761 -0.006916344 0 -0.9999857 -0.005362153 0 -0.9999925 -0.003885567 0 -0.9999976 -0.002253651 0 -0.9999997 -7.77124e-4 0 -0.9999997 7.77124e-4 0 -0.9999974 0.002331316 0 -0.9999929 0.003807902 0 -0.9999857 0.005362153 0 -0.9999767 0.006838679 0 -0.9999641 0.008470594 0 -0.9999506 0.00994718 0 -0.999934 0.01150143 0 -0.9999148 0.01305568 0 -0.9998945 0.0145322 0 -0.9998707 0.01608645 0 -0.9998445 0.0176407 0 -0.9998158 0.01919496 0 -0.9997864 0.02067148 0 -0.9997531 0.02222573 0 -0.9997172 0.02377992 0 -0.9996811 0.02525651 0 -0.9996384 0.02688843 0 -0.9995977 0.02836495 0 -0.9995524 0.02991926 0 -0.9995047 0.03147339 0 -0.9994571 0.03295004 0 -0.9994046 0.03450441 0 -0.9993497 0.03605842 0 -0.9992954 0.03753513 0 -0.9992358 0.03908932 0 -0.9991738 0.04064351 0 -0.9991126 0.04212021 0 -0.9990425 0.04375201 0 -0.9989767 0.0452286 0 -0.9989051 0.04678273 0 -0.9988312 0.04833704 0 -0.9987586 0.04981368 0 -0.9986798 0.05136775 0 -0.9985986 0.05292207 0 -0.9985151 0.05447626 0 -0.9984334 0.05595296 0 -0.9983451 0.05750703 0 -0.998259 0.0589838 0 -0.9981613 0.0606153 0 -0.9980705 0.06209236 0 -0.9979726 0.06364607 0 -0.9978773 0.06512308 0 -0.9977747 0.06667727 0 -0.9976749 0.06815397 0 -0.9975621 0.06978553 0 -0.9974576 0.07126224 0 -0.9973455 0.07281643 0 -0.9972308 0.07437044 0 -0.9971196 0.07584738 0 -0.997 0.07740139 0 -0.9968782 0.07895565 0 -0.9967601 0.08043241 0 -0.9966335 0.08198624 0 -0.9965044 0.08354067 0 -0.9963796 0.08501732 0 -0.9962457 0.08657175 0 -0.9961094 0.08812552 0 -0.9959776 0.08960247 0 -0.9958366 0.09115672 0 -0.9956932 0.09271025 0 -0.9955545 0.09418743 0 -0.9954063 0.09574145 0 -0.9952555 0.0972957 0 -0.9951101 0.0987727 0 -0.9949547 0.100326 0 -0.9948046 0.1018036 0 -0.9946443 0.1033573 0 -0.9944816 0.1049118 0 -0.9943247 0.1063882 0 -0.9941572 0.1079427 0 -0.9939873 0.1094964 0 -0.9938235 0.1109731 0 -0.9936487 0.1125274 0 -0.9934716 0.1140808 0 -0.9933007 0.1155583 0 -0.9931188 0.1171123 0 -0.9929434 0.1185894 0 -0.9927567 0.1201428 0 -0.9925767 0.1216205 0 -0.9923852 0.1231738 0 -0.9921909 0.1247287 0 -0.9920043 0.1262044 0 -0.9918054 0.127758 0 -0.9916138 0.1292374 0 -0.9914102 0.1307892 0 -0.9912142 0.1322668 0 -0.9910057 0.1338204 0 -0.9907944 0.135375 0 -0.9905917 0.1368517 0 -0.9903864 0.1383281 0 -0.9901574 0.1399592 0 -0.9899474 0.1414363 0 -0.9897353 0.1429131 0 -0.9895207 0.1443909 0 -0.9892814 0.146022 0 -0.9890627 0.1474963 0 -0.9888294 0.149052 0 -0.9886057 0.1505284 0 -0.9883796 0.152006 0 -0.9881395 0.1535592 0 -0.9879088 0.1550362 0 -0.9876635 0.1565915 0 -0.9874283 0.1580678 0 -0.9871784 0.1596209 0 -0.9869382 0.1610994 0 -0.986696 0.1625761 0 -0.9864265 0.1642037 0 -0.9861789 0.1656842 0 -0.9859299 0.1671597 0 -0.9856655 0.168712 0 -0.9854114 0.1701899 0 -0.9851415 0.1717445 0 -0.984883 0.1732217 0 -0.9846224 0.1746968 0 -0.9843448 0.1762536 0 -0.9840797 0.1777278 0 -0.9837978 0.179282 0 -0.9835137 0.1808341 0 -0.9832404 0.1823139 0 -0.9829656 0.18379 0 -0.9826744 0.1853406 0 -0.9823937 0.1868228 0 -0.9821124 0.1882957 0 -0.9818276 0.1897754 0 -0.9815262 0.1913278 0 -0.9812368 0.1928066 0 -0.9809308 0.1943579 0 -0.9806371 0.1958341 0 -0.9803251 0.19739 0 -0.9800269 0.1988651 0 -0.9797261 0.2003418 0 -0.9794074 0.2018944 0 -0.9791012 0.2033739 0 -0.9787936 0.2048491 0 -0.978483 0.2063277 0 -0.9781539 0.2078822 0 -0.9778396 0.209356 0 -0.9775056 0.2109094 0 -0.9771859 0.2123861 0 -0.9768634 0.2138643 0 -0.9765387 0.2153421 0 -0.9762118 0.2168194 0 -0.9758656 0.2183722 0 -0.9755345 0.2198464 0 -0.9751999 0.2213264 0 -0.9748638 0.2228016 0 -0.9745072 0.2243564 0 -0.9741661 0.2258327 0 -0.9738228 0.2273085 0 -0.9734764 0.2287881 0 -0.9731285 0.2302628 0 -0.97276 0.2318149 0 -0.972406 0.233295 0 -0.9720332 0.2348437 0 -0.9716935 0.2362449 0 -0.9713144 0.2377991 0 -0.9709514 0.2392772 0 -0.9705871 0.2407501 0 -0.9702191 0.2422294 0 -0.9698482 0.2437103 0 -0.9694766 0.2451838 0 -0.9690832 0.2467343 0 -0.968706 0.2482113 0 -0.9683446 0.2496171 0 -0.9679441 0.2511658 0 -0.9675607 0.2526386 0 -0.9671727 0.2541203 0 -0.9667836 0.2555967 0 -0.9663716 0.2571499 0 -0.9659986 0.2585477 0 -0.9656013 0.2600271 0 -0.9652019 0.261506 0 -0.9648016 0.2629793 0 -0.9643975 0.2644569 0 -0.9639912 0.265934 0 -0.9635814 0.2674154 0 -0.963172 0.2688862 0 -0.9627576 0.2703663 0 -0.9623423 0.2718408 0 -0.9619043 0.2733866 0 -0.9614815 0.27487 0 -0.9610608 0.2763373 0 -0.9606319 0.2778245 0 -0.9602051 0.2792957 0 -0.9597957 0.2806997 0 -0.9593631 0.2821748 0 -0.9589282 0.2836491 0 -0.9584895 0.285128 0 -0.9580501 0.286601 0 -0.9576036 0.2880893 0 -0.9571629 0.2895501 0 -0.9567134 0.2910317 0 -0.9562851 0.2924362 0 -0.955811 0.2939821 0 -0.9553766 0.2953907 0 -0.9549215 0.2968587 0 -0.954459 0.2983425 0 -0.9539976 0.2998145 0 -0.9535322 0.3012913 0 -0.9530887 0.3026912 0 -0.952619 0.3041666 0 -0.9521449 0.3056469 0 -0.9516724 0.3071151 0 -0.951192 0.3085997 0 -0.950736 0.3100019 0 -0.9502568 0.3114678 0 -0.9497696 0.3129503 0 -0.949307 0.3143504 0 -0.9488173 0.3158255 0 -0.9483233 0.3173059 0 -0.947829 0.3187795 0 -0.9473578 0.3201767 0 -0.946857 0.3216547 0 -0.9463539 0.323132 0 -0.9458526 0.3245965 0 -0.9453429 0.3260781 0 -0.9448569 0.3274835 0 -0.9443448 0.3289577 0 -0.9438323 0.3304249 0 -0.9433399 0.3318281 0 -0.9428188 0.3333058 0 -0.942322 0.3347076 0 -0.9417964 0.3361838 0 -0.9412932 0.3375902 0 -0.9407653 0.3390586 0 -0.9402601 0.3404574 0 -0.9397231 0.3419365 0 -0.9392113 0.34334 0 -0.9386721 0.3448112 0 -0.9381307 0.3462815 0 -0.93761 0.3476889 0 -0.9370641 0.3491575 0 -0.9365136 0.3506316 0 -0.9360143 0.3519622 0 -0.9354568 0.353441 0 -0.934902 0.354906 0 -0.9343684 0.3563088 0 -0.9338276 0.3577237 0 -0.9332685 0.3591796 0 -0.9327234 0.3605929 0 -0.9321574 0.3620534 0 -0.9315815 0.3635326 0 -0.9310612 0.364863 0 -0.9304835 0.3663339 0 -0.9299274 0.3677433 0 -0.9293743 0.3691385 0 -0.92879 0.3706067 0 -0.9282273 0.3720136 0 -0.9276382 0.3734799 0 -0.9270983 0.3748183 0 -0.9265049 0.3762828 0 -0.9259037 0.3777597 0 -0.9253602 0.3790889 0 -0.9247602 0.3805505 0 -0.9241797 0.3819583 0 -0.9235693 0.3834314 0 -0.9230177 0.3847575 0 -0.922403 0.3862288 0 -0.9218109 0.3876401 0 -0.9212254 0.3890296 0 -0.9206039 0.390498 0 -0.920036 0.3918337 0 -0.9194132 0.3932932 0 -0.9188101 0.3946999 0 -0.9181797 0.3961644 0 -0.9175975 0.397511 0 -0.9169941 0.3989009 0 -0.9163855 0.4002969 0 -0.9157432 0.4017645 0 -0.9151557 0.4031006 0 -0.9145088 0.404566 0 -0.9138885 0.4059655 0 -0.9132917 0.4073063 0 -0.9126414 0.4087614 0 -0.9120146 0.4101579 0 -0.9114116 0.4114962 0 -0.910748 0.4129626 0 -0.9101148 0.4143561 0 -0.9094762 0.4157561 0 -0.9088614 0.4170982 0 -0.9081959 0.4185456 0 -0.9075769 0.4198859 0 -0.9069298 0.421282 0 -0.9062471 0.4227483 0 -0.905629 0.424071 0 -0.9049684 0.4254789 0 -0.9043091 0.4268783 0 -0.9036548 0.4282618 0 -0.9030178 0.4296032 0 -0.9023219 0.4310629 0 -0.901688 0.4323875 0 -0.9010144 0.4337894 0 -0.9003423 0.4351826 0 -0.8996912 0.4365271 0 -0.8990185 0.4379106 0 -0.8983364 0.4393084 0 -0.8976558 0.4406974 0 -0.8969963 0.4420381 0 -0.8963116 0.4434251 0 -0.895648 0.444764 0 -0.8949241 0.4462186 0 -0.8942601 0.4475477 0 -0.8935629 0.448938 0 -0.8928598 0.4503349 0 -0.8921898 0.451661 0 -0.8914822 0.4530556 0 -0.8908001 0.4543955 0 -0.8900924 0.4557802 0 -0.8893826 0.4571636 0 -0.8886943 0.4585005 0 -0.8880038 0.4598362 0 -0.8872877 0.4612163 0 -0.8865932 0.4625501 0 -0.8858604 0.4639518 0 -0.8851702 0.4652675 0 -0.8844373 0.466659 0 -0.8837345 0.4679886 0 -0.8830254 0.4693252 0 -0.8822584 0.4707657 0 -0.8815494 0.472092 0 -0.8808296 0.4734335 0 -0.8800885 0.4748099 0 -0.8793734 0.4761329 0 -0.8786475 0.4774713 0 -0.8778911 0.4788603 0 -0.8771699 0.4801801 0 -0.8764423 0.481507 0 -0.8757125 0.4828329 0 -0.8749808 0.4841576 0 -0.8742141 0.4855406 0 -0.8734737 0.4868714 0 -0.8727027 0.4882519 0 -0.8719582 0.4895803 0 -0.8712116 0.4909077 0 -0.8704677 0.4922257 0 -0.8697124 0.4935591 0 -0.8689309 0.4949334 0 -0.8681714 0.4962645 0 -0.8674098 0.4975944 0 -0.8666559 0.4989066 0 -0.8658901 0.5002342 0 -0.8651273 0.5015524 0 -0.8643575 0.5028778 0 -0.8635957 0.5041851 0 -0.8628119 0.5055251 0 -0.8620361 0.5068469 0 -0.8612682 0.5081506 0 -0.8604784 0.5094872 0 -0.8596964 0.5108054 0 -0.8589125 0.5121224 0 -0.8581163 0.5134554 0 -0.8573284 0.51477 0 -0.8565727 0.5160264 0 -0.8557361 0.5174128 0 -0.8549525 0.5187064 0 -0.8541356 0.5200505 0 -0.8533376 0.5213589 0 -0.8525722 0.5226094 0 -0.8517597 0.5239327 0 -0.8509451 0.5252546 0 -0.8501285 0.5265753 0 -0.8493207 0.5278773 0 -0.848524 0.5291569 0 -0.8477122 0.5304564 0 -0.8469225 0.5317163 0 -0.8460848 0.5330482 0 -0.8452562 0.5343614 0 -0.8444366 0.5356556 0 -0.8436279 0.5369283 0 -0.8428044 0.5382199 0 -0.8419566 0.5395454 0 -0.8411066 0.5408695 0 -0.8403013 0.5421198 0 -0.8394941 0.5433689 0 -0.838638 0.5446892 0 -0.8378269 0.5459359 0 -0.8369669 0.5472536 0 -0.8361165 0.5485521 0 -0.835288 0.5498127 0 -0.8344458 0.5510902 0 -0.8336012 0.5523667 0 -0.8327551 0.5536416 0 -0.8318949 0.5549334 0 -0.8310567 0.5561878 0 -0.8301685 0.5575127 0 -0.8293384 0.5587466 0 -0.8284585 0.5600507 0 -0.8276364 0.5612648 0 -0.8267524 0.5625662 0 -0.8259025 0.563813 0 -0.8250147 0.5651115 0 -0.8241609 0.5663557 0 -0.8232567 0.5676694 0 -0.822423 0.5688766 0 -0.8215272 0.5701693 0 -0.8206533 0.5714265 0 -0.8197901 0.5726641 0 -0.8189252 0.5739004 0 -0.8180089 0.5752056 0 -0.8171639 0.5764056 0 -0.8162437 0.577708 0 -0.8153581 0.5789571 0 -0.8144837 0.5801866 0 -0.8135812 0.5814514 0 -0.8127031 0.5826781 0 -0.8117967 0.5839403 0 -0.8109149 0.5851643 0 -0.8100281 0.5863912 0 -0.8091191 0.5876449 0 -0.8082283 0.5888693 0 -0.8073021 0.5901384 0 -0.8063977 0.5913738 0 -0.8054776 0.5926263 0 -0.8045556 0.5938775 0 -0.8036825 0.5950584 0 -0.8027333 0.5963383 0 -0.8018427 0.5975353 0 -0.800913 0.5987808 0 -0.7999953 0.6000062 0 -0.7990618 0.6012489 0 -0.7981638 0.6024405 0 -0.7972265 0.6036804 0 -0.7963247 0.6048695 0 -0.7953605 0.6061369 0 -0.7944549 0.6073232 0 -0.79351 0.6085572 0 -0.7925865 0.6097596 0 -0.7916523 0.6109719 0 -0.7906874 0.6122202 0 -0.7897872 0.6133809 0 -0.7888184 0.6146264 0 -0.7878854 0.615822 0 -0.7869423 0.6170268 0 -0.7859677 0.6182677 0 -0.7850291 0.6194591 0 -0.7840656 0.6206781 0 -0.7831231 0.6218668 0 -0.7821561 0.6230827 0 -0.7812251 0.6242496 0 -0.780224 0.6255003 0 -0.7792894 0.6266643 0 -0.7783531 0.6278269 0 -0.7773843 0.6290261 0 -0.7764444 0.6301859 0 -0.7753957 0.6314758 0 -0.7744522 0.6326325 0 -0.7734915 0.6338068 0 -0.7725133 0.6349988 0 -0.7715488 0.6361702 0 -0.7705984 0.6373212 0 -0.7696145 0.6385088 0 -0.7686066 0.6397219 0 -0.767635 0.6408874 0 -0.7666456 0.6420705 0 -0.7656705 0.6432331 0 -0.7646936 0.6443942 0 -0.7636604 0.6456183 0 -0.7626799 0.6467761 0 -0.7616814 0.6479518 0 -0.7607195 0.6490809 0 -0.7597336 0.6502344 0 -0.7587298 0.6514056 0 -0.757724 0.6525752 0 -0.7567165 0.6537433 0 -0.7557237 0.6548906 0 -0.7546741 0.6560999 0 -0.7536998 0.657219 0 -0.752685 0.6583808 0 -0.7516686 0.6595411 0 -0.7506889 0.6606559 0 -0.7496689 0.6618131 0 -0.7486472 0.6629687 0 -0.7476065 0.664142 0 -0.7465813 0.6652943 0 -0.7455542 0.666445 0 -0.7445255 0.667594 0 -0.743555 0.6686749 0 -0.7425054 0.6698402 0 -0.7414889 0.6709653 0 -0.7404357 0.6721273 0 -0.7394194 0.6732451 0 -0.7383804 0.6743845 0 -0.7373606 0.6754994 0 -0.7363004 0.6766549 0 -0.7352561 0.6777893 0 -0.7341745 0.6789609 0 -0.7332044 0.6800084 0 -0.7321552 0.6811379 0 -0.7310682 0.6823044 0 -0.7300363 0.6834084 0 -0.7289639 0.6845523 0 -0.7279673 0.685612 0 -0.7268914 0.6867524 0 -0.7258139 0.6878913 0 -0.7248122 0.6889466 0 -0.7237128 0.6901014 0 -0.7226486 0.6912156 0 -0.7216234 0.6922859 0 -0.7205187 0.6934356 0 -0.7194885 0.6945044 0 -0.7184192 0.6956104 0 -0.7173094 0.6967549 0 -0.7162944 0.6977983 0 -0.7151811 0.6989393 0 -0.7141437 0.6999992 0 -0.7130461 0.7011173 0 -0.7119665 0.7022135 0 -0.7109044 0.7032887 0 -0.7098022 0.7044011 0 -0.7087369 0.705473 0 -0.7076506 0.7065626 0 -0.7065626 0.7076506 0 -0.705473 0.7087369 0 -0.7044205 0.7097829 0 -0.7033084 0.710885 0 -0.702194 0.7119856 0 -0.7011367 0.713027 0 -0.700019 0.7141243 0 -0.6989194 0.7152005 0 -0.6978182 0.7162749 0 -0.6967543 0.7173099 0 -0.6956111 0.7184186 0 -0.6945238 0.7194698 0 -0.6934551 0.7205 0 -0.6922867 0.7216225 0 -0.6912147 0.7226495 0 -0.6901412 0.7236748 0 -0.6889476 0.7248112 0 -0.6878708 0.7258332 0 -0.6867536 0.7268903 0 -0.6856325 0.7279479 0 -0.6845122 0.7290014 0 -0.6834084 0.7300363 0 -0.6822643 0.7311057 0 -0.6811781 0.7321178 0 -0.6800486 0.7331671 0 -0.6789593 0.734176 0 -0.677749 0.7352934 0 -0.6766566 0.7362987 0 -0.6755205 0.7373412 0 -0.6743652 0.738398 0 -0.673247 0.7394177 0 -0.6721273 0.7404357 0 -0.6709673 0.741487 0 -0.6698616 0.742486 0 -0.6687157 0.7435182 0 -0.6675725 0.7445448 0 -0.6664234 0.7455735 0 -0.6652943 0.7465813 0 -0.664142 0.7476065 0 -0.6629712 0.748645 0 -0.6618157 0.7496666 0 -0.6606585 0.7506865 0 -0.6595218 0.7516855 0 -0.6583836 0.7526826 0 -0.6571998 0.7537165 0 -0.6560585 0.7547101 0 -0.6548714 0.7557405 0 -0.6537656 0.7566972 0 -0.6525976 0.7577048 0 -0.651428 0.7587106 0 -0.6502569 0.7597145 0 -0.6491226 0.7606839 0 -0.647971 0.7616651 0 -0.6467728 0.7626827 0 -0.6455956 0.7636795 0 -0.6443942 0.7646936 0 -0.6432368 0.7656674 0 -0.6420705 0.7666456 0 -0.6408874 0.767635 0 -0.639741 0.7685906 0 -0.6385319 0.7695955 0 -0.6373443 0.7705792 0 -0.6361702 0.7715488 0 -0.6349797 0.7725288 0 -0.6337645 0.7735261 0 -0.6326091 0.7744712 0 -0.6314524 0.7754147 0 -0.6302093 0.7764253 0 -0.6290495 0.7773653 0 -0.6278504 0.778334 0 -0.6266407 0.7793084 0 -0.6254767 0.7802429 0 -0.6242496 0.7812251 0 -0.6230589 0.782175 0 -0.6218668 0.7831231 0 -0.620697 0.7840505 0 -0.6194162 0.7850628 0 -0.6182677 0.7859677 0 -0.6170079 0.786957 0 -0.6158461 0.7878664 0 -0.6146452 0.7888037 0 -0.6134052 0.7897683 0 -0.6122015 0.7907019 0 -0.6109719 0.7916523 0 -0.6098028 0.7925532 0 -0.6085572 0.79351 0 -0.6073477 0.7944362 0 -0.6061123 0.7953792 0 -0.6048754 0.7963201 0 -0.6036991 0.7972123 0 -0.6024466 0.7981592 0 -0.6012428 0.7990666 0 -0.5999876 0.8000093 0 -0.5987808 0.800913 0 -0.5975353 0.8018427 0 -0.5963132 0.8027518 0 -0.5950649 0.8036776 0 -0.5938524 0.8045741 0 -0.5926263 0.8054776 0 -0.5913738 0.8063977 0 -0.5901198 0.8073157 0 -0.5888762 0.8082234 0 -0.5876703 0.8091005 0 -0.5863982 0.810023 0 -0.5851643 0.8109149 0 -0.5839403 0.8117967 0 -0.5826781 0.8127031 0 -0.5814514 0.8135812 0 -0.5801866 0.8144837 0 -0.5789313 0.8153765 0 -0.5776896 0.8162566 0 -0.5764315 0.8171455 0 -0.5751613 0.8180401 0 -0.5739004 0.8189252 0 -0.5726641 0.8197901 0 -0.5714265 0.8206533 0 -0.5701512 0.8215399 0 -0.5688584 0.8224356 0 -0.5676431 0.8232749 0 -0.5663375 0.8241735 0 -0.5650669 0.8250452 0 -0.5638214 0.8258968 0 -0.5625481 0.8267646 0 -0.5612734 0.8276306 0 -0.560024 0.8284765 0 -0.5587466 0.8293384 0 -0.5574946 0.8301805 0 -0.5561878 0.8310567 0 -0.5549334 0.8318949 0 -0.5536507 0.8327491 0 -0.5523667 0.8336012 0 -0.5510902 0.8344458 0 -0.5497949 0.8352997 0 -0.5485342 0.8361281 0 -0.5472536 0.8369669 0 -0.5459632 0.8378092 0 -0.544707 0.8386265 0 -0.5433866 0.8394826 0 -0.5421198 0.8403013 0 -0.5408598 0.8411129 0 -0.5395355 0.8419629 0 -0.5382376 0.8427933 0 -0.5369107 0.8436391 0 -0.535638 0.8444477 0 -0.534379 0.8452451 0 -0.5330482 0.8460848 0 -0.5317442 0.8469051 0 -0.530439 0.8477233 0 -0.5291743 0.8485131 0 -0.5278667 0.8493273 0 -0.5265299 0.8501566 0 -0.5252546 0.8509451 0 -0.5239154 0.8517704 0 -0.5226094 0.8525722 0 -0.5213305 0.8533548 0 -0.5200222 0.8541529 0 -0.518678 0.8549698 0 -0.5173955 0.8557464 0 -0.5160549 0.8565555 0 -0.51477 0.8573284 0 -0.5134554 0.8581163 0 -0.5121054 0.8589227 0 -0.5108224 0.8596862 0 -0.5094701 0.8604885 0 -0.5081794 0.8612512 0 -0.5068639 0.8620262 0 -0.5055081 0.8628219 0 -0.5041851 0.8635957 0 -0.5028946 0.8643478 0 -0.5015355 0.8651371 0 -0.5002427 0.8658853 0 -0.498869 0.8666775 0 -0.4975569 0.8674314 0 -0.4962435 0.8681834 0 -0.4948956 0.8689524 0 -0.4935507 0.869717 0 -0.4922339 0.870463 0 -0.490916 0.871207 0 -0.4895508 0.8719748 0 -0.4882306 0.8727147 0 -0.4868796 0.8734691 0 -0.4855406 0.8742141 0 -0.4841873 0.8749644 0 -0.4828627 0.8756961 0 -0.481507 0.8764423 0 -0.4801801 0.8771699 0 -0.4788222 0.8779119 0 -0.4774631 0.8786518 0 -0.4761029 0.8793896 0 -0.4747879 0.8801004 0 -0.4734254 0.8808339 0 -0.4720618 0.8815655 0 -0.4707435 0.8822701 0 -0.4693475 0.8830136 0 -0.4680109 0.8837228 0 -0.466659 0.8844373 0 -0.46529 0.8851583 0 -0.4639518 0.8858604 0 -0.4625806 0.8865773 0 -0.4612084 0.8872919 0 -0.4598362 0.8880038 0 -0.4585083 0.8886902 0 -0.4571329 0.8893985 0 -0.4557722 0.8900964 0 -0.4543955 0.8908001 0 -0.4530326 0.8914939 0 -0.4516531 0.8921937 0 -0.4503039 0.8928754 0 -0.448938 0.8935629 0 -0.44754 0.8942641 0 -0.4461875 0.8949396 0 -0.4447873 0.8956363 0 -0.4434328 0.8963078 0 -0.4420772 0.8969771 0 -0.4406897 0.8976595 0 -0.4393008 0.8983402 0 -0.4379106 0.8990185 0 -0.4365662 0.8996722 0 -0.4351435 0.9003611 0 -0.4337818 0.9010181 0 -0.4323875 0.901688 0 -0.4310389 0.9023334 0 -0.4296424 0.9029991 0 -0.4282618 0.9036548 0 -0.4268466 0.9043241 0 -0.4254789 0.9049684 0 -0.4240636 0.9056326 0 -0.4227238 0.9062586 0 -0.4213213 0.9069114 0 -0.4198859 0.9075769 0 -0.4185136 0.9082106 0 -0.4171377 0.9088433 0 -0.4157634 0.9094728 0 -0.414324 0.9101295 0 -0.4129626 0.910748 0 -0.4115357 0.9113937 0 -0.4101256 0.9120291 0 -0.4087614 0.9126414 0 -0.4073315 0.9132804 0 -0.405933 0.9139029 0 -0.404566 0.9145088 0 -0.4031331 0.9151414 0 -0.4017318 0.9157574 0 -0.4003296 0.9163712 0 -0.398908 0.9169911 0 -0.397518 0.9175944 0 -0.3961316 0.9181938 0 -0.3946929 0.9188131 0 -0.3932673 0.9194242 0 -0.3918737 0.9200191 0 -0.390465 0.9206178 0 -0.3890696 0.9212085 0 -0.3876401 0.9218109 0 -0.3862288 0.922403 0 -0.3847837 0.9230068 0 -0.3833984 0.9235832 0 -0.3819983 0.9241631 0 -0.3805505 0.9247602 0 -0.3791154 0.9253494 0 -0.3777264 0.9259173 0 -0.3763229 0.9264886 0 -0.3748517 0.9270849 0 -0.3734465 0.9276517 0 -0.3720404 0.9282166 0 -0.3706001 0.9287927 0 -0.3691721 0.9293611 0 -0.3677433 0.9299274 0 -0.3663339 0.9304835 0 -0.3649033 0.9310455 0 -0.3634923 0.9315972 0 -0.3620131 0.932173 0 -0.3606267 0.9327102 0 -0.3591796 0.9332685 0 -0.3577237 0.9338276 0 -0.3563088 0.9343684 0 -0.354906 0.934902 0 -0.3534474 0.9354545 0 -0.3519962 0.9360014 0 -0.3505911 0.9365286 0 -0.3491297 0.9370744 0 -0.3476889 0.93761 0 -0.3462815 0.9381307 0 -0.3448175 0.9386698 0 -0.3433742 0.9391987 0 -0.3419427 0.9397209 0 -0.3404855 0.9402499 0 -0.3390524 0.9407675 0 -0.3376185 0.9412831 0 -0.3361838 0.9417964 0 -0.3347015 0.9423242 0 -0.3332652 0.9428332 0 -0.3318281 0.9433399 0 -0.3303902 0.9438445 0 -0.328917 0.9443589 0 -0.3274775 0.944859 0 -0.3260374 0.945357 0 -0.3245965 0.9458526 0 -0.323132 0.9463539 0 -0.3216896 0.9468452 0 -0.3202116 0.9473461 0 -0.3187795 0.947829 0 -0.3173466 0.9483096 0 -0.3158664 0.9488038 0 -0.3143854 0.9492955 0 -0.3129503 0.9497696 0 -0.3115029 0.9502453 0 -0.3100427 0.9507227 0 -0.3085941 0.9511939 0 -0.3071095 0.9516743 0 -0.3056469 0.9521449 0 -0.3042075 0.9526059 0 -0.3027209 0.9530794 0 -0.3012913 0.9535322 0 -0.2998145 0.9539976 0 -0.2983369 0.9544607 0 -0.2968941 0.9549104 0 -0.2953907 0.9553766 0 -0.2939821 0.955811 0 -0.2924663 0.9562758 0 -0.2910317 0.9567134 0 -0.2895501 0.9571629 0 -0.2880893 0.9576036 0 -0.2866063 0.9580485 0 -0.2851333 0.9584879 0 -0.2836848 0.9589177 0 -0.2822105 0.9593526 0 -0.2806997 0.9597957 0 -0.2792599 0.9602156 0 -0.2777939 0.9606408 0 -0.2762962 0.9610726 0 -0.2748392 0.9614902 0 -0.2733866 0.9619043 0 -0.2718718 0.9623335 0 -0.2704023 0.9627474 0 -0.2689222 0.9631619 0 -0.2674515 0.9635714 0 -0.2659701 0.9639813 0 -0.2644881 0.964389 0 -0.2630155 0.9647916 0 -0.2615422 0.9651921 0 -0.2600585 0.9655929 0 -0.2585477 0.9659986 0 -0.2571185 0.96638 0 -0.2555967 0.9667836 0 -0.2541203 0.9671727 0 -0.2526434 0.9675595 0 -0.2511658 0.9679441 0 -0.2496512 0.9683359 0 -0.2482136 0.9687054 0 -0.2466979 0.9690924 0 -0.2451861 0.9694761 0 -0.2437468 0.969839 0 -0.2422294 0.9702191 0 -0.2407479 0.9705877 0 -0.2392428 0.9709599 0 -0.2378014 0.9713139 0 -0.2362449 0.9716935 0 -0.234807 0.972042 0 -0.233295 0.972406 0 -0.2318149 0.97276 0 -0.2303017 0.9731193 0 -0.2288249 0.9734676 0 -0.2273064 0.9738233 0 -0.2258327 0.9741661 0 -0.2243543 0.9745077 0 -0.2228385 0.9748555 0 -0.2213264 0.9751999 0 -0.2198464 0.9755345 0 -0.2183743 0.9758651 0 -0.2168564 0.9762036 0 -0.2153421 0.9765387 0 -0.2138643 0.9768634 0 -0.212349 0.977194 0 -0.2108743 0.9775133 0 -0.2093579 0.9778391 0 -0.2078822 0.9781539 0 -0.2063649 0.9784751 0 -0.204851 0.9787932 0 -0.2033739 0.9791012 0 -0.2018552 0.9794155 0 -0.2003437 0.9797258 0 -0.1988278 0.9800345 0 -0.1973527 0.9803326 0 -0.1958359 0.9806368 0 -0.1943598 0.9809304 0 -0.1928458 0.9812291 0 -0.1913278 0.9815262 0 -0.1898128 0.9818203 0 -0.1882939 0.9821128 0 -0.1868228 0.9823937 0 -0.1853031 0.9826815 0 -0.18379 0.9829656 0 -0.1822764 0.9832474 0 -0.1807965 0.9835206 0 -0.179282 0.9837978 0 -0.1777262 0.98408 0 -0.1762519 0.9843451 0 -0.1747328 0.9846159 0 -0.1732577 0.9848766 0 -0.1717068 0.9851481 0 -0.1701899 0.9854114 0 -0.1687104 0.9856657 0 -0.1671581 0.9859302 0 -0.1656842 0.9861789 0 -0.1641659 0.9864329 0 -0.1626124 0.9866901 0 -0.1611373 0.986932 0 -0.1596209 0.9871784 0 -0.1581072 0.987422 0 -0.1565901 0.9876638 0 -0.1550726 0.9879032 0 -0.1535607 0.9881393 0 -0.1520426 0.988374 0 -0.1504919 0.9886113 0 -0.1490139 0.9888351 0 -0.1474949 0.9890629 0 -0.1459839 0.989287 0 -0.1444289 0.9895153 0 -0.1429525 0.9897296 0 -0.1413996 0.9899526 0 -0.1399224 0.9901625 0 -0.1383662 0.9903812 0 -0.1368504 0.9905918 0 -0.135375 0.9907944 0 -0.1338204 0.9910057 0 -0.132268 0.991214 0 -0.1307892 0.9914102 0 -0.1292744 0.9916089 0 -0.1277186 0.9918105 0 -0.1262056 0.9920041 0 -0.1247281 0.992191 0 -0.1231738 0.9923852 0 -0.1216205 0.9925767 0 -0.1201422 0.9927567 0 -0.1185894 0.9929434 0 -0.1170734 0.9931233 0 -0.1155583 0.9933007 0 -0.1140419 0.993476 0 -0.1125274 0.9936487 0 -0.1109731 0.9938235 0 -0.109458 0.9939915 0 -0.1079427 0.9941572 0 -0.1063877 0.9943248 0 -0.1049124 0.9944816 0 -0.1033578 0.9946443 0 -0.1018031 0.9948046 0 -0.100326 0.9949547 0 -0.0987727 0.9951101 0 -0.09725672 0.9952594 0 -0.09574145 0.9954063 0 -0.09418743 0.9955545 0 -0.09267175 0.9956968 0 -0.09115672 0.9958366 0 -0.08960288 0.9959776 0 -0.08808654 0.9961129 0 -0.08657175 0.9962457 0 -0.08501732 0.9963796 0 -0.08350205 0.9965076 0 -0.08198666 0.9966335 0 -0.08043241 0.9967601 0 -0.07891738 0.9968813 0 -0.07740139 0.997 0 -0.07584738 0.9971196 0 -0.07433182 0.9972336 0 -0.07281607 0.9973455 0 -0.07126224 0.9974576 0 -0.06974685 0.9975647 0 -0.06819266 0.9976722 0 -0.06667762 0.9977747 0 -0.06516176 0.9978748 0 -0.06360769 0.997975 0 -0.06209218 0.9980705 0 -0.06057655 0.9981636 0 -0.05902236 0.9982568 0 -0.05746835 0.9983474 0 -0.05595314 0.9984334 0 -0.05443751 0.9985172 0 -0.05292207 0.9985986 0 -0.05136775 0.9986798 0 -0.0498138 0.9987586 0 -0.04829823 0.998833 0 -0.04678285 0.9989051 0 -0.04522854 0.9989767 0 -0.04371333 0.9990442 0 -0.04215902 0.999111 0 -0.04064363 0.9991738 0 -0.03912812 0.9992343 0 -0.03753513 0.9992954 0 -0.03605842 0.9993497 0 -0.03450441 0.9994046 0 -0.03298878 0.9994558 0 -0.03143459 0.9995059 0 -0.02991926 0.9995524 0 -0.02836501 0.9995976 0 -0.02684962 0.9996396 0 -0.02529537 0.9996801 0 -0.02377998 0.9997172 0 -0.02222573 0.9997531 0 -0.02071028 0.9997856 0 -0.01919496 0.9998158 0 -0.0176407 0.9998445 0 -0.01608645 0.9998707 0 -0.01457107 0.9998939 0 -0.01305568 0.9999148 0 -0.01150143 0.999934 0 -0.00994718 0.9999506 0 -0.008470594 0.9999641 0 -0.006877541 0.9999763 0 -0.005362153 0.9999856 0 -0.003846704 0.9999927 0 0 0 1 -0.002292513 0.9999974 0 -7.77124e-4 0.9999997 0 0 0 -1 0.002292513 0.9999974 0 0.005362153 0.9999856 0 0.006877541 0.9999763 0 0.008470594 0.9999641 0 0.01305568 0.9999148 0 0.01457107 0.9998939 0 0.01608645 0.9998707 0 0.0176407 0.9998445 0 0.02222573 0.9997531 0 0.02377998 0.9997172 0 0.02836501 0.9995976 0 0.02991926 0.9995524 0 0.03298878 0.9994558 0 0.04064363 0.9991738 0 0.04371333 0.9990442 0 0.04522854 0.9989767 0 0.04678285 0.9989051 0 0.0498138 0.9987586 0 0.05595314 0.9984334 0 0.05902236 0.9982568 0 0.06209218 0.9980705 0 0.06360769 0.997975 0 0.06667762 0.9977747 0 0.07281607 0.9973455 0 0.07891738 0.9968813 0 0.08198666 0.9966335 0 0.08808654 0.9961129 0 0.08960288 0.9959776 0 0.09725672 0.9952594 0 0.1018031 0.9948046 0 0.1033578 0.9946443 0 0.1049124 0.9944816 0 0.1063877 0.9943248 0 0.1140419 0.993476 0 0.1170734 0.9931233 0 0.1201422 0.9927567 0 0.1247281 0.992191 0 0.1262056 0.9920041 0 0.1277186 0.9918105 0 0.1292744 0.9916089 0 0.132268 0.991214 0 0.1368504 0.9905918 0 0.1399224 0.9901625 0 0.1413996 0.9899526 0 0.1429525 0.9897296 0 0.1474949 0.9890629 0 0.1504919 0.9886113 0 0.1520426 0.988374 0 0.1535607 0.9881393 0 0.1550726 0.9879032 0 0.1565901 0.9876638 0 0.1581072 0.987422 0 0.1626124 0.9866901 0 0.1671581 0.9859302 0 0.1687104 0.9856657 0 0.1732577 0.9848766 0 0.1747328 0.9846159 0 0.1762519 0.9843451 0 0.1777262 0.98408 0 0.1882939 0.9821128 0 0.1928458 0.9812291 0 0.1943598 0.9809304 0 0.1958359 0.9806368 0 0.2003437 0.9797258 0 0.2018552 0.9794155 0 0.204851 0.9787932 0 0.2093579 0.9778391 0 0.2108743 0.9775133 0 0.2183743 0.9758651 0 0.2243543 0.9745077 0 0.2273064 0.9738233 0 0.2303017 0.9731193 0 0.2378014 0.9713139 0 0.2392428 0.9709599 0 0.2407479 0.9705877 0 0.2451861 0.9694761 0 0.2482136 0.9687054 0 0.2496512 0.9683359 0 0.2526434 0.9675595 0 0.2571185 0.96638 0 0.2600585 0.9655929 0 0.2644881 0.964389 0 0.2718718 0.9623335 0 0.2748392 0.9614902 0 0.2762962 0.9610726 0 0.2777939 0.9606408 0 0.2851333 0.9584879 0 0.2866063 0.9580485 0 0.2924663 0.9562758 0 0.2983369 0.9544607 0 0.3027209 0.9530794 0 0.3042075 0.9526059 0 0.3071095 0.9516743 0 0.3085941 0.9511939 0 0.3100427 0.9507227 0 0.3158664 0.9488038 0 0.3173466 0.9483096 0 0.3260374 0.945357 0 0.3274775 0.944859 0 0.328917 0.9443589 0 0.3332652 0.9428332 0 0.3347015 0.9423242 0 0.3376185 0.9412831 0 0.3390524 0.9407675 0 0.3404855 0.9402499 0 0.3419427 0.9397209 0 0.3448175 0.9386698 0 0.3491297 0.9370744 0 0.3505911 0.9365286 0 0.3534474 0.9354545 0 0.3620131 0.932173 0 0.3634923 0.9315972 0 0.3649033 0.9310455 0 0.3706001 0.9287927 0 0.3720404 0.9282166 0 0.3763229 0.9264886 0 0.3791154 0.9253494 0 0.3819983 0.9241631 0 0.3847837 0.9230068 0 0.3890696 0.9212085 0 0.3918737 0.9200191 0 0.3932673 0.9194242 0 0.3946929 0.9188131 0 0.397518 0.9175944 0 0.398908 0.9169911 0 0.4073315 0.9132804 0 0.4115357 0.9113937 0 0.4157634 0.9094728 0 0.4171377 0.9088433 0 0.4213213 0.9069114 0 0.4227238 0.9062586 0 0.4240636 0.9056326 0 0.4296424 0.9029991 0 0.4310389 0.9023334 0 0.4337818 0.9010181 0 0.4351435 0.9003611 0 0.4365662 0.8996722 0 0.4393008 0.8983402 0 0.4406897 0.8976595 0 0.4420772 0.8969771 0 0.4434328 0.8963078 0 0.4447873 0.8956363 0 0.44754 0.8942641 0 0.4516531 0.8921937 0 0.4530326 0.8914939 0 0.4557722 0.8900964 0 0.4585083 0.8886902 0 0.4612084 0.8872919 0 0.46529 0.8851583 0 0.4680109 0.8837228 0 0.4693475 0.8830136 0 0.4707435 0.8822701 0 0.4734254 0.8808339 0 0.4747879 0.8801004 0 0.4774631 0.8786518 0 0.4788222 0.8779119 0 0.4868796 0.8734691 0 0.4882306 0.8727147 0 0.490916 0.871207 0 0.4922339 0.870463 0 0.4935507 0.869717 0 0.4948956 0.8689524 0 0.4962435 0.8681834 0 0.4975569 0.8674314 0 0.498869 0.8666775 0 0.5002427 0.8658853 0 0.5015355 0.8651371 0 0.5028946 0.8643478 0 0.5055081 0.8628219 0 0.5068639 0.8620262 0 0.5094701 0.8604885 0 0.5108224 0.8596862 0 0.5121054 0.8589227 0 0.5173955 0.8557464 0 0.5239154 0.8517704 0 0.5265299 0.8501566 0 0.5278667 0.8493273 0 0.5291743 0.8485131 0 0.530439 0.8477233 0 0.534379 0.8452451 0 0.535638 0.8444477 0 0.5369107 0.8436391 0 0.5382376 0.8427933 0 0.5395355 0.8419629 0 0.5408598 0.8411129 0 0.5433866 0.8394826 0 0.544707 0.8386265 0 0.5485342 0.8361281 0 0.5497949 0.8352997 0 0.5536507 0.8327491 0 0.5574946 0.8301805 0 0.5612734 0.8276306 0 0.5625481 0.8267646 0 0.5638214 0.8258968 0 0.5650669 0.8250452 0 0.5663375 0.8241735 0 0.5688584 0.8224356 0 0.5701512 0.8215399 0 0.5751613 0.8180401 0 0.5776896 0.8162566 0 0.5863982 0.810023 0 0.5888762 0.8082234 0 0.5901198 0.8073157 0 0.5950649 0.8036776 0 0.5999876 0.8000093 0 0.6012428 0.7990666 0 0.6024466 0.7981592 0 0.6036991 0.7972123 0 0.6048754 0.7963201 0 0.6098028 0.7925532 0 0.6122015 0.7907019 0 0.6146452 0.7888037 0 0.6170079 0.786957 0 0.6194162 0.7850628 0 0.620697 0.7840505 0 0.6337645 0.7735261 0 0.6349797 0.7725288 0 0.639741 0.7685906 0 0.6432368 0.7656674 0 0.6467728 0.7626827 0 0.647971 0.7616651 0 0.6491226 0.7606839 0 0.6548714 0.7557405 0 0.6560585 0.7547101 0 0.6571998 0.7537165 0 0.6583836 0.7526826 0 0.6595218 0.7516855 0 0.6606585 0.7506865 0 0.6618157 0.7496666 0 0.6629712 0.748645 0 0.6687157 0.7435182 0 0.6709673 0.741487 0 0.673247 0.7394177 0 0.6743652 0.738398 0 0.6766566 0.7362987 0 0.677749 0.7352934 0 0.6789593 0.734176 0 0.6800486 0.7331671 0 0.6811781 0.7321178 0 0.6822643 0.7311057 0 0.6845122 0.7290014 0 0.6867536 0.7268903 0 0.6889476 0.7248112 0 0.6901412 0.7236748 0 0.6912147 0.7226495 0 0.6922867 0.7216225 0 0.6934551 0.7205 0 0.6945238 0.7194698 0 0.6956111 0.7184186 0 0.6967543 0.7173099 0 0.7011367 0.713027 0 0.702194 0.7119856 0 0.7044205 0.7097829 0 0.7109044 0.7032887 0 0.7141437 0.6999992 0 0.7151811 0.6989393 0 0.7162944 0.6977983 0 0.7173094 0.6967549 0 0.7184192 0.6956104 0 0.7216234 0.6922859 0 0.7226486 0.6912156 0 0.7237128 0.6901014 0 0.7248122 0.6889466 0 0.7258139 0.6878913 0 0.7268914 0.6867524 0 0.7279673 0.685612 0 0.7289639 0.6845523 0 0.7310682 0.6823044 0 0.7321552 0.6811379 0 0.7332044 0.6800084 0 0.7341745 0.6789609 0 0.7352561 0.6777893 0 0.7363004 0.6766549 0 0.7373606 0.6754994 0 0.7394194 0.6732451 0 0.7414889 0.6709653 0 0.7425054 0.6698402 0 0.743555 0.6686749 0 0.7445255 0.667594 0 0.7455542 0.666445 0 0.7486472 0.6629687 0 0.7496689 0.6618131 0 0.7506889 0.6606559 0 0.752685 0.6583808 0 0.7546741 0.6560999 0 0.7567165 0.6537433 0 0.757724 0.6525752 0 0.7587298 0.6514056 0 0.7597336 0.6502344 0 0.7607195 0.6490809 0 0.7626799 0.6467761 0 0.7636604 0.6456183 0 0.7656705 0.6432331 0 0.7696145 0.6385088 0 0.7705984 0.6373212 0 0.7734915 0.6338068 0 0.7744522 0.6326325 0 0.7753957 0.6314758 0 0.7764444 0.6301859 0 0.7773843 0.6290261 0 0.7783531 0.6278269 0 0.7792894 0.6266643 0 0.780224 0.6255003 0 0.7821561 0.6230827 0 0.7850291 0.6194591 0 0.7878854 0.615822 0 0.7897872 0.6133809 0 0.7925865 0.6097596 0 0.7944549 0.6073232 0 0.7953605 0.6061369 0 0.7963247 0.6048695 0 0.7981638 0.6024405 0 0.7990618 0.6012489 0 0.8027333 0.5963383 0 0.8036825 0.5950584 0 0.8045556 0.5938775 0 0.8082283 0.5888693 0 0.8091191 0.5876449 0 0.8100281 0.5863912 0 0.8153581 0.5789571 0 0.8171639 0.5764056 0 0.8180089 0.5752056 0 0.8232567 0.5676694 0 0.8250147 0.5651115 0 0.8259025 0.563813 0 0.8276364 0.5612648 0 0.8284585 0.5600507 0 0.8327551 0.5536416 0 0.8378269 0.5459359 0 0.8411066 0.5408695 0 0.8419566 0.5395454 0 0.8469225 0.5317163 0 0.8493207 0.5278773 0 0.8501285 0.5265753 0 0.8533376 0.5213589 0 0.8541356 0.5200505 0 0.8549525 0.5187064 0 0.8565727 0.5160264 0 0.8612682 0.5081506 0 0.8666559 0.4989066 0 0.8674098 0.4975944 0 0.8681714 0.4962645 0 0.8689309 0.4949334 0 0.8719582 0.4895803 0 0.8727027 0.4882519 0 0.8749808 0.4841576 0 0.8757125 0.4828329 0 0.8778911 0.4788603 0 0.8793734 0.4761329 0 0.8800885 0.4748099 0 0.8815494 0.472092 0 0.8822584 0.4707657 0 0.8830254 0.4693252 0 0.8837345 0.4679886 0 0.8851702 0.4652675 0 0.8865932 0.4625501 0 0.8893826 0.4571636 0 0.8914822 0.4530556 0 0.8928598 0.4503349 0 0.8949241 0.4462186 0 0.895648 0.444764 0 0.8969963 0.4420381 0 0.8996912 0.4365271 0 0.9003423 0.4351826 0 0.9023219 0.4310629 0 0.9030178 0.4296032 0 0.9043091 0.4268783 0 0.9062471 0.4227483 0 0.9069298 0.421282 0 0.9081959 0.4185456 0 0.9088614 0.4170982 0 0.9101148 0.4143561 0 0.9114116 0.4114962 0 0.9120146 0.4101579 0 0.9132917 0.4073063 0 0.9138885 0.4059655 0 0.9151557 0.4031006 0 0.9157432 0.4017645 0 0.9163855 0.4002969 0 0.9181797 0.3961644 0 0.9194132 0.3932932 0 0.920036 0.3918337 0 0.9206039 0.390498 0 0.9212254 0.3890296 0 0.9230177 0.3847575 0 0.9235693 0.3834314 0 0.9241797 0.3819583 0 0.9253602 0.3790889 0 0.9259037 0.3777597 0 0.9265049 0.3762828 0 0.9270983 0.3748183 0 0.9276382 0.3734799 0 0.9282273 0.3720136 0 0.9293743 0.3691385 0 0.9310612 0.364863 0 0.9315815 0.3635326 0 0.9321574 0.3620534 0 0.9327234 0.3605929 0 0.9360143 0.3519622 0 0.9365136 0.3506316 0 0.9370641 0.3491575 0 0.9392113 0.34334 0 0.9402601 0.3404574 0 0.9412932 0.3375902 0 0.9428188 0.3333058 0 0.9438323 0.3304249 0 0.9443448 0.3289577 0 0.9453429 0.3260781 0 0.946857 0.3216547 0 0.9473578 0.3201767 0 0.9483233 0.3173059 0 0.9488173 0.3158255 0 0.949307 0.3143504 0 0.9502568 0.3114678 0 0.950736 0.3100019 0 0.952619 0.3041666 0 0.9530887 0.3026912 0 0.9549215 0.2968587 0 0.9562851 0.2924362 0 0.9589282 0.2836491 0 0.9593631 0.2821748 0 0.9602051 0.2792957 0 0.9606319 0.2778245 0 0.9610608 0.2763373 0 0.9614815 0.27487 0 0.9623423 0.2718408 0 0.9627576 0.2703663 0 0.963172 0.2688862 0 0.9635814 0.2674154 0 0.9639912 0.265934 0 0.9643975 0.2644569 0 0.9648016 0.2629793 0 0.9652019 0.261506 0 0.9656013 0.2600271 0 0.9663716 0.2571499 0 0.9683446 0.2496171 0 0.9690832 0.2467343 0 0.9698482 0.2437103 0 0.9709514 0.2392772 0 0.9720332 0.2348437 0 0.9731285 0.2302628 0 0.9734764 0.2287881 0 0.9748638 0.2228016 0 0.9762118 0.2168194 0 0.9771859 0.2123861 0 0.9775056 0.2109094 0 0.978483 0.2063277 0 0.9794074 0.2018944 0 0.9800269 0.1988651 0 0.9803251 0.19739 0 0.9812368 0.1928066 0 0.9818276 0.1897754 0 0.9826744 0.1853406 0 0.9832404 0.1823139 0 0.9835137 0.1808341 0 0.9846224 0.1746968 0 0.984883 0.1732217 0 0.9851415 0.1717445 0 0.9864265 0.1642037 0 0.986696 0.1625761 0 0.9869382 0.1610994 0 0.9874283 0.1580678 0 0.9879088 0.1550362 0 0.9883796 0.152006 0 0.9886057 0.1505284 0 0.9888294 0.149052 0 0.9892814 0.146022 0 0.9895207 0.1443909 0 0.9897353 0.1429131 0 0.9899474 0.1414363 0 0.9901574 0.1399592 0 0.9903864 0.1383281 0 0.9916138 0.1292374 0 0.9918054 0.127758 0 0.9931188 0.1171123 0 0.9934716 0.1140808 0 0.9939873 0.1094964 0 0.9952555 0.0972957 0 0.9956932 0.09271025 0 0.9961094 0.08812552 0 0.9965044 0.08354067 0 0.9968782 0.07895565 0 0.9972308 0.07437044 0 0.9975621 0.06978553 0 0.9976749 0.06815397 0 0.9978773 0.06512308 0 0.9979726 0.06364607 0 0.9981613 0.0606153 0 0.998259 0.0589838 0 0.9983451 0.05750703 0 0.9985151 0.05447626 0 0.9988312 0.04833704 0 0.9990425 0.04375201 0 0.9991126 0.04212021 0 0.9992358 0.03908932 0 0.9994571 0.03295004 0 0.9995047 0.03147339 0 0.9996384 0.02688843 0 0.9996811 0.02525651 0 0.9997864 0.02067148 0 0.9998945 0.0145322 0 0.9999767 0.006838679 0 0.9999929 0.003807902 0 0.9999974 0.002331316 0 0.9999976 -0.002253651 0 0.9999925 -0.003885567 0 0.9999761 -0.006916344 0 0.9998933 -0.01460987 0 0.9997847 -0.02074915 0 0.999679 -0.02533417 0 0.9996406 -0.02681082 0 0.9995071 -0.03139579 0 0.9994544 -0.03302764 0 0.9992328 -0.03916692 0 0.9991094 -0.04219782 0 0.9990459 -0.0436744 0 0.9988349 -0.04825949 0 0.9985194 -0.05439877 0 0.9983496 -0.05742961 0 0.9982544 -0.05906122 0 0.9981659 -0.06053787 0 0.9979775 -0.06356871 0 0.9978722 -0.06520044 0 0.9976696 -0.06823134 0 0.9975675 -0.06970816 0 0.9972366 -0.07429319 0 0.9968843 -0.0788784 0 0.9965109 -0.08346349 0 0.9961163 -0.08804845 0 0.9957003 -0.09263318 0 0.9952631 -0.09721869 0 0.9939957 -0.1094197 0 0.9934804 -0.1140041 0 0.9931278 -0.1170357 0 0.9918153 -0.1276816 0 0.9916038 -0.1293138 0 0.9903759 -0.1384043 0 0.990168 -0.1398831 0 0.9899582 -0.1413601 0 0.9897242 -0.1429892 0 0.9895097 -0.144467 0 0.9892926 -0.1459459 0 0.9888408 -0.148976 0 0.9886173 -0.1504525 0 0.988368 -0.152082 0 0.987897 -0.155112 0 0.9874162 -0.1581435 0 0.9869258 -0.1611751 0 0.9866836 -0.1626517 0 0.9864391 -0.164128 0 0.9851547 -0.1716691 0 0.9848697 -0.1732971 0 0.984609 -0.1747722 0 0.9835276 -0.1807589 0 0.9832543 -0.1822388 0 0.9826885 -0.1852656 0 0.9818131 -0.1898503 0 0.9812222 -0.1928814 0 0.9803401 -0.1973153 0 0.980042 -0.1987905 0 0.9794227 -0.2018198 0 0.9784673 -0.2064021 0 0.9775217 -0.2108351 0 0.977202 -0.2123119 0 0.9761953 -0.2168934 0 0.974847 -0.2228754 0 0.973459 -0.2288617 0 0.9731111 -0.2303364 0 0.972051 -0.2347703 0 0.9709694 -0.2392039 0 0.9698298 -0.2437834 0 0.9691018 -0.2466614 0 0.9683259 -0.2496899 0 0.9663909 -0.2570773 0 0.9655818 -0.2600996 0 0.9651823 -0.2615784 0 0.9647818 -0.2630516 0 0.9643778 -0.2645292 0 0.9639714 -0.2660062 0 0.9635614 -0.2674875 0 0.9631519 -0.2689583 0 0.9627374 -0.2704384 0 0.9623219 -0.2719128 0 0.961502 -0.2747981 0 0.9610815 -0.2762655 0 0.9606527 -0.2777528 0 0.960226 -0.279224 0 0.959342 -0.2822462 0 0.958907 -0.2837205 0 0.9562634 -0.2925073 0 0.9548994 -0.2969295 0 0.9530663 -0.3027618 0 0.9525964 -0.3042371 0 0.950713 -0.3100721 0 0.9502337 -0.311538 0 0.9492838 -0.3144204 0 0.9487941 -0.3158956 0 0.9483 -0.3173757 0 0.9473343 -0.3202465 0 0.9468334 -0.3217244 0 0.9453668 -0.3260086 0 0.9443689 -0.3288884 0 0.9438566 -0.3303557 0 0.9428433 -0.3332368 0 0.9412685 -0.3376591 0 0.9402351 -0.3405261 0 0.9391862 -0.3434085 0 0.9370896 -0.3490893 0 0.9365391 -0.3505634 0 0.9359886 -0.3520302 0 0.9326972 -0.3606605 0 0.9321836 -0.3619859 0 0.9316079 -0.3634652 0 0.9310348 -0.3649303 0 0.9293477 -0.3692057 0 0.9282004 -0.3720806 0 0.9276652 -0.373413 0 0.9270713 -0.3748851 0 0.9264779 -0.3763495 0 0.9259309 -0.3776931 0 0.925333 -0.3791555 0 0.9241522 -0.3820246 0 0.9235969 -0.3833652 0 0.9229902 -0.3848237 0 0.9211975 -0.3890956 0 0.9206318 -0.3904321 0 0.9200081 -0.3918995 0 0.9194412 -0.3932275 0 0.9182079 -0.3960988 0 0.916357 -0.4003622 0 0.9157717 -0.4016993 0 0.9151271 -0.4031657 0 0.9139174 -0.4059005 0 0.9132628 -0.4073711 0 0.9120437 -0.4100933 0 0.9113824 -0.4115607 0 0.9101441 -0.4142918 0 0.908832 -0.4171624 0 0.9082254 -0.4184815 0 0.9069001 -0.4213459 0 0.906277 -0.4226844 0 0.9043391 -0.4268148 0 0.9029877 -0.4296666 0 0.9023522 -0.4309996 0 0.9003728 -0.4351196 0 0.8996606 -0.43659 0 0.8969655 -0.4421007 0 0.8956169 -0.4448263 0 0.894955 -0.4461564 0 0.892891 -0.4502729 0 0.8915137 -0.4529939 0 0.8894143 -0.4571022 0 0.8865614 -0.4626112 0 0.8851382 -0.4653285 0 0.8837024 -0.4680493 0 0.8829933 -0.4693859 0 0.8822906 -0.4707052 0 0.8815817 -0.4720317 0 0.880121 -0.4747497 0 0.8794059 -0.4760729 0 0.8779238 -0.4788004 0 0.8756797 -0.4828925 0 0.874948 -0.4842171 0 0.8727359 -0.4881927 0 0.8719915 -0.4895213 0 0.8689644 -0.4948747 0 0.8682049 -0.4962059 0 0.8674435 -0.497536 0 0.8666895 -0.4988482 0 0.8612342 -0.5082082 0 0.8565384 -0.5160834 0 0.854987 -0.5186496 0 0.8541701 -0.5199939 0 0.8533722 -0.5213023 0 0.8501633 -0.5265192 0 0.8493555 -0.5278213 0 0.8468877 -0.5317721 0 0.8419919 -0.5394903 0 0.8411419 -0.5408146 0 0.8377915 -0.5459904 0 0.8327192 -0.5536955 0 0.8284945 -0.5599973 0 0.8276003 -0.561318 0 0.8258664 -0.563866 0 0.8250509 -0.5650586 0 0.823293 -0.5676168 0 0.8180455 -0.5751537 0 0.8171273 -0.5764575 0 0.8153948 -0.5789054 0 0.8099912 -0.5864422 0 0.8090821 -0.5876957 0 0.8081914 -0.5889201 0 0.8045927 -0.5938271 0 0.8036453 -0.5951086 0 0.8027704 -0.5962883 0 0.7990993 -0.6011993 0 0.7981264 -0.60249 0 0.7962872 -0.6049187 0 0.7953978 -0.6060877 0 0.7944175 -0.6073723 0 0.7925489 -0.6098084 0 0.7897496 -0.6134294 0 0.7878477 -0.6158702 0 0.7850668 -0.6194112 0 0.7821939 -0.6230351 0 0.780262 -0.625453 0 0.7793273 -0.6266171 0 0.7783151 -0.627874 0 0.7773463 -0.629073 0 0.7764063 -0.6302327 0 0.7754337 -0.631429 0 0.7744903 -0.6325859 0 0.7735296 -0.6337603 0 0.7705602 -0.6373673 0 0.7695763 -0.6385549 0 0.7656322 -0.6432787 0 0.7636988 -0.6455729 0 0.7627182 -0.646731 0 0.760681 -0.6491259 0 0.7596953 -0.6502793 0 0.7586914 -0.6514503 0 0.7576856 -0.6526198 0 0.756678 -0.6537878 0 0.7547126 -0.6560556 0 0.7526465 -0.6584249 0 0.7506504 -0.6606997 0 0.7496303 -0.6618568 0 0.7486086 -0.6630123 0 0.7455929 -0.6664018 0 0.7445641 -0.667551 0 0.7435163 -0.6687179 0 0.7424666 -0.669883 0 0.7414502 -0.6710079 0 0.7393807 -0.6732876 0 0.7373219 -0.6755416 0 0.7362616 -0.676697 0 0.7352949 -0.6777474 0 0.7342132 -0.678919 0 0.7331656 -0.6800501 0 0.7321165 -0.6811795 0 0.731107 -0.6822629 0 0.7290026 -0.684511 0 0.7279285 -0.6856531 0 0.7268526 -0.6867935 0 0.7258527 -0.6878503 0 0.7247734 -0.6889874 0 0.7236739 -0.6901421 0 0.7226874 -0.691175 0 0.7215845 -0.6923264 0 0.7183804 -0.6956505 0 0.7173482 -0.6967149 0 0.7162555 -0.6978381 0 0.7152199 -0.6988996 0 0.7141049 -0.7000388 0 0.7108656 -0.703328 0 0.7043817 -0.7098215 0 0.7022329 -0.7119473 0 0.7010979 -0.7130652 0 0.6967155 -0.7173476 0 0.6956499 -0.718381 0 0.694485 -0.7195073 0 0.6934162 -0.7205374 0 0.6923255 -0.7215853 0 0.6911759 -0.7226866 0 0.6901023 -0.7237119 0 0.6889864 -0.7247744 0 0.6867924 -0.7268537 0 0.684551 -0.7289651 0 0.6823031 -0.7310695 0 0.6811394 -0.7321538 0 0.6800099 -0.733203 0 0.6789205 -0.7342118 0 0.6777877 -0.7352577 0 0.6766954 -0.7362632 0 0.6744039 -0.7383627 0 0.6732857 -0.7393825 0 0.6710059 -0.741452 0 0.668677 -0.7435531 0 0.6630098 -0.7486108 0 0.6618543 -0.7496326 0 0.6606971 -0.7506526 0 0.6595603 -0.7516517 0 0.6584221 -0.752649 0 0.6572383 -0.753683 0 0.6560969 -0.7546766 0 0.6549099 -0.7557071 0 0.6490842 -0.7607166 0 0.6479327 -0.7616977 0 0.6467344 -0.7627154 0 0.643275 -0.7656352 0 0.6397027 -0.7686223 0 0.6350178 -0.7724975 0 0.6338026 -0.7734948 0 0.6206592 -0.7840805 0 0.619454 -0.7850329 0 0.6170456 -0.7869274 0 0.6146075 -0.7888331 0 0.6122391 -0.7906728 0 0.6097652 -0.7925821 0 0.6049128 -0.7962917 0 0.6036617 -0.7972406 0 0.602484 -0.798131 0 0.6012054 -0.7990946 0 0.6000249 -0.7999814 0 0.5951021 -0.8036502 0 0.5901569 -0.8072886 0 0.5889132 -0.8081964 0 0.5864351 -0.8099963 0 0.5777263 -0.8162307 0 0.5751979 -0.8180144 0 0.5701875 -0.8215146 0 0.5688948 -0.8224104 0 0.5663738 -0.8241485 0 0.5651032 -0.8250204 0 0.5638576 -0.825872 0 0.5625842 -0.8267401 0 0.5613095 -0.827606 0 0.5575307 -0.8301565 0 0.5536865 -0.8327252 0 0.5498306 -0.8352763 0 0.5485699 -0.8361048 0 0.5446715 -0.8386495 0 0.5433512 -0.8395056 0 0.5408244 -0.8411356 0 0.5395002 -0.8419856 0 0.5382023 -0.8428158 0 0.5369459 -0.8436168 0 0.5356732 -0.8444254 0 0.5343438 -0.8452673 0 0.5304739 -0.8477013 0 0.5291395 -0.8485349 0 0.5278319 -0.8493489 0 0.5265646 -0.8501351 0 0.52395 -0.8517491 0 0.51743 -0.8557257 0 0.5121396 -0.8589023 0 0.5107883 -0.8597065 0 0.5095041 -0.8604682 0 0.5068299 -0.8620461 0 0.505542 -0.862802 0 0.5028609 -0.8643674 0 0.5015692 -0.8651176 0 0.5002259 -0.865895 0 0.4988858 -0.8666679 0 0.4975736 -0.8674219 0 0.4962269 -0.868193 0 0.4949124 -0.868943 0 0.4935674 -0.8697076 0 0.4922173 -0.8704724 0 0.4908995 -0.8712164 0 0.4882141 -0.872724 0 0.4868631 -0.8734783 0 0.4788385 -0.8779031 0 0.4774794 -0.878643 0 0.4747716 -0.8801091 0 0.4734416 -0.8808253 0 0.4707274 -0.8822788 0 0.4693635 -0.883005 0 0.4680269 -0.8837142 0 0.4653059 -0.8851499 0 0.4612243 -0.8872836 0 0.4584925 -0.8886983 0 0.4557881 -0.8900884 0 0.4530169 -0.8915019 0 0.4516688 -0.8921858 0 0.4475555 -0.8942562 0 0.4448028 -0.8956286 0 0.4434173 -0.8963153 0 0.4420617 -0.8969846 0 0.4407051 -0.897652 0 0.4393161 -0.8983327 0 0.4365509 -0.8996796 0 0.4351587 -0.9003538 0 0.4337969 -0.9010106 0 0.4310238 -0.9023407 0 0.4296274 -0.9030063 0 0.4240784 -0.9056255 0 0.4227089 -0.9062656 0 0.4213066 -0.9069184 0 0.417123 -0.9088501 0 0.4157487 -0.9094795 0 0.4115211 -0.9114002 0 0.4073459 -0.913274 0 0.3988938 -0.9169973 0 0.3975039 -0.9176005 0 0.394707 -0.918807 0 0.3932533 -0.9194303 0 0.3918597 -0.9200251 0 0.3890556 -0.9212143 0 0.3847975 -0.9230011 0 0.3819846 -0.9241688 0 0.3791291 -0.9253439 0 0.3763093 -0.9264942 0 0.3720538 -0.9282112 0 0.3706134 -0.9287872 0 0.3648901 -0.9310507 0 0.3635055 -0.9315922 0 0.3620262 -0.932168 0 0.3534346 -0.9354593 0 0.3506039 -0.9365239 0 0.3491171 -0.9370792 0 0.3448049 -0.9386744 0 0.3419302 -0.9397253 0 0.340498 -0.9402453 0 0.3390648 -0.9407631 0 0.3376309 -0.9412787 0 0.3347138 -0.9423199 0 0.3332774 -0.9428288 0 0.328929 -0.9443547 0 0.3274896 -0.9448549 0 0.3260493 -0.9453528 0 0.317335 -0.9483136 0 0.3158547 -0.9488075 0 0.3100313 -0.9507264 0 0.3086054 -0.9511902 0 0.3071208 -0.9516705 0 0.3041962 -0.9526095 0 0.3027321 -0.9530758 0 0.298348 -0.9544572 0 0.2924771 -0.9562725 0 0.2865957 -0.9580517 0 0.2851227 -0.958491 0 0.2777835 -0.9606438 0 0.2763065 -0.9610697 0 0.2748289 -0.9614932 0 0.2718819 -0.9623307 0 0.2644981 -0.9643862 0 0.2600682 -0.9655903 0 0.2571088 -0.9663825 0 0.2526338 -0.967562 0 0.2496559 -0.9683346 0 0.2482089 -0.9687066 0 0.2451815 -0.9694772 0 0.2407524 -0.9705866 0 0.2392383 -0.9709609 0 0.2377969 -0.971315 0 0.2302974 -0.9731203 0 0.2273107 -0.9738223 0 0.2243586 -0.9745067 0 0.2183701 -0.9758661 0 0.2108702 -0.9775141 0 0.2093539 -0.97784 0 0.2048471 -0.978794 0 0.201859 -0.9794147 0 0.2003399 -0.9797266 0 0.1958321 -0.9806375 0 0.1943561 -0.9809311 0 0.1928421 -0.9812299 0 0.1882975 -0.9821121 0 0.1777296 -0.9840794 0 0.1762552 -0.9843445 0 0.1747362 -0.9846154 0 0.1732611 -0.984876 0 0.1687136 -0.9856652 0 0.1671614 -0.9859296 0 0.1626155 -0.9866896 0 0.1581041 -0.9874225 0 0.156593 -0.9876633 0 0.1550756 -0.9879027 0 0.1535578 -0.9881398 0 0.1520455 -0.9883735 0 0.150489 -0.9886118 0 0.1474977 -0.9890625 0 0.1429497 -0.98973 0 0.1413968 -0.989953 0 0.1399198 -0.9901629 0 0.136853 -0.9905914 0 0.1322655 -0.9912143 0 0.1292769 -0.9916086 0 0.127721 -0.9918102 0 0.1262032 -0.9920045 0 0.1247293 -0.9921909 0 0.1201434 -0.9927566 0 0.1170746 -0.9931232 0 0.114043 -0.9934759 0 0.1063887 -0.9943246 0 0.1049113 -0.9944816 0 0.1033568 -0.9946444 0 0.101804 -0.9948046 0 0.09725767 -0.9952592 0 0.08960205 -0.9959778 0 0.08808743 -0.9961128 0 0.08198583 -0.9966335 0 0.0789166 -0.9968813 0 0.07281678 -0.9973453 0 0.06667697 -0.9977747 0 0.06360709 -0.9979751 0 0.06209248 -0.9980705 0 0.05902266 -0.9982568 0 0.05595284 -0.9984334 0 0.04981356 -0.9987586 0 0.04678261 -0.9989051 0 0.04522871 -0.9989767 0 0.04371309 -0.9990442 0 0.04064339 -0.9991738 0 0.03298896 -0.9994558 0 0.0299192 -0.9995524 0 0.02836495 -0.9995977 0 0.02377992 -0.9997172 0 0.02222579 -0.9997531 0 0.01764065 -0.9998445 0 0.01608639 -0.9998706 0 0.01457101 -0.9998939 0 0.01305562 -0.9999148 0 0.008470654 -0.9999642 0 0.006877541 -0.9999763 0 0.005362153 -0.9999857 0 0.002292513 -0.9999974 0 -0.002292513 -0.9999974 0 -0.005362153 -0.9999856 0 -0.006877541 -0.9999763 0 -0.008470594 -0.9999641 0 -0.01305568 -0.9999148 0 -0.01457107 -0.9998939 0 -0.01608645 -0.9998707 0 -0.0176407 -0.9998445 0 -0.02222573 -0.9997531 0 -0.02377998 -0.9997172 0 -0.02836501 -0.9995976 0 -0.02991926 -0.9995524 0 -0.03298878 -0.9994558 0 -0.04064363 -0.9991738 0 -0.04371333 -0.9990442 0 -0.04522854 -0.9989767 0 -0.04678285 -0.9989051 0 -0.0498138 -0.9987586 0 -0.05595314 -0.9984334 0 -0.05902236 -0.9982568 0 -0.06209218 -0.9980705 0 -0.06360769 -0.997975 0 -0.06667762 -0.9977747 0 -0.07281607 -0.9973455 0 -0.07891738 -0.9968813 0 -0.08198666 -0.9966335 0 -0.08808654 -0.9961129 0 -0.08960288 -0.9959776 0 -0.09725672 -0.9952594 0 -0.1018031 -0.9948046 0 -0.1033578 -0.9946443 0 -0.1049124 -0.9944816 0 -0.1063877 -0.9943248 0 -0.1140419 -0.993476 0 -0.1170734 -0.9931233 0 -0.1201422 -0.9927567 0 -0.1247281 -0.992191 0 -0.1262056 -0.9920041 0 -0.1277186 -0.9918105 0 -0.1292744 -0.9916089 0 -0.132268 -0.991214 0 -0.1368504 -0.9905918 0 -0.1399224 -0.9901625 0 -0.1413996 -0.9899526 0 -0.1429525 -0.9897296 0 -0.1474949 -0.9890629 0 -0.1504919 -0.9886113 0 -0.1520426 -0.988374 0 -0.1535607 -0.9881393 0 -0.1550726 -0.9879032 0 -0.1565901 -0.9876638 0 -0.1581072 -0.987422 0 -0.1626124 -0.9866901 0 -0.1671581 -0.9859302 0 -0.1687104 -0.9856657 0 -0.1732577 -0.9848766 0 -0.1747328 -0.9846159 0 -0.1762519 -0.9843451 0 -0.1777262 -0.98408 0 -0.1882939 -0.9821128 0 -0.1928458 -0.9812291 0 -0.1943598 -0.9809304 0 -0.1958359 -0.9806368 0 -0.2003437 -0.9797258 0 -0.2018552 -0.9794155 0 -0.204851 -0.9787932 0 -0.2093579 -0.9778391 0 -0.2108743 -0.9775133 0 -0.2183743 -0.9758651 0 -0.2243543 -0.9745077 0 -0.2273064 -0.9738233 0 -0.2303017 -0.9731193 0 -0.2378014 -0.9713139 0 -0.2392428 -0.9709599 0 -0.2407479 -0.9705877 0 -0.2451861 -0.9694761 0 -0.2482136 -0.9687054 0 -0.2496512 -0.9683359 0 -0.2526434 -0.9675595 0 -0.2571185 -0.96638 0 -0.2600585 -0.9655929 0 -0.2644881 -0.964389 0 -0.2718718 -0.9623335 0 -0.2748392 -0.9614902 0 -0.2762962 -0.9610726 0 -0.2777939 -0.9606408 0 -0.2851333 -0.9584879 0 -0.2866063 -0.9580485 0 -0.2924663 -0.9562758 0 -0.2983369 -0.9544607 0 -0.3027209 -0.9530794 0 -0.3042075 -0.9526059 0 -0.3071095 -0.9516743 0 -0.3085941 -0.9511939 0 -0.3100427 -0.9507227 0 -0.3158664 -0.9488038 0 -0.3173466 -0.9483096 0 -0.3260374 -0.945357 0 -0.3274775 -0.944859 0 -0.328917 -0.9443589 0 -0.3332652 -0.9428332 0 -0.3347015 -0.9423242 0 -0.3376185 -0.9412831 0 -0.3390524 -0.9407675 0 -0.3404855 -0.9402499 0 -0.3419427 -0.9397209 0 -0.3448175 -0.9386698 0 -0.3491297 -0.9370744 0 -0.3505911 -0.9365286 0 -0.3534474 -0.9354545 0 -0.3620131 -0.932173 0 -0.3634923 -0.9315972 0 -0.3649033 -0.9310455 0 -0.3706001 -0.9287927 0 -0.3720404 -0.9282166 0 -0.3763229 -0.9264886 0 -0.3791154 -0.9253494 0 -0.3819983 -0.9241631 0 -0.3847837 -0.9230068 0 -0.3890696 -0.9212085 0 -0.3918737 -0.9200191 0 -0.3932673 -0.9194242 0 -0.3946929 -0.9188131 0 -0.397518 -0.9175944 0 -0.398908 -0.9169911 0 -0.4073315 -0.9132804 0 -0.4115357 -0.9113937 0 -0.4157634 -0.9094728 0 -0.4171377 -0.9088433 0 -0.4213213 -0.9069114 0 -0.4227238 -0.9062586 0 -0.4240636 -0.9056326 0 -0.4296424 -0.9029991 0 -0.4310389 -0.9023334 0 -0.4337818 -0.9010181 0 -0.4351435 -0.9003611 0 -0.4365662 -0.8996722 0 -0.4393008 -0.8983402 0 -0.4406897 -0.8976595 0 -0.4420772 -0.8969771 0 -0.4434328 -0.8963078 0 -0.4447873 -0.8956363 0 -0.44754 -0.8942641 0 -0.4516531 -0.8921937 0 -0.4530326 -0.8914939 0 -0.4557722 -0.8900964 0 -0.4585083 -0.8886902 0 -0.4612084 -0.8872919 0 -0.46529 -0.8851583 0 -0.4680109 -0.8837228 0 -0.4693475 -0.8830136 0 -0.4707435 -0.8822701 0 -0.4734254 -0.8808339 0 -0.4747879 -0.8801004 0 -0.4774631 -0.8786518 0 -0.4788222 -0.8779119 0 -0.4868796 -0.8734691 0 -0.4882306 -0.8727147 0 -0.490916 -0.871207 0 -0.4922339 -0.870463 0 -0.4935507 -0.869717 0 -0.4948956 -0.8689524 0 -0.4962435 -0.8681834 0 -0.4975569 -0.8674314 0 -0.498869 -0.8666775 0 -0.5002427 -0.8658853 0 -0.5015355 -0.8651371 0 -0.5028946 -0.8643478 0 -0.5055081 -0.8628219 0 -0.5068639 -0.8620262 0 -0.5094701 -0.8604885 0 -0.5108224 -0.8596862 0 -0.5121054 -0.8589227 0 -0.5173955 -0.8557464 0 -0.5239154 -0.8517704 0 -0.5265299 -0.8501566 0 -0.5278667 -0.8493273 0 -0.5291743 -0.8485131 0 -0.530439 -0.8477233 0 -0.534379 -0.8452451 0 -0.535638 -0.8444477 0 -0.5369107 -0.8436391 0 -0.5382376 -0.8427933 0 -0.5395355 -0.8419629 0 -0.5408598 -0.8411129 0 -0.5433866 -0.8394826 0 -0.544707 -0.8386265 0 -0.5485342 -0.8361281 0 -0.5497949 -0.8352997 0 -0.5536507 -0.8327491 0 -0.5574946 -0.8301805 0 -0.5612734 -0.8276306 0 -0.5625481 -0.8267646 0 -0.5638214 -0.8258968 0 -0.5650669 -0.8250452 0 -0.5663375 -0.8241735 0 -0.5688584 -0.8224356 0 -0.5701512 -0.8215399 0 -0.5751613 -0.8180401 0 -0.5776896 -0.8162566 0 -0.5863982 -0.810023 0 -0.5888762 -0.8082234 0 -0.5901198 -0.8073157 0 -0.5950649 -0.8036776 0 -0.5999876 -0.8000093 0 -0.6012428 -0.7990666 0 -0.6024466 -0.7981592 0 -0.6036991 -0.7972123 0 -0.6048754 -0.7963201 0 -0.6098028 -0.7925532 0 -0.6122015 -0.7907019 0 -0.6146452 -0.7888037 0 -0.6170079 -0.786957 0 -0.6194162 -0.7850628 0 -0.620697 -0.7840505 0 -0.6337645 -0.7735261 0 -0.6349797 -0.7725288 0 -0.639741 -0.7685906 0 -0.6432368 -0.7656674 0 -0.6467728 -0.7626827 0 -0.647971 -0.7616651 0 -0.6491226 -0.7606839 0 -0.6548714 -0.7557405 0 -0.6560585 -0.7547101 0 -0.6571998 -0.7537165 0 -0.6583836 -0.7526826 0 -0.6595218 -0.7516855 0 -0.6606585 -0.7506865 0 -0.6618157 -0.7496666 0 -0.6629712 -0.748645 0 -0.6687157 -0.7435182 0 -0.6709673 -0.741487 0 -0.673247 -0.7394177 0 -0.6743652 -0.738398 0 -0.6766566 -0.7362987 0 -0.677749 -0.7352934 0 -0.6789593 -0.734176 0 -0.6800486 -0.7331671 0 -0.6811781 -0.7321178 0 -0.6822643 -0.7311057 0 -0.6845122 -0.7290014 0 -0.6867536 -0.7268903 0 -0.6889476 -0.7248112 0 -0.6901412 -0.7236748 0 -0.6912147 -0.7226495 0 -0.6922867 -0.7216225 0 -0.6934551 -0.7205 0 -0.6945238 -0.7194698 0 -0.6956111 -0.7184186 0 -0.6967543 -0.7173099 0 -0.7011367 -0.713027 0 -0.702194 -0.7119856 0 -0.7044205 -0.7097829 0 -0.7109044 -0.7032887 0 -0.7141437 -0.6999992 0 -0.7151811 -0.6989393 0 -0.7162944 -0.6977983 0 -0.7173094 -0.6967549 0 -0.7184192 -0.6956104 0 -0.7216234 -0.6922859 0 -0.7226486 -0.6912156 0 -0.7237128 -0.6901014 0 -0.7248122 -0.6889466 0 -0.7258139 -0.6878913 0 -0.7268914 -0.6867524 0 -0.7279673 -0.685612 0 -0.7289639 -0.6845523 0 -0.7310682 -0.6823044 0 -0.7321552 -0.6811379 0 -0.7332044 -0.6800084 0 -0.7341745 -0.6789609 0 -0.7352561 -0.6777893 0 -0.7363004 -0.6766549 0 -0.7373606 -0.6754994 0 -0.7394194 -0.6732451 0 -0.7414889 -0.6709653 0 -0.7425054 -0.6698402 0 -0.743555 -0.6686749 0 -0.7445255 -0.667594 0 -0.7455542 -0.666445 0 -0.7486472 -0.6629687 0 -0.7496689 -0.6618131 0 -0.7506889 -0.6606559 0 -0.752685 -0.6583808 0 -0.7546741 -0.6560999 0 -0.7567165 -0.6537433 0 -0.757724 -0.6525752 0 -0.7587298 -0.6514056 0 -0.7597336 -0.6502344 0 -0.7607195 -0.6490809 0 -0.7626799 -0.6467761 0 -0.7636604 -0.6456183 0 -0.7656705 -0.6432331 0 -0.7696145 -0.6385088 0 -0.7705984 -0.6373212 0 -0.7734915 -0.6338068 0 -0.7744522 -0.6326325 0 -0.7753957 -0.6314758 0 -0.7764444 -0.6301859 0 -0.7773843 -0.6290261 0 -0.7783531 -0.6278269 0 -0.7792894 -0.6266643 0 -0.780224 -0.6255003 0 -0.7821561 -0.6230827 0 -0.7850291 -0.6194591 0 -0.7878854 -0.615822 0 -0.7897872 -0.6133809 0 -0.7925865 -0.6097596 0 -0.7944549 -0.6073232 0 -0.7953605 -0.6061369 0 -0.7963247 -0.6048695 0 -0.7981638 -0.6024405 0 -0.7990618 -0.6012489 0 -0.8027333 -0.5963383 0 -0.8036825 -0.5950584 0 -0.8045556 -0.5938775 0 -0.8082283 -0.5888693 0 -0.8091191 -0.5876449 0 -0.8100281 -0.5863912 0 -0.8153581 -0.5789571 0 -0.8171639 -0.5764056 0 -0.8180089 -0.5752056 0 -0.8232567 -0.5676694 0 -0.8250147 -0.5651115 0 -0.8259025 -0.563813 0 -0.8276364 -0.5612648 0 -0.8284585 -0.5600507 0 -0.8327551 -0.5536416 0 -0.8378269 -0.5459359 0 -0.8411066 -0.5408695 0 -0.8419566 -0.5395454 0 -0.8469225 -0.5317163 0 -0.8493207 -0.5278773 0 -0.8501285 -0.5265753 0 -0.8533376 -0.5213589 0 -0.8541356 -0.5200505 0 -0.8549525 -0.5187064 0 -0.8565727 -0.5160264 0 -0.8612682 -0.5081506 0 -0.8666559 -0.4989066 0 -0.8674098 -0.4975944 0 -0.8681714 -0.4962645 0 -0.8689309 -0.4949334 0 -0.8719582 -0.4895803 0 -0.8727027 -0.4882519 0 -0.8749808 -0.4841576 0 -0.8757125 -0.4828329 0 -0.8778911 -0.4788603 0 -0.8793734 -0.4761329 0 -0.8800885 -0.4748099 0 -0.8815494 -0.472092 0 -0.8822584 -0.4707657 0 -0.8830254 -0.4693252 0 -0.8837345 -0.4679886 0 -0.8851702 -0.4652675 0 -0.8865932 -0.4625501 0 -0.8893826 -0.4571636 0 -0.8914822 -0.4530556 0 -0.8928598 -0.4503349 0 -0.8949241 -0.4462186 0 -0.895648 -0.444764 0 -0.8969963 -0.4420381 0 -0.8996912 -0.4365271 0 -0.9003423 -0.4351826 0 -0.9023219 -0.4310629 0 -0.9030178 -0.4296032 0 -0.9043091 -0.4268783 0 -0.9062471 -0.4227483 0 -0.9069298 -0.421282 0 -0.9081959 -0.4185456 0 -0.9088614 -0.4170982 0 -0.9101148 -0.4143561 0 -0.9114116 -0.4114962 0 -0.9120146 -0.4101579 0 -0.9132917 -0.4073063 0 -0.9138885 -0.4059655 0 -0.9151557 -0.4031006 0 -0.9157432 -0.4017645 0 -0.9163855 -0.4002969 0 -0.9181797 -0.3961644 0 -0.9194132 -0.3932932 0 -0.920036 -0.3918337 0 -0.9206039 -0.390498 0 -0.9212254 -0.3890296 0 -0.9230177 -0.3847575 0 -0.9235693 -0.3834314 0 -0.9241797 -0.3819583 0 -0.9253602 -0.3790889 0 -0.9259037 -0.3777597 0 -0.9265049 -0.3762828 0 -0.9270983 -0.3748183 0 -0.9276382 -0.3734799 0 -0.9282273 -0.3720136 0 -0.9293743 -0.3691385 0 -0.9310612 -0.364863 0 -0.9315815 -0.3635326 0 -0.9321574 -0.3620534 0 -0.9327234 -0.3605929 0 -0.9360143 -0.3519622 0 -0.9365136 -0.3506316 0 -0.9370641 -0.3491575 0 -0.9392113 -0.34334 0 -0.9402601 -0.3404574 0 -0.9412932 -0.3375902 0 -0.9428188 -0.3333058 0 -0.9438323 -0.3304249 0 -0.9443448 -0.3289577 0 -0.9453429 -0.3260781 0 -0.946857 -0.3216547 0 -0.9473578 -0.3201767 0 -0.9483233 -0.3173059 0 -0.9488173 -0.3158255 0 -0.949307 -0.3143504 0 -0.9502568 -0.3114678 0 -0.950736 -0.3100019 0 -0.952619 -0.3041666 0 -0.9530887 -0.3026912 0 -0.9549215 -0.2968587 0 -0.9562851 -0.2924362 0 -0.9589282 -0.2836491 0 -0.9593631 -0.2821748 0 -0.9602051 -0.2792957 0 -0.9606319 -0.2778245 0 -0.9610608 -0.2763373 0 -0.9614815 -0.27487 0 -0.9623423 -0.2718408 0 -0.9627576 -0.2703663 0 -0.963172 -0.2688862 0 -0.9635814 -0.2674154 0 -0.9639912 -0.265934 0 -0.9643975 -0.2644569 0 -0.9648016 -0.2629793 0 -0.9652019 -0.261506 0 -0.9656013 -0.2600271 0 -0.9663716 -0.2571499 0 -0.9683446 -0.2496171 0 -0.9690832 -0.2467343 0 -0.9698482 -0.2437103 0 -0.9709514 -0.2392772 0 -0.9720332 -0.2348437 0 -0.9731285 -0.2302628 0 -0.9734764 -0.2287881 0 -0.9748638 -0.2228016 0 -0.9762118 -0.2168194 0 -0.9771859 -0.2123861 0 -0.9775056 -0.2109094 0 -0.978483 -0.2063277 0 -0.9794074 -0.2018944 0 -0.9800269 -0.1988651 0 -0.9803251 -0.19739 0 -0.9812368 -0.1928066 0 -0.9818276 -0.1897754 0 -0.9826744 -0.1853406 0 -0.9832404 -0.1823139 0 -0.9835137 -0.1808341 0 -0.9846224 -0.1746968 0 -0.984883 -0.1732217 0 -0.9851415 -0.1717445 0 -0.9864265 -0.1642037 0 -0.986696 -0.1625761 0 -0.9869382 -0.1610994 0 -0.9874283 -0.1580678 0 -0.9879088 -0.1550362 0 -0.9883796 -0.152006 0 -0.9886057 -0.1505284 0 -0.9888294 -0.149052 0 -0.9892814 -0.146022 0 -0.9895207 -0.1443909 0 -0.9897353 -0.1429131 0 -0.9899474 -0.1414363 0 -0.9901574 -0.1399592 0 -0.9903864 -0.1383281 0 -0.9916138 -0.1292374 0 -0.9918054 -0.127758 0 -0.9931188 -0.1171123 0 -0.9934716 -0.1140808 0 -0.9939873 -0.1094964 0 -0.9952555 -0.0972957 0 -0.9956932 -0.09271025 0 -0.9961094 -0.08812552 0 -0.9965044 -0.08354067 0 -0.9968782 -0.07895565 0 -0.9972308 -0.07437044 0 -0.9975621 -0.06978553 0 -0.9976749 -0.06815397 0 -0.9978773 -0.06512308 0 -0.9979726 -0.06364607 0 -0.9981613 -0.0606153 0 -0.998259 -0.0589838 0 -0.9983451 -0.05750703 0 -0.9985151 -0.05447626 0 -0.9988312 -0.04833704 0 -0.9990425 -0.04375201 0 -0.9991126 -0.04212021 0 -0.9992358 -0.03908932 0 -0.9994571 -0.03295004 0 -0.9995047 -0.03147339 0 -0.9996384 -0.02688843 0 -0.9996811 -0.02525651 0 -0.9997864 -0.02067148 0 -0.9998945 -0.0145322 0 -0.9999767 -0.006838679 0 -0.9999929 -0.003807902 0 -0.9999974 -0.002331316 0 -0.9999976 0.002253651 0 -0.9999925 0.003885567 0 -0.9999761 0.006916344 0 -0.9998933 0.01460987 0 -0.9997847 0.02074915 0 -0.999679 0.02533417 0 -0.9996406 0.02681082 0 -0.9995071 0.03139579 0 -0.9994544 0.03302764 0 -0.9992328 0.03916692 0 -0.9991094 0.04219782 0 -0.9990459 0.0436744 0 -0.9988349 0.04825949 0 -0.9985194 0.05439877 0 -0.9983496 0.05742961 0 -0.9982544 0.05906122 0 -0.9981659 0.06053787 0 -0.9979775 0.06356871 0 -0.9978722 0.06520044 0 -0.9976696 0.06823134 0 -0.9975675 0.06970816 0 -0.9972366 0.07429319 0 -0.9968843 0.0788784 0 -0.9965109 0.08346349 0 -0.9961163 0.08804845 0 -0.9957003 0.09263318 0 -0.9952631 0.09721869 0 -0.9939957 0.1094197 0 -0.9934804 0.1140041 0 -0.9931278 0.1170357 0 -0.9918153 0.1276816 0 -0.9916038 0.1293138 0 -0.9903759 0.1384043 0 -0.990168 0.1398831 0 -0.9899582 0.1413601 0 -0.9897242 0.1429892 0 -0.9895097 0.144467 0 -0.9892926 0.1459459 0 -0.9888408 0.148976 0 -0.9886173 0.1504525 0 -0.988368 0.152082 0 -0.987897 0.155112 0 -0.9874162 0.1581435 0 -0.9869258 0.1611751 0 -0.9866836 0.1626517 0 -0.9864391 0.164128 0 -0.9851547 0.1716691 0 -0.9848697 0.1732971 0 -0.984609 0.1747722 0 -0.9835276 0.1807589 0 -0.9832543 0.1822388 0 -0.9826885 0.1852656 0 -0.9818131 0.1898503 0 -0.9812222 0.1928814 0 -0.9803401 0.1973153 0 -0.980042 0.1987905 0 -0.9794227 0.2018198 0 -0.9784673 0.2064021 0 -0.9775217 0.2108351 0 -0.977202 0.2123119 0 -0.9761953 0.2168934 0 -0.974847 0.2228754 0 -0.973459 0.2288617 0 -0.9731111 0.2303364 0 -0.972051 0.2347703 0 -0.9709694 0.2392039 0 -0.9698298 0.2437834 0 -0.9691018 0.2466614 0 -0.9683259 0.2496899 0 -0.9663909 0.2570773 0 -0.9655818 0.2600996 0 -0.9651823 0.2615784 0 -0.9647818 0.2630516 0 -0.9643778 0.2645292 0 -0.9639714 0.2660062 0 -0.9635614 0.2674875 0 -0.9631519 0.2689583 0 -0.9627374 0.2704384 0 -0.9623219 0.2719128 0 -0.961502 0.2747981 0 -0.9610815 0.2762655 0 -0.9606527 0.2777528 0 -0.960226 0.279224 0 -0.959342 0.2822462 0 -0.958907 0.2837205 0 -0.9562634 0.2925073 0 -0.9548994 0.2969295 0 -0.9530663 0.3027618 0 -0.9525964 0.3042371 0 -0.950713 0.3100721 0 -0.9502337 0.311538 0 -0.9492838 0.3144204 0 -0.9487941 0.3158956 0 -0.9483 0.3173757 0 -0.9473343 0.3202465 0 -0.9468334 0.3217244 0 -0.9453668 0.3260086 0 -0.9443689 0.3288884 0 -0.9438566 0.3303557 0 -0.9428433 0.3332368 0 -0.9412685 0.3376591 0 -0.9402351 0.3405261 0 -0.9391862 0.3434085 0 -0.9370896 0.3490893 0 -0.9365391 0.3505634 0 -0.9359886 0.3520302 0 -0.9326972 0.3606605 0 -0.9321836 0.3619859 0 -0.9316079 0.3634652 0 -0.9310348 0.3649303 0 -0.9293477 0.3692057 0 -0.9282004 0.3720806 0 -0.9276652 0.373413 0 -0.9270713 0.3748851 0 -0.9264779 0.3763495 0 -0.9259309 0.3776931 0 -0.925333 0.3791555 0 -0.9241522 0.3820246 0 -0.9235969 0.3833652 0 -0.9229902 0.3848237 0 -0.9211975 0.3890956 0 -0.9206318 0.3904321 0 -0.9200081 0.3918995 0 -0.9194412 0.3932275 0 -0.9182079 0.3960988 0 -0.916357 0.4003622 0 -0.9157717 0.4016993 0 -0.9151271 0.4031657 0 -0.9139174 0.4059005 0 -0.9132628 0.4073711 0 -0.9120437 0.4100933 0 -0.9113824 0.4115607 0 -0.9101441 0.4142918 0 -0.908832 0.4171624 0 -0.9082254 0.4184815 0 -0.9069001 0.4213459 0 -0.906277 0.4226844 0 -0.9043391 0.4268148 0 -0.9029877 0.4296666 0 -0.9023522 0.4309996 0 -0.9003728 0.4351196 0 -0.8996606 0.43659 0 -0.8969655 0.4421007 0 -0.8956169 0.4448263 0 -0.894955 0.4461564 0 -0.892891 0.4502729 0 -0.8915137 0.4529939 0 -0.8894143 0.4571022 0 -0.8865614 0.4626112 0 -0.8851382 0.4653285 0 -0.8837024 0.4680493 0 -0.8829933 0.4693859 0 -0.8822906 0.4707052 0 -0.8815817 0.4720317 0 -0.880121 0.4747497 0 -0.8794059 0.4760729 0 -0.8779238 0.4788004 0 -0.8756797 0.4828925 0 -0.874948 0.4842171 0 -0.8727359 0.4881927 0 -0.8719915 0.4895213 0 -0.8689644 0.4948747 0 -0.8682049 0.4962059 0 -0.8674435 0.497536 0 -0.8666895 0.4988482 0 -0.8612342 0.5082082 0 -0.8565384 0.5160834 0 -0.854987 0.5186496 0 -0.8541701 0.5199939 0 -0.8533722 0.5213023 0 -0.8501633 0.5265192 0 -0.8493555 0.5278213 0 -0.8468877 0.5317721 0 -0.8419919 0.5394903 0 -0.8411419 0.5408146 0 -0.8377915 0.5459904 0 -0.8327192 0.5536955 0 -0.8284945 0.5599973 0 -0.8276003 0.561318 0 -0.8258664 0.563866 0 -0.8250509 0.5650586 0 -0.823293 0.5676168 0 -0.8180455 0.5751537 0 -0.8171273 0.5764575 0 -0.8153948 0.5789054 0 -0.8099912 0.5864422 0 -0.8090821 0.5876957 0 -0.8081914 0.5889201 0 -0.8045927 0.5938271 0 -0.8036453 0.5951086 0 -0.8027704 0.5962883 0 -0.7990993 0.6011993 0 -0.7981264 0.60249 0 -0.7962872 0.6049187 0 -0.7953978 0.6060877 0 -0.7944175 0.6073723 0 -0.7925489 0.6098084 0 -0.7897496 0.6134294 0 -0.7878477 0.6158702 0 -0.7850668 0.6194112 0 -0.7821939 0.6230351 0 -0.780262 0.625453 0 -0.7793273 0.6266171 0 -0.7783151 0.627874 0 -0.7773463 0.629073 0 -0.7764063 0.6302327 0 -0.7754337 0.631429 0 -0.7744903 0.6325859 0 -0.7735296 0.6337603 0 -0.7705602 0.6373673 0 -0.7695763 0.6385549 0 -0.7656322 0.6432787 0 -0.7636988 0.6455729 0 -0.7627182 0.646731 0 -0.760681 0.6491259 0 -0.7596953 0.6502793 0 -0.7586914 0.6514503 0 -0.7576856 0.6526198 0 -0.756678 0.6537878 0 -0.7547126 0.6560556 0 -0.7526465 0.6584249 0 -0.7506504 0.6606997 0 -0.7496303 0.6618568 0 -0.7486086 0.6630123 0 -0.7455929 0.6664018 0 -0.7445641 0.667551 0 -0.7435163 0.6687179 0 -0.7424666 0.669883 0 -0.7414502 0.6710079 0 -0.7393807 0.6732876 0 -0.7373219 0.6755416 0 -0.7362616 0.676697 0 -0.7352949 0.6777474 0 -0.7342132 0.678919 0 -0.7331656 0.6800501 0 -0.7321165 0.6811795 0 -0.731107 0.6822629 0 -0.7290026 0.684511 0 -0.7279285 0.6856531 0 -0.7268526 0.6867935 0 -0.7258527 0.6878503 0 -0.7247734 0.6889874 0 -0.7236739 0.6901421 0 -0.7226874 0.691175 0 -0.7215845 0.6923264 0 -0.7183804 0.6956505 0 -0.7173482 0.6967149 0 -0.7162555 0.6978381 0 -0.7152199 0.6988996 0 -0.7141049 0.7000388 0 -0.7108656 0.703328 0 -0.7043817 0.7098215 0 -0.7022329 0.7119473 0 -0.7010979 0.7130652 0 -0.6967155 0.7173476 0 -0.6956499 0.718381 0 -0.694485 0.7195073 0 -0.6934162 0.7205374 0 -0.6923255 0.7215853 0 -0.6911759 0.7226866 0 -0.6901023 0.7237119 0 -0.6889864 0.7247744 0 -0.6867924 0.7268537 0 -0.684551 0.7289651 0 -0.6823031 0.7310695 0 -0.6811394 0.7321538 0 -0.6800099 0.733203 0 -0.6789205 0.7342118 0 -0.6777877 0.7352577 0 -0.6766954 0.7362632 0 -0.6744039 0.7383627 0 -0.6732857 0.7393825 0 -0.6710059 0.741452 0 -0.668677 0.7435531 0 -0.6630098 0.7486108 0 -0.6618543 0.7496326 0 -0.6606971 0.7506526 0 -0.6595603 0.7516517 0 -0.6584221 0.752649 0 -0.6572383 0.753683 0 -0.6560969 0.7546766 0 -0.6549099 0.7557071 0 -0.6490842 0.7607166 0 -0.6479327 0.7616977 0 -0.6467344 0.7627154 0 -0.643275 0.7656352 0 -0.6397027 0.7686223 0 -0.6350178 0.7724975 0 -0.6338026 0.7734948 0 -0.6206592 0.7840805 0 -0.619454 0.7850329 0 -0.6170456 0.7869274 0 -0.6146075 0.7888331 0 -0.6122391 0.7906728 0 -0.6097652 0.7925821 0 -0.6049128 0.7962917 0 -0.6036617 0.7972406 0 -0.602484 0.798131 0 -0.6012054 0.7990946 0 -0.6000249 0.7999814 0 -0.5951021 0.8036502 0 -0.5901569 0.8072886 0 -0.5889132 0.8081964 0 -0.5864351 0.8099963 0 -0.5777263 0.8162307 0 -0.5751979 0.8180144 0 -0.5701875 0.8215146 0 -0.5688948 0.8224104 0 -0.5663738 0.8241485 0 -0.5651032 0.8250204 0 -0.5638576 0.825872 0 -0.5625842 0.8267401 0 -0.5613095 0.827606 0 -0.5575307 0.8301565 0 -0.5536865 0.8327252 0 -0.5498306 0.8352763 0 -0.5485699 0.8361048 0 -0.5446715 0.8386495 0 -0.5433512 0.8395056 0 -0.5408244 0.8411356 0 -0.5395002 0.8419856 0 -0.5382023 0.8428158 0 -0.5369459 0.8436168 0 -0.5356732 0.8444254 0 -0.5343438 0.8452673 0 -0.5304739 0.8477013 0 -0.5291395 0.8485349 0 -0.5278319 0.8493489 0 -0.5265646 0.8501351 0 -0.52395 0.8517491 0 -0.51743 0.8557257 0 -0.5121396 0.8589023 0 -0.5107883 0.8597065 0 -0.5095041 0.8604682 0 -0.5068299 0.8620461 0 -0.505542 0.862802 0 -0.5028609 0.8643674 0 -0.5015692 0.8651176 0 -0.5002259 0.865895 0 -0.4988858 0.8666679 0 -0.4975736 0.8674219 0 -0.4962269 0.868193 0 -0.4949124 0.868943 0 -0.4935674 0.8697076 0 -0.4922173 0.8704724 0 -0.4908995 0.8712164 0 -0.4882141 0.872724 0 -0.4868631 0.8734783 0 -0.4788385 0.8779031 0 -0.4774794 0.878643 0 -0.4747716 0.8801091 0 -0.4734416 0.8808253 0 -0.4707274 0.8822788 0 -0.4693635 0.883005 0 -0.4680269 0.8837142 0 -0.4653059 0.8851499 0 -0.4612243 0.8872836 0 -0.4584925 0.8886983 0 -0.4557881 0.8900884 0 -0.4530169 0.8915019 0 -0.4516688 0.8921858 0 -0.4475555 0.8942562 0 -0.4448028 0.8956286 0 -0.4434173 0.8963153 0 -0.4420617 0.8969846 0 -0.4407051 0.897652 0 -0.4393161 0.8983327 0 -0.4365509 0.8996796 0 -0.4351587 0.9003538 0 -0.4337969 0.9010106 0 -0.4310238 0.9023407 0 -0.4296274 0.9030063 0 -0.4240784 0.9056255 0 -0.4227089 0.9062656 0 -0.4213066 0.9069184 0 -0.417123 0.9088501 0 -0.4157487 0.9094795 0 -0.4115211 0.9114002 0 -0.4073459 0.913274 0 -0.3988938 0.9169973 0 -0.3975039 0.9176005 0 -0.394707 0.918807 0 -0.3932533 0.9194303 0 -0.3918597 0.9200251 0 -0.3890556 0.9212143 0 -0.3847975 0.9230011 0 -0.3819846 0.9241688 0 -0.3791291 0.9253439 0 -0.3763093 0.9264942 0 -0.3720538 0.9282112 0 -0.3706134 0.9287872 0 -0.3648901 0.9310507 0 -0.3635055 0.9315922 0 -0.3620262 0.932168 0 -0.3534346 0.9354593 0 -0.3506039 0.9365239 0 -0.3491171 0.9370792 0 -0.3448049 0.9386744 0 -0.3419302 0.9397253 0 -0.340498 0.9402453 0 -0.3390648 0.9407631 0 -0.3376309 0.9412787 0 -0.3347138 0.9423199 0 -0.3332774 0.9428288 0 -0.328929 0.9443547 0 -0.3274896 0.9448549 0 -0.3260493 0.9453528 0 -0.317335 0.9483136 0 -0.3158547 0.9488075 0 -0.3100313 0.9507264 0 -0.3086054 0.9511902 0 -0.3071208 0.9516705 0 -0.3041962 0.9526095 0 -0.3027321 0.9530758 0 -0.298348 0.9544572 0 -0.2924771 0.9562725 0 -0.2865957 0.9580517 0 -0.2851227 0.958491 0 -0.2777835 0.9606438 0 -0.2763065 0.9610697 0 -0.2748289 0.9614932 0 -0.2718819 0.9623307 0 -0.2644981 0.9643862 0 -0.2600682 0.9655903 0 -0.2571088 0.9663825 0 -0.2526338 0.967562 0 -0.2496559 0.9683346 0 -0.2482089 0.9687066 0 -0.2451815 0.9694772 0 -0.2407524 0.9705866 0 -0.2392383 0.9709609 0 -0.2377969 0.971315 0 -0.2302974 0.9731203 0 -0.2273107 0.9738223 0 -0.2243586 0.9745067 0 -0.2183701 0.9758661 0 -0.2108702 0.9775141 0 -0.2093539 0.97784 0 -0.2048471 0.978794 0 -0.201859 0.9794147 0 -0.2003399 0.9797266 0 -0.1958321 0.9806375 0 -0.1943561 0.9809311 0 -0.1928421 0.9812299 0 -0.1882975 0.9821121 0 -0.1777296 0.9840794 0 -0.1762552 0.9843445 0 -0.1747362 0.9846154 0 -0.1732611 0.984876 0 -0.1687136 0.9856652 0 -0.1671614 0.9859296 0 -0.1626155 0.9866896 0 -0.1581041 0.9874225 0 -0.156593 0.9876633 0 -0.1550756 0.9879027 0 -0.1535578 0.9881398 0 -0.1520455 0.9883735 0 -0.150489 0.9886118 0 -0.1474977 0.9890625 0 -0.1429497 0.98973 0 -0.1413968 0.989953 0 -0.1399198 0.9901629 0 -0.136853 0.9905914 0 -0.1322655 0.9912143 0 -0.1292769 0.9916086 0 -0.127721 0.9918102 0 -0.1262032 0.9920045 0 -0.1247293 0.9921909 0 -0.1201434 0.9927566 0 -0.1170746 0.9931232 0 -0.114043 0.9934759 0 -0.1063887 0.9943246 0 -0.1049113 0.9944816 0 -0.1033568 0.9946444 0 -0.101804 0.9948046 0 -0.09725767 0.9952592 0 -0.08960205 0.9959778 0 -0.08808743 0.9961128 0 -0.08198583 0.9966335 0 -0.0789166 0.9968813 0 -0.07281678 0.9973453 0 -0.06667697 0.9977747 0 -0.06360709 0.9979751 0 -0.06209248 0.9980705 0 -0.05902266 0.9982568 0 -0.05595284 0.9984334 0 -0.04981356 0.9987586 0 -0.04678261 0.9989051 0 -0.04522871 0.9989767 0 -0.04371309 0.9990442 0 -0.04064339 0.9991738 0 -0.03298896 0.9994558 0 -0.0299192 0.9995524 0 -0.02836495 0.9995977 0 -0.02377992 0.9997172 0 -0.02222579 0.9997531 0 -0.01764065 0.9998445 0 -0.01608639 0.9998706 0 -0.01457101 0.9998939 0 -0.01305562 0.9999148 0 -0.008470654 0.9999642 0 -0.006877541 0.9999763 0 -0.005362153 0.9999857 0 0.04275882 0 0.9990855 -0.04275882 0 0.9990855 -0.004029154 0 0.9999919 0.004029154 0 0.9999919 -6.71925e-4 0 0.9999998 6.72088e-4 0 0.9999998 6.71925e-4 0 0.9999998 -6.72088e-4 0 0.9999998 -3.97512e-6 0 1 3.97512e-6 0 1 -0.002292513 0.9999974 0 -0.01611483 0 -0.9998702 0.01611483 0 -0.9998702 -0.002688229 0 -0.9999964 0.002688229 0 -0.9999964 0.001343786 0 -0.9999991 -0.001343786 0 -0.9999991 1.68022e-4 0 -1 -1.68022e-4 0 -1 -4.2053e-5 0 -1 4.2104e-5 0 -1 -4.20532e-5 0 -1 4.2053e-5 0 -1 -4.2104e-5 0 -1 4.20532e-5 0 -1 + + + + + + + + + + 1 1 0.9997559 0.5 1 0.5 0.9997559 1 0.9995117 0.5 0.9997559 0.5 0.9995117 1 0.9992676 0.5 0.9995117 0.5 0.9992676 1 0.9990234 0.5 0.9992676 0.5 0.9990234 1 0.9987793 0.5 0.9990234 0.5 0.9987793 1 0.9985352 0.5 0.9987793 0.5 0.9985352 1 0.998291 0.5 0.9985352 0.5 0.998291 1 0.9980469 0.5 0.998291 0.5 0.9980469 1 0.9978027 0.5 0.9980469 0.5 0.9978027 1 0.9975586 0.5 0.9978027 0.5 0.9975586 1 0.9973145 0.5 0.9975586 0.5 0.9973145 1 0.9970703 0.5 0.9973145 0.5 0.9970703 1 0.9968262 0.5 0.9970703 0.5 0.9968262 1 0.996582 0.5 0.9968262 0.5 0.996582 1 0.9963379 0.5 0.996582 0.5 0.9963379 1 0.9960938 0.5 0.9963379 0.5 0.9960938 1 0.9958496 0.5 0.9960938 0.5 0.9958496 1 0.9956055 0.5 0.9958496 0.5 0.9956055 1 0.9953613 0.5 0.9956055 0.5 0.9953613 1 0.9951172 0.5 0.9953613 0.5 0.9951172 1 0.9948731 0.5 0.9951172 0.5 0.9948731 1 0.9946289 0.5 0.9948731 0.5 0.9946289 1 0.9943848 0.5 0.9946289 0.5 0.9943848 1 0.9941406 0.5 0.9943848 0.5 0.9941406 1 0.9938965 0.5 0.9941406 0.5 0.9938965 1 0.9936524 0.5 0.9938965 0.5 0.9936524 1 0.9934082 0.5 0.9936524 0.5 0.9934082 1 0.9931641 0.5 0.9934082 0.5 0.9931641 1 0.9929199 0.5 0.9931641 0.5 0.9929199 1 0.9926758 0.5 0.9929199 0.5 0.9926758 1 0.9924317 0.5 0.9926758 0.5 0.9924317 1 0.9921875 0.5 0.9924317 0.5 0.9921875 1 0.9919434 0.5 0.9921875 0.5 0.9919434 1 0.9916992 0.5 0.9919434 0.5 0.9916992 1 0.9914551 0.5 0.9916992 0.5 0.9914551 1 0.9912109 0.5 0.9914551 0.5 0.9912109 1 0.9909668 0.5 0.9912109 0.5 0.9909668 1 0.9907227 0.5 0.9909668 0.5 0.9907227 1 0.9904785 0.5 0.9907227 0.5 0.9904785 1 0.9902344 0.5 0.9904785 0.5 0.9902344 1 0.9899902 0.5 0.9902344 0.5 0.9899902 1 0.9897461 0.5 0.9899902 0.5 0.9897461 1 0.989502 0.5 0.9897461 0.5 0.989502 1 0.9892578 0.5 0.989502 0.5 0.9892578 1 0.9890137 0.5 0.9892578 0.5 0.9890137 1 0.9887695 0.5 0.9890137 0.5 0.9887695 1 0.9885254 0.5 0.9887695 0.5 0.9885254 1 0.9882813 0.5 0.9885254 0.5 0.9882813 1 0.9880371 0.5 0.9882813 0.5 0.9880371 1 0.987793 0.5 0.9880371 0.5 0.987793 1 0.9875488 0.5 0.987793 0.5 0.9875488 1 0.9873047 0.5 0.9875488 0.5 0.9873047 1 0.9870606 0.5 0.9873047 0.5 0.9870606 1 0.9868164 0.5 0.9870606 0.5 0.9868164 1 0.9865723 0.5 0.9868164 0.5 0.9865723 1 0.9863281 0.5 0.9865723 0.5 0.9863281 1 0.986084 0.5 0.9863281 0.5 0.986084 1 0.9858399 0.5 0.986084 0.5 0.9858399 1 0.9855957 0.5 0.9858399 0.5 0.9855957 1 0.9853516 0.5 0.9855957 0.5 0.9853516 1 0.9851074 0.5 0.9853516 0.5 0.9851074 1 0.9848633 0.5 0.9851074 0.5 0.9848633 1 0.9846192 0.5 0.9848633 0.5 0.9846192 1 0.984375 0.5 0.9846192 0.5 0.984375 1 0.9841309 0.5 0.984375 0.5 0.9841309 1 0.9838867 0.5 0.9841309 0.5 0.9838867 1 0.9836426 0.5 0.9838867 0.5 0.9836426 1 0.9833984 0.5 0.9836426 0.5 0.9833984 1 0.9831543 0.5 0.9833984 0.5 0.9831543 1 0.9829102 0.5 0.9831543 0.5 0.9829102 1 0.982666 0.5 0.9829102 0.5 0.982666 1 0.9824219 0.5 0.982666 0.5 0.9824219 1 0.9821777 0.5 0.9824219 0.5 0.9821777 1 0.9819336 0.5 0.9821777 0.5 0.9819336 1 0.9816895 0.5 0.9819336 0.5 0.9816895 1 0.9814453 0.5 0.9816895 0.5 0.9814453 1 0.9812012 0.5 0.9814453 0.5 0.9812012 1 0.980957 0.5 0.9812012 0.5 0.980957 1 0.9807129 0.5 0.980957 0.5 0.9807129 1 0.9804688 0.5 0.9807129 0.5 0.9804688 1 0.9802246 0.5 0.9804688 0.5 0.9802246 1 0.9799805 0.5 0.9802246 0.5 0.9799805 1 0.9797363 0.5 0.9799805 0.5 0.9797363 1 0.9794922 0.5 0.9797363 0.5 0.9794922 1 0.9792481 0.5 0.9794922 0.5 0.9792481 1 0.9790039 0.5 0.9792481 0.5 0.9790039 1 0.9787598 0.5 0.9790039 0.5 0.9787598 1 0.9785156 0.5 0.9787598 0.5 0.9785156 1 0.9782715 0.5 0.9785156 0.5 0.9782715 1 0.9780274 0.5 0.9782715 0.5 0.9780274 1 0.9777832 0.5 0.9780274 0.5 0.9777832 1 0.9775391 0.5 0.9777832 0.5 0.9775391 1 0.9772949 0.5 0.9775391 0.5 0.9772949 1 0.9770508 0.5 0.9772949 0.5 0.9770508 1 0.9768067 0.5 0.9770508 0.5 0.9768067 1 0.9765625 0.5 0.9768067 0.5 0.9765625 1 0.9763184 0.5 0.9765625 0.5 0.9763184 1 0.9760742 0.5 0.9763184 0.5 0.9760742 1 0.9758301 0.5 0.9760742 0.5 0.9758301 1 0.9755859 0.5 0.9758301 0.5 0.9755859 1 0.9753418 0.5 0.9755859 0.5 0.9753418 1 0.9750977 0.5 0.9753418 0.5 0.9750977 1 0.9748535 0.5 0.9750977 0.5 0.9748535 1 0.9746094 0.5 0.9748535 0.5 0.9746094 1 0.9743652 0.5 0.9746094 0.5 0.9743652 1 0.9741211 0.5 0.9743652 0.5 0.9741211 1 0.973877 0.5 0.9741211 0.5 0.973877 1 0.9736328 0.5 0.973877 0.5 0.9736328 1 0.9733887 0.5 0.9736328 0.5 0.9733887 1 0.9731445 0.5 0.9733887 0.5 0.9731445 1 0.9729004 0.5 0.9731445 0.5 0.9729004 1 0.9726563 0.5 0.9729004 0.5 0.9726563 1 0.9724121 0.5 0.9726563 0.5 0.9724121 1 0.972168 0.5 0.9724121 0.5 0.972168 1 0.9719238 0.5 0.972168 0.5 0.9719238 1 0.9716797 0.5 0.9719238 0.5 0.9716797 1 0.9714356 0.5 0.9716797 0.5 0.9714356 1 0.9711914 0.5 0.9714356 0.5 0.9711914 1 0.9709473 0.5 0.9711914 0.5 0.9709473 1 0.9707031 0.5 0.9709473 0.5 0.9707031 1 0.970459 0.5 0.9707031 0.5 0.970459 1 0.9702149 0.5 0.970459 0.5 0.9702149 1 0.9699707 0.5 0.9702149 0.5 0.9699707 1 0.9697266 0.5 0.9699707 0.5 0.9697266 1 0.9694824 0.5 0.9697266 0.5 0.9694824 1 0.9692383 0.5 0.9694824 0.5 0.9692383 1 0.9689942 0.5 0.9692383 0.5 0.9689942 1 0.96875 0.5 0.9689942 0.5 0.96875 1 0.9685059 0.5 0.96875 0.5 0.9685059 1 0.9682617 0.5 0.9685059 0.5 0.9682617 1 0.9680176 0.5 0.9682617 0.5 0.9680176 1 0.9677734 0.5 0.9680176 0.5 0.9677734 1 0.9675293 0.5 0.9677734 0.5 0.9675293 1 0.9672852 0.5 0.9675293 0.5 0.9672852 1 0.967041 0.5 0.9672852 0.5 0.967041 1 0.9667969 0.5 0.967041 0.5 0.9667969 1 0.9665527 0.5 0.9667969 0.5 0.9665527 1 0.9663086 0.5 0.9665527 0.5 0.9663086 1 0.9660645 0.5 0.9663086 0.5 0.9660645 1 0.9658203 0.5 0.9660645 0.5 0.9658203 1 0.9655762 0.5 0.9658203 0.5 0.9655762 1 0.965332 0.5 0.9655762 0.5 0.965332 1 0.9650879 0.5 0.965332 0.5 0.9650879 1 0.9648438 0.5 0.9650879 0.5 0.9648438 1 0.9645996 0.5 0.9648438 0.5 0.9645996 1 0.9643555 0.5 0.9645996 0.5 0.9643555 1 0.9641113 0.5 0.9643555 0.5 0.9641113 1 0.9638672 0.5 0.9641113 0.5 0.9638672 1 0.9636231 0.5 0.9638672 0.5 0.9636231 1 0.9633789 0.5 0.9636231 0.5 0.9633789 1 0.9631348 0.5 0.9633789 0.5 0.9631348 1 0.9628906 0.5 0.9631348 0.5 0.9628906 1 0.9626465 0.5 0.9628906 0.5 0.9626465 1 0.9624024 0.5 0.9626465 0.5 0.9624024 1 0.9621582 0.5 0.9624024 0.5 0.9621582 1 0.9619141 0.5 0.9621582 0.5 0.9619141 1 0.9616699 0.5 0.9619141 0.5 0.9616699 1 0.9614258 0.5 0.9616699 0.5 0.9614258 1 0.9611817 0.5 0.9614258 0.5 0.9611817 1 0.9609375 0.5 0.9611817 0.5 0.9609375 1 0.9606934 0.5 0.9609375 0.5 0.9606934 1 0.9604492 0.5 0.9606934 0.5 0.9604492 1 0.9602051 0.5 0.9604492 0.5 0.9602051 1 0.9599609 0.5 0.9602051 0.5 0.9599609 1 0.9597168 0.5 0.9599609 0.5 0.9597168 1 0.9594727 0.5 0.9597168 0.5 0.9594727 1 0.9592285 0.5 0.9594727 0.5 0.9592285 1 0.9589844 0.5 0.9592285 0.5 0.9589844 1 0.9587402 0.5 0.9589844 0.5 0.9587402 1 0.9584961 0.5 0.9587402 0.5 0.9584961 1 0.958252 0.5 0.9584961 0.5 0.958252 1 0.9580078 0.5 0.958252 0.5 0.9580078 1 0.9577637 0.5 0.9580078 0.5 0.9577637 1 0.9575195 0.5 0.9577637 0.5 0.9575195 1 0.9572754 0.5 0.9575195 0.5 0.9572754 1 0.9570313 0.5 0.9572754 0.5 0.9570313 1 0.9567871 0.5 0.9570313 0.5 0.9567871 1 0.956543 0.5 0.9567871 0.5 0.956543 1 0.9562988 0.5 0.956543 0.5 0.9562988 1 0.9560547 0.5 0.9562988 0.5 0.9560547 1 0.9558106 0.5 0.9560547 0.5 0.9558106 1 0.9555664 0.5 0.9558106 0.5 0.9555664 1 0.9553223 0.5 0.9555664 0.5 0.9553223 1 0.9550781 0.5 0.9553223 0.5 0.9550781 1 0.954834 0.5 0.9550781 0.5 0.954834 1 0.9545899 0.5 0.954834 0.5 0.9545899 1 0.9543457 0.5 0.9545899 0.5 0.9543457 1 0.9541016 0.5 0.9543457 0.5 0.9541016 1 0.9538574 0.5 0.9541016 0.5 0.9538574 1 0.9536133 0.5 0.9538574 0.5 0.9536133 1 0.9533692 0.5 0.9536133 0.5 0.9533692 1 0.953125 0.5 0.9533692 0.5 0.953125 1 0.9528809 0.5 0.953125 0.5 0.9528809 1 0.9526367 0.5 0.9528809 0.5 0.9526367 1 0.9523926 0.5 0.9526367 0.5 0.9523926 1 0.9521484 0.5 0.9523926 0.5 0.9521484 1 0.9519043 0.5 0.9521484 0.5 0.9519043 1 0.9516602 0.5 0.9519043 0.5 0.9516602 1 0.951416 0.5 0.9516602 0.5 0.951416 1 0.9511719 0.5 0.951416 0.5 0.9511719 1 0.9509277 0.5 0.9511719 0.5 0.9509277 1 0.9506836 0.5 0.9509277 0.5 0.9506836 1 0.9504395 0.5 0.9506836 0.5 0.9504395 1 0.9501953 0.5 0.9504395 0.5 0.9501953 1 0.9499512 0.5 0.9501953 0.5 0.9499512 1 0.949707 0.5 0.9499512 0.5 0.949707 1 0.9494629 0.5 0.949707 0.5 0.9494629 1 0.9492188 0.5 0.9494629 0.5 0.9492188 1 0.9489746 0.5 0.9492188 0.5 0.9489746 1 0.9487305 0.5 0.9489746 0.5 0.9487305 1 0.9484863 0.5 0.9487305 0.5 0.9484863 1 0.9482422 0.5 0.9484863 0.5 0.9482422 1 0.9479981 0.5 0.9482422 0.5 0.9479981 1 0.9477539 0.5 0.9479981 0.5 0.9477539 1 0.9475098 0.5 0.9477539 0.5 0.9475098 1 0.9472656 0.5 0.9475098 0.5 0.9472656 1 0.9470215 0.5 0.9472656 0.5 0.9470215 1 0.9467774 0.5 0.9470215 0.5 0.9467774 1 0.9465332 0.5 0.9467774 0.5 0.9465332 1 0.9462891 0.5 0.9465332 0.5 0.9462891 1 0.9460449 0.5 0.9462891 0.5 0.9460449 1 0.9458008 0.5 0.9460449 0.5 0.9458008 1 0.9455567 0.5 0.9458008 0.5 0.9455567 1 0.9453125 0.5 0.9455567 0.5 0.9453125 1 0.9450684 0.5 0.9453125 0.5 0.9450684 1 0.9448242 0.5 0.9450684 0.5 0.9448242 1 0.9445801 0.5 0.9448242 0.5 0.9445801 1 0.9443359 0.5 0.9445801 0.5 0.9443359 1 0.9440918 0.5 0.9443359 0.5 0.9440918 1 0.9438477 0.5 0.9440918 0.5 0.9438477 1 0.9436035 0.5 0.9438477 0.5 0.9436035 1 0.9433594 0.5 0.9436035 0.5 0.9433594 1 0.9431152 0.5 0.9433594 0.5 0.9431152 1 0.9428711 0.5 0.9431152 0.5 0.9428711 1 0.942627 0.5 0.9428711 0.5 0.942627 1 0.9423828 0.5 0.942627 0.5 0.9423828 1 0.9421387 0.5 0.9423828 0.5 0.9421387 1 0.9418945 0.5 0.9421387 0.5 0.9418945 1 0.9416504 0.5 0.9418945 0.5 0.9416504 1 0.9414063 0.5 0.9416504 0.5 0.9414063 1 0.9411621 0.5 0.9414063 0.5 0.9411621 1 0.940918 0.5 0.9411621 0.5 0.940918 1 0.9406738 0.5 0.940918 0.5 0.9406738 1 0.9404297 0.5 0.9406738 0.5 0.9404297 1 0.9401856 0.5 0.9404297 0.5 0.9401856 1 0.9399414 0.5 0.9401856 0.5 0.9399414 1 0.9396973 0.5 0.9399414 0.5 0.9396973 1 0.9394531 0.5 0.9396973 0.5 0.9394531 1 0.939209 0.5 0.9394531 0.5 0.939209 1 0.9389649 0.5 0.939209 0.5 0.9389649 1 0.9387207 0.5 0.9389649 0.5 0.9387207 1 0.9384766 0.5 0.9387207 0.5 0.9384766 1 0.9382324 0.5 0.9384766 0.5 0.9382324 1 0.9379883 0.5 0.9382324 0.5 0.9379883 1 0.9377442 0.5 0.9379883 0.5 0.9377442 1 0.9375 0.5 0.9377442 0.5 0.9375 1 0.9372559 0.5 0.9375 0.5 0.9372559 1 0.9370117 0.5 0.9372559 0.5 0.9370117 1 0.9367676 0.5 0.9370117 0.5 0.9367676 1 0.9365234 0.5 0.9367676 0.5 0.9365234 1 0.9362793 0.5 0.9365234 0.5 0.9362793 1 0.9360352 0.5 0.9362793 0.5 0.9360352 1 0.935791 0.5 0.9360352 0.5 0.935791 1 0.9355469 0.5 0.935791 0.5 0.9355469 1 0.9353027 0.5 0.9355469 0.5 0.9353027 1 0.9350586 0.5 0.9353027 0.5 0.9350586 1 0.9348145 0.5 0.9350586 0.5 0.9348145 1 0.9345703 0.5 0.9348145 0.5 0.9345703 1 0.9343262 0.5 0.9345703 0.5 0.9343262 1 0.934082 0.5 0.9343262 0.5 0.934082 1 0.9338379 0.5 0.934082 0.5 0.9338379 1 0.9335938 0.5 0.9338379 0.5 0.9335938 1 0.9333496 0.5 0.9335938 0.5 0.9333496 1 0.9331055 0.5 0.9333496 0.5 0.9331055 1 0.9328613 0.5 0.9331055 0.5 0.9328613 1 0.9326172 0.5 0.9328613 0.5 0.9326172 1 0.9323731 0.5 0.9326172 0.5 0.9323731 1 0.9321289 0.5 0.9323731 0.5 0.9321289 1 0.9318848 0.5 0.9321289 0.5 0.9318848 1 0.9316406 0.5 0.9318848 0.5 0.9316406 1 0.9313965 0.5 0.9316406 0.5 0.9313965 1 0.9311524 0.5 0.9313965 0.5 0.9311524 1 0.9309082 0.5 0.9311524 0.5 0.9309082 1 0.9306641 0.5 0.9309082 0.5 0.9306641 1 0.9304199 0.5 0.9306641 0.5 0.9304199 1 0.9301758 0.5 0.9304199 0.5 0.9301758 1 0.9299317 0.5 0.9301758 0.5 0.9299317 1 0.9296875 0.5 0.9299317 0.5 0.9296875 1 0.9294434 0.5 0.9296875 0.5 0.9294434 1 0.9291992 0.5 0.9294434 0.5 0.9291992 1 0.9289551 0.5 0.9291992 0.5 0.9289551 1 0.9287109 0.5 0.9289551 0.5 0.9287109 1 0.9284668 0.5 0.9287109 0.5 0.9284668 1 0.9282227 0.5 0.9284668 0.5 0.9282227 1 0.9279785 0.5 0.9282227 0.5 0.9279785 1 0.9277344 0.5 0.9279785 0.5 0.9277344 1 0.9274902 0.5 0.9277344 0.5 0.9274902 1 0.9272461 0.5 0.9274902 0.5 0.9272461 1 0.927002 0.5 0.9272461 0.5 0.927002 1 0.9267578 0.5 0.927002 0.5 0.9267578 1 0.9265137 0.5 0.9267578 0.5 0.9265137 1 0.9262695 0.5 0.9265137 0.5 0.9262695 1 0.9260254 0.5 0.9262695 0.5 0.9260254 1 0.9257813 0.5 0.9260254 0.5 0.9257813 1 0.9255371 0.5 0.9257813 0.5 0.9255371 1 0.925293 0.5 0.9255371 0.5 0.925293 1 0.9250488 0.5 0.925293 0.5 0.9250488 1 0.9248047 0.5 0.9250488 0.5 0.9248047 1 0.9245606 0.5 0.9248047 0.5 0.9245606 1 0.9243164 0.5 0.9245606 0.5 0.9243164 1 0.9240723 0.5 0.9243164 0.5 0.9240723 1 0.9238281 0.5 0.9240723 0.5 0.9238281 1 0.923584 0.5 0.9238281 0.5 0.923584 1 0.9233399 0.5 0.923584 0.5 0.9233399 1 0.9230957 0.5 0.9233399 0.5 0.9230957 1 0.9228516 0.5 0.9230957 0.5 0.9228516 1 0.9226074 0.5 0.9228516 0.5 0.9226074 1 0.9223633 0.5 0.9226074 0.5 0.9223633 1 0.9221192 0.5 0.9223633 0.5 0.9221192 1 0.921875 0.5 0.9221192 0.5 0.921875 1 0.9216309 0.5 0.921875 0.5 0.9216309 1 0.9213867 0.5 0.9216309 0.5 0.9213867 1 0.9211426 0.5 0.9213867 0.5 0.9211426 1 0.9208984 0.5 0.9211426 0.5 0.9208984 1 0.9206543 0.5 0.9208984 0.5 0.9206543 1 0.9204102 0.5 0.9206543 0.5 0.9204102 1 0.920166 0.5 0.9204102 0.5 0.920166 1 0.9199219 0.5 0.920166 0.5 0.9199219 1 0.9196777 0.5 0.9199219 0.5 0.9196777 1 0.9194336 0.5 0.9196777 0.5 0.9194336 1 0.9191895 0.5 0.9194336 0.5 0.9191895 1 0.9189453 0.5 0.9191895 0.5 0.9189453 1 0.9187012 0.5 0.9189453 0.5 0.9187012 1 0.918457 0.5 0.9187012 0.5 0.918457 1 0.9182129 0.5 0.918457 0.5 0.9182129 1 0.9179688 0.5 0.9182129 0.5 0.9179688 1 0.9177246 0.5 0.9179688 0.5 0.9177246 1 0.9174805 0.5 0.9177246 0.5 0.9174805 1 0.9172363 0.5 0.9174805 0.5 0.9172363 1 0.9169922 0.5 0.9172363 0.5 0.9169922 1 0.9167481 0.5 0.9169922 0.5 0.9167481 1 0.9165039 0.5 0.9167481 0.5 0.9165039 1 0.9162598 0.5 0.9165039 0.5 0.9162598 1 0.9160156 0.5 0.9162598 0.5 0.9160156 1 0.9157715 0.5 0.9160156 0.5 0.9157715 1 0.9155274 0.5 0.9157715 0.5 0.9155274 1 0.9152832 0.5 0.9155274 0.5 0.9152832 1 0.9150391 0.5 0.9152832 0.5 0.9150391 1 0.9147949 0.5 0.9150391 0.5 0.9147949 1 0.9145508 0.5 0.9147949 0.5 0.9145508 1 0.9143067 0.5 0.9145508 0.5 0.9143067 1 0.9140625 0.5 0.9143067 0.5 0.9140625 1 0.9138184 0.5 0.9140625 0.5 0.9138184 1 0.9135742 0.5 0.9138184 0.5 0.9135742 1 0.9133301 0.5 0.9135742 0.5 0.9133301 1 0.9130859 0.5 0.9133301 0.5 0.9130859 1 0.9128418 0.5 0.9130859 0.5 0.9128418 1 0.9125977 0.5 0.9128418 0.5 0.9125977 1 0.9123535 0.5 0.9125977 0.5 0.9123535 1 0.9121094 0.5 0.9123535 0.5 0.9121094 1 0.9118652 0.5 0.9121094 0.5 0.9118652 1 0.9116211 0.5 0.9118652 0.5 0.9116211 1 0.911377 0.5 0.9116211 0.5 0.911377 1 0.9111328 0.5 0.911377 0.5 0.9111328 1 0.9108887 0.5 0.9111328 0.5 0.9108887 1 0.9106445 0.5 0.9108887 0.5 0.9106445 1 0.9104004 0.5 0.9106445 0.5 0.9104004 1 0.9101563 0.5 0.9104004 0.5 0.9101563 1 0.9099121 0.5 0.9101563 0.5 0.9099121 1 0.909668 0.5 0.9099121 0.5 0.909668 1 0.9094238 0.5 0.909668 0.5 0.9094238 1 0.9091797 0.5 0.9094238 0.5 0.9091797 1 0.9089356 0.5 0.9091797 0.5 0.9089356 1 0.9086914 0.5 0.9089356 0.5 0.9086914 1 0.9084473 0.5 0.9086914 0.5 0.9084473 1 0.9082031 0.5 0.9084473 0.5 0.9082031 1 0.907959 0.5 0.9082031 0.5 0.907959 1 0.9077149 0.5 0.907959 0.5 0.9077149 1 0.9074707 0.5 0.9077149 0.5 0.9074707 1 0.9072266 0.5 0.9074707 0.5 0.9072266 1 0.9069824 0.5 0.9072266 0.5 0.9069824 1 0.9067383 0.5 0.9069824 0.5 0.9067383 1 0.9064942 0.5 0.9067383 0.5 0.9064942 1 0.90625 0.5 0.9064942 0.5 0.90625 1 0.9060059 0.5 0.90625 0.5 0.9060059 1 0.9057617 0.5 0.9060059 0.5 0.9057617 1 0.9055176 0.5 0.9057617 0.5 0.9055176 1 0.9052734 0.5 0.9055176 0.5 0.9052734 1 0.9050293 0.5 0.9052734 0.5 0.9050293 1 0.9047852 0.5 0.9050293 0.5 0.9047852 1 0.904541 0.5 0.9047852 0.5 0.904541 1 0.9042969 0.5 0.904541 0.5 0.9042969 1 0.9040527 0.5 0.9042969 0.5 0.9040527 1 0.9038086 0.5 0.9040527 0.5 0.9038086 1 0.9035645 0.5 0.9038086 0.5 0.9035645 1 0.9033203 0.5 0.9035645 0.5 0.9033203 1 0.9030762 0.5 0.9033203 0.5 0.9030762 1 0.902832 0.5 0.9030762 0.5 0.902832 1 0.9025879 0.5 0.902832 0.5 0.9025879 1 0.9023438 0.5 0.9025879 0.5 0.9023438 1 0.9020996 0.5 0.9023438 0.5 0.9020996 1 0.9018555 0.5 0.9020996 0.5 0.9018555 1 0.9016113 0.5 0.9018555 0.5 0.9016113 1 0.9013672 0.5 0.9016113 0.5 0.9013672 1 0.9011231 0.5 0.9013672 0.5 0.9011231 1 0.9008789 0.5 0.9011231 0.5 0.9008789 1 0.9006348 0.5 0.9008789 0.5 0.9006348 1 0.9003906 0.5 0.9006348 0.5 0.9003906 1 0.9001465 0.5 0.9003906 0.5 0.9001465 1 0.8999024 0.5 0.9001465 0.5 0.8999024 1 0.8996582 0.5 0.8999024 0.5 0.8996582 1 0.8994141 0.5 0.8996582 0.5 0.8994141 1 0.8991699 0.5 0.8994141 0.5 0.8991699 1 0.8989258 0.5 0.8991699 0.5 0.8989258 1 0.8986817 0.5 0.8989258 0.5 0.8986817 1 0.8984375 0.5 0.8986817 0.5 0.8984375 1 0.8981934 0.5 0.8984375 0.5 0.8981934 1 0.8979492 0.5 0.8981934 0.5 0.8979492 1 0.8977051 0.5 0.8979492 0.5 0.8977051 1 0.8974609 0.5 0.8977051 0.5 0.8974609 1 0.8972168 0.5 0.8974609 0.5 0.8972168 1 0.8969727 0.5 0.8972168 0.5 0.8969727 1 0.8967285 0.5 0.8969727 0.5 0.8967285 1 0.8964844 0.5 0.8967285 0.5 0.8964844 1 0.8962402 0.5 0.8964844 0.5 0.8962402 1 0.8959961 0.5 0.8962402 0.5 0.8959961 1 0.895752 0.5 0.8959961 0.5 0.895752 1 0.8955078 0.5 0.895752 0.5 0.8955078 1 0.8952637 0.5 0.8955078 0.5 0.8952637 1 0.8950195 0.5 0.8952637 0.5 0.8950195 1 0.8947754 0.5 0.8950195 0.5 0.8947754 1 0.8945313 0.5 0.8947754 0.5 0.8945313 1 0.8942871 0.5 0.8945313 0.5 0.8942871 1 0.894043 0.5 0.8942871 0.5 0.894043 1 0.8937988 0.5 0.894043 0.5 0.8937988 1 0.8935547 0.5 0.8937988 0.5 0.8935547 1 0.8933106 0.5 0.8935547 0.5 0.8933106 1 0.8930664 0.5 0.8933106 0.5 0.8930664 1 0.8928223 0.5 0.8930664 0.5 0.8928223 1 0.8925781 0.5 0.8928223 0.5 0.8925781 1 0.892334 0.5 0.8925781 0.5 0.892334 1 0.8920899 0.5 0.892334 0.5 0.8920899 1 0.8918457 0.5 0.8920899 0.5 0.8918457 1 0.8916016 0.5 0.8918457 0.5 0.8916016 1 0.8913574 0.5 0.8916016 0.5 0.8913574 1 0.8911133 0.5 0.8913574 0.5 0.8911133 1 0.8908692 0.5 0.8911133 0.5 0.8908692 1 0.890625 0.5 0.8908692 0.5 0.890625 1 0.8903809 0.5 0.890625 0.5 0.8903809 1 0.8901367 0.5 0.8903809 0.5 0.8901367 1 0.8898926 0.5 0.8901367 0.5 0.8898926 1 0.8896484 0.5 0.8898926 0.5 0.8896484 1 0.8894043 0.5 0.8896484 0.5 0.8894043 1 0.8891602 0.5 0.8894043 0.5 0.8891602 1 0.888916 0.5 0.8891602 0.5 0.888916 1 0.8886719 0.5 0.888916 0.5 0.8886719 1 0.8884277 0.5 0.8886719 0.5 0.8884277 1 0.8881836 0.5 0.8884277 0.5 0.8881836 1 0.8879395 0.5 0.8881836 0.5 0.8879395 1 0.8876953 0.5 0.8879395 0.5 0.8876953 1 0.8874512 0.5 0.8876953 0.5 0.8874512 1 0.887207 0.5 0.8874512 0.5 0.887207 1 0.8869629 0.5 0.887207 0.5 0.8869629 1 0.8867188 0.5 0.8869629 0.5 0.8867188 1 0.8864746 0.5 0.8867188 0.5 0.8864746 1 0.8862305 0.5 0.8864746 0.5 0.8862305 1 0.8859863 0.5 0.8862305 0.5 0.8859863 1 0.8857422 0.5 0.8859863 0.5 0.8857422 1 0.8854981 0.5 0.8857422 0.5 0.8854981 1 0.8852539 0.5 0.8854981 0.5 0.8852539 1 0.8850098 0.5 0.8852539 0.5 0.8850098 1 0.8847656 0.5 0.8850098 0.5 0.8847656 1 0.8845215 0.5 0.8847656 0.5 0.8845215 1 0.8842774 0.5 0.8845215 0.5 0.8842774 1 0.8840332 0.5 0.8842774 0.5 0.8840332 1 0.8837891 0.5 0.8840332 0.5 0.8837891 1 0.8835449 0.5 0.8837891 0.5 0.8835449 1 0.8833008 0.5 0.8835449 0.5 0.8833008 1 0.8830567 0.5 0.8833008 0.5 0.8830567 1 0.8828125 0.5 0.8830567 0.5 0.8828125 1 0.8825684 0.5 0.8828125 0.5 0.8825684 1 0.8823242 0.5 0.8825684 0.5 0.8823242 1 0.8820801 0.5 0.8823242 0.5 0.8820801 1 0.8818359 0.5 0.8820801 0.5 0.8818359 1 0.8815918 0.5 0.8818359 0.5 0.8815918 1 0.8813477 0.5 0.8815918 0.5 0.8813477 1 0.8811035 0.5 0.8813477 0.5 0.8811035 1 0.8808594 0.5 0.8811035 0.5 0.8808594 1 0.8806152 0.5 0.8808594 0.5 0.8806152 1 0.8803711 0.5 0.8806152 0.5 0.8803711 1 0.880127 0.5 0.8803711 0.5 0.880127 1 0.8798828 0.5 0.880127 0.5 0.8798828 1 0.8796387 0.5 0.8798828 0.5 0.8796387 1 0.8793945 0.5 0.8796387 0.5 0.8793945 1 0.8791504 0.5 0.8793945 0.5 0.8791504 1 0.8789063 0.5 0.8791504 0.5 0.8789063 1 0.8786621 0.5 0.8789063 0.5 0.8786621 1 0.878418 0.5 0.8786621 0.5 0.878418 1 0.8781738 0.5 0.878418 0.5 0.8781738 1 0.8779297 0.5 0.8781738 0.5 0.8779297 1 0.8776856 0.5 0.8779297 0.5 0.8776856 1 0.8774414 0.5 0.8776856 0.5 0.8774414 1 0.8771973 0.5 0.8774414 0.5 0.8771973 1 0.8769531 0.5 0.8771973 0.5 0.8769531 1 0.876709 0.5 0.8769531 0.5 0.876709 1 0.8764649 0.5 0.876709 0.5 0.8764649 1 0.8762207 0.5 0.8764649 0.5 0.8762207 1 0.8759766 0.5 0.8762207 0.5 0.8759766 1 0.8757324 0.5 0.8759766 0.5 0.8757324 1 0.8754883 0.5 0.8757324 0.5 0.8754883 1 0.8752442 0.5 0.8754883 0.5 0.8752442 1 0.875 0.5 0.8752442 0.5 0.875 1 0.8747559 0.5 0.875 0.5 0.8747559 1 0.8745117 0.5 0.8747559 0.5 0.8745117 1 0.8742676 0.5 0.8745117 0.5 0.8742676 1 0.8740234 0.5 0.8742676 0.5 0.8740234 1 0.8737793 0.5 0.8740234 0.5 0.8737793 1 0.8735352 0.5 0.8737793 0.5 0.8735352 1 0.873291 0.5 0.8735352 0.5 0.873291 1 0.8730469 0.5 0.873291 0.5 0.8730469 1 0.8728027 0.5 0.8730469 0.5 0.8728027 1 0.8725586 0.5 0.8728027 0.5 0.8725586 1 0.8723145 0.5 0.8725586 0.5 0.8723145 1 0.8720703 0.5 0.8723145 0.5 0.8720703 1 0.8718262 0.5 0.8720703 0.5 0.8718262 1 0.871582 0.5 0.8718262 0.5 0.871582 1 0.8713379 0.5 0.871582 0.5 0.8713379 1 0.8710938 0.5 0.8713379 0.5 0.8710938 1 0.8708496 0.5 0.8710938 0.5 0.8708496 1 0.8706055 0.5 0.8708496 0.5 0.8706055 1 0.8703613 0.5 0.8706055 0.5 0.8703613 1 0.8701172 0.5 0.8703613 0.5 0.8701172 1 0.8698731 0.5 0.8701172 0.5 0.8698731 1 0.8696289 0.5 0.8698731 0.5 0.8696289 1 0.8693848 0.5 0.8696289 0.5 0.8693848 1 0.8691406 0.5 0.8693848 0.5 0.8691406 1 0.8688965 0.5 0.8691406 0.5 0.8688965 1 0.8686524 0.5 0.8688965 0.5 0.8686524 1 0.8684082 0.5 0.8686524 0.5 0.8684082 1 0.8681641 0.5 0.8684082 0.5 0.8681641 1 0.8679199 0.5 0.8681641 0.5 0.8679199 1 0.8676758 0.5 0.8679199 0.5 0.8676758 1 0.8674317 0.5 0.8676758 0.5 0.8674317 1 0.8671875 0.5 0.8674317 0.5 0.8671875 1 0.8669434 0.5 0.8671875 0.5 0.8669434 1 0.8666992 0.5 0.8669434 0.5 0.8666992 1 0.8664551 0.5 0.8666992 0.5 0.8664551 1 0.8662109 0.5 0.8664551 0.5 0.8662109 1 0.8659668 0.5 0.8662109 0.5 0.8659668 1 0.8657227 0.5 0.8659668 0.5 0.8657227 1 0.8654785 0.5 0.8657227 0.5 0.8654785 1 0.8652344 0.5 0.8654785 0.5 0.8652344 1 0.8649902 0.5 0.8652344 0.5 0.8649902 1 0.8647461 0.5 0.8649902 0.5 0.8647461 1 0.864502 0.5 0.8647461 0.5 0.864502 1 0.8642578 0.5 0.864502 0.5 0.8642578 1 0.8640137 0.5 0.8642578 0.5 0.8640137 1 0.8637695 0.5 0.8640137 0.5 0.8637695 1 0.8635254 0.5 0.8637695 0.5 0.8635254 1 0.8632813 0.5 0.8635254 0.5 0.8632813 1 0.8630371 0.5 0.8632813 0.5 0.8630371 1 0.862793 0.5 0.8630371 0.5 0.862793 1 0.8625488 0.5 0.862793 0.5 0.8625488 1 0.8623047 0.5 0.8625488 0.5 0.8623047 1 0.8620606 0.5 0.8623047 0.5 0.8620606 1 0.8618164 0.5 0.8620606 0.5 0.8618164 1 0.8615723 0.5 0.8618164 0.5 0.8615723 1 0.8613281 0.5 0.8615723 0.5 0.8613281 1 0.861084 0.5 0.8613281 0.5 0.861084 1 0.8608399 0.5 0.861084 0.5 0.8608399 1 0.8605957 0.5 0.8608399 0.5 0.8605957 1 0.8603516 0.5 0.8605957 0.5 0.8603516 1 0.8601074 0.5 0.8603516 0.5 0.8601074 1 0.8598633 0.5 0.8601074 0.5 0.8598633 1 0.8596192 0.5 0.8598633 0.5 0.8596192 1 0.859375 0.5 0.8596192 0.5 0.859375 1 0.8591309 0.5 0.859375 0.5 0.8591309 1 0.8588867 0.5 0.8591309 0.5 0.8588867 1 0.8586426 0.5 0.8588867 0.5 0.8586426 1 0.8583984 0.5 0.8586426 0.5 0.8583984 1 0.8581543 0.5 0.8583984 0.5 0.8581543 1 0.8579102 0.5 0.8581543 0.5 0.8579102 1 0.857666 0.5 0.8579102 0.5 0.857666 1 0.8574219 0.5 0.857666 0.5 0.8574219 1 0.8571777 0.5 0.8574219 0.5 0.8571777 1 0.8569336 0.5 0.8571777 0.5 0.8569336 1 0.8566895 0.5 0.8569336 0.5 0.8566895 1 0.8564453 0.5 0.8566895 0.5 0.8564453 1 0.8562012 0.5 0.8564453 0.5 0.8562012 1 0.855957 0.5 0.8562012 0.5 0.855957 1 0.8557129 0.5 0.855957 0.5 0.8557129 1 0.8554688 0.5 0.8557129 0.5 0.8554688 1 0.8552246 0.5 0.8554688 0.5 0.8552246 1 0.8549805 0.5 0.8552246 0.5 0.8549805 1 0.8547363 0.5 0.8549805 0.5 0.8547363 1 0.8544922 0.5 0.8547363 0.5 0.8544922 1 0.8542481 0.5 0.8544922 0.5 0.8542481 1 0.8540039 0.5 0.8542481 0.5 0.8540039 1 0.8537598 0.5 0.8540039 0.5 0.8537598 1 0.8535156 0.5 0.8537598 0.5 0.8535156 1 0.8532715 0.5 0.8535156 0.5 0.8532715 1 0.8530274 0.5 0.8532715 0.5 0.8530274 1 0.8527832 0.5 0.8530274 0.5 0.8527832 1 0.8525391 0.5 0.8527832 0.5 0.8525391 1 0.8522949 0.5 0.8525391 0.5 0.8522949 1 0.8520508 0.5 0.8522949 0.5 0.8520508 1 0.8518067 0.5 0.8520508 0.5 0.8518067 1 0.8515625 0.5 0.8518067 0.5 0.8515625 1 0.8513184 0.5 0.8515625 0.5 0.8513184 1 0.8510742 0.5 0.8513184 0.5 0.8510742 1 0.8508301 0.5 0.8510742 0.5 0.8508301 1 0.8505859 0.5 0.8508301 0.5 0.8505859 1 0.8503418 0.5 0.8505859 0.5 0.8503418 1 0.8500977 0.5 0.8503418 0.5 0.8500977 1 0.8498535 0.5 0.8500977 0.5 0.8498535 1 0.8496094 0.5 0.8498535 0.5 0.8496094 1 0.8493652 0.5 0.8496094 0.5 0.8493652 1 0.8491211 0.5 0.8493652 0.5 0.8491211 1 0.848877 0.5 0.8491211 0.5 0.848877 1 0.8486328 0.5 0.848877 0.5 0.8486328 1 0.8483887 0.5 0.8486328 0.5 0.8483887 1 0.8481445 0.5 0.8483887 0.5 0.8481445 1 0.8479004 0.5 0.8481445 0.5 0.8479004 1 0.8476563 0.5 0.8479004 0.5 0.8476563 1 0.8474121 0.5 0.8476563 0.5 0.8474121 1 0.847168 0.5 0.8474121 0.5 0.847168 1 0.8469238 0.5 0.847168 0.5 0.8469238 1 0.8466797 0.5 0.8469238 0.5 0.8466797 1 0.8464356 0.5 0.8466797 0.5 0.8464356 1 0.8461914 0.5 0.8464356 0.5 0.8461914 1 0.8459473 0.5 0.8461914 0.5 0.8459473 1 0.8457031 0.5 0.8459473 0.5 0.8457031 1 0.845459 0.5 0.8457031 0.5 0.845459 1 0.8452149 0.5 0.845459 0.5 0.8452149 1 0.8449707 0.5 0.8452149 0.5 0.8449707 1 0.8447266 0.5 0.8449707 0.5 0.8447266 1 0.8444824 0.5 0.8447266 0.5 0.8444824 1 0.8442383 0.5 0.8444824 0.5 0.8442383 1 0.8439942 0.5 0.8442383 0.5 0.8439942 1 0.84375 0.5 0.8439942 0.5 0.84375 1 0.8435059 0.5 0.84375 0.5 0.8435059 1 0.8432617 0.5 0.8435059 0.5 0.8432617 1 0.8430176 0.5 0.8432617 0.5 0.8430176 1 0.8427734 0.5 0.8430176 0.5 0.8427734 1 0.8425293 0.5 0.8427734 0.5 0.8425293 1 0.8422852 0.5 0.8425293 0.5 0.8422852 1 0.842041 0.5 0.8422852 0.5 0.842041 1 0.8417969 0.5 0.842041 0.5 0.8417969 1 0.8415527 0.5 0.8417969 0.5 0.8415527 1 0.8413086 0.5 0.8415527 0.5 0.8413086 1 0.8410645 0.5 0.8413086 0.5 0.8410645 1 0.8408203 0.5 0.8410645 0.5 0.8408203 1 0.8405762 0.5 0.8408203 0.5 0.8405762 1 0.840332 0.5 0.8405762 0.5 0.840332 1 0.8400879 0.5 0.840332 0.5 0.8400879 1 0.8398438 0.5 0.8400879 0.5 0.8398438 1 0.8395996 0.5 0.8398438 0.5 0.8395996 1 0.8393555 0.5 0.8395996 0.5 0.8393555 1 0.8391113 0.5 0.8393555 0.5 0.8391113 1 0.8388672 0.5 0.8391113 0.5 0.8388672 1 0.8386231 0.5 0.8388672 0.5 0.8386231 1 0.8383789 0.5 0.8386231 0.5 0.8383789 1 0.8381348 0.5 0.8383789 0.5 0.8381348 1 0.8378906 0.5 0.8381348 0.5 0.8378906 1 0.8376465 0.5 0.8378906 0.5 0.8376465 1 0.8374024 0.5 0.8376465 0.5 0.8374024 1 0.8371582 0.5 0.8374024 0.5 0.8371582 1 0.8369141 0.5 0.8371582 0.5 0.8369141 1 0.8366699 0.5 0.8369141 0.5 0.8366699 1 0.8364258 0.5 0.8366699 0.5 0.8364258 1 0.8361817 0.5 0.8364258 0.5 0.8361817 1 0.8359375 0.5 0.8361817 0.5 0.8359375 1 0.8356934 0.5 0.8359375 0.5 0.8356934 1 0.8354492 0.5 0.8356934 0.5 0.8354492 1 0.8352051 0.5 0.8354492 0.5 0.8352051 1 0.8349609 0.5 0.8352051 0.5 0.8349609 1 0.8347168 0.5 0.8349609 0.5 0.8347168 1 0.8344727 0.5 0.8347168 0.5 0.8344727 1 0.8342285 0.5 0.8344727 0.5 0.8342285 1 0.8339844 0.5 0.8342285 0.5 0.8339844 1 0.8337402 0.5 0.8339844 0.5 0.8337402 1 0.8334961 0.5 0.8337402 0.5 0.8334961 1 0.833252 0.5 0.8334961 0.5 0.833252 1 0.8330078 0.5 0.833252 0.5 0.8330078 1 0.8327637 0.5 0.8330078 0.5 0.8327637 1 0.8325195 0.5 0.8327637 0.5 0.8325195 1 0.8322754 0.5 0.8325195 0.5 0.8322754 1 0.8320313 0.5 0.8322754 0.5 0.8320313 1 0.8317871 0.5 0.8320313 0.5 0.8317871 1 0.831543 0.5 0.8317871 0.5 0.831543 1 0.8312988 0.5 0.831543 0.5 0.8312988 1 0.8310547 0.5 0.8312988 0.5 0.8310547 1 0.8308106 0.5 0.8310547 0.5 0.8308106 1 0.8305664 0.5 0.8308106 0.5 0.8305664 1 0.8303223 0.5 0.8305664 0.5 0.8303223 1 0.8300781 0.5 0.8303223 0.5 0.8300781 1 0.829834 0.5 0.8300781 0.5 0.829834 1 0.8295899 0.5 0.829834 0.5 0.8295899 1 0.8293457 0.5 0.8295899 0.5 0.8293457 1 0.8291016 0.5 0.8293457 0.5 0.8291016 1 0.8288574 0.5 0.8291016 0.5 0.8288574 1 0.8286133 0.5 0.8288574 0.5 0.8286133 1 0.8283692 0.5 0.8286133 0.5 0.8283692 1 0.828125 0.5 0.8283692 0.5 0.828125 1 0.8278809 0.5 0.828125 0.5 0.8278809 1 0.8276367 0.5 0.8278809 0.5 0.8276367 1 0.8273926 0.5 0.8276367 0.5 0.8273926 1 0.8271484 0.5 0.8273926 0.5 0.8271484 1 0.8269043 0.5 0.8271484 0.5 0.8269043 1 0.8266602 0.5 0.8269043 0.5 0.8266602 1 0.826416 0.5 0.8266602 0.5 0.826416 1 0.8261719 0.5 0.826416 0.5 0.8261719 1 0.8259277 0.5 0.8261719 0.5 0.8259277 1 0.8256836 0.5 0.8259277 0.5 0.8256836 1 0.8254395 0.5 0.8256836 0.5 0.8254395 1 0.8251953 0.5 0.8254395 0.5 0.8251953 1 0.8249512 0.5 0.8251953 0.5 0.8249512 1 0.824707 0.5 0.8249512 0.5 0.824707 1 0.8244629 0.5 0.824707 0.5 0.8244629 1 0.8242188 0.5 0.8244629 0.5 0.8242188 1 0.8239746 0.5 0.8242188 0.5 0.8239746 1 0.8237305 0.5 0.8239746 0.5 0.8237305 1 0.8234863 0.5 0.8237305 0.5 0.8234863 1 0.8232422 0.5 0.8234863 0.5 0.8232422 1 0.8229981 0.5 0.8232422 0.5 0.8229981 1 0.8227539 0.5 0.8229981 0.5 0.8227539 1 0.8225098 0.5 0.8227539 0.5 0.8225098 1 0.8222656 0.5 0.8225098 0.5 0.8222656 1 0.8220215 0.5 0.8222656 0.5 0.8220215 1 0.8217774 0.5 0.8220215 0.5 0.8217774 1 0.8215332 0.5 0.8217774 0.5 0.8215332 1 0.8212891 0.5 0.8215332 0.5 0.8212891 1 0.8210449 0.5 0.8212891 0.5 0.8210449 1 0.8208008 0.5 0.8210449 0.5 0.8208008 1 0.8205567 0.5 0.8208008 0.5 0.8205567 1 0.8203125 0.5 0.8205567 0.5 0.8203125 1 0.8200684 0.5 0.8203125 0.5 0.8200684 1 0.8198242 0.5 0.8200684 0.5 0.8198242 1 0.8195801 0.5 0.8198242 0.5 0.8195801 1 0.8193359 0.5 0.8195801 0.5 0.8193359 1 0.8190918 0.5 0.8193359 0.5 0.8190918 1 0.8188477 0.5 0.8190918 0.5 0.8188477 1 0.8186035 0.5 0.8188477 0.5 0.8186035 1 0.8183594 0.5 0.8186035 0.5 0.8183594 1 0.8181152 0.5 0.8183594 0.5 0.8181152 1 0.8178711 0.5 0.8181152 0.5 0.8178711 1 0.817627 0.5 0.8178711 0.5 0.817627 1 0.8173828 0.5 0.817627 0.5 0.8173828 1 0.8171387 0.5 0.8173828 0.5 0.8171387 1 0.8168945 0.5 0.8171387 0.5 0.8168945 1 0.8166504 0.5 0.8168945 0.5 0.8166504 1 0.8164063 0.5 0.8166504 0.5 0.8164063 1 0.8161621 0.5 0.8164063 0.5 0.8161621 1 0.815918 0.5 0.8161621 0.5 0.815918 1 0.8156738 0.5 0.815918 0.5 0.8156738 1 0.8154297 0.5 0.8156738 0.5 0.8154297 1 0.8151856 0.5 0.8154297 0.5 0.8151856 1 0.8149414 0.5 0.8151856 0.5 0.8149414 1 0.8146973 0.5 0.8149414 0.5 0.8146973 1 0.8144531 0.5 0.8146973 0.5 0.8144531 1 0.814209 0.5 0.8144531 0.5 0.814209 1 0.8139649 0.5 0.814209 0.5 0.8139649 1 0.8137207 0.5 0.8139649 0.5 0.8137207 1 0.8134766 0.5 0.8137207 0.5 0.8134766 1 0.8132324 0.5 0.8134766 0.5 0.8132324 1 0.8129883 0.5 0.8132324 0.5 0.8129883 1 0.8127442 0.5 0.8129883 0.5 0.8127442 1 0.8125 0.5 0.8127442 0.5 0.8125 1 0.8122559 0.5 0.8125 0.5 0.8122559 1 0.8120117 0.5 0.8122559 0.5 0.8120117 1 0.8117676 0.5 0.8120117 0.5 0.8117676 1 0.8115234 0.5 0.8117676 0.5 0.8115234 1 0.8112793 0.5 0.8115234 0.5 0.8112793 1 0.8110352 0.5 0.8112793 0.5 0.8110352 1 0.810791 0.5 0.8110352 0.5 0.810791 1 0.8105469 0.5 0.810791 0.5 0.8105469 1 0.8103027 0.5 0.8105469 0.5 0.8103027 1 0.8100586 0.5 0.8103027 0.5 0.8100586 1 0.8098145 0.5 0.8100586 0.5 0.8098145 1 0.8095703 0.5 0.8098145 0.5 0.8095703 1 0.8093262 0.5 0.8095703 0.5 0.8093262 1 0.809082 0.5 0.8093262 0.5 0.809082 1 0.8088379 0.5 0.809082 0.5 0.8088379 1 0.8085938 0.5 0.8088379 0.5 0.8085938 1 0.8083496 0.5 0.8085938 0.5 0.8083496 1 0.8081055 0.5 0.8083496 0.5 0.8081055 1 0.8078613 0.5 0.8081055 0.5 0.8078613 1 0.8076172 0.5 0.8078613 0.5 0.8076172 1 0.8073731 0.5 0.8076172 0.5 0.8073731 1 0.8071289 0.5 0.8073731 0.5 0.8071289 1 0.8068848 0.5 0.8071289 0.5 0.8068848 1 0.8066406 0.5 0.8068848 0.5 0.8066406 1 0.8063965 0.5 0.8066406 0.5 0.8063965 1 0.8061524 0.5 0.8063965 0.5 0.8061524 1 0.8059082 0.5 0.8061524 0.5 0.8059082 1 0.8056641 0.5 0.8059082 0.5 0.8056641 1 0.8054199 0.5 0.8056641 0.5 0.8054199 1 0.8051758 0.5 0.8054199 0.5 0.8051758 1 0.8049317 0.5 0.8051758 0.5 0.8049317 1 0.8046875 0.5 0.8049317 0.5 0.8046875 1 0.8044434 0.5 0.8046875 0.5 0.8044434 1 0.8041992 0.5 0.8044434 0.5 0.8041992 1 0.8039551 0.5 0.8041992 0.5 0.8039551 1 0.8037109 0.5 0.8039551 0.5 0.8037109 1 0.8034668 0.5 0.8037109 0.5 0.8034668 1 0.8032227 0.5 0.8034668 0.5 0.8032227 1 0.8029785 0.5 0.8032227 0.5 0.8029785 1 0.8027344 0.5 0.8029785 0.5 0.8027344 1 0.8024902 0.5 0.8027344 0.5 0.8024902 1 0.8022461 0.5 0.8024902 0.5 0.8022461 1 0.802002 0.5 0.8022461 0.5 0.802002 1 0.8017578 0.5 0.802002 0.5 0.8017578 1 0.8015137 0.5 0.8017578 0.5 0.8015137 1 0.8012695 0.5 0.8015137 0.5 0.8012695 1 0.8010254 0.5 0.8012695 0.5 0.8010254 1 0.8007813 0.5 0.8010254 0.5 0.8007813 1 0.8005371 0.5 0.8007813 0.5 0.8005371 1 0.800293 0.5 0.8005371 0.5 0.800293 1 0.8000488 0.5 0.800293 0.5 0.8000488 1 0.7998047 0.5 0.8000488 0.5 0.7998047 1 0.7995606 0.5 0.7998047 0.5 0.7995606 1 0.7993164 0.5 0.7995606 0.5 0.7993164 1 0.7990723 0.5 0.7993164 0.5 0.7990723 1 0.7988281 0.5 0.7990723 0.5 0.7988281 1 0.798584 0.5 0.7988281 0.5 0.798584 1 0.7983399 0.5 0.798584 0.5 0.7983399 1 0.7980957 0.5 0.7983399 0.5 0.7980957 1 0.7978516 0.5 0.7980957 0.5 0.7978516 1 0.7976074 0.5 0.7978516 0.5 0.7976074 1 0.7973633 0.5 0.7976074 0.5 0.7973633 1 0.7971192 0.5 0.7973633 0.5 0.7971192 1 0.796875 0.5 0.7971192 0.5 0.796875 1 0.7966309 0.5 0.796875 0.5 0.7966309 1 0.7963867 0.5 0.7966309 0.5 0.7963867 1 0.7961426 0.5 0.7963867 0.5 0.7961426 1 0.7958984 0.5 0.7961426 0.5 0.7958984 1 0.7956543 0.5 0.7958984 0.5 0.7956543 1 0.7954102 0.5 0.7956543 0.5 0.7954102 1 0.795166 0.5 0.7954102 0.5 0.795166 1 0.7949219 0.5 0.795166 0.5 0.7949219 1 0.7946777 0.5 0.7949219 0.5 0.7946777 1 0.7944336 0.5 0.7946777 0.5 0.7944336 1 0.7941895 0.5 0.7944336 0.5 0.7941895 1 0.7939453 0.5 0.7941895 0.5 0.7939453 1 0.7937012 0.5 0.7939453 0.5 0.7937012 1 0.793457 0.5 0.7937012 0.5 0.793457 1 0.7932129 0.5 0.793457 0.5 0.7932129 1 0.7929688 0.5 0.7932129 0.5 0.7929688 1 0.7927246 0.5 0.7929688 0.5 0.7927246 1 0.7924805 0.5 0.7927246 0.5 0.7924805 1 0.7922363 0.5 0.7924805 0.5 0.7922363 1 0.7919922 0.5 0.7922363 0.5 0.7919922 1 0.7917481 0.5 0.7919922 0.5 0.7917481 1 0.7915039 0.5 0.7917481 0.5 0.7915039 1 0.7912598 0.5 0.7915039 0.5 0.7912598 1 0.7910156 0.5 0.7912598 0.5 0.7910156 1 0.7907715 0.5 0.7910156 0.5 0.7907715 1 0.7905274 0.5 0.7907715 0.5 0.7905274 1 0.7902832 0.5 0.7905274 0.5 0.7902832 1 0.7900391 0.5 0.7902832 0.5 0.7900391 1 0.7897949 0.5 0.7900391 0.5 0.7897949 1 0.7895508 0.5 0.7897949 0.5 0.7895508 1 0.7893067 0.5 0.7895508 0.5 0.7893067 1 0.7890625 0.5 0.7893067 0.5 0.7890625 1 0.7888184 0.5 0.7890625 0.5 0.7888184 1 0.7885742 0.5 0.7888184 0.5 0.7885742 1 0.7883301 0.5 0.7885742 0.5 0.7883301 1 0.7880859 0.5 0.7883301 0.5 0.7880859 1 0.7878418 0.5 0.7880859 0.5 0.7878418 1 0.7875977 0.5 0.7878418 0.5 0.7875977 1 0.7873535 0.5 0.7875977 0.5 0.7873535 1 0.7871094 0.5 0.7873535 0.5 0.7871094 1 0.7868652 0.5 0.7871094 0.5 0.7868652 1 0.7866211 0.5 0.7868652 0.5 0.7866211 1 0.786377 0.5 0.7866211 0.5 0.786377 1 0.7861328 0.5 0.786377 0.5 0.7861328 1 0.7858887 0.5 0.7861328 0.5 0.7858887 1 0.7856445 0.5 0.7858887 0.5 0.7856445 1 0.7854004 0.5 0.7856445 0.5 0.7854004 1 0.7851563 0.5 0.7854004 0.5 0.7851563 1 0.7849121 0.5 0.7851563 0.5 0.7849121 1 0.784668 0.5 0.7849121 0.5 0.784668 1 0.7844238 0.5 0.784668 0.5 0.7844238 1 0.7841797 0.5 0.7844238 0.5 0.7841797 1 0.7839356 0.5 0.7841797 0.5 0.7839356 1 0.7836914 0.5 0.7839356 0.5 0.7836914 1 0.7834473 0.5 0.7836914 0.5 0.7834473 1 0.7832031 0.5 0.7834473 0.5 0.7832031 1 0.782959 0.5 0.7832031 0.5 0.782959 1 0.7827149 0.5 0.782959 0.5 0.7827149 1 0.7824707 0.5 0.7827149 0.5 0.7824707 1 0.7822266 0.5 0.7824707 0.5 0.7822266 1 0.7819824 0.5 0.7822266 0.5 0.7819824 1 0.7817383 0.5 0.7819824 0.5 0.7817383 1 0.7814942 0.5 0.7817383 0.5 0.7814942 1 0.78125 0.5 0.7814942 0.5 0.78125 1 0.7810059 0.5 0.78125 0.5 0.7810059 1 0.7807617 0.5 0.7810059 0.5 0.7807617 1 0.7805176 0.5 0.7807617 0.5 0.7805176 1 0.7802734 0.5 0.7805176 0.5 0.7802734 1 0.7800293 0.5 0.7802734 0.5 0.7800293 1 0.7797852 0.5 0.7800293 0.5 0.7797852 1 0.779541 0.5 0.7797852 0.5 0.779541 1 0.7792969 0.5 0.779541 0.5 0.7792969 1 0.7790527 0.5 0.7792969 0.5 0.7790527 1 0.7788086 0.5 0.7790527 0.5 0.7788086 1 0.7785645 0.5 0.7788086 0.5 0.7785645 1 0.7783203 0.5 0.7785645 0.5 0.7783203 1 0.7780762 0.5 0.7783203 0.5 0.7780762 1 0.777832 0.5 0.7780762 0.5 0.777832 1 0.7775879 0.5 0.777832 0.5 0.7775879 1 0.7773438 0.5 0.7775879 0.5 0.7773438 1 0.7770996 0.5 0.7773438 0.5 0.7770996 1 0.7768555 0.5 0.7770996 0.5 0.7768555 1 0.7766113 0.5 0.7768555 0.5 0.7766113 1 0.7763672 0.5 0.7766113 0.5 0.7763672 1 0.7761231 0.5 0.7763672 0.5 0.7761231 1 0.7758789 0.5 0.7761231 0.5 0.7758789 1 0.7756348 0.5 0.7758789 0.5 0.7756348 1 0.7753906 0.5 0.7756348 0.5 0.7753906 1 0.7751465 0.5 0.7753906 0.5 0.7751465 1 0.7749024 0.5 0.7751465 0.5 0.7749024 1 0.7746582 0.5 0.7749024 0.5 0.7746582 1 0.7744141 0.5 0.7746582 0.5 0.7744141 1 0.7741699 0.5 0.7744141 0.5 0.7741699 1 0.7739258 0.5 0.7741699 0.5 0.7739258 1 0.7736817 0.5 0.7739258 0.5 0.7736817 1 0.7734375 0.5 0.7736817 0.5 0.7734375 1 0.7731934 0.5 0.7734375 0.5 0.7731934 1 0.7729492 0.5 0.7731934 0.5 0.7729492 1 0.7727051 0.5 0.7729492 0.5 0.7727051 1 0.7724609 0.5 0.7727051 0.5 0.7724609 1 0.7722168 0.5 0.7724609 0.5 0.7722168 1 0.7719727 0.5 0.7722168 0.5 0.7719727 1 0.7717285 0.5 0.7719727 0.5 0.7717285 1 0.7714844 0.5 0.7717285 0.5 0.7714844 1 0.7712402 0.5 0.7714844 0.5 0.7712402 1 0.7709961 0.5 0.7712402 0.5 0.7709961 1 0.770752 0.5 0.7709961 0.5 0.770752 1 0.7705078 0.5 0.770752 0.5 0.7705078 1 0.7702637 0.5 0.7705078 0.5 0.7702637 1 0.7700195 0.5 0.7702637 0.5 0.7700195 1 0.7697754 0.5 0.7700195 0.5 0.7697754 1 0.7695313 0.5 0.7697754 0.5 0.7695313 1 0.7692871 0.5 0.7695313 0.5 0.7692871 1 0.769043 0.5 0.7692871 0.5 0.769043 1 0.7687988 0.5 0.769043 0.5 0.7687988 1 0.7685547 0.5 0.7687988 0.5 0.7685547 1 0.7683106 0.5 0.7685547 0.5 0.7683106 1 0.7680664 0.5 0.7683106 0.5 0.7680664 1 0.7678223 0.5 0.7680664 0.5 0.7678223 1 0.7675781 0.5 0.7678223 0.5 0.7675781 1 0.767334 0.5 0.7675781 0.5 0.767334 1 0.7670899 0.5 0.767334 0.5 0.7670899 1 0.7668457 0.5 0.7670899 0.5 0.7668457 1 0.7666016 0.5 0.7668457 0.5 0.7666016 1 0.7663574 0.5 0.7666016 0.5 0.7663574 1 0.7661133 0.5 0.7663574 0.5 0.7661133 1 0.7658692 0.5 0.7661133 0.5 0.7658692 1 0.765625 0.5 0.7658692 0.5 0.765625 1 0.7653809 0.5 0.765625 0.5 0.7653809 1 0.7651367 0.5 0.7653809 0.5 0.7651367 1 0.7648926 0.5 0.7651367 0.5 0.7648926 1 0.7646484 0.5 0.7648926 0.5 0.7646484 1 0.7644043 0.5 0.7646484 0.5 0.7644043 1 0.7641602 0.5 0.7644043 0.5 0.7641602 1 0.763916 0.5 0.7641602 0.5 0.763916 1 0.7636719 0.5 0.763916 0.5 0.7636719 1 0.7634277 0.5 0.7636719 0.5 0.7634277 1 0.7631836 0.5 0.7634277 0.5 0.7631836 1 0.7629395 0.5 0.7631836 0.5 0.7629395 1 0.7626953 0.5 0.7629395 0.5 0.7626953 1 0.7624512 0.5 0.7626953 0.5 0.7624512 1 0.762207 0.5 0.7624512 0.5 0.762207 1 0.7619629 0.5 0.762207 0.5 0.7619629 1 0.7617188 0.5 0.7619629 0.5 0.7617188 1 0.7614746 0.5 0.7617188 0.5 0.7614746 1 0.7612305 0.5 0.7614746 0.5 0.7612305 1 0.7609863 0.5 0.7612305 0.5 0.7609863 1 0.7607422 0.5 0.7609863 0.5 0.7607422 1 0.7604981 0.5 0.7607422 0.5 0.7604981 1 0.7602539 0.5 0.7604981 0.5 0.7602539 1 0.7600098 0.5 0.7602539 0.5 0.7600098 1 0.7597656 0.5 0.7600098 0.5 0.7597656 1 0.7595215 0.5 0.7597656 0.5 0.7595215 1 0.7592774 0.5 0.7595215 0.5 0.7592774 1 0.7590332 0.5 0.7592774 0.5 0.7590332 1 0.7587891 0.5 0.7590332 0.5 0.7587891 1 0.7585449 0.5 0.7587891 0.5 0.7585449 1 0.7583008 0.5 0.7585449 0.5 0.7583008 1 0.7580567 0.5 0.7583008 0.5 0.7580567 1 0.7578125 0.5 0.7580567 0.5 0.7578125 1 0.7575684 0.5 0.7578125 0.5 0.7575684 1 0.7573242 0.5 0.7575684 0.5 0.7573242 1 0.7570801 0.5 0.7573242 0.5 0.7570801 1 0.7568359 0.5 0.7570801 0.5 0.7568359 1 0.7565918 0.5 0.7568359 0.5 0.7565918 1 0.7563477 0.5 0.7565918 0.5 0.7563477 1 0.7561035 0.5 0.7563477 0.5 0.7561035 1 0.7558594 0.5 0.7561035 0.5 0.7558594 1 0.7556152 0.5 0.7558594 0.5 0.7556152 1 0.7553711 0.5 0.7556152 0.5 0.7553711 1 0.755127 0.5 0.7553711 0.5 0.755127 1 0.7548828 0.5 0.755127 0.5 0.7548828 1 0.7546387 0.5 0.7548828 0.5 0.7546387 1 0.7543945 0.5 0.7546387 0.5 0.7543945 1 0.7541504 0.5 0.7543945 0.5 0.7541504 1 0.7539063 0.5 0.7541504 0.5 0.7539063 1 0.7536621 0.5 0.7539063 0.5 0.7536621 1 0.753418 0.5 0.7536621 0.5 0.753418 1 0.7531738 0.5 0.753418 0.5 0.7531738 1 0.7529297 0.5 0.7531738 0.5 0.7529297 1 0.7526856 0.5 0.7529297 0.5 0.7526856 1 0.7524414 0.5 0.7526856 0.5 0.7524414 1 0.7521973 0.5 0.7524414 0.5 0.7521973 1 0.7519531 0.5 0.7521973 0.5 0.7519531 1 0.751709 0.5 0.7519531 0.5 0.751709 1 0.7514649 0.5 0.751709 0.5 0.7514649 1 0.7512207 0.5 0.7514649 0.5 0.7512207 1 0.7509766 0.5 0.7512207 0.5 0.7509766 1 0.7507324 0.5 0.7509766 0.5 0.7507324 1 0.7504883 0.5 0.7507324 0.5 0.7504883 1 0.7502442 0.5 0.7504883 0.5 0.7502442 1 0.75 0.5 0.7502442 0.5 0.75 1 0.7497559 0.5 0.75 0.5 0.7497559 1 0.7495117 0.5 0.7497559 0.5 0.7495117 1 0.7492676 0.5 0.7495117 0.5 0.7492676 1 0.7490234 0.5 0.7492676 0.5 0.7490234 1 0.7487793 0.5 0.7490234 0.5 0.7487793 1 0.7485352 0.5 0.7487793 0.5 0.7485352 1 0.748291 0.5 0.7485352 0.5 0.748291 1 0.7480469 0.5 0.748291 0.5 0.7480469 1 0.7478027 0.5 0.7480469 0.5 0.7478027 1 0.7475586 0.5 0.7478027 0.5 0.7475586 1 0.7473145 0.5 0.7475586 0.5 0.7473145 1 0.7470703 0.5 0.7473145 0.5 0.7470703 1 0.7468262 0.5 0.7470703 0.5 0.7468262 1 0.746582 0.5 0.7468262 0.5 0.746582 1 0.7463379 0.5 0.746582 0.5 0.7463379 1 0.7460938 0.5 0.7463379 0.5 0.7460938 1 0.7458496 0.5 0.7460938 0.5 0.7458496 1 0.7456055 0.5 0.7458496 0.5 0.7456055 1 0.7453613 0.5 0.7456055 0.5 0.7453613 1 0.7451172 0.5 0.7453613 0.5 0.7451172 1 0.7448731 0.5 0.7451172 0.5 0.7448731 1 0.7446289 0.5 0.7448731 0.5 0.7446289 1 0.7443848 0.5 0.7446289 0.5 0.7443848 1 0.7441406 0.5 0.7443848 0.5 0.7441406 1 0.7438965 0.5 0.7441406 0.5 0.7438965 1 0.7436524 0.5 0.7438965 0.5 0.7436524 1 0.7434082 0.5 0.7436524 0.5 0.7434082 1 0.7431641 0.5 0.7434082 0.5 0.7431641 1 0.7429199 0.5 0.7431641 0.5 0.7429199 1 0.7426758 0.5 0.7429199 0.5 0.7426758 1 0.7424317 0.5 0.7426758 0.5 0.7424317 1 0.7421875 0.5 0.7424317 0.5 0.7421875 1 0.7419434 0.5 0.7421875 0.5 0.7419434 1 0.7416992 0.5 0.7419434 0.5 0.7416992 1 0.7414551 0.5 0.7416992 0.5 0.7414551 1 0.7412109 0.5 0.7414551 0.5 0.7412109 1 0.7409668 0.5 0.7412109 0.5 0.7409668 1 0.7407227 0.5 0.7409668 0.5 0.7407227 1 0.7404785 0.5 0.7407227 0.5 0.7404785 1 0.7402344 0.5 0.7404785 0.5 0.7402344 1 0.7399902 0.5 0.7402344 0.5 0.7399902 1 0.7397461 0.5 0.7399902 0.5 0.7397461 1 0.739502 0.5 0.7397461 0.5 0.739502 1 0.7392578 0.5 0.739502 0.5 0.7392578 1 0.7390137 0.5 0.7392578 0.5 0.7390137 1 0.7387695 0.5 0.7390137 0.5 0.7387695 1 0.7385254 0.5 0.7387695 0.5 0.7385254 1 0.7382813 0.5 0.7385254 0.5 0.7382813 1 0.7380371 0.5 0.7382813 0.5 0.7380371 1 0.737793 0.5 0.7380371 0.5 0.737793 1 0.7375488 0.5 0.737793 0.5 0.7375488 1 0.7373047 0.5 0.7375488 0.5 0.7373047 1 0.7370606 0.5 0.7373047 0.5 0.7370606 1 0.7368164 0.5 0.7370606 0.5 0.7368164 1 0.7365723 0.5 0.7368164 0.5 0.7365723 1 0.7363281 0.5 0.7365723 0.5 0.7363281 1 0.736084 0.5 0.7363281 0.5 0.736084 1 0.7358399 0.5 0.736084 0.5 0.7358399 1 0.7355957 0.5 0.7358399 0.5 0.7355957 1 0.7353516 0.5 0.7355957 0.5 0.7353516 1 0.7351074 0.5 0.7353516 0.5 0.7351074 1 0.7348633 0.5 0.7351074 0.5 0.7348633 1 0.7346192 0.5 0.7348633 0.5 0.7346192 1 0.734375 0.5 0.7346192 0.5 0.734375 1 0.7341309 0.5 0.734375 0.5 0.7341309 1 0.7338867 0.5 0.7341309 0.5 0.7338867 1 0.7336426 0.5 0.7338867 0.5 0.7336426 1 0.7333984 0.5 0.7336426 0.5 0.7333984 1 0.7331543 0.5 0.7333984 0.5 0.7331543 1 0.7329102 0.5 0.7331543 0.5 0.7329102 1 0.732666 0.5 0.7329102 0.5 0.732666 1 0.7324219 0.5 0.732666 0.5 0.7324219 1 0.7321777 0.5 0.7324219 0.5 0.7321777 1 0.7319336 0.5 0.7321777 0.5 0.7319336 1 0.7316895 0.5 0.7319336 0.5 0.7316895 1 0.7314453 0.5 0.7316895 0.5 0.7314453 1 0.7312012 0.5 0.7314453 0.5 0.7312012 1 0.730957 0.5 0.7312012 0.5 0.730957 1 0.7307129 0.5 0.730957 0.5 0.7307129 1 0.7304688 0.5 0.7307129 0.5 0.7304688 1 0.7302246 0.5 0.7304688 0.5 0.7302246 1 0.7299805 0.5 0.7302246 0.5 0.7299805 1 0.7297363 0.5 0.7299805 0.5 0.7297363 1 0.7294922 0.5 0.7297363 0.5 0.7294922 1 0.7292481 0.5 0.7294922 0.5 0.7292481 1 0.7290039 0.5 0.7292481 0.5 0.7290039 1 0.7287598 0.5 0.7290039 0.5 0.7287598 1 0.7285156 0.5 0.7287598 0.5 0.7285156 1 0.7282715 0.5 0.7285156 0.5 0.7282715 1 0.7280274 0.5 0.7282715 0.5 0.7280274 1 0.7277832 0.5 0.7280274 0.5 0.7277832 1 0.7275391 0.5 0.7277832 0.5 0.7275391 1 0.7272949 0.5 0.7275391 0.5 0.7272949 1 0.7270508 0.5 0.7272949 0.5 0.7270508 1 0.7268067 0.5 0.7270508 0.5 0.7268067 1 0.7265625 0.5 0.7268067 0.5 0.7265625 1 0.7263184 0.5 0.7265625 0.5 0.7263184 1 0.7260742 0.5 0.7263184 0.5 0.7260742 1 0.7258301 0.5 0.7260742 0.5 0.7258301 1 0.7255859 0.5 0.7258301 0.5 0.7255859 1 0.7253418 0.5 0.7255859 0.5 0.7253418 1 0.7250977 0.5 0.7253418 0.5 0.7250977 1 0.7248535 0.5 0.7250977 0.5 0.7248535 1 0.7246094 0.5 0.7248535 0.5 0.7246094 1 0.7243652 0.5 0.7246094 0.5 0.7243652 1 0.7241211 0.5 0.7243652 0.5 0.7241211 1 0.723877 0.5 0.7241211 0.5 0.723877 1 0.7236328 0.5 0.723877 0.5 0.7236328 1 0.7233887 0.5 0.7236328 0.5 0.7233887 1 0.7231445 0.5 0.7233887 0.5 0.7231445 1 0.7229004 0.5 0.7231445 0.5 0.7229004 1 0.7226563 0.5 0.7229004 0.5 0.7226563 1 0.7224121 0.5 0.7226563 0.5 0.7224121 1 0.722168 0.5 0.7224121 0.5 0.722168 1 0.7219238 0.5 0.722168 0.5 0.7219238 1 0.7216797 0.5 0.7219238 0.5 0.7216797 1 0.7214356 0.5 0.7216797 0.5 0.7214356 1 0.7211914 0.5 0.7214356 0.5 0.7211914 1 0.7209473 0.5 0.7211914 0.5 0.7209473 1 0.7207031 0.5 0.7209473 0.5 0.7207031 1 0.720459 0.5 0.7207031 0.5 0.720459 1 0.7202149 0.5 0.720459 0.5 0.7202149 1 0.7199707 0.5 0.7202149 0.5 0.7199707 1 0.7197266 0.5 0.7199707 0.5 0.7197266 1 0.7194824 0.5 0.7197266 0.5 0.7194824 1 0.7192383 0.5 0.7194824 0.5 0.7192383 1 0.7189942 0.5 0.7192383 0.5 0.7189942 1 0.71875 0.5 0.7189942 0.5 0.71875 1 0.7185059 0.5 0.71875 0.5 0.7185059 1 0.7182617 0.5 0.7185059 0.5 0.7182617 1 0.7180176 0.5 0.7182617 0.5 0.7180176 1 0.7177734 0.5 0.7180176 0.5 0.7177734 1 0.7175293 0.5 0.7177734 0.5 0.7175293 1 0.7172852 0.5 0.7175293 0.5 0.7172852 1 0.717041 0.5 0.7172852 0.5 0.717041 1 0.7167969 0.5 0.717041 0.5 0.7167969 1 0.7165527 0.5 0.7167969 0.5 0.7165527 1 0.7163086 0.5 0.7165527 0.5 0.7163086 1 0.7160645 0.5 0.7163086 0.5 0.7160645 1 0.7158203 0.5 0.7160645 0.5 0.7158203 1 0.7155762 0.5 0.7158203 0.5 0.7155762 1 0.715332 0.5 0.7155762 0.5 0.715332 1 0.7150879 0.5 0.715332 0.5 0.7150879 1 0.7148438 0.5 0.7150879 0.5 0.7148438 1 0.7145996 0.5 0.7148438 0.5 0.7145996 1 0.7143555 0.5 0.7145996 0.5 0.7143555 1 0.7141113 0.5 0.7143555 0.5 0.7141113 1 0.7138672 0.5 0.7141113 0.5 0.7138672 1 0.7136231 0.5 0.7138672 0.5 0.7136231 1 0.7133789 0.5 0.7136231 0.5 0.7133789 1 0.7131348 0.5 0.7133789 0.5 0.7131348 1 0.7128906 0.5 0.7131348 0.5 0.7128906 1 0.7126465 0.5 0.7128906 0.5 0.7126465 1 0.7124024 0.5 0.7126465 0.5 0.7124024 1 0.7121582 0.5 0.7124024 0.5 0.7121582 1 0.7119141 0.5 0.7121582 0.5 0.7119141 1 0.7116699 0.5 0.7119141 0.5 0.7116699 1 0.7114258 0.5 0.7116699 0.5 0.7114258 1 0.7111817 0.5 0.7114258 0.5 0.7111817 1 0.7109375 0.5 0.7111817 0.5 0.7109375 1 0.7106934 0.5 0.7109375 0.5 0.7106934 1 0.7104492 0.5 0.7106934 0.5 0.7104492 1 0.7102051 0.5 0.7104492 0.5 0.7102051 1 0.7099609 0.5 0.7102051 0.5 0.7099609 1 0.7097168 0.5 0.7099609 0.5 0.7097168 1 0.7094727 0.5 0.7097168 0.5 0.7094727 1 0.7092285 0.5 0.7094727 0.5 0.7092285 1 0.7089844 0.5 0.7092285 0.5 0.7089844 1 0.7087402 0.5 0.7089844 0.5 0.7087402 1 0.7084961 0.5 0.7087402 0.5 0.7084961 1 0.708252 0.5 0.7084961 0.5 0.708252 1 0.7080078 0.5 0.708252 0.5 0.7080078 1 0.7077637 0.5 0.7080078 0.5 0.7077637 1 0.7075195 0.5 0.7077637 0.5 0.7075195 1 0.7072754 0.5 0.7075195 0.5 0.7072754 1 0.7070313 0.5 0.7072754 0.5 0.7070313 1 0.7067871 0.5 0.7070313 0.5 0.7067871 1 0.706543 0.5 0.7067871 0.5 0.706543 1 0.7062988 0.5 0.706543 0.5 0.7062988 1 0.7060547 0.5 0.7062988 0.5 0.7060547 1 0.7058106 0.5 0.7060547 0.5 0.7058106 1 0.7055664 0.5 0.7058106 0.5 0.7055664 1 0.7053223 0.5 0.7055664 0.5 0.7053223 1 0.7050781 0.5 0.7053223 0.5 0.7050781 1 0.704834 0.5 0.7050781 0.5 0.704834 1 0.7045899 0.5 0.704834 0.5 0.7045899 1 0.7043457 0.5 0.7045899 0.5 0.7043457 1 0.7041016 0.5 0.7043457 0.5 0.7041016 1 0.7038574 0.5 0.7041016 0.5 0.7038574 1 0.7036133 0.5 0.7038574 0.5 0.7036133 1 0.7033692 0.5 0.7036133 0.5 0.7033692 1 0.703125 0.5 0.7033692 0.5 0.703125 1 0.7028809 0.5 0.703125 0.5 0.7028809 1 0.7026367 0.5 0.7028809 0.5 0.7026367 1 0.7023926 0.5 0.7026367 0.5 0.7023926 1 0.7021484 0.5 0.7023926 0.5 0.7021484 1 0.7019043 0.5 0.7021484 0.5 0.7019043 1 0.7016602 0.5 0.7019043 0.5 0.7016602 1 0.701416 0.5 0.7016602 0.5 0.701416 1 0.7011719 0.5 0.701416 0.5 0.7011719 1 0.7009277 0.5 0.7011719 0.5 0.7009277 1 0.7006836 0.5 0.7009277 0.5 0.7006836 1 0.7004395 0.5 0.7006836 0.5 0.7004395 1 0.7001953 0.5 0.7004395 0.5 0.7001953 1 0.6999512 0.5 0.7001953 0.5 0.6999512 1 0.699707 0.5 0.6999512 0.5 0.699707 1 0.6994629 0.5 0.699707 0.5 0.6994629 1 0.6992188 0.5 0.6994629 0.5 0.6992188 1 0.6989746 0.5 0.6992188 0.5 0.6989746 1 0.6987305 0.5 0.6989746 0.5 0.6987305 1 0.6984863 0.5 0.6987305 0.5 0.6984863 1 0.6982422 0.5 0.6984863 0.5 0.6982422 1 0.6979981 0.5 0.6982422 0.5 0.6979981 1 0.6977539 0.5 0.6979981 0.5 0.6977539 1 0.6975098 0.5 0.6977539 0.5 0.6975098 1 0.6972656 0.5 0.6975098 0.5 0.6972656 1 0.6970215 0.5 0.6972656 0.5 0.6970215 1 0.6967774 0.5 0.6970215 0.5 0.6967774 1 0.6965332 0.5 0.6967774 0.5 0.6965332 1 0.6962891 0.5 0.6965332 0.5 0.6962891 1 0.6960449 0.5 0.6962891 0.5 0.6960449 1 0.6958008 0.5 0.6960449 0.5 0.6958008 1 0.6955567 0.5 0.6958008 0.5 0.6955567 1 0.6953125 0.5 0.6955567 0.5 0.6953125 1 0.6950684 0.5 0.6953125 0.5 0.6950684 1 0.6948242 0.5 0.6950684 0.5 0.6948242 1 0.6945801 0.5 0.6948242 0.5 0.6945801 1 0.6943359 0.5 0.6945801 0.5 0.6943359 1 0.6940918 0.5 0.6943359 0.5 0.6940918 1 0.6938477 0.5 0.6940918 0.5 0.6938477 1 0.6936035 0.5 0.6938477 0.5 0.6936035 1 0.6933594 0.5 0.6936035 0.5 0.6933594 1 0.6931152 0.5 0.6933594 0.5 0.6931152 1 0.6928711 0.5 0.6931152 0.5 0.6928711 1 0.692627 0.5 0.6928711 0.5 0.692627 1 0.6923828 0.5 0.692627 0.5 0.6923828 1 0.6921387 0.5 0.6923828 0.5 0.6921387 1 0.6918945 0.5 0.6921387 0.5 0.6918945 1 0.6916504 0.5 0.6918945 0.5 0.6916504 1 0.6914063 0.5 0.6916504 0.5 0.6914063 1 0.6911621 0.5 0.6914063 0.5 0.6911621 1 0.690918 0.5 0.6911621 0.5 0.690918 1 0.6906738 0.5 0.690918 0.5 0.6906738 1 0.6904297 0.5 0.6906738 0.5 0.6904297 1 0.6901856 0.5 0.6904297 0.5 0.6901856 1 0.6899414 0.5 0.6901856 0.5 0.6899414 1 0.6896973 0.5 0.6899414 0.5 0.6896973 1 0.6894531 0.5 0.6896973 0.5 0.6894531 1 0.689209 0.5 0.6894531 0.5 0.689209 1 0.6889649 0.5 0.689209 0.5 0.6889649 1 0.6887207 0.5 0.6889649 0.5 0.6887207 1 0.6884766 0.5 0.6887207 0.5 0.6884766 1 0.6882324 0.5 0.6884766 0.5 0.6882324 1 0.6879883 0.5 0.6882324 0.5 0.6879883 1 0.6877442 0.5 0.6879883 0.5 0.6877442 1 0.6875 0.5 0.6877442 0.5 0.6875 1 0.6872559 0.5 0.6875 0.5 0.6872559 1 0.6870117 0.5 0.6872559 0.5 0.6870117 1 0.6867676 0.5 0.6870117 0.5 0.6867676 1 0.6865234 0.5 0.6867676 0.5 0.6865234 1 0.6862793 0.5 0.6865234 0.5 0.6862793 1 0.6860352 0.5 0.6862793 0.5 0.6860352 1 0.685791 0.5 0.6860352 0.5 0.685791 1 0.6855469 0.5 0.685791 0.5 0.6855469 1 0.6853027 0.5 0.6855469 0.5 0.6853027 1 0.6850586 0.5 0.6853027 0.5 0.6850586 1 0.6848145 0.5 0.6850586 0.5 0.6848145 1 0.6845703 0.5 0.6848145 0.5 0.6845703 1 0.6843262 0.5 0.6845703 0.5 0.6843262 1 0.684082 0.5 0.6843262 0.5 0.684082 1 0.6838379 0.5 0.684082 0.5 0.6838379 1 0.6835938 0.5 0.6838379 0.5 0.6835938 1 0.6833496 0.5 0.6835938 0.5 0.6833496 1 0.6831055 0.5 0.6833496 0.5 0.6831055 1 0.6828613 0.5 0.6831055 0.5 0.6828613 1 0.6826172 0.5 0.6828613 0.5 0.6826172 1 0.6823731 0.5 0.6826172 0.5 0.6823731 1 0.6821289 0.5 0.6823731 0.5 0.6821289 1 0.6818848 0.5 0.6821289 0.5 0.6818848 1 0.6816406 0.5 0.6818848 0.5 0.6816406 1 0.6813965 0.5 0.6816406 0.5 0.6813965 1 0.6811524 0.5 0.6813965 0.5 0.6811524 1 0.6809082 0.5 0.6811524 0.5 0.6809082 1 0.6806641 0.5 0.6809082 0.5 0.6806641 1 0.6804199 0.5 0.6806641 0.5 0.6804199 1 0.6801758 0.5 0.6804199 0.5 0.6801758 1 0.6799317 0.5 0.6801758 0.5 0.6799317 1 0.6796875 0.5 0.6799317 0.5 0.6796875 1 0.6794434 0.5 0.6796875 0.5 0.6794434 1 0.6791992 0.5 0.6794434 0.5 0.6791992 1 0.6789551 0.5 0.6791992 0.5 0.6789551 1 0.6787109 0.5 0.6789551 0.5 0.6787109 1 0.6784668 0.5 0.6787109 0.5 0.6784668 1 0.6782227 0.5 0.6784668 0.5 0.6782227 1 0.6779785 0.5 0.6782227 0.5 0.6779785 1 0.6777344 0.5 0.6779785 0.5 0.6777344 1 0.6774902 0.5 0.6777344 0.5 0.6774902 1 0.6772461 0.5 0.6774902 0.5 0.6772461 1 0.677002 0.5 0.6772461 0.5 0.677002 1 0.6767578 0.5 0.677002 0.5 0.6767578 1 0.6765137 0.5 0.6767578 0.5 0.6765137 1 0.6762695 0.5 0.6765137 0.5 0.6762695 1 0.6760254 0.5 0.6762695 0.5 0.6760254 1 0.6757813 0.5 0.6760254 0.5 0.6757813 1 0.6755371 0.5 0.6757813 0.5 0.6755371 1 0.675293 0.5 0.6755371 0.5 0.675293 1 0.6750488 0.5 0.675293 0.5 0.6750488 1 0.6748047 0.5 0.6750488 0.5 0.6748047 1 0.6745606 0.5 0.6748047 0.5 0.6745606 1 0.6743164 0.5 0.6745606 0.5 0.6743164 1 0.6740723 0.5 0.6743164 0.5 0.6740723 1 0.6738281 0.5 0.6740723 0.5 0.6738281 1 0.673584 0.5 0.6738281 0.5 0.673584 1 0.6733399 0.5 0.673584 0.5 0.6733399 1 0.6730957 0.5 0.6733399 0.5 0.6730957 1 0.6728516 0.5 0.6730957 0.5 0.6728516 1 0.6726074 0.5 0.6728516 0.5 0.6726074 1 0.6723633 0.5 0.6726074 0.5 0.6723633 1 0.6721192 0.5 0.6723633 0.5 0.6721192 1 0.671875 0.5 0.6721192 0.5 0.671875 1 0.6716309 0.5 0.671875 0.5 0.6716309 1 0.6713867 0.5 0.6716309 0.5 0.6713867 1 0.6711426 0.5 0.6713867 0.5 0.6711426 1 0.6708984 0.5 0.6711426 0.5 0.6708984 1 0.6706543 0.5 0.6708984 0.5 0.6706543 1 0.6704102 0.5 0.6706543 0.5 0.6704102 1 0.670166 0.5 0.6704102 0.5 0.670166 1 0.6699219 0.5 0.670166 0.5 0.6699219 1 0.6696777 0.5 0.6699219 0.5 0.6696777 1 0.6694336 0.5 0.6696777 0.5 0.6694336 1 0.6691895 0.5 0.6694336 0.5 0.6691895 1 0.6689453 0.5 0.6691895 0.5 0.6689453 1 0.6687012 0.5 0.6689453 0.5 0.6687012 1 0.668457 0.5 0.6687012 0.5 0.668457 1 0.6682129 0.5 0.668457 0.5 0.6682129 1 0.6679688 0.5 0.6682129 0.5 0.6679688 1 0.6677246 0.5 0.6679688 0.5 0.6677246 1 0.6674805 0.5 0.6677246 0.5 0.6674805 1 0.6672363 0.5 0.6674805 0.5 0.6672363 1 0.6669922 0.5 0.6672363 0.5 0.6669922 1 0.6667481 0.5 0.6669922 0.5 0.6667481 1 0.6665039 0.5 0.6667481 0.5 0.6665039 1 0.6662598 0.5 0.6665039 0.5 0.6662598 1 0.6660156 0.5 0.6662598 0.5 0.6660156 1 0.6657715 0.5 0.6660156 0.5 0.6657715 1 0.6655274 0.5 0.6657715 0.5 0.6655274 1 0.6652832 0.5 0.6655274 0.5 0.6652832 1 0.6650391 0.5 0.6652832 0.5 0.6650391 1 0.6647949 0.5 0.6650391 0.5 0.6647949 1 0.6645508 0.5 0.6647949 0.5 0.6645508 1 0.6643067 0.5 0.6645508 0.5 0.6643067 1 0.6640625 0.5 0.6643067 0.5 0.6640625 1 0.6638184 0.5 0.6640625 0.5 0.6638184 1 0.6635742 0.5 0.6638184 0.5 0.6635742 1 0.6633301 0.5 0.6635742 0.5 0.6633301 1 0.6630859 0.5 0.6633301 0.5 0.6630859 1 0.6628418 0.5 0.6630859 0.5 0.6628418 1 0.6625977 0.5 0.6628418 0.5 0.6625977 1 0.6623535 0.5 0.6625977 0.5 0.6623535 1 0.6621094 0.5 0.6623535 0.5 0.6621094 1 0.6618652 0.5 0.6621094 0.5 0.6618652 1 0.6616211 0.5 0.6618652 0.5 0.6616211 1 0.661377 0.5 0.6616211 0.5 0.661377 1 0.6611328 0.5 0.661377 0.5 0.6611328 1 0.6608887 0.5 0.6611328 0.5 0.6608887 1 0.6606445 0.5 0.6608887 0.5 0.6606445 1 0.6604004 0.5 0.6606445 0.5 0.6604004 1 0.6601563 0.5 0.6604004 0.5 0.6601563 1 0.6599121 0.5 0.6601563 0.5 0.6599121 1 0.659668 0.5 0.6599121 0.5 0.659668 1 0.6594238 0.5 0.659668 0.5 0.6594238 1 0.6591797 0.5 0.6594238 0.5 0.6591797 1 0.6589356 0.5 0.6591797 0.5 0.6589356 1 0.6586914 0.5 0.6589356 0.5 0.6586914 1 0.6584473 0.5 0.6586914 0.5 0.6584473 1 0.6582031 0.5 0.6584473 0.5 0.6582031 1 0.657959 0.5 0.6582031 0.5 0.657959 1 0.6577149 0.5 0.657959 0.5 0.6577149 1 0.6574707 0.5 0.6577149 0.5 0.6574707 1 0.6572266 0.5 0.6574707 0.5 0.6572266 1 0.6569824 0.5 0.6572266 0.5 0.6569824 1 0.6567383 0.5 0.6569824 0.5 0.6567383 1 0.6564942 0.5 0.6567383 0.5 0.6564942 1 0.65625 0.5 0.6564942 0.5 0.65625 1 0.6560059 0.5 0.65625 0.5 0.6560059 1 0.6557617 0.5 0.6560059 0.5 0.6557617 1 0.6555176 0.5 0.6557617 0.5 0.6555176 1 0.6552734 0.5 0.6555176 0.5 0.6552734 1 0.6550293 0.5 0.6552734 0.5 0.6550293 1 0.6547852 0.5 0.6550293 0.5 0.6547852 1 0.654541 0.5 0.6547852 0.5 0.654541 1 0.6542969 0.5 0.654541 0.5 0.6542969 1 0.6540527 0.5 0.6542969 0.5 0.6540527 1 0.6538086 0.5 0.6540527 0.5 0.6538086 1 0.6535645 0.5 0.6538086 0.5 0.6535645 1 0.6533203 0.5 0.6535645 0.5 0.6533203 1 0.6530762 0.5 0.6533203 0.5 0.6530762 1 0.652832 0.5 0.6530762 0.5 0.652832 1 0.6525879 0.5 0.652832 0.5 0.6525879 1 0.6523438 0.5 0.6525879 0.5 0.6523438 1 0.6520996 0.5 0.6523438 0.5 0.6520996 1 0.6518555 0.5 0.6520996 0.5 0.6518555 1 0.6516113 0.5 0.6518555 0.5 0.6516113 1 0.6513672 0.5 0.6516113 0.5 0.6513672 1 0.6511231 0.5 0.6513672 0.5 0.6511231 1 0.6508789 0.5 0.6511231 0.5 0.6508789 1 0.6506348 0.5 0.6508789 0.5 0.6506348 1 0.6503906 0.5 0.6506348 0.5 0.6503906 1 0.6501465 0.5 0.6503906 0.5 0.6501465 1 0.6499024 0.5 0.6501465 0.5 0.6499024 1 0.6496582 0.5 0.6499024 0.5 0.6496582 1 0.6494141 0.5 0.6496582 0.5 0.6494141 1 0.6491699 0.5 0.6494141 0.5 0.6491699 1 0.6489258 0.5 0.6491699 0.5 0.6489258 1 0.6486817 0.5 0.6489258 0.5 0.6486817 1 0.6484375 0.5 0.6486817 0.5 0.6484375 1 0.6481934 0.5 0.6484375 0.5 0.6481934 1 0.6479492 0.5 0.6481934 0.5 0.6479492 1 0.6477051 0.5 0.6479492 0.5 0.6477051 1 0.6474609 0.5 0.6477051 0.5 0.6474609 1 0.6472168 0.5 0.6474609 0.5 0.6472168 1 0.6469727 0.5 0.6472168 0.5 0.6469727 1 0.6467285 0.5 0.6469727 0.5 0.6467285 1 0.6464844 0.5 0.6467285 0.5 0.6464844 1 0.6462402 0.5 0.6464844 0.5 0.6462402 1 0.6459961 0.5 0.6462402 0.5 0.6459961 1 0.645752 0.5 0.6459961 0.5 0.645752 1 0.6455078 0.5 0.645752 0.5 0.6455078 1 0.6452637 0.5 0.6455078 0.5 0.6452637 1 0.6450195 0.5 0.6452637 0.5 0.6450195 1 0.6447754 0.5 0.6450195 0.5 0.6447754 1 0.6445313 0.5 0.6447754 0.5 0.6445313 1 0.6442871 0.5 0.6445313 0.5 0.6442871 1 0.644043 0.5 0.6442871 0.5 0.644043 1 0.6437988 0.5 0.644043 0.5 0.6437988 1 0.6435547 0.5 0.6437988 0.5 0.6435547 1 0.6433106 0.5 0.6435547 0.5 0.6433106 1 0.6430664 0.5 0.6433106 0.5 0.6430664 1 0.6428223 0.5 0.6430664 0.5 0.6428223 1 0.6425781 0.5 0.6428223 0.5 0.6425781 1 0.642334 0.5 0.6425781 0.5 0.642334 1 0.6420899 0.5 0.642334 0.5 0.6420899 1 0.6418457 0.5 0.6420899 0.5 0.6418457 1 0.6416016 0.5 0.6418457 0.5 0.6416016 1 0.6413574 0.5 0.6416016 0.5 0.6413574 1 0.6411133 0.5 0.6413574 0.5 0.6411133 1 0.6408692 0.5 0.6411133 0.5 0.6408692 1 0.640625 0.5 0.6408692 0.5 0.640625 1 0.6403809 0.5 0.640625 0.5 0.6403809 1 0.6401367 0.5 0.6403809 0.5 0.6401367 1 0.6398926 0.5 0.6401367 0.5 0.6398926 1 0.6396484 0.5 0.6398926 0.5 0.6396484 1 0.6394043 0.5 0.6396484 0.5 0.6394043 1 0.6391602 0.5 0.6394043 0.5 0.6391602 1 0.638916 0.5 0.6391602 0.5 0.638916 1 0.6386719 0.5 0.638916 0.5 0.6386719 1 0.6384277 0.5 0.6386719 0.5 0.6384277 1 0.6381836 0.5 0.6384277 0.5 0.6381836 1 0.6379395 0.5 0.6381836 0.5 0.6379395 1 0.6376953 0.5 0.6379395 0.5 0.6376953 1 0.6374512 0.5 0.6376953 0.5 0.6374512 1 0.637207 0.5 0.6374512 0.5 0.637207 1 0.6369629 0.5 0.637207 0.5 0.6369629 1 0.6367188 0.5 0.6369629 0.5 0.6367188 1 0.6364746 0.5 0.6367188 0.5 0.6364746 1 0.6362305 0.5 0.6364746 0.5 0.6362305 1 0.6359863 0.5 0.6362305 0.5 0.6359863 1 0.6357422 0.5 0.6359863 0.5 0.6357422 1 0.6354981 0.5 0.6357422 0.5 0.6354981 1 0.6352539 0.5 0.6354981 0.5 0.6352539 1 0.6350098 0.5 0.6352539 0.5 0.6350098 1 0.6347656 0.5 0.6350098 0.5 0.6347656 1 0.6345215 0.5 0.6347656 0.5 0.6345215 1 0.6342774 0.5 0.6345215 0.5 0.6342774 1 0.6340332 0.5 0.6342774 0.5 0.6340332 1 0.6337891 0.5 0.6340332 0.5 0.6337891 1 0.6335449 0.5 0.6337891 0.5 0.6335449 1 0.6333008 0.5 0.6335449 0.5 0.6333008 1 0.6330567 0.5 0.6333008 0.5 0.6330567 1 0.6328125 0.5 0.6330567 0.5 0.6328125 1 0.6325684 0.5 0.6328125 0.5 0.6325684 1 0.6323242 0.5 0.6325684 0.5 0.6323242 1 0.6320801 0.5 0.6323242 0.5 0.6320801 1 0.6318359 0.5 0.6320801 0.5 0.6318359 1 0.6315918 0.5 0.6318359 0.5 0.6315918 1 0.6313477 0.5 0.6315918 0.5 0.6313477 1 0.6311035 0.5 0.6313477 0.5 0.6311035 1 0.6308594 0.5 0.6311035 0.5 0.6308594 1 0.6306152 0.5 0.6308594 0.5 0.6306152 1 0.6303711 0.5 0.6306152 0.5 0.6303711 1 0.630127 0.5 0.6303711 0.5 0.630127 1 0.6298828 0.5 0.630127 0.5 0.6298828 1 0.6296387 0.5 0.6298828 0.5 0.6296387 1 0.6293945 0.5 0.6296387 0.5 0.6293945 1 0.6291504 0.5 0.6293945 0.5 0.6291504 1 0.6289063 0.5 0.6291504 0.5 0.6289063 1 0.6286621 0.5 0.6289063 0.5 0.6286621 1 0.628418 0.5 0.6286621 0.5 0.628418 1 0.6281738 0.5 0.628418 0.5 0.6281738 1 0.6279297 0.5 0.6281738 0.5 0.6279297 1 0.6276856 0.5 0.6279297 0.5 0.6276856 1 0.6274414 0.5 0.6276856 0.5 0.6274414 1 0.6271973 0.5 0.6274414 0.5 0.6271973 1 0.6269531 0.5 0.6271973 0.5 0.6269531 1 0.626709 0.5 0.6269531 0.5 0.626709 1 0.6264649 0.5 0.626709 0.5 0.6264649 1 0.6262207 0.5 0.6264649 0.5 0.6262207 1 0.6259766 0.5 0.6262207 0.5 0.6259766 1 0.6257324 0.5 0.6259766 0.5 0.6257324 1 0.6254883 0.5 0.6257324 0.5 0.6254883 1 0.6252442 0.5 0.6254883 0.5 0.6252442 1 0.625 0.5 0.6252442 0.5 0.625 1 0.6247559 0.5 0.625 0.5 0.6247559 1 0.6245117 0.5 0.6247559 0.5 0.6245117 1 0.6242676 0.5 0.6245117 0.5 0.6242676 1 0.6240234 0.5 0.6242676 0.5 0.6240234 1 0.6237793 0.5 0.6240234 0.5 0.6237793 1 0.6235352 0.5 0.6237793 0.5 0.6235352 1 0.623291 0.5 0.6235352 0.5 0.623291 1 0.6230469 0.5 0.623291 0.5 0.6230469 1 0.6228027 0.5 0.6230469 0.5 0.6228027 1 0.6225586 0.5 0.6228027 0.5 0.6225586 1 0.6223145 0.5 0.6225586 0.5 0.6223145 1 0.6220703 0.5 0.6223145 0.5 0.6220703 1 0.6218262 0.5 0.6220703 0.5 0.6218262 1 0.621582 0.5 0.6218262 0.5 0.621582 1 0.6213379 0.5 0.621582 0.5 0.6213379 1 0.6210938 0.5 0.6213379 0.5 0.6210938 1 0.6208496 0.5 0.6210938 0.5 0.6208496 1 0.6206055 0.5 0.6208496 0.5 0.6206055 1 0.6203613 0.5 0.6206055 0.5 0.6203613 1 0.6201172 0.5 0.6203613 0.5 0.6201172 1 0.6198731 0.5 0.6201172 0.5 0.6198731 1 0.6196289 0.5 0.6198731 0.5 0.6196289 1 0.6193848 0.5 0.6196289 0.5 0.6193848 1 0.6191406 0.5 0.6193848 0.5 0.6191406 1 0.6188965 0.5 0.6191406 0.5 0.6188965 1 0.6186524 0.5 0.6188965 0.5 0.6186524 1 0.6184082 0.5 0.6186524 0.5 0.6184082 1 0.6181641 0.5 0.6184082 0.5 0.6181641 1 0.6179199 0.5 0.6181641 0.5 0.6179199 1 0.6176758 0.5 0.6179199 0.5 0.6176758 1 0.6174317 0.5 0.6176758 0.5 0.6174317 1 0.6171875 0.5 0.6174317 0.5 0.6171875 1 0.6169434 0.5 0.6171875 0.5 0.6169434 1 0.6166992 0.5 0.6169434 0.5 0.6166992 1 0.6164551 0.5 0.6166992 0.5 0.6164551 1 0.6162109 0.5 0.6164551 0.5 0.6162109 1 0.6159668 0.5 0.6162109 0.5 0.6159668 1 0.6157227 0.5 0.6159668 0.5 0.6157227 1 0.6154785 0.5 0.6157227 0.5 0.6154785 1 0.6152344 0.5 0.6154785 0.5 0.6152344 1 0.6149902 0.5 0.6152344 0.5 0.6149902 1 0.6147461 0.5 0.6149902 0.5 0.6147461 1 0.614502 0.5 0.6147461 0.5 0.614502 1 0.6142578 0.5 0.614502 0.5 0.6142578 1 0.6140137 0.5 0.6142578 0.5 0.6140137 1 0.6137695 0.5 0.6140137 0.5 0.6137695 1 0.6135254 0.5 0.6137695 0.5 0.6135254 1 0.6132813 0.5 0.6135254 0.5 0.6132813 1 0.6130371 0.5 0.6132813 0.5 0.6130371 1 0.612793 0.5 0.6130371 0.5 0.612793 1 0.6125488 0.5 0.612793 0.5 0.6125488 1 0.6123047 0.5 0.6125488 0.5 0.6123047 1 0.6120606 0.5 0.6123047 0.5 0.6120606 1 0.6118164 0.5 0.6120606 0.5 0.6118164 1 0.6115723 0.5 0.6118164 0.5 0.6115723 1 0.6113281 0.5 0.6115723 0.5 0.6113281 1 0.611084 0.5 0.6113281 0.5 0.611084 1 0.6108399 0.5 0.611084 0.5 0.6108399 1 0.6105957 0.5 0.6108399 0.5 0.6105957 1 0.6103516 0.5 0.6105957 0.5 0.6103516 1 0.6101074 0.5 0.6103516 0.5 0.6101074 1 0.6098633 0.5 0.6101074 0.5 0.6098633 1 0.6096192 0.5 0.6098633 0.5 0.6096192 1 0.609375 0.5 0.6096192 0.5 0.609375 1 0.6091309 0.5 0.609375 0.5 0.6091309 1 0.6088867 0.5 0.6091309 0.5 0.6088867 1 0.6086426 0.5 0.6088867 0.5 0.6086426 1 0.6083984 0.5 0.6086426 0.5 0.6083984 1 0.6081543 0.5 0.6083984 0.5 0.6081543 1 0.6079102 0.5 0.6081543 0.5 0.6079102 1 0.607666 0.5 0.6079102 0.5 0.607666 1 0.6074219 0.5 0.607666 0.5 0.6074219 1 0.6071777 0.5 0.6074219 0.5 0.6071777 1 0.6069336 0.5 0.6071777 0.5 0.6069336 1 0.6066895 0.5 0.6069336 0.5 0.6066895 1 0.6064453 0.5 0.6066895 0.5 0.6064453 1 0.6062012 0.5 0.6064453 0.5 0.6062012 1 0.605957 0.5 0.6062012 0.5 0.605957 1 0.6057129 0.5 0.605957 0.5 0.6057129 1 0.6054688 0.5 0.6057129 0.5 0.6054688 1 0.6052246 0.5 0.6054688 0.5 0.6052246 1 0.6049805 0.5 0.6052246 0.5 0.6049805 1 0.6047363 0.5 0.6049805 0.5 0.6047363 1 0.6044922 0.5 0.6047363 0.5 0.6044922 1 0.6042481 0.5 0.6044922 0.5 0.6042481 1 0.6040039 0.5 0.6042481 0.5 0.6040039 1 0.6037598 0.5 0.6040039 0.5 0.6037598 1 0.6035156 0.5 0.6037598 0.5 0.6035156 1 0.6032715 0.5 0.6035156 0.5 0.6032715 1 0.6030274 0.5 0.6032715 0.5 0.6030274 1 0.6027832 0.5 0.6030274 0.5 0.6027832 1 0.6025391 0.5 0.6027832 0.5 0.6025391 1 0.6022949 0.5 0.6025391 0.5 0.6022949 1 0.6020508 0.5 0.6022949 0.5 0.6020508 1 0.6018067 0.5 0.6020508 0.5 0.6018067 1 0.6015625 0.5 0.6018067 0.5 0.6015625 1 0.6013184 0.5 0.6015625 0.5 0.6013184 1 0.6010742 0.5 0.6013184 0.5 0.6010742 1 0.6008301 0.5 0.6010742 0.5 0.6008301 1 0.6005859 0.5 0.6008301 0.5 0.6005859 1 0.6003418 0.5 0.6005859 0.5 0.6003418 1 0.6000977 0.5 0.6003418 0.5 0.6000977 1 0.5998535 0.5 0.6000977 0.5 0.5998535 1 0.5996094 0.5 0.5998535 0.5 0.5996094 1 0.5993652 0.5 0.5996094 0.5 0.5993652 1 0.5991211 0.5 0.5993652 0.5 0.5991211 1 0.598877 0.5 0.5991211 0.5 0.598877 1 0.5986328 0.5 0.598877 0.5 0.5986328 1 0.5983887 0.5 0.5986328 0.5 0.5983887 1 0.5981445 0.5 0.5983887 0.5 0.5981445 1 0.5979004 0.5 0.5981445 0.5 0.5979004 1 0.5976563 0.5 0.5979004 0.5 0.5976563 1 0.5974121 0.5 0.5976563 0.5 0.5974121 1 0.597168 0.5 0.5974121 0.5 0.597168 1 0.5969238 0.5 0.597168 0.5 0.5969238 1 0.5966797 0.5 0.5969238 0.5 0.5966797 1 0.5964356 0.5 0.5966797 0.5 0.5964356 1 0.5961914 0.5 0.5964356 0.5 0.5961914 1 0.5959473 0.5 0.5961914 0.5 0.5959473 1 0.5957031 0.5 0.5959473 0.5 0.5957031 1 0.595459 0.5 0.5957031 0.5 0.595459 1 0.5952149 0.5 0.595459 0.5 0.5952149 1 0.5949707 0.5 0.5952149 0.5 0.5949707 1 0.5947266 0.5 0.5949707 0.5 0.5947266 1 0.5944824 0.5 0.5947266 0.5 0.5944824 1 0.5942383 0.5 0.5944824 0.5 0.5942383 1 0.5939942 0.5 0.5942383 0.5 0.5939942 1 0.59375 0.5 0.5939942 0.5 0.59375 1 0.5935059 0.5 0.59375 0.5 0.5935059 1 0.5932617 0.5 0.5935059 0.5 0.5932617 1 0.5930176 0.5 0.5932617 0.5 0.5930176 1 0.5927734 0.5 0.5930176 0.5 0.5927734 1 0.5925293 0.5 0.5927734 0.5 0.5925293 1 0.5922852 0.5 0.5925293 0.5 0.5922852 1 0.592041 0.5 0.5922852 0.5 0.592041 1 0.5917969 0.5 0.592041 0.5 0.5917969 1 0.5915527 0.5 0.5917969 0.5 0.5915527 1 0.5913086 0.5 0.5915527 0.5 0.5913086 1 0.5910645 0.5 0.5913086 0.5 0.5910645 1 0.5908203 0.5 0.5910645 0.5 0.5908203 1 0.5905762 0.5 0.5908203 0.5 0.5905762 1 0.590332 0.5 0.5905762 0.5 0.590332 1 0.5900879 0.5 0.590332 0.5 0.5900879 1 0.5898438 0.5 0.5900879 0.5 0.5898438 1 0.5895996 0.5 0.5898438 0.5 0.5895996 1 0.5893555 0.5 0.5895996 0.5 0.5893555 1 0.5891113 0.5 0.5893555 0.5 0.5891113 1 0.5888672 0.5 0.5891113 0.5 0.5888672 1 0.5886231 0.5 0.5888672 0.5 0.5886231 1 0.5883789 0.5 0.5886231 0.5 0.5883789 1 0.5881348 0.5 0.5883789 0.5 0.5881348 1 0.5878906 0.5 0.5881348 0.5 0.5878906 1 0.5876465 0.5 0.5878906 0.5 0.5876465 1 0.5874024 0.5 0.5876465 0.5 0.5874024 1 0.5871582 0.5 0.5874024 0.5 0.5871582 1 0.5869141 0.5 0.5871582 0.5 0.5869141 1 0.5866699 0.5 0.5869141 0.5 0.5866699 1 0.5864258 0.5 0.5866699 0.5 0.5864258 1 0.5861817 0.5 0.5864258 0.5 0.5861817 1 0.5859375 0.5 0.5861817 0.5 0.5859375 1 0.5856934 0.5 0.5859375 0.5 0.5856934 1 0.5854492 0.5 0.5856934 0.5 0.5854492 1 0.5852051 0.5 0.5854492 0.5 0.5852051 1 0.5849609 0.5 0.5852051 0.5 0.5849609 1 0.5847168 0.5 0.5849609 0.5 0.5847168 1 0.5844727 0.5 0.5847168 0.5 0.5844727 1 0.5842285 0.5 0.5844727 0.5 0.5842285 1 0.5839844 0.5 0.5842285 0.5 0.5839844 1 0.5837402 0.5 0.5839844 0.5 0.5837402 1 0.5834961 0.5 0.5837402 0.5 0.5834961 1 0.583252 0.5 0.5834961 0.5 0.583252 1 0.5830078 0.5 0.583252 0.5 0.5830078 1 0.5827637 0.5 0.5830078 0.5 0.5827637 1 0.5825195 0.5 0.5827637 0.5 0.5825195 1 0.5822754 0.5 0.5825195 0.5 0.5822754 1 0.5820313 0.5 0.5822754 0.5 0.5820313 1 0.5817871 0.5 0.5820313 0.5 0.5817871 1 0.581543 0.5 0.5817871 0.5 0.581543 1 0.5812988 0.5 0.581543 0.5 0.5812988 1 0.5810547 0.5 0.5812988 0.5 0.5810547 1 0.5808106 0.5 0.5810547 0.5 0.5808106 1 0.5805664 0.5 0.5808106 0.5 0.5805664 1 0.5803223 0.5 0.5805664 0.5 0.5803223 1 0.5800781 0.5 0.5803223 0.5 0.5800781 1 0.579834 0.5 0.5800781 0.5 0.579834 1 0.5795899 0.5 0.579834 0.5 0.5795899 1 0.5793457 0.5 0.5795899 0.5 0.5793457 1 0.5791016 0.5 0.5793457 0.5 0.5791016 1 0.5788574 0.5 0.5791016 0.5 0.5788574 1 0.5786133 0.5 0.5788574 0.5 0.5786133 1 0.5783692 0.5 0.5786133 0.5 0.5783692 1 0.578125 0.5 0.5783692 0.5 0.578125 1 0.5778809 0.5 0.578125 0.5 0.5778809 1 0.5776367 0.5 0.5778809 0.5 0.5776367 1 0.5773926 0.5 0.5776367 0.5 0.5773926 1 0.5771484 0.5 0.5773926 0.5 0.5771484 1 0.5769043 0.5 0.5771484 0.5 0.5769043 1 0.5766602 0.5 0.5769043 0.5 0.5766602 1 0.576416 0.5 0.5766602 0.5 0.576416 1 0.5761719 0.5 0.576416 0.5 0.5761719 1 0.5759277 0.5 0.5761719 0.5 0.5759277 1 0.5756836 0.5 0.5759277 0.5 0.5756836 1 0.5754395 0.5 0.5756836 0.5 0.5754395 1 0.5751953 0.5 0.5754395 0.5 0.5751953 1 0.5749512 0.5 0.5751953 0.5 0.5749512 1 0.574707 0.5 0.5749512 0.5 0.574707 1 0.5744629 0.5 0.574707 0.5 0.5744629 1 0.5742188 0.5 0.5744629 0.5 0.5742188 1 0.5739746 0.5 0.5742188 0.5 0.5739746 1 0.5737305 0.5 0.5739746 0.5 0.5737305 1 0.5734863 0.5 0.5737305 0.5 0.5734863 1 0.5732422 0.5 0.5734863 0.5 0.5732422 1 0.5729981 0.5 0.5732422 0.5 0.5729981 1 0.5727539 0.5 0.5729981 0.5 0.5727539 1 0.5725098 0.5 0.5727539 0.5 0.5725098 1 0.5722656 0.5 0.5725098 0.5 0.5722656 1 0.5720215 0.5 0.5722656 0.5 0.5720215 1 0.5717774 0.5 0.5720215 0.5 0.5717774 1 0.5715332 0.5 0.5717774 0.5 0.5715332 1 0.5712891 0.5 0.5715332 0.5 0.5712891 1 0.5710449 0.5 0.5712891 0.5 0.5710449 1 0.5708008 0.5 0.5710449 0.5 0.5708008 1 0.5705567 0.5 0.5708008 0.5 0.5705567 1 0.5703125 0.5 0.5705567 0.5 0.5703125 1 0.5700684 0.5 0.5703125 0.5 0.5700684 1 0.5698242 0.5 0.5700684 0.5 0.5698242 1 0.5695801 0.5 0.5698242 0.5 0.5695801 1 0.5693359 0.5 0.5695801 0.5 0.5693359 1 0.5690918 0.5 0.5693359 0.5 0.5690918 1 0.5688477 0.5 0.5690918 0.5 0.5688477 1 0.5686035 0.5 0.5688477 0.5 0.5686035 1 0.5683594 0.5 0.5686035 0.5 0.5683594 1 0.5681152 0.5 0.5683594 0.5 0.5681152 1 0.5678711 0.5 0.5681152 0.5 0.5678711 1 0.567627 0.5 0.5678711 0.5 0.567627 1 0.5673828 0.5 0.567627 0.5 0.5673828 1 0.5671387 0.5 0.5673828 0.5 0.5671387 1 0.5668945 0.5 0.5671387 0.5 0.5668945 1 0.5666504 0.5 0.5668945 0.5 0.5666504 1 0.5664063 0.5 0.5666504 0.5 0.5664063 1 0.5661621 0.5 0.5664063 0.5 0.5661621 1 0.565918 0.5 0.5661621 0.5 0.565918 1 0.5656738 0.5 0.565918 0.5 0.5656738 1 0.5654297 0.5 0.5656738 0.5 0.5654297 1 0.5651856 0.5 0.5654297 0.5 0.5651856 1 0.5649414 0.5 0.5651856 0.5 0.5649414 1 0.5646973 0.5 0.5649414 0.5 0.5646973 1 0.5644531 0.5 0.5646973 0.5 0.5644531 1 0.564209 0.5 0.5644531 0.5 0.564209 1 0.5639649 0.5 0.564209 0.5 0.5639649 1 0.5637207 0.5 0.5639649 0.5 0.5637207 1 0.5634766 0.5 0.5637207 0.5 0.5634766 1 0.5632324 0.5 0.5634766 0.5 0.5632324 1 0.5629883 0.5 0.5632324 0.5 0.5629883 1 0.5627442 0.5 0.5629883 0.5 0.5627442 1 0.5625 0.5 0.5627442 0.5 0.5625 1 0.5622559 0.5 0.5625 0.5 0.5622559 1 0.5620117 0.5 0.5622559 0.5 0.5620117 1 0.5617676 0.5 0.5620117 0.5 0.5617676 1 0.5615234 0.5 0.5617676 0.5 0.5615234 1 0.5612793 0.5 0.5615234 0.5 0.5612793 1 0.5610352 0.5 0.5612793 0.5 0.5610352 1 0.560791 0.5 0.5610352 0.5 0.560791 1 0.5605469 0.5 0.560791 0.5 0.5605469 1 0.5603027 0.5 0.5605469 0.5 0.5603027 1 0.5600586 0.5 0.5603027 0.5 0.5600586 1 0.5598145 0.5 0.5600586 0.5 0.5598145 1 0.5595703 0.5 0.5598145 0.5 0.5595703 1 0.5593262 0.5 0.5595703 0.5 0.5593262 1 0.559082 0.5 0.5593262 0.5 0.559082 1 0.5588379 0.5 0.559082 0.5 0.5588379 1 0.5585938 0.5 0.5588379 0.5 0.5585938 1 0.5583496 0.5 0.5585938 0.5 0.5583496 1 0.5581055 0.5 0.5583496 0.5 0.5581055 1 0.5578613 0.5 0.5581055 0.5 0.5578613 1 0.5576172 0.5 0.5578613 0.5 0.5576172 1 0.5573731 0.5 0.5576172 0.5 0.5573731 1 0.5571289 0.5 0.5573731 0.5 0.5571289 1 0.5568848 0.5 0.5571289 0.5 0.5568848 1 0.5566406 0.5 0.5568848 0.5 0.5566406 1 0.5563965 0.5 0.5566406 0.5 0.5563965 1 0.5561524 0.5 0.5563965 0.5 0.5561524 1 0.5559082 0.5 0.5561524 0.5 0.5559082 1 0.5556641 0.5 0.5559082 0.5 0.5556641 1 0.5554199 0.5 0.5556641 0.5 0.5554199 1 0.5551758 0.5 0.5554199 0.5 0.5551758 1 0.5549317 0.5 0.5551758 0.5 0.5549317 1 0.5546875 0.5 0.5549317 0.5 0.5546875 1 0.5544434 0.5 0.5546875 0.5 0.5544434 1 0.5541992 0.5 0.5544434 0.5 0.5541992 1 0.5539551 0.5 0.5541992 0.5 0.5539551 1 0.5537109 0.5 0.5539551 0.5 0.5537109 1 0.5534668 0.5 0.5537109 0.5 0.5534668 1 0.5532227 0.5 0.5534668 0.5 0.5532227 1 0.5529785 0.5 0.5532227 0.5 0.5529785 1 0.5527344 0.5 0.5529785 0.5 0.5527344 1 0.5524902 0.5 0.5527344 0.5 0.5524902 1 0.5522461 0.5 0.5524902 0.5 0.5522461 1 0.552002 0.5 0.5522461 0.5 0.552002 1 0.5517578 0.5 0.552002 0.5 0.5517578 1 0.5515137 0.5 0.5517578 0.5 0.5515137 1 0.5512695 0.5 0.5515137 0.5 0.5512695 1 0.5510254 0.5 0.5512695 0.5 0.5510254 1 0.5507813 0.5 0.5510254 0.5 0.5507813 1 0.5505371 0.5 0.5507813 0.5 0.5505371 1 0.550293 0.5 0.5505371 0.5 0.550293 1 0.5500488 0.5 0.550293 0.5 0.5500488 1 0.5498047 0.5 0.5500488 0.5 0.5498047 1 0.5495606 0.5 0.5498047 0.5 0.5495606 1 0.5493164 0.5 0.5495606 0.5 0.5493164 1 0.5490723 0.5 0.5493164 0.5 0.5490723 1 0.5488281 0.5 0.5490723 0.5 0.5488281 1 0.548584 0.5 0.5488281 0.5 0.548584 1 0.5483399 0.5 0.548584 0.5 0.5483399 1 0.5480957 0.5 0.5483399 0.5 0.5480957 1 0.5478516 0.5 0.5480957 0.5 0.5478516 1 0.5476074 0.5 0.5478516 0.5 0.5476074 1 0.5473633 0.5 0.5476074 0.5 0.5473633 1 0.5471192 0.5 0.5473633 0.5 0.5471192 1 0.546875 0.5 0.5471192 0.5 0.546875 1 0.5466309 0.5 0.546875 0.5 0.5466309 1 0.5463867 0.5 0.5466309 0.5 0.5463867 1 0.5461426 0.5 0.5463867 0.5 0.5461426 1 0.5458984 0.5 0.5461426 0.5 0.5458984 1 0.5456543 0.5 0.5458984 0.5 0.5456543 1 0.5454102 0.5 0.5456543 0.5 0.5454102 1 0.545166 0.5 0.5454102 0.5 0.545166 1 0.5449219 0.5 0.545166 0.5 0.5449219 1 0.5446777 0.5 0.5449219 0.5 0.5446777 1 0.5444336 0.5 0.5446777 0.5 0.5444336 1 0.5441895 0.5 0.5444336 0.5 0.5441895 1 0.5439453 0.5 0.5441895 0.5 0.5439453 1 0.5437012 0.5 0.5439453 0.5 0.5437012 1 0.543457 0.5 0.5437012 0.5 0.543457 1 0.5432129 0.5 0.543457 0.5 0.5432129 1 0.5429688 0.5 0.5432129 0.5 0.5429688 1 0.5427246 0.5 0.5429688 0.5 0.5427246 1 0.5424805 0.5 0.5427246 0.5 0.5424805 1 0.5422363 0.5 0.5424805 0.5 0.5422363 1 0.5419922 0.5 0.5422363 0.5 0.5419922 1 0.5417481 0.5 0.5419922 0.5 0.5417481 1 0.5415039 0.5 0.5417481 0.5 0.5415039 1 0.5412598 0.5 0.5415039 0.5 0.5412598 1 0.5410156 0.5 0.5412598 0.5 0.5410156 1 0.5407715 0.5 0.5410156 0.5 0.5407715 1 0.5405274 0.5 0.5407715 0.5 0.5405274 1 0.5402832 0.5 0.5405274 0.5 0.5402832 1 0.5400391 0.5 0.5402832 0.5 0.5400391 1 0.5397949 0.5 0.5400391 0.5 0.5397949 1 0.5395508 0.5 0.5397949 0.5 0.5395508 1 0.5393067 0.5 0.5395508 0.5 0.5393067 1 0.5390625 0.5 0.5393067 0.5 0.5390625 1 0.5388184 0.5 0.5390625 0.5 0.5388184 1 0.5385742 0.5 0.5388184 0.5 0.5385742 1 0.5383301 0.5 0.5385742 0.5 0.5383301 1 0.5380859 0.5 0.5383301 0.5 0.5380859 1 0.5378418 0.5 0.5380859 0.5 0.5378418 1 0.5375977 0.5 0.5378418 0.5 0.5375977 1 0.5373535 0.5 0.5375977 0.5 0.5373535 1 0.5371094 0.5 0.5373535 0.5 0.5371094 1 0.5368652 0.5 0.5371094 0.5 0.5368652 1 0.5366211 0.5 0.5368652 0.5 0.5366211 1 0.536377 0.5 0.5366211 0.5 0.536377 1 0.5361328 0.5 0.536377 0.5 0.5361328 1 0.5358887 0.5 0.5361328 0.5 0.5358887 1 0.5356445 0.5 0.5358887 0.5 0.5356445 1 0.5354004 0.5 0.5356445 0.5 0.5354004 1 0.5351563 0.5 0.5354004 0.5 0.5351563 1 0.5349121 0.5 0.5351563 0.5 0.5349121 1 0.534668 0.5 0.5349121 0.5 0.534668 1 0.5344238 0.5 0.534668 0.5 0.5344238 1 0.5341797 0.5 0.5344238 0.5 0.5341797 1 0.5339356 0.5 0.5341797 0.5 0.5339356 1 0.5336914 0.5 0.5339356 0.5 0.5336914 1 0.5334473 0.5 0.5336914 0.5 0.5334473 1 0.5332031 0.5 0.5334473 0.5 0.5332031 1 0.532959 0.5 0.5332031 0.5 0.532959 1 0.5327149 0.5 0.532959 0.5 0.5327149 1 0.5324707 0.5 0.5327149 0.5 0.5324707 1 0.5322266 0.5 0.5324707 0.5 0.5322266 1 0.5319824 0.5 0.5322266 0.5 0.5319824 1 0.5317383 0.5 0.5319824 0.5 0.5317383 1 0.5314942 0.5 0.5317383 0.5 0.5314942 1 0.53125 0.5 0.5314942 0.5 0.53125 1 0.5310059 0.5 0.53125 0.5 0.5310059 1 0.5307617 0.5 0.5310059 0.5 0.5307617 1 0.5305176 0.5 0.5307617 0.5 0.5305176 1 0.5302734 0.5 0.5305176 0.5 0.5302734 1 0.5300293 0.5 0.5302734 0.5 0.5300293 1 0.5297852 0.5 0.5300293 0.5 0.5297852 1 0.529541 0.5 0.5297852 0.5 0.529541 1 0.5292969 0.5 0.529541 0.5 0.5292969 1 0.5290527 0.5 0.5292969 0.5 0.5290527 1 0.5288086 0.5 0.5290527 0.5 0.5288086 1 0.5285645 0.5 0.5288086 0.5 0.5285645 1 0.5283203 0.5 0.5285645 0.5 0.5283203 1 0.5280762 0.5 0.5283203 0.5 0.5280762 1 0.527832 0.5 0.5280762 0.5 0.527832 1 0.5275879 0.5 0.527832 0.5 0.5275879 1 0.5273438 0.5 0.5275879 0.5 0.5273438 1 0.5270996 0.5 0.5273438 0.5 0.5270996 1 0.5268555 0.5 0.5270996 0.5 0.5268555 1 0.5266113 0.5 0.5268555 0.5 0.5266113 1 0.5263672 0.5 0.5266113 0.5 0.5263672 1 0.5261231 0.5 0.5263672 0.5 0.5261231 1 0.5258789 0.5 0.5261231 0.5 0.5258789 1 0.5256348 0.5 0.5258789 0.5 0.5256348 1 0.5253906 0.5 0.5256348 0.5 0.5253906 1 0.5251465 0.5 0.5253906 0.5 0.5251465 1 0.5249024 0.5 0.5251465 0.5 0.5249024 1 0.5246582 0.5 0.5249024 0.5 0.5246582 1 0.5244141 0.5 0.5246582 0.5 0.5244141 1 0.5241699 0.5 0.5244141 0.5 0.5241699 1 0.5239258 0.5 0.5241699 0.5 0.5239258 1 0.5236817 0.5 0.5239258 0.5 0.5236817 1 0.5234375 0.5 0.5236817 0.5 0.5234375 1 0.5231934 0.5 0.5234375 0.5 0.5231934 1 0.5229492 0.5 0.5231934 0.5 0.5229492 1 0.5227051 0.5 0.5229492 0.5 0.5227051 1 0.5224609 0.5 0.5227051 0.5 0.5224609 1 0.5222168 0.5 0.5224609 0.5 0.5222168 1 0.5219727 0.5 0.5222168 0.5 0.5219727 1 0.5217285 0.5 0.5219727 0.5 0.5217285 1 0.5214844 0.5 0.5217285 0.5 0.5214844 1 0.5212402 0.5 0.5214844 0.5 0.5212402 1 0.5209961 0.5 0.5212402 0.5 0.5209961 1 0.520752 0.5 0.5209961 0.5 0.520752 1 0.5205078 0.5 0.520752 0.5 0.5205078 1 0.5202637 0.5 0.5205078 0.5 0.5202637 1 0.5200195 0.5 0.5202637 0.5 0.5200195 1 0.5197754 0.5 0.5200195 0.5 0.5197754 1 0.5195313 0.5 0.5197754 0.5 0.5195313 1 0.5192871 0.5 0.5195313 0.5 0.5192871 1 0.519043 0.5 0.5192871 0.5 0.519043 1 0.5187988 0.5 0.519043 0.5 0.5187988 1 0.5185547 0.5 0.5187988 0.5 0.5185547 1 0.5183106 0.5 0.5185547 0.5 0.5183106 1 0.5180664 0.5 0.5183106 0.5 0.5180664 1 0.5178223 0.5 0.5180664 0.5 0.5178223 1 0.5175781 0.5 0.5178223 0.5 0.5175781 1 0.517334 0.5 0.5175781 0.5 0.517334 1 0.5170899 0.5 0.517334 0.5 0.5170899 1 0.5168457 0.5 0.5170899 0.5 0.5168457 1 0.5166016 0.5 0.5168457 0.5 0.5166016 1 0.5163574 0.5 0.5166016 0.5 0.5163574 1 0.5161133 0.5 0.5163574 0.5 0.5161133 1 0.5158692 0.5 0.5161133 0.5 0.5158692 1 0.515625 0.5 0.5158692 0.5 0.515625 1 0.5153809 0.5 0.515625 0.5 0.5153809 1 0.5151367 0.5 0.5153809 0.5 0.5151367 1 0.5148926 0.5 0.5151367 0.5 0.5148926 1 0.5146484 0.5 0.5148926 0.5 0.5146484 1 0.5144043 0.5 0.5146484 0.5 0.5144043 1 0.5141602 0.5 0.5144043 0.5 0.5141602 1 0.513916 0.5 0.5141602 0.5 0.513916 1 0.5136719 0.5 0.513916 0.5 0.5136719 1 0.5134277 0.5 0.5136719 0.5 0.5134277 1 0.5131836 0.5 0.5134277 0.5 0.5131836 1 0.5129395 0.5 0.5131836 0.5 0.5129395 1 0.5126953 0.5 0.5129395 0.5 0.5126953 1 0.5124512 0.5 0.5126953 0.5 0.5124512 1 0.512207 0.5 0.5124512 0.5 0.512207 1 0.5119629 0.5 0.512207 0.5 0.5119629 1 0.5117188 0.5 0.5119629 0.5 0.5117188 1 0.5114746 0.5 0.5117188 0.5 0.5114746 1 0.5112305 0.5 0.5114746 0.5 0.5112305 1 0.5109863 0.5 0.5112305 0.5 0.5109863 1 0.5107422 0.5 0.5109863 0.5 0.5107422 1 0.5104981 0.5 0.5107422 0.5 0.5104981 1 0.5102539 0.5 0.5104981 0.5 0.5102539 1 0.5100098 0.5 0.5102539 0.5 0.5100098 1 0.5097656 0.5 0.5100098 0.5 0.5097656 1 0.5095215 0.5 0.5097656 0.5 0.5095215 1 0.5092774 0.5 0.5095215 0.5 0.5092774 1 0.5090332 0.5 0.5092774 0.5 0.5090332 1 0.5087891 0.5 0.5090332 0.5 0.5087891 1 0.5085449 0.5 0.5087891 0.5 0.5085449 1 0.5083008 0.5 0.5085449 0.5 0.5083008 1 0.5080567 0.5 0.5083008 0.5 0.5080567 1 0.5078125 0.5 0.5080567 0.5 0.5078125 1 0.5075684 0.5 0.5078125 0.5 0.5075684 1 0.5073242 0.5 0.5075684 0.5 0.5073242 1 0.5070801 0.5 0.5073242 0.5 0.5070801 1 0.5068359 0.5 0.5070801 0.5 0.5068359 1 0.5065918 0.5 0.5068359 0.5 0.5065918 1 0.5063477 0.5 0.5065918 0.5 0.5063477 1 0.5061035 0.5 0.5063477 0.5 0.5061035 1 0.5058594 0.5 0.5061035 0.5 0.5058594 1 0.5056152 0.5 0.5058594 0.5 0.5056152 1 0.5053711 0.5 0.5056152 0.5 0.5053711 1 0.505127 0.5 0.5053711 0.5 0.505127 1 0.5048828 0.5 0.505127 0.5 0.5048828 1 0.5046387 0.5 0.5048828 0.5 0.5046387 1 0.5043945 0.5 0.5046387 0.5 0.5043945 1 0.5041504 0.5 0.5043945 0.5 0.5041504 1 0.5039063 0.5 0.5041504 0.5 0.5039063 1 0.5036621 0.5 0.5039063 0.5 0.5036621 1 0.503418 0.5 0.5036621 0.5 0.503418 1 0.5031738 0.5 0.503418 0.5 0.5031738 1 0.5029297 0.5 0.5031738 0.5 0.5029297 1 0.5026856 0.5 0.5029297 0.5 0.5026856 1 0.5024414 0.5 0.5026856 0.5 0.5024414 1 0.5021973 0.5 0.5024414 0.5 0.5021973 1 0.5019531 0.5 0.5021973 0.5 0.5019531 1 0.501709 0.5 0.5019531 0.5 0.501709 1 0.5014649 0.5 0.501709 0.5 0.5014649 1 0.5012207 0.5 0.5014649 0.5 0.5012207 1 0.5009766 0.5 0.5012207 0.5 0.5009766 1 0.5007324 0.5 0.5009766 0.5 0.5007324 1 0.5004883 0.5 0.5007324 0.5 0.5004883 1 0.5002442 0.5 0.5004883 0.5 0.5002442 1 0.5 0.5 0.5002442 0.5 0.5 1 0.4997559 0.5 0.5 0.5 0.4997559 1 0.4995117 0.5 0.4997559 0.5 0.4995117 1 0.4992676 0.5 0.4995117 0.5 0.4992676 1 0.4990234 0.5 0.4992676 0.5 0.4990234 1 0.4987793 0.5 0.4990234 0.5 0.4987793 1 0.4985352 0.5 0.4987793 0.5 0.4985352 1 0.498291 0.5 0.4985352 0.5 0.498291 1 0.4980469 0.5 0.498291 0.5 0.4980469 1 0.4978027 0.5 0.4980469 0.5 0.4978027 1 0.4975586 0.5 0.4978027 0.5 0.4975586 1 0.4973145 0.5 0.4975586 0.5 0.4973145 1 0.4970703 0.5 0.4973145 0.5 0.4970703 1 0.4968262 0.5 0.4970703 0.5 0.4968262 1 0.496582 0.5 0.4968262 0.5 0.496582 1 0.4963379 0.5 0.496582 0.5 0.4963379 1 0.4960938 0.5 0.4963379 0.5 0.4960938 1 0.4958496 0.5 0.4960938 0.5 0.4958496 1 0.4956055 0.5 0.4958496 0.5 0.4956055 1 0.4953613 0.5 0.4956055 0.5 0.4953613 1 0.4951172 0.5 0.4953613 0.5 0.4951172 1 0.4948731 0.5 0.4951172 0.5 0.4948731 1 0.4946289 0.5 0.4948731 0.5 0.4946289 1 0.4943848 0.5 0.4946289 0.5 0.4943848 1 0.4941406 0.5 0.4943848 0.5 0.4941406 1 0.4938965 0.5 0.4941406 0.5 0.4938965 1 0.4936524 0.5 0.4938965 0.5 0.4936524 1 0.4934082 0.5 0.4936524 0.5 0.4934082 1 0.4931641 0.5 0.4934082 0.5 0.4931641 1 0.4929199 0.5 0.4931641 0.5 0.4929199 1 0.4926758 0.5 0.4929199 0.5 0.4926758 1 0.4924317 0.5 0.4926758 0.5 0.4924317 1 0.4921875 0.5 0.4924317 0.5 0.4921875 1 0.4919434 0.5 0.4921875 0.5 0.4919434 1 0.4916992 0.5 0.4919434 0.5 0.4916992 1 0.4914551 0.5 0.4916992 0.5 0.4914551 1 0.4912109 0.5 0.4914551 0.5 0.4912109 1 0.4909668 0.5 0.4912109 0.5 0.4909668 1 0.4907227 0.5 0.4909668 0.5 0.4907227 1 0.4904785 0.5 0.4907227 0.5 0.4904785 1 0.4902344 0.5 0.4904785 0.5 0.4902344 1 0.4899902 0.5 0.4902344 0.5 0.4899902 1 0.4897461 0.5 0.4899902 0.5 0.4897461 1 0.489502 0.5 0.4897461 0.5 0.489502 1 0.4892578 0.5 0.489502 0.5 0.4892578 1 0.4890137 0.5 0.4892578 0.5 0.4890137 1 0.4887695 0.5 0.4890137 0.5 0.4887695 1 0.4885254 0.5 0.4887695 0.5 0.4885254 1 0.4882813 0.5 0.4885254 0.5 0.4882813 1 0.4880371 0.5 0.4882813 0.5 0.4880371 1 0.487793 0.5 0.4880371 0.5 0.487793 1 0.4875488 0.5 0.487793 0.5 0.4875488 1 0.4873047 0.5 0.4875488 0.5 0.4873047 1 0.4870606 0.5 0.4873047 0.5 0.4870606 1 0.4868164 0.5 0.4870606 0.5 0.4868164 1 0.4865723 0.5 0.4868164 0.5 0.4865723 1 0.4863281 0.5 0.4865723 0.5 0.4863281 1 0.486084 0.5 0.4863281 0.5 0.486084 1 0.4858399 0.5 0.486084 0.5 0.4858399 1 0.4855957 0.5 0.4858399 0.5 0.4855957 1 0.4853516 0.5 0.4855957 0.5 0.4853516 1 0.4851074 0.5 0.4853516 0.5 0.4851074 1 0.4848633 0.5 0.4851074 0.5 0.4848633 1 0.4846192 0.5 0.4848633 0.5 0.4846192 1 0.484375 0.5 0.4846192 0.5 0.484375 1 0.4841309 0.5 0.484375 0.5 0.4841309 1 0.4838867 0.5 0.4841309 0.5 0.4838867 1 0.4836426 0.5 0.4838867 0.5 0.4836426 1 0.4833984 0.5 0.4836426 0.5 0.4833984 1 0.4831543 0.5 0.4833984 0.5 0.4831543 1 0.4829102 0.5 0.4831543 0.5 0.4829102 1 0.482666 0.5 0.4829102 0.5 0.482666 1 0.4824219 0.5 0.482666 0.5 0.4824219 1 0.4821777 0.5 0.4824219 0.5 0.4821777 1 0.4819336 0.5 0.4821777 0.5 0.4819336 1 0.4816895 0.5 0.4819336 0.5 0.4816895 1 0.4814453 0.5 0.4816895 0.5 0.4814453 1 0.4812012 0.5 0.4814453 0.5 0.4812012 1 0.480957 0.5 0.4812012 0.5 0.480957 1 0.4807129 0.5 0.480957 0.5 0.4807129 1 0.4804688 0.5 0.4807129 0.5 0.4804688 1 0.4802246 0.5 0.4804688 0.5 0.4802246 1 0.4799805 0.5 0.4802246 0.5 0.4799805 1 0.4797363 0.5 0.4799805 0.5 0.4797363 1 0.4794922 0.5 0.4797363 0.5 0.4794922 1 0.4792481 0.5 0.4794922 0.5 0.4792481 1 0.4790039 0.5 0.4792481 0.5 0.4790039 1 0.4787598 0.5 0.4790039 0.5 0.4787598 1 0.4785156 0.5 0.4787598 0.5 0.4785156 1 0.4782715 0.5 0.4785156 0.5 0.4782715 1 0.4780274 0.5 0.4782715 0.5 0.4780274 1 0.4777832 0.5 0.4780274 0.5 0.4777832 1 0.4775391 0.5 0.4777832 0.5 0.4775391 1 0.4772949 0.5 0.4775391 0.5 0.4772949 1 0.4770508 0.5 0.4772949 0.5 0.4770508 1 0.4768067 0.5 0.4770508 0.5 0.4768067 1 0.4765625 0.5 0.4768067 0.5 0.4765625 1 0.4763184 0.5 0.4765625 0.5 0.4763184 1 0.4760742 0.5 0.4763184 0.5 0.4760742 1 0.4758301 0.5 0.4760742 0.5 0.4758301 1 0.4755859 0.5 0.4758301 0.5 0.4755859 1 0.4753418 0.5 0.4755859 0.5 0.4753418 1 0.4750977 0.5 0.4753418 0.5 0.4750977 1 0.4748535 0.5 0.4750977 0.5 0.4748535 1 0.4746094 0.5 0.4748535 0.5 0.4746094 1 0.4743652 0.5 0.4746094 0.5 0.4743652 1 0.4741211 0.5 0.4743652 0.5 0.4741211 1 0.473877 0.5 0.4741211 0.5 0.473877 1 0.4736328 0.5 0.473877 0.5 0.4736328 1 0.4733887 0.5 0.4736328 0.5 0.4733887 1 0.4731445 0.5 0.4733887 0.5 0.4731445 1 0.4729004 0.5 0.4731445 0.5 0.4729004 1 0.4726563 0.5 0.4729004 0.5 0.4726563 1 0.4724121 0.5 0.4726563 0.5 0.4724121 1 0.472168 0.5 0.4724121 0.5 0.472168 1 0.4719238 0.5 0.472168 0.5 0.4719238 1 0.4716797 0.5 0.4719238 0.5 0.4716797 1 0.4714356 0.5 0.4716797 0.5 0.4714356 1 0.4711914 0.5 0.4714356 0.5 0.4711914 1 0.4709473 0.5 0.4711914 0.5 0.4709473 1 0.4707031 0.5 0.4709473 0.5 0.4707031 1 0.470459 0.5 0.4707031 0.5 0.470459 1 0.4702149 0.5 0.470459 0.5 0.4702149 1 0.4699707 0.5 0.4702149 0.5 0.4699707 1 0.4697266 0.5 0.4699707 0.5 0.4697266 1 0.4694824 0.5 0.4697266 0.5 0.4694824 1 0.4692383 0.5 0.4694824 0.5 0.4692383 1 0.4689942 0.5 0.4692383 0.5 0.4689942 1 0.46875 0.5 0.4689942 0.5 0.46875 1 0.4685059 0.5 0.46875 0.5 0.4685059 1 0.4682617 0.5 0.4685059 0.5 0.4682617 1 0.4680176 0.5 0.4682617 0.5 0.4680176 1 0.4677734 0.5 0.4680176 0.5 0.4677734 1 0.4675293 0.5 0.4677734 0.5 0.4675293 1 0.4672852 0.5 0.4675293 0.5 0.4672852 1 0.467041 0.5 0.4672852 0.5 0.467041 1 0.4667969 0.5 0.467041 0.5 0.4667969 1 0.4665527 0.5 0.4667969 0.5 0.4665527 1 0.4663086 0.5 0.4665527 0.5 0.4663086 1 0.4660645 0.5 0.4663086 0.5 0.4660645 1 0.4658203 0.5 0.4660645 0.5 0.4658203 1 0.4655762 0.5 0.4658203 0.5 0.4655762 1 0.465332 0.5 0.4655762 0.5 0.465332 1 0.4650879 0.5 0.465332 0.5 0.4650879 1 0.4648438 0.5 0.4650879 0.5 0.4648438 1 0.4645996 0.5 0.4648438 0.5 0.4645996 1 0.4643555 0.5 0.4645996 0.5 0.4643555 1 0.4641113 0.5 0.4643555 0.5 0.4641113 1 0.4638672 0.5 0.4641113 0.5 0.4638672 1 0.4636231 0.5 0.4638672 0.5 0.4636231 1 0.4633789 0.5 0.4636231 0.5 0.4633789 1 0.4631348 0.5 0.4633789 0.5 0.4631348 1 0.4628906 0.5 0.4631348 0.5 0.4628906 1 0.4626465 0.5 0.4628906 0.5 0.4626465 1 0.4624024 0.5 0.4626465 0.5 0.4624024 1 0.4621582 0.5 0.4624024 0.5 0.4621582 1 0.4619141 0.5 0.4621582 0.5 0.4619141 1 0.4616699 0.5 0.4619141 0.5 0.4616699 1 0.4614258 0.5 0.4616699 0.5 0.4614258 1 0.4611817 0.5 0.4614258 0.5 0.4611817 1 0.4609375 0.5 0.4611817 0.5 0.4609375 1 0.4606934 0.5 0.4609375 0.5 0.4606934 1 0.4604492 0.5 0.4606934 0.5 0.4604492 1 0.4602051 0.5 0.4604492 0.5 0.4602051 1 0.4599609 0.5 0.4602051 0.5 0.4599609 1 0.4597168 0.5 0.4599609 0.5 0.4597168 1 0.4594727 0.5 0.4597168 0.5 0.4594727 1 0.4592285 0.5 0.4594727 0.5 0.4592285 1 0.4589844 0.5 0.4592285 0.5 0.4589844 1 0.4587402 0.5 0.4589844 0.5 0.4587402 1 0.4584961 0.5 0.4587402 0.5 0.4584961 1 0.458252 0.5 0.4584961 0.5 0.458252 1 0.4580078 0.5 0.458252 0.5 0.4580078 1 0.4577637 0.5 0.4580078 0.5 0.4577637 1 0.4575195 0.5 0.4577637 0.5 0.4575195 1 0.4572754 0.5 0.4575195 0.5 0.4572754 1 0.4570313 0.5 0.4572754 0.5 0.4570313 1 0.4567871 0.5 0.4570313 0.5 0.4567871 1 0.456543 0.5 0.4567871 0.5 0.456543 1 0.4562988 0.5 0.456543 0.5 0.4562988 1 0.4560547 0.5 0.4562988 0.5 0.4560547 1 0.4558106 0.5 0.4560547 0.5 0.4558106 1 0.4555664 0.5 0.4558106 0.5 0.4555664 1 0.4553223 0.5 0.4555664 0.5 0.4553223 1 0.4550781 0.5 0.4553223 0.5 0.4550781 1 0.454834 0.5 0.4550781 0.5 0.454834 1 0.4545899 0.5 0.454834 0.5 0.4545899 1 0.4543457 0.5 0.4545899 0.5 0.4543457 1 0.4541016 0.5 0.4543457 0.5 0.4541016 1 0.4538574 0.5 0.4541016 0.5 0.4538574 1 0.4536133 0.5 0.4538574 0.5 0.4536133 1 0.4533692 0.5 0.4536133 0.5 0.4533692 1 0.453125 0.5 0.4533692 0.5 0.453125 1 0.4528809 0.5 0.453125 0.5 0.4528809 1 0.4526367 0.5 0.4528809 0.5 0.4526367 1 0.4523926 0.5 0.4526367 0.5 0.4523926 1 0.4521484 0.5 0.4523926 0.5 0.4521484 1 0.4519043 0.5 0.4521484 0.5 0.4519043 1 0.4516602 0.5 0.4519043 0.5 0.4516602 1 0.451416 0.5 0.4516602 0.5 0.451416 1 0.4511719 0.5 0.451416 0.5 0.4511719 1 0.4509277 0.5 0.4511719 0.5 0.4509277 1 0.4506836 0.5 0.4509277 0.5 0.4506836 1 0.4504395 0.5 0.4506836 0.5 0.4504395 1 0.4501953 0.5 0.4504395 0.5 0.4501953 1 0.4499512 0.5 0.4501953 0.5 0.4499512 1 0.449707 0.5 0.4499512 0.5 0.449707 1 0.4494629 0.5 0.449707 0.5 0.4494629 1 0.4492188 0.5 0.4494629 0.5 0.4492188 1 0.4489746 0.5 0.4492188 0.5 0.4489746 1 0.4487305 0.5 0.4489746 0.5 0.4487305 1 0.4484863 0.5 0.4487305 0.5 0.4484863 1 0.4482422 0.5 0.4484863 0.5 0.4482422 1 0.4479981 0.5 0.4482422 0.5 0.4479981 1 0.4477539 0.5 0.4479981 0.5 0.4477539 1 0.4475098 0.5 0.4477539 0.5 0.4475098 1 0.4472656 0.5 0.4475098 0.5 0.4472656 1 0.4470215 0.5 0.4472656 0.5 0.4470215 1 0.4467774 0.5 0.4470215 0.5 0.4467774 1 0.4465332 0.5 0.4467774 0.5 0.4465332 1 0.4462891 0.5 0.4465332 0.5 0.4462891 1 0.4460449 0.5 0.4462891 0.5 0.4460449 1 0.4458008 0.5 0.4460449 0.5 0.4458008 1 0.4455567 0.5 0.4458008 0.5 0.4455567 1 0.4453125 0.5 0.4455567 0.5 0.4453125 1 0.4450684 0.5 0.4453125 0.5 0.4450684 1 0.4448242 0.5 0.4450684 0.5 0.4448242 1 0.4445801 0.5 0.4448242 0.5 0.4445801 1 0.4443359 0.5 0.4445801 0.5 0.4443359 1 0.4440918 0.5 0.4443359 0.5 0.4440918 1 0.4438477 0.5 0.4440918 0.5 0.4438477 1 0.4436035 0.5 0.4438477 0.5 0.4436035 1 0.4433594 0.5 0.4436035 0.5 0.4433594 1 0.4431152 0.5 0.4433594 0.5 0.4431152 1 0.4428711 0.5 0.4431152 0.5 0.4428711 1 0.442627 0.5 0.4428711 0.5 0.442627 1 0.4423828 0.5 0.442627 0.5 0.4423828 1 0.4421387 0.5 0.4423828 0.5 0.4421387 1 0.4418945 0.5 0.4421387 0.5 0.4418945 1 0.4416504 0.5 0.4418945 0.5 0.4416504 1 0.4414063 0.5 0.4416504 0.5 0.4414063 1 0.4411621 0.5 0.4414063 0.5 0.4411621 1 0.440918 0.5 0.4411621 0.5 0.440918 1 0.4406738 0.5 0.440918 0.5 0.4406738 1 0.4404297 0.5 0.4406738 0.5 0.4404297 1 0.4401856 0.5 0.4404297 0.5 0.4401856 1 0.4399414 0.5 0.4401856 0.5 0.4399414 1 0.4396973 0.5 0.4399414 0.5 0.4396973 1 0.4394531 0.5 0.4396973 0.5 0.4394531 1 0.439209 0.5 0.4394531 0.5 0.439209 1 0.4389649 0.5 0.439209 0.5 0.4389649 1 0.4387207 0.5 0.4389649 0.5 0.4387207 1 0.4384766 0.5 0.4387207 0.5 0.4384766 1 0.4382324 0.5 0.4384766 0.5 0.4382324 1 0.4379883 0.5 0.4382324 0.5 0.4379883 1 0.4377442 0.5 0.4379883 0.5 0.4377442 1 0.4375 0.5 0.4377442 0.5 0.4375 1 0.4372559 0.5 0.4375 0.5 0.4372559 1 0.4370117 0.5 0.4372559 0.5 0.4370117 1 0.4367676 0.5 0.4370117 0.5 0.4367676 1 0.4365234 0.5 0.4367676 0.5 0.4365234 1 0.4362793 0.5 0.4365234 0.5 0.4362793 1 0.4360352 0.5 0.4362793 0.5 0.4360352 1 0.435791 0.5 0.4360352 0.5 0.435791 1 0.4355469 0.5 0.435791 0.5 0.4355469 1 0.4353027 0.5 0.4355469 0.5 0.4353027 1 0.4350586 0.5 0.4353027 0.5 0.4350586 1 0.4348145 0.5 0.4350586 0.5 0.4348145 1 0.4345703 0.5 0.4348145 0.5 0.4345703 1 0.4343262 0.5 0.4345703 0.5 0.4343262 1 0.434082 0.5 0.4343262 0.5 0.434082 1 0.4338379 0.5 0.434082 0.5 0.4338379 1 0.4335938 0.5 0.4338379 0.5 0.4335938 1 0.4333496 0.5 0.4335938 0.5 0.4333496 1 0.4331055 0.5 0.4333496 0.5 0.4331055 1 0.4328613 0.5 0.4331055 0.5 0.4328613 1 0.4326172 0.5 0.4328613 0.5 0.4326172 1 0.4323731 0.5 0.4326172 0.5 0.4323731 1 0.4321289 0.5 0.4323731 0.5 0.4321289 1 0.4318848 0.5 0.4321289 0.5 0.4318848 1 0.4316406 0.5 0.4318848 0.5 0.4316406 1 0.4313965 0.5 0.4316406 0.5 0.4313965 1 0.4311524 0.5 0.4313965 0.5 0.4311524 1 0.4309082 0.5 0.4311524 0.5 0.4309082 1 0.4306641 0.5 0.4309082 0.5 0.4306641 1 0.4304199 0.5 0.4306641 0.5 0.4304199 1 0.4301758 0.5 0.4304199 0.5 0.4301758 1 0.4299317 0.5 0.4301758 0.5 0.4299317 1 0.4296875 0.5 0.4299317 0.5 0.4296875 1 0.4294434 0.5 0.4296875 0.5 0.4294434 1 0.4291992 0.5 0.4294434 0.5 0.4291992 1 0.4289551 0.5 0.4291992 0.5 0.4289551 1 0.4287109 0.5 0.4289551 0.5 0.4287109 1 0.4284668 0.5 0.4287109 0.5 0.4284668 1 0.4282227 0.5 0.4284668 0.5 0.4282227 1 0.4279785 0.5 0.4282227 0.5 0.4279785 1 0.4277344 0.5 0.4279785 0.5 0.4277344 1 0.4274902 0.5 0.4277344 0.5 0.4274902 1 0.4272461 0.5 0.4274902 0.5 0.4272461 1 0.427002 0.5 0.4272461 0.5 0.427002 1 0.4267578 0.5 0.427002 0.5 0.4267578 1 0.4265137 0.5 0.4267578 0.5 0.4265137 1 0.4262695 0.5 0.4265137 0.5 0.4262695 1 0.4260254 0.5 0.4262695 0.5 0.4260254 1 0.4257813 0.5 0.4260254 0.5 0.4257813 1 0.4255371 0.5 0.4257813 0.5 0.4255371 1 0.425293 0.5 0.4255371 0.5 0.425293 1 0.4250488 0.5 0.425293 0.5 0.4250488 1 0.4248047 0.5 0.4250488 0.5 0.4248047 1 0.4245606 0.5 0.4248047 0.5 0.4245606 1 0.4243164 0.5 0.4245606 0.5 0.4243164 1 0.4240723 0.5 0.4243164 0.5 0.4240723 1 0.4238281 0.5 0.4240723 0.5 0.4238281 1 0.423584 0.5 0.4238281 0.5 0.423584 1 0.4233399 0.5 0.423584 0.5 0.4233399 1 0.4230957 0.5 0.4233399 0.5 0.4230957 1 0.4228516 0.5 0.4230957 0.5 0.4228516 1 0.4226074 0.5 0.4228516 0.5 0.4226074 1 0.4223633 0.5 0.4226074 0.5 0.4223633 1 0.4221192 0.5 0.4223633 0.5 0.4221192 1 0.421875 0.5 0.4221192 0.5 0.421875 1 0.4216309 0.5 0.421875 0.5 0.4216309 1 0.4213867 0.5 0.4216309 0.5 0.4213867 1 0.4211426 0.5 0.4213867 0.5 0.4211426 1 0.4208984 0.5 0.4211426 0.5 0.4208984 1 0.4206543 0.5 0.4208984 0.5 0.4206543 1 0.4204102 0.5 0.4206543 0.5 0.4204102 1 0.420166 0.5 0.4204102 0.5 0.420166 1 0.4199219 0.5 0.420166 0.5 0.4199219 1 0.4196777 0.5 0.4199219 0.5 0.4196777 1 0.4194336 0.5 0.4196777 0.5 0.4194336 1 0.4191895 0.5 0.4194336 0.5 0.4191895 1 0.4189453 0.5 0.4191895 0.5 0.4189453 1 0.4187012 0.5 0.4189453 0.5 0.4187012 1 0.418457 0.5 0.4187012 0.5 0.418457 1 0.4182129 0.5 0.418457 0.5 0.4182129 1 0.4179688 0.5 0.4182129 0.5 0.4179688 1 0.4177246 0.5 0.4179688 0.5 0.4177246 1 0.4174805 0.5 0.4177246 0.5 0.4174805 1 0.4172363 0.5 0.4174805 0.5 0.4172363 1 0.4169922 0.5 0.4172363 0.5 0.4169922 1 0.4167481 0.5 0.4169922 0.5 0.4167481 1 0.4165039 0.5 0.4167481 0.5 0.4165039 1 0.4162598 0.5 0.4165039 0.5 0.4162598 1 0.4160156 0.5 0.4162598 0.5 0.4160156 1 0.4157715 0.5 0.4160156 0.5 0.4157715 1 0.4155274 0.5 0.4157715 0.5 0.4155274 1 0.4152832 0.5 0.4155274 0.5 0.4152832 1 0.4150391 0.5 0.4152832 0.5 0.4150391 1 0.4147949 0.5 0.4150391 0.5 0.4147949 1 0.4145508 0.5 0.4147949 0.5 0.4145508 1 0.4143067 0.5 0.4145508 0.5 0.4143067 1 0.4140625 0.5 0.4143067 0.5 0.4140625 1 0.4138184 0.5 0.4140625 0.5 0.4138184 1 0.4135742 0.5 0.4138184 0.5 0.4135742 1 0.4133301 0.5 0.4135742 0.5 0.4133301 1 0.4130859 0.5 0.4133301 0.5 0.4130859 1 0.4128418 0.5 0.4130859 0.5 0.4128418 1 0.4125977 0.5 0.4128418 0.5 0.4125977 1 0.4123535 0.5 0.4125977 0.5 0.4123535 1 0.4121094 0.5 0.4123535 0.5 0.4121094 1 0.4118652 0.5 0.4121094 0.5 0.4118652 1 0.4116211 0.5 0.4118652 0.5 0.4116211 1 0.411377 0.5 0.4116211 0.5 0.411377 1 0.4111328 0.5 0.411377 0.5 0.4111328 1 0.4108887 0.5 0.4111328 0.5 0.4108887 1 0.4106445 0.5 0.4108887 0.5 0.4106445 1 0.4104004 0.5 0.4106445 0.5 0.4104004 1 0.4101563 0.5 0.4104004 0.5 0.4101563 1 0.4099121 0.5 0.4101563 0.5 0.4099121 1 0.409668 0.5 0.4099121 0.5 0.409668 1 0.4094238 0.5 0.409668 0.5 0.4094238 1 0.4091797 0.5 0.4094238 0.5 0.4091797 1 0.4089356 0.5 0.4091797 0.5 0.4089356 1 0.4086914 0.5 0.4089356 0.5 0.4086914 1 0.4084473 0.5 0.4086914 0.5 0.4084473 1 0.4082031 0.5 0.4084473 0.5 0.4082031 1 0.407959 0.5 0.4082031 0.5 0.407959 1 0.4077149 0.5 0.407959 0.5 0.4077149 1 0.4074707 0.5 0.4077149 0.5 0.4074707 1 0.4072266 0.5 0.4074707 0.5 0.4072266 1 0.4069824 0.5 0.4072266 0.5 0.4069824 1 0.4067383 0.5 0.4069824 0.5 0.4067383 1 0.4064942 0.5 0.4067383 0.5 0.4064942 1 0.40625 0.5 0.4064942 0.5 0.40625 1 0.4060059 0.5 0.40625 0.5 0.4060059 1 0.4057617 0.5 0.4060059 0.5 0.4057617 1 0.4055176 0.5 0.4057617 0.5 0.4055176 1 0.4052734 0.5 0.4055176 0.5 0.4052734 1 0.4050293 0.5 0.4052734 0.5 0.4050293 1 0.4047852 0.5 0.4050293 0.5 0.4047852 1 0.404541 0.5 0.4047852 0.5 0.404541 1 0.4042969 0.5 0.404541 0.5 0.4042969 1 0.4040527 0.5 0.4042969 0.5 0.4040527 1 0.4038086 0.5 0.4040527 0.5 0.4038086 1 0.4035645 0.5 0.4038086 0.5 0.4035645 1 0.4033203 0.5 0.4035645 0.5 0.4033203 1 0.4030762 0.5 0.4033203 0.5 0.4030762 1 0.402832 0.5 0.4030762 0.5 0.402832 1 0.4025879 0.5 0.402832 0.5 0.4025879 1 0.4023438 0.5 0.4025879 0.5 0.4023438 1 0.4020996 0.5 0.4023438 0.5 0.4020996 1 0.4018555 0.5 0.4020996 0.5 0.4018555 1 0.4016113 0.5 0.4018555 0.5 0.4016113 1 0.4013672 0.5 0.4016113 0.5 0.4013672 1 0.4011231 0.5 0.4013672 0.5 0.4011231 1 0.4008789 0.5 0.4011231 0.5 0.4008789 1 0.4006348 0.5 0.4008789 0.5 0.4006348 1 0.4003906 0.5 0.4006348 0.5 0.4003906 1 0.4001465 0.5 0.4003906 0.5 0.4001465 1 0.3999024 0.5 0.4001465 0.5 0.3999024 1 0.3996582 0.5 0.3999024 0.5 0.3996582 1 0.3994141 0.5 0.3996582 0.5 0.3994141 1 0.3991699 0.5 0.3994141 0.5 0.3991699 1 0.3989258 0.5 0.3991699 0.5 0.3989258 1 0.3986817 0.5 0.3989258 0.5 0.3986817 1 0.3984375 0.5 0.3986817 0.5 0.3984375 1 0.3981934 0.5 0.3984375 0.5 0.3981934 1 0.3979492 0.5 0.3981934 0.5 0.3979492 1 0.3977051 0.5 0.3979492 0.5 0.3977051 1 0.3974609 0.5 0.3977051 0.5 0.3974609 1 0.3972168 0.5 0.3974609 0.5 0.3972168 1 0.3969727 0.5 0.3972168 0.5 0.3969727 1 0.3967285 0.5 0.3969727 0.5 0.3967285 1 0.3964844 0.5 0.3967285 0.5 0.3964844 1 0.3962402 0.5 0.3964844 0.5 0.3962402 1 0.3959961 0.5 0.3962402 0.5 0.3959961 1 0.395752 0.5 0.3959961 0.5 0.395752 1 0.3955078 0.5 0.395752 0.5 0.3955078 1 0.3952637 0.5 0.3955078 0.5 0.3952637 1 0.3950195 0.5 0.3952637 0.5 0.3950195 1 0.3947754 0.5 0.3950195 0.5 0.3947754 1 0.3945313 0.5 0.3947754 0.5 0.3945313 1 0.3942871 0.5 0.3945313 0.5 0.3942871 1 0.394043 0.5 0.3942871 0.5 0.394043 1 0.3937988 0.5 0.394043 0.5 0.3937988 1 0.3935547 0.5 0.3937988 0.5 0.3935547 1 0.3933106 0.5 0.3935547 0.5 0.3933106 1 0.3930664 0.5 0.3933106 0.5 0.3930664 1 0.3928223 0.5 0.3930664 0.5 0.3928223 1 0.3925781 0.5 0.3928223 0.5 0.3925781 1 0.392334 0.5 0.3925781 0.5 0.392334 1 0.3920899 0.5 0.392334 0.5 0.3920899 1 0.3918457 0.5 0.3920899 0.5 0.3918457 1 0.3916016 0.5 0.3918457 0.5 0.3916016 1 0.3913574 0.5 0.3916016 0.5 0.3913574 1 0.3911133 0.5 0.3913574 0.5 0.3911133 1 0.3908692 0.5 0.3911133 0.5 0.3908692 1 0.390625 0.5 0.3908692 0.5 0.390625 1 0.3903809 0.5 0.390625 0.5 0.3903809 1 0.3901367 0.5 0.3903809 0.5 0.3901367 1 0.3898926 0.5 0.3901367 0.5 0.3898926 1 0.3896484 0.5 0.3898926 0.5 0.3896484 1 0.3894043 0.5 0.3896484 0.5 0.3894043 1 0.3891602 0.5 0.3894043 0.5 0.3891602 1 0.388916 0.5 0.3891602 0.5 0.388916 1 0.3886719 0.5 0.388916 0.5 0.3886719 1 0.3884277 0.5 0.3886719 0.5 0.3884277 1 0.3881836 0.5 0.3884277 0.5 0.3881836 1 0.3879395 0.5 0.3881836 0.5 0.3879395 1 0.3876953 0.5 0.3879395 0.5 0.3876953 1 0.3874512 0.5 0.3876953 0.5 0.3874512 1 0.387207 0.5 0.3874512 0.5 0.387207 1 0.3869629 0.5 0.387207 0.5 0.3869629 1 0.3867188 0.5 0.3869629 0.5 0.3867188 1 0.3864746 0.5 0.3867188 0.5 0.3864746 1 0.3862305 0.5 0.3864746 0.5 0.3862305 1 0.3859863 0.5 0.3862305 0.5 0.3859863 1 0.3857422 0.5 0.3859863 0.5 0.3857422 1 0.3854981 0.5 0.3857422 0.5 0.3854981 1 0.3852539 0.5 0.3854981 0.5 0.3852539 1 0.3850098 0.5 0.3852539 0.5 0.3850098 1 0.3847656 0.5 0.3850098 0.5 0.3847656 1 0.3845215 0.5 0.3847656 0.5 0.3845215 1 0.3842774 0.5 0.3845215 0.5 0.3842774 1 0.3840332 0.5 0.3842774 0.5 0.3840332 1 0.3837891 0.5 0.3840332 0.5 0.3837891 1 0.3835449 0.5 0.3837891 0.5 0.3835449 1 0.3833008 0.5 0.3835449 0.5 0.3833008 1 0.3830567 0.5 0.3833008 0.5 0.3830567 1 0.3828125 0.5 0.3830567 0.5 0.3828125 1 0.3825684 0.5 0.3828125 0.5 0.3825684 1 0.3823242 0.5 0.3825684 0.5 0.3823242 1 0.3820801 0.5 0.3823242 0.5 0.3820801 1 0.3818359 0.5 0.3820801 0.5 0.3818359 1 0.3815918 0.5 0.3818359 0.5 0.3815918 1 0.3813477 0.5 0.3815918 0.5 0.3813477 1 0.3811035 0.5 0.3813477 0.5 0.3811035 1 0.3808594 0.5 0.3811035 0.5 0.3808594 1 0.3806152 0.5 0.3808594 0.5 0.3806152 1 0.3803711 0.5 0.3806152 0.5 0.3803711 1 0.380127 0.5 0.3803711 0.5 0.380127 1 0.3798828 0.5 0.380127 0.5 0.3798828 1 0.3796387 0.5 0.3798828 0.5 0.3796387 1 0.3793945 0.5 0.3796387 0.5 0.3793945 1 0.3791504 0.5 0.3793945 0.5 0.3791504 1 0.3789063 0.5 0.3791504 0.5 0.3789063 1 0.3786621 0.5 0.3789063 0.5 0.3786621 1 0.378418 0.5 0.3786621 0.5 0.378418 1 0.3781738 0.5 0.378418 0.5 0.3781738 1 0.3779297 0.5 0.3781738 0.5 0.3779297 1 0.3776856 0.5 0.3779297 0.5 0.3776856 1 0.3774414 0.5 0.3776856 0.5 0.3774414 1 0.3771973 0.5 0.3774414 0.5 0.3771973 1 0.3769531 0.5 0.3771973 0.5 0.3769531 1 0.376709 0.5 0.3769531 0.5 0.376709 1 0.3764649 0.5 0.376709 0.5 0.3764649 1 0.3762207 0.5 0.3764649 0.5 0.3762207 1 0.3759766 0.5 0.3762207 0.5 0.3759766 1 0.3757324 0.5 0.3759766 0.5 0.3757324 1 0.3754883 0.5 0.3757324 0.5 0.3754883 1 0.3752442 0.5 0.3754883 0.5 0.3752442 1 0.375 0.5 0.3752442 0.5 0.375 1 0.3747559 0.5 0.375 0.5 0.3747559 1 0.3745117 0.5 0.3747559 0.5 0.3745117 1 0.3742676 0.5 0.3745117 0.5 0.3742676 1 0.3740234 0.5 0.3742676 0.5 0.3740234 1 0.3737793 0.5 0.3740234 0.5 0.3737793 1 0.3735352 0.5 0.3737793 0.5 0.3735352 1 0.373291 0.5 0.3735352 0.5 0.373291 1 0.3730469 0.5 0.373291 0.5 0.3730469 1 0.3728027 0.5 0.3730469 0.5 0.3728027 1 0.3725586 0.5 0.3728027 0.5 0.3725586 1 0.3723145 0.5 0.3725586 0.5 0.3723145 1 0.3720703 0.5 0.3723145 0.5 0.3720703 1 0.3718262 0.5 0.3720703 0.5 0.3718262 1 0.371582 0.5 0.3718262 0.5 0.371582 1 0.3713379 0.5 0.371582 0.5 0.3713379 1 0.3710938 0.5 0.3713379 0.5 0.3710938 1 0.3708496 0.5 0.3710938 0.5 0.3708496 1 0.3706055 0.5 0.3708496 0.5 0.3706055 1 0.3703613 0.5 0.3706055 0.5 0.3703613 1 0.3701172 0.5 0.3703613 0.5 0.3701172 1 0.3698731 0.5 0.3701172 0.5 0.3698731 1 0.3696289 0.5 0.3698731 0.5 0.3696289 1 0.3693848 0.5 0.3696289 0.5 0.3693848 1 0.3691406 0.5 0.3693848 0.5 0.3691406 1 0.3688965 0.5 0.3691406 0.5 0.3688965 1 0.3686524 0.5 0.3688965 0.5 0.3686524 1 0.3684082 0.5 0.3686524 0.5 0.3684082 1 0.3681641 0.5 0.3684082 0.5 0.3681641 1 0.3679199 0.5 0.3681641 0.5 0.3679199 1 0.3676758 0.5 0.3679199 0.5 0.3676758 1 0.3674317 0.5 0.3676758 0.5 0.3674317 1 0.3671875 0.5 0.3674317 0.5 0.3671875 1 0.3669434 0.5 0.3671875 0.5 0.3669434 1 0.3666992 0.5 0.3669434 0.5 0.3666992 1 0.3664551 0.5 0.3666992 0.5 0.3664551 1 0.3662109 0.5 0.3664551 0.5 0.3662109 1 0.3659668 0.5 0.3662109 0.5 0.3659668 1 0.3657227 0.5 0.3659668 0.5 0.3657227 1 0.3654785 0.5 0.3657227 0.5 0.3654785 1 0.3652344 0.5 0.3654785 0.5 0.3652344 1 0.3649902 0.5 0.3652344 0.5 0.3649902 1 0.3647461 0.5 0.3649902 0.5 0.3647461 1 0.364502 0.5 0.3647461 0.5 0.364502 1 0.3642578 0.5 0.364502 0.5 0.3642578 1 0.3640137 0.5 0.3642578 0.5 0.3640137 1 0.3637695 0.5 0.3640137 0.5 0.3637695 1 0.3635254 0.5 0.3637695 0.5 0.3635254 1 0.3632813 0.5 0.3635254 0.5 0.3632813 1 0.3630371 0.5 0.3632813 0.5 0.3630371 1 0.362793 0.5 0.3630371 0.5 0.362793 1 0.3625488 0.5 0.362793 0.5 0.3625488 1 0.3623047 0.5 0.3625488 0.5 0.3623047 1 0.3620606 0.5 0.3623047 0.5 0.3620606 1 0.3618164 0.5 0.3620606 0.5 0.3618164 1 0.3615723 0.5 0.3618164 0.5 0.3615723 1 0.3613281 0.5 0.3615723 0.5 0.3613281 1 0.361084 0.5 0.3613281 0.5 0.361084 1 0.3608399 0.5 0.361084 0.5 0.3608399 1 0.3605957 0.5 0.3608399 0.5 0.3605957 1 0.3603516 0.5 0.3605957 0.5 0.3603516 1 0.3601074 0.5 0.3603516 0.5 0.3601074 1 0.3598633 0.5 0.3601074 0.5 0.3598633 1 0.3596192 0.5 0.3598633 0.5 0.3596192 1 0.359375 0.5 0.3596192 0.5 0.359375 1 0.3591309 0.5 0.359375 0.5 0.3591309 1 0.3588867 0.5 0.3591309 0.5 0.3588867 1 0.3586426 0.5 0.3588867 0.5 0.3586426 1 0.3583984 0.5 0.3586426 0.5 0.3583984 1 0.3581543 0.5 0.3583984 0.5 0.3581543 1 0.3579102 0.5 0.3581543 0.5 0.3579102 1 0.357666 0.5 0.3579102 0.5 0.357666 1 0.3574219 0.5 0.357666 0.5 0.3574219 1 0.3571777 0.5 0.3574219 0.5 0.3571777 1 0.3569336 0.5 0.3571777 0.5 0.3569336 1 0.3566895 0.5 0.3569336 0.5 0.3566895 1 0.3564453 0.5 0.3566895 0.5 0.3564453 1 0.3562012 0.5 0.3564453 0.5 0.3562012 1 0.355957 0.5 0.3562012 0.5 0.355957 1 0.3557129 0.5 0.355957 0.5 0.3557129 1 0.3554688 0.5 0.3557129 0.5 0.3554688 1 0.3552246 0.5 0.3554688 0.5 0.3552246 1 0.3549805 0.5 0.3552246 0.5 0.3549805 1 0.3547363 0.5 0.3549805 0.5 0.3547363 1 0.3544922 0.5 0.3547363 0.5 0.3544922 1 0.3542481 0.5 0.3544922 0.5 0.3542481 1 0.3540039 0.5 0.3542481 0.5 0.3540039 1 0.3537598 0.5 0.3540039 0.5 0.3537598 1 0.3535156 0.5 0.3537598 0.5 0.3535156 1 0.3532715 0.5 0.3535156 0.5 0.3532715 1 0.3530274 0.5 0.3532715 0.5 0.3530274 1 0.3527832 0.5 0.3530274 0.5 0.3527832 1 0.3525391 0.5 0.3527832 0.5 0.3525391 1 0.3522949 0.5 0.3525391 0.5 0.3522949 1 0.3520508 0.5 0.3522949 0.5 0.3520508 1 0.3518067 0.5 0.3520508 0.5 0.3518067 1 0.3515625 0.5 0.3518067 0.5 0.3515625 1 0.3513184 0.5 0.3515625 0.5 0.3513184 1 0.3510742 0.5 0.3513184 0.5 0.3510742 1 0.3508301 0.5 0.3510742 0.5 0.3508301 1 0.3505859 0.5 0.3508301 0.5 0.3505859 1 0.3503418 0.5 0.3505859 0.5 0.3503418 1 0.3500977 0.5 0.3503418 0.5 0.3500977 1 0.3498535 0.5 0.3500977 0.5 0.3498535 1 0.3496094 0.5 0.3498535 0.5 0.3496094 1 0.3493652 0.5 0.3496094 0.5 0.3493652 1 0.3491211 0.5 0.3493652 0.5 0.3491211 1 0.348877 0.5 0.3491211 0.5 0.348877 1 0.3486328 0.5 0.348877 0.5 0.3486328 1 0.3483887 0.5 0.3486328 0.5 0.3483887 1 0.3481445 0.5 0.3483887 0.5 0.3481445 1 0.3479004 0.5 0.3481445 0.5 0.3479004 1 0.3476563 0.5 0.3479004 0.5 0.3476563 1 0.3474121 0.5 0.3476563 0.5 0.3474121 1 0.347168 0.5 0.3474121 0.5 0.347168 1 0.3469238 0.5 0.347168 0.5 0.3469238 1 0.3466797 0.5 0.3469238 0.5 0.3466797 1 0.3464356 0.5 0.3466797 0.5 0.3464356 1 0.3461914 0.5 0.3464356 0.5 0.3461914 1 0.3459473 0.5 0.3461914 0.5 0.3459473 1 0.3457031 0.5 0.3459473 0.5 0.3457031 1 0.345459 0.5 0.3457031 0.5 0.345459 1 0.3452149 0.5 0.345459 0.5 0.3452149 1 0.3449707 0.5 0.3452149 0.5 0.3449707 1 0.3447266 0.5 0.3449707 0.5 0.3447266 1 0.3444824 0.5 0.3447266 0.5 0.3444824 1 0.3442383 0.5 0.3444824 0.5 0.3442383 1 0.3439942 0.5 0.3442383 0.5 0.3439942 1 0.34375 0.5 0.3439942 0.5 0.34375 1 0.3435059 0.5 0.34375 0.5 0.3435059 1 0.3432617 0.5 0.3435059 0.5 0.3432617 1 0.3430176 0.5 0.3432617 0.5 0.3430176 1 0.3427734 0.5 0.3430176 0.5 0.3427734 1 0.3425293 0.5 0.3427734 0.5 0.3425293 1 0.3422852 0.5 0.3425293 0.5 0.3422852 1 0.342041 0.5 0.3422852 0.5 0.342041 1 0.3417969 0.5 0.342041 0.5 0.3417969 1 0.3415527 0.5 0.3417969 0.5 0.3415527 1 0.3413086 0.5 0.3415527 0.5 0.3413086 1 0.3410645 0.5 0.3413086 0.5 0.3410645 1 0.3408203 0.5 0.3410645 0.5 0.3408203 1 0.3405762 0.5 0.3408203 0.5 0.3405762 1 0.340332 0.5 0.3405762 0.5 0.340332 1 0.3400879 0.5 0.340332 0.5 0.3400879 1 0.3398438 0.5 0.3400879 0.5 0.3398438 1 0.3395996 0.5 0.3398438 0.5 0.3395996 1 0.3393555 0.5 0.3395996 0.5 0.3393555 1 0.3391113 0.5 0.3393555 0.5 0.3391113 1 0.3388672 0.5 0.3391113 0.5 0.3388672 1 0.3386231 0.5 0.3388672 0.5 0.3386231 1 0.3383789 0.5 0.3386231 0.5 0.3383789 1 0.3381348 0.5 0.3383789 0.5 0.3381348 1 0.3378906 0.5 0.3381348 0.5 0.3378906 1 0.3376465 0.5 0.3378906 0.5 0.3376465 1 0.3374024 0.5 0.3376465 0.5 0.3374024 1 0.3371582 0.5 0.3374024 0.5 0.3371582 1 0.3369141 0.5 0.3371582 0.5 0.3369141 1 0.3366699 0.5 0.3369141 0.5 0.3366699 1 0.3364258 0.5 0.3366699 0.5 0.3364258 1 0.3361817 0.5 0.3364258 0.5 0.3361817 1 0.3359375 0.5 0.3361817 0.5 0.3359375 1 0.3356934 0.5 0.3359375 0.5 0.3356934 1 0.3354492 0.5 0.3356934 0.5 0.3354492 1 0.3352051 0.5 0.3354492 0.5 0.3352051 1 0.3349609 0.5 0.3352051 0.5 0.3349609 1 0.3347168 0.5 0.3349609 0.5 0.3347168 1 0.3344727 0.5 0.3347168 0.5 0.3344727 1 0.3342285 0.5 0.3344727 0.5 0.3342285 1 0.3339844 0.5 0.3342285 0.5 0.3339844 1 0.3337402 0.5 0.3339844 0.5 0.3337402 1 0.3334961 0.5 0.3337402 0.5 0.3334961 1 0.333252 0.5 0.3334961 0.5 0.333252 1 0.3330078 0.5 0.333252 0.5 0.3330078 1 0.3327637 0.5 0.3330078 0.5 0.3327637 1 0.3325195 0.5 0.3327637 0.5 0.3325195 1 0.3322754 0.5 0.3325195 0.5 0.3322754 1 0.3320313 0.5 0.3322754 0.5 0.3320313 1 0.3317871 0.5 0.3320313 0.5 0.3317871 1 0.331543 0.5 0.3317871 0.5 0.331543 1 0.3312988 0.5 0.331543 0.5 0.3312988 1 0.3310547 0.5 0.3312988 0.5 0.3310547 1 0.3308106 0.5 0.3310547 0.5 0.3308106 1 0.3305664 0.5 0.3308106 0.5 0.3305664 1 0.3303223 0.5 0.3305664 0.5 0.3303223 1 0.3300781 0.5 0.3303223 0.5 0.3300781 1 0.329834 0.5 0.3300781 0.5 0.329834 1 0.3295899 0.5 0.329834 0.5 0.3295899 1 0.3293457 0.5 0.3295899 0.5 0.3293457 1 0.3291016 0.5 0.3293457 0.5 0.3291016 1 0.3288574 0.5 0.3291016 0.5 0.3288574 1 0.3286133 0.5 0.3288574 0.5 0.3286133 1 0.3283692 0.5 0.3286133 0.5 0.3283692 1 0.328125 0.5 0.3283692 0.5 0.328125 1 0.3278809 0.5 0.328125 0.5 0.3278809 1 0.3276367 0.5 0.3278809 0.5 0.3276367 1 0.3273926 0.5 0.3276367 0.5 0.3273926 1 0.3271484 0.5 0.3273926 0.5 0.3271484 1 0.3269043 0.5 0.3271484 0.5 0.3269043 1 0.3266602 0.5 0.3269043 0.5 0.3266602 1 0.326416 0.5 0.3266602 0.5 0.326416 1 0.3261719 0.5 0.326416 0.5 0.3261719 1 0.3259277 0.5 0.3261719 0.5 0.3259277 1 0.3256836 0.5 0.3259277 0.5 0.3256836 1 0.3254395 0.5 0.3256836 0.5 0.3254395 1 0.3251953 0.5 0.3254395 0.5 0.3251953 1 0.3249512 0.5 0.3251953 0.5 0.3249512 1 0.324707 0.5 0.3249512 0.5 0.324707 1 0.3244629 0.5 0.324707 0.5 0.3244629 1 0.3242188 0.5 0.3244629 0.5 0.3242188 1 0.3239746 0.5 0.3242188 0.5 0.3239746 1 0.3237305 0.5 0.3239746 0.5 0.3237305 1 0.3234863 0.5 0.3237305 0.5 0.3234863 1 0.3232422 0.5 0.3234863 0.5 0.3232422 1 0.3229981 0.5 0.3232422 0.5 0.3229981 1 0.3227539 0.5 0.3229981 0.5 0.3227539 1 0.3225098 0.5 0.3227539 0.5 0.3225098 1 0.3222656 0.5 0.3225098 0.5 0.3222656 1 0.3220215 0.5 0.3222656 0.5 0.3220215 1 0.3217774 0.5 0.3220215 0.5 0.3217774 1 0.3215332 0.5 0.3217774 0.5 0.3215332 1 0.3212891 0.5 0.3215332 0.5 0.3212891 1 0.3210449 0.5 0.3212891 0.5 0.3210449 1 0.3208008 0.5 0.3210449 0.5 0.3208008 1 0.3205567 0.5 0.3208008 0.5 0.3205567 1 0.3203125 0.5 0.3205567 0.5 0.3203125 1 0.3200684 0.5 0.3203125 0.5 0.3200684 1 0.3198242 0.5 0.3200684 0.5 0.3198242 1 0.3195801 0.5 0.3198242 0.5 0.3195801 1 0.3193359 0.5 0.3195801 0.5 0.3193359 1 0.3190918 0.5 0.3193359 0.5 0.3190918 1 0.3188477 0.5 0.3190918 0.5 0.3188477 1 0.3186035 0.5 0.3188477 0.5 0.3186035 1 0.3183594 0.5 0.3186035 0.5 0.3183594 1 0.3181152 0.5 0.3183594 0.5 0.3181152 1 0.3178711 0.5 0.3181152 0.5 0.3178711 1 0.317627 0.5 0.3178711 0.5 0.317627 1 0.3173828 0.5 0.317627 0.5 0.3173828 1 0.3171387 0.5 0.3173828 0.5 0.3171387 1 0.3168945 0.5 0.3171387 0.5 0.3168945 1 0.3166504 0.5 0.3168945 0.5 0.3166504 1 0.3164063 0.5 0.3166504 0.5 0.3164063 1 0.3161621 0.5 0.3164063 0.5 0.3161621 1 0.315918 0.5 0.3161621 0.5 0.315918 1 0.3156738 0.5 0.315918 0.5 0.3156738 1 0.3154297 0.5 0.3156738 0.5 0.3154297 1 0.3151856 0.5 0.3154297 0.5 0.3151856 1 0.3149414 0.5 0.3151856 0.5 0.3149414 1 0.3146973 0.5 0.3149414 0.5 0.3146973 1 0.3144531 0.5 0.3146973 0.5 0.3144531 1 0.314209 0.5 0.3144531 0.5 0.314209 1 0.3139649 0.5 0.314209 0.5 0.3139649 1 0.3137207 0.5 0.3139649 0.5 0.3137207 1 0.3134766 0.5 0.3137207 0.5 0.3134766 1 0.3132324 0.5 0.3134766 0.5 0.3132324 1 0.3129883 0.5 0.3132324 0.5 0.3129883 1 0.3127442 0.5 0.3129883 0.5 0.3127442 1 0.3125 0.5 0.3127442 0.5 0.3125 1 0.3122559 0.5 0.3125 0.5 0.3122559 1 0.3120117 0.5 0.3122559 0.5 0.3120117 1 0.3117676 0.5 0.3120117 0.5 0.3117676 1 0.3115234 0.5 0.3117676 0.5 0.3115234 1 0.3112793 0.5 0.3115234 0.5 0.3112793 1 0.3110352 0.5 0.3112793 0.5 0.3110352 1 0.310791 0.5 0.3110352 0.5 0.310791 1 0.3105469 0.5 0.310791 0.5 0.3105469 1 0.3103027 0.5 0.3105469 0.5 0.3103027 1 0.3100586 0.5 0.3103027 0.5 0.3100586 1 0.3098145 0.5 0.3100586 0.5 0.3098145 1 0.3095703 0.5 0.3098145 0.5 0.3095703 1 0.3093262 0.5 0.3095703 0.5 0.3093262 1 0.309082 0.5 0.3093262 0.5 0.309082 1 0.3088379 0.5 0.309082 0.5 0.3088379 1 0.3085938 0.5 0.3088379 0.5 0.3085938 1 0.3083496 0.5 0.3085938 0.5 0.3083496 1 0.3081055 0.5 0.3083496 0.5 0.3081055 1 0.3078613 0.5 0.3081055 0.5 0.3078613 1 0.3076172 0.5 0.3078613 0.5 0.3076172 1 0.3073731 0.5 0.3076172 0.5 0.3073731 1 0.3071289 0.5 0.3073731 0.5 0.3071289 1 0.3068848 0.5 0.3071289 0.5 0.3068848 1 0.3066406 0.5 0.3068848 0.5 0.3066406 1 0.3063965 0.5 0.3066406 0.5 0.3063965 1 0.3061524 0.5 0.3063965 0.5 0.3061524 1 0.3059082 0.5 0.3061524 0.5 0.3059082 1 0.3056641 0.5 0.3059082 0.5 0.3056641 1 0.3054199 0.5 0.3056641 0.5 0.3054199 1 0.3051758 0.5 0.3054199 0.5 0.3051758 1 0.3049317 0.5 0.3051758 0.5 0.3049317 1 0.3046875 0.5 0.3049317 0.5 0.3046875 1 0.3044434 0.5 0.3046875 0.5 0.3044434 1 0.3041992 0.5 0.3044434 0.5 0.3041992 1 0.3039551 0.5 0.3041992 0.5 0.3039551 1 0.3037109 0.5 0.3039551 0.5 0.3037109 1 0.3034668 0.5 0.3037109 0.5 0.3034668 1 0.3032227 0.5 0.3034668 0.5 0.3032227 1 0.3029785 0.5 0.3032227 0.5 0.3029785 1 0.3027344 0.5 0.3029785 0.5 0.3027344 1 0.3024902 0.5 0.3027344 0.5 0.3024902 1 0.3022461 0.5 0.3024902 0.5 0.3022461 1 0.302002 0.5 0.3022461 0.5 0.302002 1 0.3017578 0.5 0.302002 0.5 0.3017578 1 0.3015137 0.5 0.3017578 0.5 0.3015137 1 0.3012695 0.5 0.3015137 0.5 0.3012695 1 0.3010254 0.5 0.3012695 0.5 0.3010254 1 0.3007813 0.5 0.3010254 0.5 0.3007813 1 0.3005371 0.5 0.3007813 0.5 0.3005371 1 0.300293 0.5 0.3005371 0.5 0.300293 1 0.3000488 0.5 0.300293 0.5 0.3000488 1 0.2998047 0.5 0.3000488 0.5 0.2998047 1 0.2995606 0.5 0.2998047 0.5 0.2995606 1 0.2993164 0.5 0.2995606 0.5 0.2993164 1 0.2990723 0.5 0.2993164 0.5 0.2990723 1 0.2988281 0.5 0.2990723 0.5 0.2988281 1 0.298584 0.5 0.2988281 0.5 0.298584 1 0.2983399 0.5 0.298584 0.5 0.2983399 1 0.2980957 0.5 0.2983399 0.5 0.2980957 1 0.2978516 0.5 0.2980957 0.5 0.2978516 1 0.2976074 0.5 0.2978516 0.5 0.2976074 1 0.2973633 0.5 0.2976074 0.5 0.2973633 1 0.2971192 0.5 0.2973633 0.5 0.2971192 1 0.296875 0.5 0.2971192 0.5 0.296875 1 0.2966309 0.5 0.296875 0.5 0.2966309 1 0.2963867 0.5 0.2966309 0.5 0.2963867 1 0.2961426 0.5 0.2963867 0.5 0.2961426 1 0.2958984 0.5 0.2961426 0.5 0.2958984 1 0.2956543 0.5 0.2958984 0.5 0.2956543 1 0.2954102 0.5 0.2956543 0.5 0.2954102 1 0.295166 0.5 0.2954102 0.5 0.295166 1 0.2949219 0.5 0.295166 0.5 0.2949219 1 0.2946777 0.5 0.2949219 0.5 0.2946777 1 0.2944336 0.5 0.2946777 0.5 0.2944336 1 0.2941895 0.5 0.2944336 0.5 0.2941895 1 0.2939453 0.5 0.2941895 0.5 0.2939453 1 0.2937012 0.5 0.2939453 0.5 0.2937012 1 0.293457 0.5 0.2937012 0.5 0.293457 1 0.2932129 0.5 0.293457 0.5 0.2932129 1 0.2929688 0.5 0.2932129 0.5 0.2929688 1 0.2927246 0.5 0.2929688 0.5 0.2927246 1 0.2924805 0.5 0.2927246 0.5 0.2924805 1 0.2922363 0.5 0.2924805 0.5 0.2922363 1 0.2919922 0.5 0.2922363 0.5 0.2919922 1 0.2917481 0.5 0.2919922 0.5 0.2917481 1 0.2915039 0.5 0.2917481 0.5 0.2915039 1 0.2912598 0.5 0.2915039 0.5 0.2912598 1 0.2910156 0.5 0.2912598 0.5 0.2910156 1 0.2907715 0.5 0.2910156 0.5 0.2907715 1 0.2905274 0.5 0.2907715 0.5 0.2905274 1 0.2902832 0.5 0.2905274 0.5 0.2902832 1 0.2900391 0.5 0.2902832 0.5 0.2900391 1 0.2897949 0.5 0.2900391 0.5 0.2897949 1 0.2895508 0.5 0.2897949 0.5 0.2895508 1 0.2893067 0.5 0.2895508 0.5 0.2893067 1 0.2890625 0.5 0.2893067 0.5 0.2890625 1 0.2888184 0.5 0.2890625 0.5 0.2888184 1 0.2885742 0.5 0.2888184 0.5 0.2885742 1 0.2883301 0.5 0.2885742 0.5 0.2883301 1 0.2880859 0.5 0.2883301 0.5 0.2880859 1 0.2878418 0.5 0.2880859 0.5 0.2878418 1 0.2875977 0.5 0.2878418 0.5 0.2875977 1 0.2873535 0.5 0.2875977 0.5 0.2873535 1 0.2871094 0.5 0.2873535 0.5 0.2871094 1 0.2868652 0.5 0.2871094 0.5 0.2868652 1 0.2866211 0.5 0.2868652 0.5 0.2866211 1 0.286377 0.5 0.2866211 0.5 0.286377 1 0.2861328 0.5 0.286377 0.5 0.2861328 1 0.2858887 0.5 0.2861328 0.5 0.2858887 1 0.2856445 0.5 0.2858887 0.5 0.2856445 1 0.2854004 0.5 0.2856445 0.5 0.2854004 1 0.2851563 0.5 0.2854004 0.5 0.2851563 1 0.2849121 0.5 0.2851563 0.5 0.2849121 1 0.284668 0.5 0.2849121 0.5 0.284668 1 0.2844238 0.5 0.284668 0.5 0.2844238 1 0.2841797 0.5 0.2844238 0.5 0.2841797 1 0.2839356 0.5 0.2841797 0.5 0.2839356 1 0.2836914 0.5 0.2839356 0.5 0.2836914 1 0.2834473 0.5 0.2836914 0.5 0.2834473 1 0.2832031 0.5 0.2834473 0.5 0.2832031 1 0.282959 0.5 0.2832031 0.5 0.282959 1 0.2827149 0.5 0.282959 0.5 0.2827149 1 0.2824707 0.5 0.2827149 0.5 0.2824707 1 0.2822266 0.5 0.2824707 0.5 0.2822266 1 0.2819824 0.5 0.2822266 0.5 0.2819824 1 0.2817383 0.5 0.2819824 0.5 0.2817383 1 0.2814942 0.5 0.2817383 0.5 0.2814942 1 0.28125 0.5 0.2814942 0.5 0.28125 1 0.2810059 0.5 0.28125 0.5 0.2810059 1 0.2807617 0.5 0.2810059 0.5 0.2807617 1 0.2805176 0.5 0.2807617 0.5 0.2805176 1 0.2802734 0.5 0.2805176 0.5 0.2802734 1 0.2800293 0.5 0.2802734 0.5 0.2800293 1 0.2797852 0.5 0.2800293 0.5 0.2797852 1 0.279541 0.5 0.2797852 0.5 0.279541 1 0.2792969 0.5 0.279541 0.5 0.2792969 1 0.2790527 0.5 0.2792969 0.5 0.2790527 1 0.2788086 0.5 0.2790527 0.5 0.2788086 1 0.2785645 0.5 0.2788086 0.5 0.2785645 1 0.2783203 0.5 0.2785645 0.5 0.2783203 1 0.2780762 0.5 0.2783203 0.5 0.2780762 1 0.277832 0.5 0.2780762 0.5 0.277832 1 0.2775879 0.5 0.277832 0.5 0.2775879 1 0.2773438 0.5 0.2775879 0.5 0.2773438 1 0.2770996 0.5 0.2773438 0.5 0.2770996 1 0.2768555 0.5 0.2770996 0.5 0.2768555 1 0.2766113 0.5 0.2768555 0.5 0.2766113 1 0.2763672 0.5 0.2766113 0.5 0.2763672 1 0.2761231 0.5 0.2763672 0.5 0.2761231 1 0.2758789 0.5 0.2761231 0.5 0.2758789 1 0.2756348 0.5 0.2758789 0.5 0.2756348 1 0.2753906 0.5 0.2756348 0.5 0.2753906 1 0.2751465 0.5 0.2753906 0.5 0.2751465 1 0.2749024 0.5 0.2751465 0.5 0.2749024 1 0.2746582 0.5 0.2749024 0.5 0.2746582 1 0.2744141 0.5 0.2746582 0.5 0.2744141 1 0.2741699 0.5 0.2744141 0.5 0.2741699 1 0.2739258 0.5 0.2741699 0.5 0.2739258 1 0.2736817 0.5 0.2739258 0.5 0.2736817 1 0.2734375 0.5 0.2736817 0.5 0.2734375 1 0.2731934 0.5 0.2734375 0.5 0.2731934 1 0.2729492 0.5 0.2731934 0.5 0.2729492 1 0.2727051 0.5 0.2729492 0.5 0.2727051 1 0.2724609 0.5 0.2727051 0.5 0.2724609 1 0.2722168 0.5 0.2724609 0.5 0.2722168 1 0.2719727 0.5 0.2722168 0.5 0.2719727 1 0.2717285 0.5 0.2719727 0.5 0.2717285 1 0.2714844 0.5 0.2717285 0.5 0.2714844 1 0.2712402 0.5 0.2714844 0.5 0.2712402 1 0.2709961 0.5 0.2712402 0.5 0.2709961 1 0.270752 0.5 0.2709961 0.5 0.270752 1 0.2705078 0.5 0.270752 0.5 0.2705078 1 0.2702637 0.5 0.2705078 0.5 0.2702637 1 0.2700195 0.5 0.2702637 0.5 0.2700195 1 0.2697754 0.5 0.2700195 0.5 0.2697754 1 0.2695313 0.5 0.2697754 0.5 0.2695313 1 0.2692871 0.5 0.2695313 0.5 0.2692871 1 0.269043 0.5 0.2692871 0.5 0.269043 1 0.2687988 0.5 0.269043 0.5 0.2687988 1 0.2685547 0.5 0.2687988 0.5 0.2685547 1 0.2683106 0.5 0.2685547 0.5 0.2683106 1 0.2680664 0.5 0.2683106 0.5 0.2680664 1 0.2678223 0.5 0.2680664 0.5 0.2678223 1 0.2675781 0.5 0.2678223 0.5 0.2675781 1 0.267334 0.5 0.2675781 0.5 0.267334 1 0.2670899 0.5 0.267334 0.5 0.2670899 1 0.2668457 0.5 0.2670899 0.5 0.2668457 1 0.2666016 0.5 0.2668457 0.5 0.2666016 1 0.2663574 0.5 0.2666016 0.5 0.2663574 1 0.2661133 0.5 0.2663574 0.5 0.2661133 1 0.2658692 0.5 0.2661133 0.5 0.2658692 1 0.265625 0.5 0.2658692 0.5 0.265625 1 0.2653809 0.5 0.265625 0.5 0.2653809 1 0.2651367 0.5 0.2653809 0.5 0.2651367 1 0.2648926 0.5 0.2651367 0.5 0.2648926 1 0.2646484 0.5 0.2648926 0.5 0.2646484 1 0.2644043 0.5 0.2646484 0.5 0.2644043 1 0.2641602 0.5 0.2644043 0.5 0.2641602 1 0.263916 0.5 0.2641602 0.5 0.263916 1 0.2636719 0.5 0.263916 0.5 0.2636719 1 0.2634277 0.5 0.2636719 0.5 0.2634277 1 0.2631836 0.5 0.2634277 0.5 0.2631836 1 0.2629395 0.5 0.2631836 0.5 0.2629395 1 0.2626953 0.5 0.2629395 0.5 0.2626953 1 0.2624512 0.5 0.2626953 0.5 0.2624512 1 0.262207 0.5 0.2624512 0.5 0.262207 1 0.2619629 0.5 0.262207 0.5 0.2619629 1 0.2617188 0.5 0.2619629 0.5 0.2617188 1 0.2614746 0.5 0.2617188 0.5 0.2614746 1 0.2612305 0.5 0.2614746 0.5 0.2612305 1 0.2609863 0.5 0.2612305 0.5 0.2609863 1 0.2607422 0.5 0.2609863 0.5 0.2607422 1 0.2604981 0.5 0.2607422 0.5 0.2604981 1 0.2602539 0.5 0.2604981 0.5 0.2602539 1 0.2600098 0.5 0.2602539 0.5 0.2600098 1 0.2597656 0.5 0.2600098 0.5 0.2597656 1 0.2595215 0.5 0.2597656 0.5 0.2595215 1 0.2592774 0.5 0.2595215 0.5 0.2592774 1 0.2590332 0.5 0.2592774 0.5 0.2590332 1 0.2587891 0.5 0.2590332 0.5 0.2587891 1 0.2585449 0.5 0.2587891 0.5 0.2585449 1 0.2583008 0.5 0.2585449 0.5 0.2583008 1 0.2580567 0.5 0.2583008 0.5 0.2580567 1 0.2578125 0.5 0.2580567 0.5 0.2578125 1 0.2575684 0.5 0.2578125 0.5 0.2575684 1 0.2573242 0.5 0.2575684 0.5 0.2573242 1 0.2570801 0.5 0.2573242 0.5 0.2570801 1 0.2568359 0.5 0.2570801 0.5 0.2568359 1 0.2565918 0.5 0.2568359 0.5 0.2565918 1 0.2563477 0.5 0.2565918 0.5 0.2563477 1 0.2561035 0.5 0.2563477 0.5 0.2561035 1 0.2558594 0.5 0.2561035 0.5 0.2558594 1 0.2556152 0.5 0.2558594 0.5 0.2556152 1 0.2553711 0.5 0.2556152 0.5 0.2553711 1 0.255127 0.5 0.2553711 0.5 0.255127 1 0.2548828 0.5 0.255127 0.5 0.2548828 1 0.2546387 0.5 0.2548828 0.5 0.2546387 1 0.2543945 0.5 0.2546387 0.5 0.2543945 1 0.2541504 0.5 0.2543945 0.5 0.2541504 1 0.2539063 0.5 0.2541504 0.5 0.2539063 1 0.2536621 0.5 0.2539063 0.5 0.2536621 1 0.253418 0.5 0.2536621 0.5 0.253418 1 0.2531738 0.5 0.253418 0.5 0.2531738 1 0.2529297 0.5 0.2531738 0.5 0.2529297 1 0.2526856 0.5 0.2529297 0.5 0.2526856 1 0.2524414 0.5 0.2526856 0.5 0.2524414 1 0.2521973 0.5 0.2524414 0.5 0.2521973 1 0.2519531 0.5 0.2521973 0.5 0.2519531 1 0.251709 0.5 0.2519531 0.5 0.251709 1 0.2514649 0.5 0.251709 0.5 0.2514649 1 0.2512207 0.5 0.2514649 0.5 0.2512207 1 0.2509766 0.5 0.2512207 0.5 0.2509766 1 0.2507324 0.5 0.2509766 0.5 0.2507324 1 0.2504883 0.5 0.2507324 0.5 0.2504883 1 0.2502442 0.5 0.2504883 0.5 0.2502442 1 0.25 0.5 0.2502442 0.5 0.25 1 0.2497558 0.5 0.25 0.5 0.2497558 1 0.2495117 0.5 0.2497558 0.5 0.2495117 1 0.2492675 0.5 0.2495117 0.5 0.2492675 1 0.2490234 0.5 0.2492675 0.5 0.2490234 1 0.2487792 0.5 0.2490234 0.5 0.2487792 1 0.2485351 0.5 0.2487792 0.5 0.2485351 1 0.248291 0.5 0.2485351 0.5 0.248291 1 0.2480468 0.5 0.248291 0.5 0.2480468 1 0.2478027 0.5 0.2480468 0.5 0.2478027 1 0.2475585 0.5 0.2478027 0.5 0.2475585 1 0.2473144 0.5 0.2475585 0.5 0.2473144 1 0.2470703 0.5 0.2473144 0.5 0.2470703 1 0.2468261 0.5 0.2470703 0.5 0.2468261 1 0.246582 0.5 0.2468261 0.5 0.246582 1 0.2463378 0.5 0.246582 0.5 0.2463378 1 0.2460937 0.5 0.2463378 0.5 0.2460937 1 0.2458496 0.5 0.2460937 0.5 0.2458496 1 0.2456054 0.5 0.2458496 0.5 0.2456054 1 0.2453613 0.5 0.2456054 0.5 0.2453613 1 0.2451171 0.5 0.2453613 0.5 0.2451171 1 0.244873 0.5 0.2451171 0.5 0.244873 1 0.2446289 0.5 0.244873 0.5 0.2446289 1 0.2443847 0.5 0.2446289 0.5 0.2443847 1 0.2441406 0.5 0.2443847 0.5 0.2441406 1 0.2438964 0.5 0.2441406 0.5 0.2438964 1 0.2436523 0.5 0.2438964 0.5 0.2436523 1 0.2434082 0.5 0.2436523 0.5 0.2434082 1 0.243164 0.5 0.2434082 0.5 0.243164 1 0.2429199 0.5 0.243164 0.5 0.2429199 1 0.2426757 0.5 0.2429199 0.5 0.2426757 1 0.2424316 0.5 0.2426757 0.5 0.2424316 1 0.2421875 0.5 0.2424316 0.5 0.2421875 1 0.2419433 0.5 0.2421875 0.5 0.2419433 1 0.2416992 0.5 0.2419433 0.5 0.2416992 1 0.241455 0.5 0.2416992 0.5 0.241455 1 0.2412109 0.5 0.241455 0.5 0.2412109 1 0.2409667 0.5 0.2412109 0.5 0.2409667 1 0.2407226 0.5 0.2409667 0.5 0.2407226 1 0.2404785 0.5 0.2407226 0.5 0.2404785 1 0.2402343 0.5 0.2404785 0.5 0.2402343 1 0.2399902 0.5 0.2402343 0.5 0.2399902 1 0.239746 0.5 0.2399902 0.5 0.239746 1 0.2395019 0.5 0.239746 0.5 0.2395019 1 0.2392578 0.5 0.2395019 0.5 0.2392578 1 0.2390136 0.5 0.2392578 0.5 0.2390136 1 0.2387695 0.5 0.2390136 0.5 0.2387695 1 0.2385253 0.5 0.2387695 0.5 0.2385253 1 0.2382812 0.5 0.2385253 0.5 0.2382812 1 0.2380371 0.5 0.2382812 0.5 0.2380371 1 0.2377929 0.5 0.2380371 0.5 0.2377929 1 0.2375488 0.5 0.2377929 0.5 0.2375488 1 0.2373046 0.5 0.2375488 0.5 0.2373046 1 0.2370605 0.5 0.2373046 0.5 0.2370605 1 0.2368164 0.5 0.2370605 0.5 0.2368164 1 0.2365722 0.5 0.2368164 0.5 0.2365722 1 0.2363281 0.5 0.2365722 0.5 0.2363281 1 0.2360839 0.5 0.2363281 0.5 0.2360839 1 0.2358398 0.5 0.2360839 0.5 0.2358398 1 0.2355957 0.5 0.2358398 0.5 0.2355957 1 0.2353515 0.5 0.2355957 0.5 0.2353515 1 0.2351074 0.5 0.2353515 0.5 0.2351074 1 0.2348632 0.5 0.2351074 0.5 0.2348632 1 0.2346191 0.5 0.2348632 0.5 0.2346191 1 0.234375 0.5 0.2346191 0.5 0.234375 1 0.2341308 0.5 0.234375 0.5 0.2341308 1 0.2338867 0.5 0.2341308 0.5 0.2338867 1 0.2336425 0.5 0.2338867 0.5 0.2336425 1 0.2333984 0.5 0.2336425 0.5 0.2333984 1 0.2331542 0.5 0.2333984 0.5 0.2331542 1 0.2329101 0.5 0.2331542 0.5 0.2329101 1 0.232666 0.5 0.2329101 0.5 0.232666 1 0.2324218 0.5 0.232666 0.5 0.2324218 1 0.2321777 0.5 0.2324218 0.5 0.2321777 1 0.2319335 0.5 0.2321777 0.5 0.2319335 1 0.2316894 0.5 0.2319335 0.5 0.2316894 1 0.2314453 0.5 0.2316894 0.5 0.2314453 1 0.2312011 0.5 0.2314453 0.5 0.2312011 1 0.230957 0.5 0.2312011 0.5 0.230957 1 0.2307128 0.5 0.230957 0.5 0.2307128 1 0.2304687 0.5 0.2307128 0.5 0.2304687 1 0.2302246 0.5 0.2304687 0.5 0.2302246 1 0.2299804 0.5 0.2302246 0.5 0.2299804 1 0.2297363 0.5 0.2299804 0.5 0.2297363 1 0.2294921 0.5 0.2297363 0.5 0.2294921 1 0.229248 0.5 0.2294921 0.5 0.229248 1 0.2290039 0.5 0.229248 0.5 0.2290039 1 0.2287597 0.5 0.2290039 0.5 0.2287597 1 0.2285156 0.5 0.2287597 0.5 0.2285156 1 0.2282714 0.5 0.2285156 0.5 0.2282714 1 0.2280273 0.5 0.2282714 0.5 0.2280273 1 0.2277832 0.5 0.2280273 0.5 0.2277832 1 0.227539 0.5 0.2277832 0.5 0.227539 1 0.2272949 0.5 0.227539 0.5 0.2272949 1 0.2270507 0.5 0.2272949 0.5 0.2270507 1 0.2268066 0.5 0.2270507 0.5 0.2268066 1 0.2265625 0.5 0.2268066 0.5 0.2265625 1 0.2263183 0.5 0.2265625 0.5 0.2263183 1 0.2260742 0.5 0.2263183 0.5 0.2260742 1 0.22583 0.5 0.2260742 0.5 0.22583 1 0.2255859 0.5 0.22583 0.5 0.2255859 1 0.2253417 0.5 0.2255859 0.5 0.2253417 1 0.2250976 0.5 0.2253417 0.5 0.2250976 1 0.2248535 0.5 0.2250976 0.5 0.2248535 1 0.2246093 0.5 0.2248535 0.5 0.2246093 1 0.2243652 0.5 0.2246093 0.5 0.2243652 1 0.224121 0.5 0.2243652 0.5 0.224121 1 0.2238769 0.5 0.224121 0.5 0.2238769 1 0.2236328 0.5 0.2238769 0.5 0.2236328 1 0.2233886 0.5 0.2236328 0.5 0.2233886 1 0.2231445 0.5 0.2233886 0.5 0.2231445 1 0.2229003 0.5 0.2231445 0.5 0.2229003 1 0.2226562 0.5 0.2229003 0.5 0.2226562 1 0.2224121 0.5 0.2226562 0.5 0.2224121 1 0.2221679 0.5 0.2224121 0.5 0.2221679 1 0.2219238 0.5 0.2221679 0.5 0.2219238 1 0.2216796 0.5 0.2219238 0.5 0.2216796 1 0.2214355 0.5 0.2216796 0.5 0.2214355 1 0.2211914 0.5 0.2214355 0.5 0.2211914 1 0.2209472 0.5 0.2211914 0.5 0.2209472 1 0.2207031 0.5 0.2209472 0.5 0.2207031 1 0.2204589 0.5 0.2207031 0.5 0.2204589 1 0.2202148 0.5 0.2204589 0.5 0.2202148 1 0.2199707 0.5 0.2202148 0.5 0.2199707 1 0.2197265 0.5 0.2199707 0.5 0.2197265 1 0.2194824 0.5 0.2197265 0.5 0.2194824 1 0.2192382 0.5 0.2194824 0.5 0.2192382 1 0.2189941 0.5 0.2192382 0.5 0.2189941 1 0.21875 0.5 0.2189941 0.5 0.21875 1 0.2185058 0.5 0.21875 0.5 0.2185058 1 0.2182617 0.5 0.2185058 0.5 0.2182617 1 0.2180175 0.5 0.2182617 0.5 0.2180175 1 0.2177734 0.5 0.2180175 0.5 0.2177734 1 0.2175292 0.5 0.2177734 0.5 0.2175292 1 0.2172851 0.5 0.2175292 0.5 0.2172851 1 0.217041 0.5 0.2172851 0.5 0.217041 1 0.2167968 0.5 0.217041 0.5 0.2167968 1 0.2165527 0.5 0.2167968 0.5 0.2165527 1 0.2163085 0.5 0.2165527 0.5 0.2163085 1 0.2160644 0.5 0.2163085 0.5 0.2160644 1 0.2158203 0.5 0.2160644 0.5 0.2158203 1 0.2155761 0.5 0.2158203 0.5 0.2155761 1 0.215332 0.5 0.2155761 0.5 0.215332 1 0.2150878 0.5 0.215332 0.5 0.2150878 1 0.2148437 0.5 0.2150878 0.5 0.2148437 1 0.2145996 0.5 0.2148437 0.5 0.2145996 1 0.2143554 0.5 0.2145996 0.5 0.2143554 1 0.2141113 0.5 0.2143554 0.5 0.2141113 1 0.2138671 0.5 0.2141113 0.5 0.2138671 1 0.213623 0.5 0.2138671 0.5 0.213623 1 0.2133789 0.5 0.213623 0.5 0.2133789 1 0.2131347 0.5 0.2133789 0.5 0.2131347 1 0.2128906 0.5 0.2131347 0.5 0.2128906 1 0.2126464 0.5 0.2128906 0.5 0.2126464 1 0.2124023 0.5 0.2126464 0.5 0.2124023 1 0.2121582 0.5 0.2124023 0.5 0.2121582 1 0.211914 0.5 0.2121582 0.5 0.211914 1 0.2116699 0.5 0.211914 0.5 0.2116699 1 0.2114257 0.5 0.2116699 0.5 0.2114257 1 0.2111816 0.5 0.2114257 0.5 0.2111816 1 0.2109375 0.5 0.2111816 0.5 0.2109375 1 0.2106933 0.5 0.2109375 0.5 0.2106933 1 0.2104492 0.5 0.2106933 0.5 0.2104492 1 0.210205 0.5 0.2104492 0.5 0.210205 1 0.2099609 0.5 0.210205 0.5 0.2099609 1 0.2097167 0.5 0.2099609 0.5 0.2097167 1 0.2094726 0.5 0.2097167 0.5 0.2094726 1 0.2092285 0.5 0.2094726 0.5 0.2092285 1 0.2089843 0.5 0.2092285 0.5 0.2089843 1 0.2087402 0.5 0.2089843 0.5 0.2087402 1 0.208496 0.5 0.2087402 0.5 0.208496 1 0.2082519 0.5 0.208496 0.5 0.2082519 1 0.2080078 0.5 0.2082519 0.5 0.2080078 1 0.2077636 0.5 0.2080078 0.5 0.2077636 1 0.2075195 0.5 0.2077636 0.5 0.2075195 1 0.2072753 0.5 0.2075195 0.5 0.2072753 1 0.2070312 0.5 0.2072753 0.5 0.2070312 1 0.2067871 0.5 0.2070312 0.5 0.2067871 1 0.2065429 0.5 0.2067871 0.5 0.2065429 1 0.2062988 0.5 0.2065429 0.5 0.2062988 1 0.2060546 0.5 0.2062988 0.5 0.2060546 1 0.2058105 0.5 0.2060546 0.5 0.2058105 1 0.2055664 0.5 0.2058105 0.5 0.2055664 1 0.2053222 0.5 0.2055664 0.5 0.2053222 1 0.2050781 0.5 0.2053222 0.5 0.2050781 1 0.2048339 0.5 0.2050781 0.5 0.2048339 1 0.2045898 0.5 0.2048339 0.5 0.2045898 1 0.2043457 0.5 0.2045898 0.5 0.2043457 1 0.2041015 0.5 0.2043457 0.5 0.2041015 1 0.2038574 0.5 0.2041015 0.5 0.2038574 1 0.2036132 0.5 0.2038574 0.5 0.2036132 1 0.2033691 0.5 0.2036132 0.5 0.2033691 1 0.203125 0.5 0.2033691 0.5 0.203125 1 0.2028808 0.5 0.203125 0.5 0.2028808 1 0.2026367 0.5 0.2028808 0.5 0.2026367 1 0.2023925 0.5 0.2026367 0.5 0.2023925 1 0.2021484 0.5 0.2023925 0.5 0.2021484 1 0.2019042 0.5 0.2021484 0.5 0.2019042 1 0.2016601 0.5 0.2019042 0.5 0.2016601 1 0.201416 0.5 0.2016601 0.5 0.201416 1 0.2011718 0.5 0.201416 0.5 0.2011718 1 0.2009277 0.5 0.2011718 0.5 0.2009277 1 0.2006835 0.5 0.2009277 0.5 0.2006835 1 0.2004394 0.5 0.2006835 0.5 0.2004394 1 0.2001953 0.5 0.2004394 0.5 0.2001953 1 0.1999511 0.5 0.2001953 0.5 0.1999511 1 0.199707 0.5 0.1999511 0.5 0.199707 1 0.1994628 0.5 0.199707 0.5 0.1994628 1 0.1992187 0.5 0.1994628 0.5 0.1992187 1 0.1989746 0.5 0.1992187 0.5 0.1989746 1 0.1987304 0.5 0.1989746 0.5 0.1987304 1 0.1984863 0.5 0.1987304 0.5 0.1984863 1 0.1982421 0.5 0.1984863 0.5 0.1982421 1 0.197998 0.5 0.1982421 0.5 0.197998 1 0.1977539 0.5 0.197998 0.5 0.1977539 1 0.1975097 0.5 0.1977539 0.5 0.1975097 1 0.1972656 0.5 0.1975097 0.5 0.1972656 1 0.1970214 0.5 0.1972656 0.5 0.1970214 1 0.1967773 0.5 0.1970214 0.5 0.1967773 1 0.1965332 0.5 0.1967773 0.5 0.1965332 1 0.196289 0.5 0.1965332 0.5 0.196289 1 0.1960449 0.5 0.196289 0.5 0.1960449 1 0.1958007 0.5 0.1960449 0.5 0.1958007 1 0.1955566 0.5 0.1958007 0.5 0.1955566 1 0.1953125 0.5 0.1955566 0.5 0.1953125 1 0.1950683 0.5 0.1953125 0.5 0.1950683 1 0.1948242 0.5 0.1950683 0.5 0.1948242 1 0.19458 0.5 0.1948242 0.5 0.19458 1 0.1943359 0.5 0.19458 0.5 0.1943359 1 0.1940917 0.5 0.1943359 0.5 0.1940917 1 0.1938476 0.5 0.1940917 0.5 0.1938476 1 0.1936035 0.5 0.1938476 0.5 0.1936035 1 0.1933593 0.5 0.1936035 0.5 0.1933593 1 0.1931152 0.5 0.1933593 0.5 0.1931152 1 0.192871 0.5 0.1931152 0.5 0.192871 1 0.1926269 0.5 0.192871 0.5 0.1926269 1 0.1923828 0.5 0.1926269 0.5 0.1923828 1 0.1921386 0.5 0.1923828 0.5 0.1921386 1 0.1918945 0.5 0.1921386 0.5 0.1918945 1 0.1916503 0.5 0.1918945 0.5 0.1916503 1 0.1914062 0.5 0.1916503 0.5 0.1914062 1 0.1911621 0.5 0.1914062 0.5 0.1911621 1 0.1909179 0.5 0.1911621 0.5 0.1909179 1 0.1906738 0.5 0.1909179 0.5 0.1906738 1 0.1904296 0.5 0.1906738 0.5 0.1904296 1 0.1901855 0.5 0.1904296 0.5 0.1901855 1 0.1899414 0.5 0.1901855 0.5 0.1899414 1 0.1896972 0.5 0.1899414 0.5 0.1896972 1 0.1894531 0.5 0.1896972 0.5 0.1894531 1 0.1892089 0.5 0.1894531 0.5 0.1892089 1 0.1889648 0.5 0.1892089 0.5 0.1889648 1 0.1887207 0.5 0.1889648 0.5 0.1887207 1 0.1884765 0.5 0.1887207 0.5 0.1884765 1 0.1882324 0.5 0.1884765 0.5 0.1882324 1 0.1879882 0.5 0.1882324 0.5 0.1879882 1 0.1877441 0.5 0.1879882 0.5 0.1877441 1 0.1875 0.5 0.1877441 0.5 0.1875 1 0.1872558 0.5 0.1875 0.5 0.1872558 1 0.1870117 0.5 0.1872558 0.5 0.1870117 1 0.1867675 0.5 0.1870117 0.5 0.1867675 1 0.1865234 0.5 0.1867675 0.5 0.1865234 1 0.1862792 0.5 0.1865234 0.5 0.1862792 1 0.1860351 0.5 0.1862792 0.5 0.1860351 1 0.185791 0.5 0.1860351 0.5 0.185791 1 0.1855468 0.5 0.185791 0.5 0.1855468 1 0.1853027 0.5 0.1855468 0.5 0.1853027 1 0.1850585 0.5 0.1853027 0.5 0.1850585 1 0.1848144 0.5 0.1850585 0.5 0.1848144 1 0.1845703 0.5 0.1848144 0.5 0.1845703 1 0.1843261 0.5 0.1845703 0.5 0.1843261 1 0.184082 0.5 0.1843261 0.5 0.184082 1 0.1838378 0.5 0.184082 0.5 0.1838378 1 0.1835937 0.5 0.1838378 0.5 0.1835937 1 0.1833496 0.5 0.1835937 0.5 0.1833496 1 0.1831054 0.5 0.1833496 0.5 0.1831054 1 0.1828613 0.5 0.1831054 0.5 0.1828613 1 0.1826171 0.5 0.1828613 0.5 0.1826171 1 0.182373 0.5 0.1826171 0.5 0.182373 1 0.1821289 0.5 0.182373 0.5 0.1821289 1 0.1818847 0.5 0.1821289 0.5 0.1818847 1 0.1816406 0.5 0.1818847 0.5 0.1816406 1 0.1813964 0.5 0.1816406 0.5 0.1813964 1 0.1811523 0.5 0.1813964 0.5 0.1811523 1 0.1809082 0.5 0.1811523 0.5 0.1809082 1 0.180664 0.5 0.1809082 0.5 0.180664 1 0.1804199 0.5 0.180664 0.5 0.1804199 1 0.1801757 0.5 0.1804199 0.5 0.1801757 1 0.1799316 0.5 0.1801757 0.5 0.1799316 1 0.1796875 0.5 0.1799316 0.5 0.1796875 1 0.1794433 0.5 0.1796875 0.5 0.1794433 1 0.1791992 0.5 0.1794433 0.5 0.1791992 1 0.178955 0.5 0.1791992 0.5 0.178955 1 0.1787109 0.5 0.178955 0.5 0.1787109 1 0.1784667 0.5 0.1787109 0.5 0.1784667 1 0.1782226 0.5 0.1784667 0.5 0.1782226 1 0.1779785 0.5 0.1782226 0.5 0.1779785 1 0.1777343 0.5 0.1779785 0.5 0.1777343 1 0.1774902 0.5 0.1777343 0.5 0.1774902 1 0.177246 0.5 0.1774902 0.5 0.177246 1 0.1770019 0.5 0.177246 0.5 0.1770019 1 0.1767578 0.5 0.1770019 0.5 0.1767578 1 0.1765136 0.5 0.1767578 0.5 0.1765136 1 0.1762695 0.5 0.1765136 0.5 0.1762695 1 0.1760253 0.5 0.1762695 0.5 0.1760253 1 0.1757812 0.5 0.1760253 0.5 0.1757812 1 0.1755371 0.5 0.1757812 0.5 0.1755371 1 0.1752929 0.5 0.1755371 0.5 0.1752929 1 0.1750488 0.5 0.1752929 0.5 0.1750488 1 0.1748046 0.5 0.1750488 0.5 0.1748046 1 0.1745605 0.5 0.1748046 0.5 0.1745605 1 0.1743164 0.5 0.1745605 0.5 0.1743164 1 0.1740722 0.5 0.1743164 0.5 0.1740722 1 0.1738281 0.5 0.1740722 0.5 0.1738281 1 0.1735839 0.5 0.1738281 0.5 0.1735839 1 0.1733398 0.5 0.1735839 0.5 0.1733398 1 0.1730957 0.5 0.1733398 0.5 0.1730957 1 0.1728515 0.5 0.1730957 0.5 0.1728515 1 0.1726074 0.5 0.1728515 0.5 0.1726074 1 0.1723632 0.5 0.1726074 0.5 0.1723632 1 0.1721191 0.5 0.1723632 0.5 0.1721191 1 0.171875 0.5 0.1721191 0.5 0.171875 1 0.1716308 0.5 0.171875 0.5 0.1716308 1 0.1713867 0.5 0.1716308 0.5 0.1713867 1 0.1711425 0.5 0.1713867 0.5 0.1711425 1 0.1708984 0.5 0.1711425 0.5 0.1708984 1 0.1706542 0.5 0.1708984 0.5 0.1706542 1 0.1704101 0.5 0.1706542 0.5 0.1704101 1 0.170166 0.5 0.1704101 0.5 0.170166 1 0.1699218 0.5 0.170166 0.5 0.1699218 1 0.1696777 0.5 0.1699218 0.5 0.1696777 1 0.1694335 0.5 0.1696777 0.5 0.1694335 1 0.1691894 0.5 0.1694335 0.5 0.1691894 1 0.1689453 0.5 0.1691894 0.5 0.1689453 1 0.1687011 0.5 0.1689453 0.5 0.1687011 1 0.168457 0.5 0.1687011 0.5 0.168457 1 0.1682128 0.5 0.168457 0.5 0.1682128 1 0.1679687 0.5 0.1682128 0.5 0.1679687 1 0.1677246 0.5 0.1679687 0.5 0.1677246 1 0.1674804 0.5 0.1677246 0.5 0.1674804 1 0.1672363 0.5 0.1674804 0.5 0.1672363 1 0.1669921 0.5 0.1672363 0.5 0.1669921 1 0.166748 0.5 0.1669921 0.5 0.166748 1 0.1665039 0.5 0.166748 0.5 0.1665039 1 0.1662597 0.5 0.1665039 0.5 0.1662597 1 0.1660156 0.5 0.1662597 0.5 0.1660156 1 0.1657714 0.5 0.1660156 0.5 0.1657714 1 0.1655273 0.5 0.1657714 0.5 0.1655273 1 0.1652832 0.5 0.1655273 0.5 0.1652832 1 0.165039 0.5 0.1652832 0.5 0.165039 1 0.1647949 0.5 0.165039 0.5 0.1647949 1 0.1645507 0.5 0.1647949 0.5 0.1645507 1 0.1643066 0.5 0.1645507 0.5 0.1643066 1 0.1640625 0.5 0.1643066 0.5 0.1640625 1 0.1638183 0.5 0.1640625 0.5 0.1638183 1 0.1635742 0.5 0.1638183 0.5 0.1635742 1 0.16333 0.5 0.1635742 0.5 0.16333 1 0.1630859 0.5 0.16333 0.5 0.1630859 1 0.1628417 0.5 0.1630859 0.5 0.1628417 1 0.1625976 0.5 0.1628417 0.5 0.1625976 1 0.1623535 0.5 0.1625976 0.5 0.1623535 1 0.1621093 0.5 0.1623535 0.5 0.1621093 1 0.1618652 0.5 0.1621093 0.5 0.1618652 1 0.161621 0.5 0.1618652 0.5 0.161621 1 0.1613769 0.5 0.161621 0.5 0.1613769 1 0.1611328 0.5 0.1613769 0.5 0.1611328 1 0.1608886 0.5 0.1611328 0.5 0.1608886 1 0.1606445 0.5 0.1608886 0.5 0.1606445 1 0.1604003 0.5 0.1606445 0.5 0.1604003 1 0.1601562 0.5 0.1604003 0.5 0.1601562 1 0.1599121 0.5 0.1601562 0.5 0.1599121 1 0.1596679 0.5 0.1599121 0.5 0.1596679 1 0.1594238 0.5 0.1596679 0.5 0.1594238 1 0.1591796 0.5 0.1594238 0.5 0.1591796 1 0.1589355 0.5 0.1591796 0.5 0.1589355 1 0.1586914 0.5 0.1589355 0.5 0.1586914 1 0.1584472 0.5 0.1586914 0.5 0.1584472 1 0.1582031 0.5 0.1584472 0.5 0.1582031 1 0.1579589 0.5 0.1582031 0.5 0.1579589 1 0.1577148 0.5 0.1579589 0.5 0.1577148 1 0.1574707 0.5 0.1577148 0.5 0.1574707 1 0.1572265 0.5 0.1574707 0.5 0.1572265 1 0.1569824 0.5 0.1572265 0.5 0.1569824 1 0.1567382 0.5 0.1569824 0.5 0.1567382 1 0.1564941 0.5 0.1567382 0.5 0.1564941 1 0.15625 0.5 0.1564941 0.5 0.15625 1 0.1560058 0.5 0.15625 0.5 0.1560058 1 0.1557617 0.5 0.1560058 0.5 0.1557617 1 0.1555175 0.5 0.1557617 0.5 0.1555175 1 0.1552734 0.5 0.1555175 0.5 0.1552734 1 0.1550292 0.5 0.1552734 0.5 0.1550292 1 0.1547851 0.5 0.1550292 0.5 0.1547851 1 0.154541 0.5 0.1547851 0.5 0.154541 1 0.1542968 0.5 0.154541 0.5 0.1542968 1 0.1540527 0.5 0.1542968 0.5 0.1540527 1 0.1538085 0.5 0.1540527 0.5 0.1538085 1 0.1535644 0.5 0.1538085 0.5 0.1535644 1 0.1533203 0.5 0.1535644 0.5 0.1533203 1 0.1530761 0.5 0.1533203 0.5 0.1530761 1 0.152832 0.5 0.1530761 0.5 0.152832 1 0.1525878 0.5 0.152832 0.5 0.1525878 1 0.1523437 0.5 0.1525878 0.5 0.1523437 1 0.1520996 0.5 0.1523437 0.5 0.1520996 1 0.1518554 0.5 0.1520996 0.5 0.1518554 1 0.1516113 0.5 0.1518554 0.5 0.1516113 1 0.1513671 0.5 0.1516113 0.5 0.1513671 1 0.151123 0.5 0.1513671 0.5 0.151123 1 0.1508789 0.5 0.151123 0.5 0.1508789 1 0.1506347 0.5 0.1508789 0.5 0.1506347 1 0.1503906 0.5 0.1506347 0.5 0.1503906 1 0.1501464 0.5 0.1503906 0.5 0.1501464 1 0.1499023 0.5 0.1501464 0.5 0.1499023 1 0.1496582 0.5 0.1499023 0.5 0.1496582 1 0.149414 0.5 0.1496582 0.5 0.149414 1 0.1491699 0.5 0.149414 0.5 0.1491699 1 0.1489257 0.5 0.1491699 0.5 0.1489257 1 0.1486816 0.5 0.1489257 0.5 0.1486816 1 0.1484375 0.5 0.1486816 0.5 0.1484375 1 0.1481933 0.5 0.1484375 0.5 0.1481933 1 0.1479492 0.5 0.1481933 0.5 0.1479492 1 0.147705 0.5 0.1479492 0.5 0.147705 1 0.1474609 0.5 0.147705 0.5 0.1474609 1 0.1472167 0.5 0.1474609 0.5 0.1472167 1 0.1469726 0.5 0.1472167 0.5 0.1469726 1 0.1467285 0.5 0.1469726 0.5 0.1467285 1 0.1464843 0.5 0.1467285 0.5 0.1464843 1 0.1462402 0.5 0.1464843 0.5 0.1462402 1 0.145996 0.5 0.1462402 0.5 0.145996 1 0.1457519 0.5 0.145996 0.5 0.1457519 1 0.1455078 0.5 0.1457519 0.5 0.1455078 1 0.1452636 0.5 0.1455078 0.5 0.1452636 1 0.1450195 0.5 0.1452636 0.5 0.1450195 1 0.1447753 0.5 0.1450195 0.5 0.1447753 1 0.1445312 0.5 0.1447753 0.5 0.1445312 1 0.1442871 0.5 0.1445312 0.5 0.1442871 1 0.1440429 0.5 0.1442871 0.5 0.1440429 1 0.1437988 0.5 0.1440429 0.5 0.1437988 1 0.1435546 0.5 0.1437988 0.5 0.1435546 1 0.1433105 0.5 0.1435546 0.5 0.1433105 1 0.1430664 0.5 0.1433105 0.5 0.1430664 1 0.1428222 0.5 0.1430664 0.5 0.1428222 1 0.1425781 0.5 0.1428222 0.5 0.1425781 1 0.1423339 0.5 0.1425781 0.5 0.1423339 1 0.1420898 0.5 0.1423339 0.5 0.1420898 1 0.1418457 0.5 0.1420898 0.5 0.1418457 1 0.1416015 0.5 0.1418457 0.5 0.1416015 1 0.1413574 0.5 0.1416015 0.5 0.1413574 1 0.1411132 0.5 0.1413574 0.5 0.1411132 1 0.1408691 0.5 0.1411132 0.5 0.1408691 1 0.140625 0.5 0.1408691 0.5 0.140625 1 0.1403808 0.5 0.140625 0.5 0.1403808 1 0.1401367 0.5 0.1403808 0.5 0.1401367 1 0.1398925 0.5 0.1401367 0.5 0.1398925 1 0.1396484 0.5 0.1398925 0.5 0.1396484 1 0.1394042 0.5 0.1396484 0.5 0.1394042 1 0.1391601 0.5 0.1394042 0.5 0.1391601 1 0.138916 0.5 0.1391601 0.5 0.138916 1 0.1386718 0.5 0.138916 0.5 0.1386718 1 0.1384277 0.5 0.1386718 0.5 0.1384277 1 0.1381835 0.5 0.1384277 0.5 0.1381835 1 0.1379394 0.5 0.1381835 0.5 0.1379394 1 0.1376953 0.5 0.1379394 0.5 0.1376953 1 0.1374511 0.5 0.1376953 0.5 0.1374511 1 0.137207 0.5 0.1374511 0.5 0.137207 1 0.1369628 0.5 0.137207 0.5 0.1369628 1 0.1367187 0.5 0.1369628 0.5 0.1367187 1 0.1364746 0.5 0.1367187 0.5 0.1364746 1 0.1362304 0.5 0.1364746 0.5 0.1362304 1 0.1359863 0.5 0.1362304 0.5 0.1359863 1 0.1357421 0.5 0.1359863 0.5 0.1357421 1 0.135498 0.5 0.1357421 0.5 0.135498 1 0.1352539 0.5 0.135498 0.5 0.1352539 1 0.1350097 0.5 0.1352539 0.5 0.1350097 1 0.1347656 0.5 0.1350097 0.5 0.1347656 1 0.1345214 0.5 0.1347656 0.5 0.1345214 1 0.1342773 0.5 0.1345214 0.5 0.1342773 1 0.1340332 0.5 0.1342773 0.5 0.1340332 1 0.133789 0.5 0.1340332 0.5 0.133789 1 0.1335449 0.5 0.133789 0.5 0.1335449 1 0.1333007 0.5 0.1335449 0.5 0.1333007 1 0.1330566 0.5 0.1333007 0.5 0.1330566 1 0.1328125 0.5 0.1330566 0.5 0.1328125 1 0.1325683 0.5 0.1328125 0.5 0.1325683 1 0.1323242 0.5 0.1325683 0.5 0.1323242 1 0.13208 0.5 0.1323242 0.5 0.13208 1 0.1318359 0.5 0.13208 0.5 0.1318359 1 0.1315917 0.5 0.1318359 0.5 0.1315917 1 0.1313476 0.5 0.1315917 0.5 0.1313476 1 0.1311035 0.5 0.1313476 0.5 0.1311035 1 0.1308593 0.5 0.1311035 0.5 0.1308593 1 0.1306152 0.5 0.1308593 0.5 0.1306152 1 0.130371 0.5 0.1306152 0.5 0.130371 1 0.1301269 0.5 0.130371 0.5 0.1301269 1 0.1298828 0.5 0.1301269 0.5 0.1298828 1 0.1296386 0.5 0.1298828 0.5 0.1296386 1 0.1293945 0.5 0.1296386 0.5 0.1293945 1 0.1291503 0.5 0.1293945 0.5 0.1291503 1 0.1289062 0.5 0.1291503 0.5 0.1289062 1 0.1286621 0.5 0.1289062 0.5 0.1286621 1 0.1284179 0.5 0.1286621 0.5 0.1284179 1 0.1281738 0.5 0.1284179 0.5 0.1281738 1 0.1279296 0.5 0.1281738 0.5 0.1279296 1 0.1276855 0.5 0.1279296 0.5 0.1276855 1 0.1274414 0.5 0.1276855 0.5 0.1274414 1 0.1271972 0.5 0.1274414 0.5 0.1271972 1 0.1269531 0.5 0.1271972 0.5 0.1269531 1 0.1267089 0.5 0.1269531 0.5 0.1267089 1 0.1264648 0.5 0.1267089 0.5 0.1264648 1 0.1262207 0.5 0.1264648 0.5 0.1262207 1 0.1259765 0.5 0.1262207 0.5 0.1259765 1 0.1257324 0.5 0.1259765 0.5 0.1257324 1 0.1254882 0.5 0.1257324 0.5 0.1254882 1 0.1252441 0.5 0.1254882 0.5 0.1252441 1 0.125 0.5 0.1252441 0.5 0.125 1 0.1247558 0.5 0.125 0.5 0.1247558 1 0.1245117 0.5 0.1247558 0.5 0.1245117 1 0.1242675 0.5 0.1245117 0.5 0.1242675 1 0.1240234 0.5 0.1242675 0.5 0.1240234 1 0.1237792 0.5 0.1240234 0.5 0.1237792 1 0.1235351 0.5 0.1237792 0.5 0.1235351 1 0.123291 0.5 0.1235351 0.5 0.123291 1 0.1230468 0.5 0.123291 0.5 0.1230468 1 0.1228027 0.5 0.1230468 0.5 0.1228027 1 0.1225585 0.5 0.1228027 0.5 0.1225585 1 0.1223144 0.5 0.1225585 0.5 0.1223144 1 0.1220703 0.5 0.1223144 0.5 0.1220703 1 0.1218261 0.5 0.1220703 0.5 0.1218261 1 0.121582 0.5 0.1218261 0.5 0.121582 1 0.1213378 0.5 0.121582 0.5 0.1213378 1 0.1210937 0.5 0.1213378 0.5 0.1210937 1 0.1208496 0.5 0.1210937 0.5 0.1208496 1 0.1206054 0.5 0.1208496 0.5 0.1206054 1 0.1203613 0.5 0.1206054 0.5 0.1203613 1 0.1201171 0.5 0.1203613 0.5 0.1201171 1 0.119873 0.5 0.1201171 0.5 0.119873 1 0.1196289 0.5 0.119873 0.5 0.1196289 1 0.1193847 0.5 0.1196289 0.5 0.1193847 1 0.1191406 0.5 0.1193847 0.5 0.1191406 1 0.1188964 0.5 0.1191406 0.5 0.1188964 1 0.1186523 0.5 0.1188964 0.5 0.1186523 1 0.1184082 0.5 0.1186523 0.5 0.1184082 1 0.118164 0.5 0.1184082 0.5 0.118164 1 0.1179199 0.5 0.118164 0.5 0.1179199 1 0.1176757 0.5 0.1179199 0.5 0.1176757 1 0.1174316 0.5 0.1176757 0.5 0.1174316 1 0.1171875 0.5 0.1174316 0.5 0.1171875 1 0.1169433 0.5 0.1171875 0.5 0.1169433 1 0.1166992 0.5 0.1169433 0.5 0.1166992 1 0.116455 0.5 0.1166992 0.5 0.116455 1 0.1162109 0.5 0.116455 0.5 0.1162109 1 0.1159667 0.5 0.1162109 0.5 0.1159667 1 0.1157226 0.5 0.1159667 0.5 0.1157226 1 0.1154785 0.5 0.1157226 0.5 0.1154785 1 0.1152343 0.5 0.1154785 0.5 0.1152343 1 0.1149902 0.5 0.1152343 0.5 0.1149902 1 0.114746 0.5 0.1149902 0.5 0.114746 1 0.1145019 0.5 0.114746 0.5 0.1145019 1 0.1142578 0.5 0.1145019 0.5 0.1142578 1 0.1140136 0.5 0.1142578 0.5 0.1140136 1 0.1137695 0.5 0.1140136 0.5 0.1137695 1 0.1135253 0.5 0.1137695 0.5 0.1135253 1 0.1132812 0.5 0.1135253 0.5 0.1132812 1 0.1130371 0.5 0.1132812 0.5 0.1130371 1 0.1127929 0.5 0.1130371 0.5 0.1127929 1 0.1125488 0.5 0.1127929 0.5 0.1125488 1 0.1123046 0.5 0.1125488 0.5 0.1123046 1 0.1120605 0.5 0.1123046 0.5 0.1120605 1 0.1118164 0.5 0.1120605 0.5 0.1118164 1 0.1115722 0.5 0.1118164 0.5 0.1115722 1 0.1113281 0.5 0.1115722 0.5 0.1113281 1 0.1110839 0.5 0.1113281 0.5 0.1110839 1 0.1108398 0.5 0.1110839 0.5 0.1108398 1 0.1105957 0.5 0.1108398 0.5 0.1105957 1 0.1103515 0.5 0.1105957 0.5 0.1103515 1 0.1101074 0.5 0.1103515 0.5 0.1101074 1 0.1098632 0.5 0.1101074 0.5 0.1098632 1 0.1096191 0.5 0.1098632 0.5 0.1096191 1 0.109375 0.5 0.1096191 0.5 0.109375 1 0.1091308 0.5 0.109375 0.5 0.1091308 1 0.1088867 0.5 0.1091308 0.5 0.1088867 1 0.1086425 0.5 0.1088867 0.5 0.1086425 1 0.1083984 0.5 0.1086425 0.5 0.1083984 1 0.1081542 0.5 0.1083984 0.5 0.1081542 1 0.1079101 0.5 0.1081542 0.5 0.1079101 1 0.107666 0.5 0.1079101 0.5 0.107666 1 0.1074218 0.5 0.107666 0.5 0.1074218 1 0.1071777 0.5 0.1074218 0.5 0.1071777 1 0.1069335 0.5 0.1071777 0.5 0.1069335 1 0.1066894 0.5 0.1069335 0.5 0.1066894 1 0.1064453 0.5 0.1066894 0.5 0.1064453 1 0.1062011 0.5 0.1064453 0.5 0.1062011 1 0.105957 0.5 0.1062011 0.5 0.105957 1 0.1057128 0.5 0.105957 0.5 0.1057128 1 0.1054687 0.5 0.1057128 0.5 0.1054687 1 0.1052246 0.5 0.1054687 0.5 0.1052246 1 0.1049804 0.5 0.1052246 0.5 0.1049804 1 0.1047363 0.5 0.1049804 0.5 0.1047363 1 0.1044921 0.5 0.1047363 0.5 0.1044921 1 0.104248 0.5 0.1044921 0.5 0.104248 1 0.1040039 0.5 0.104248 0.5 0.1040039 1 0.1037597 0.5 0.1040039 0.5 0.1037597 1 0.1035156 0.5 0.1037597 0.5 0.1035156 1 0.1032714 0.5 0.1035156 0.5 0.1032714 1 0.1030273 0.5 0.1032714 0.5 0.1030273 1 0.1027832 0.5 0.1030273 0.5 0.1027832 1 0.102539 0.5 0.1027832 0.5 0.102539 1 0.1022949 0.5 0.102539 0.5 0.1022949 1 0.1020507 0.5 0.1022949 0.5 0.1020507 1 0.1018066 0.5 0.1020507 0.5 0.1018066 1 0.1015625 0.5 0.1018066 0.5 0.1015625 1 0.1013183 0.5 0.1015625 0.5 0.1013183 1 0.1010742 0.5 0.1013183 0.5 0.1010742 1 0.10083 0.5 0.1010742 0.5 0.10083 1 0.1005859 0.5 0.10083 0.5 0.1005859 1 0.1003417 0.5 0.1005859 0.5 0.1003417 1 0.1000976 0.5 0.1003417 0.5 0.1000976 1 0.09985351 0.5 0.1000976 0.5 0.09985351 1 0.09960937 0.5 0.09985351 0.5 0.09960937 1 0.09936523 0.5 0.09960937 0.5 0.09936523 1 0.09912109 0.5 0.09936523 0.5 0.09912109 1 0.09887695 0.5 0.09912109 0.5 0.09887695 1 0.09863281 0.5 0.09887695 0.5 0.09863281 1 0.09838867 0.5 0.09863281 0.5 0.09838867 1 0.09814453 0.5 0.09838867 0.5 0.09814453 1 0.09790039 0.5 0.09814453 0.5 0.09790039 1 0.09765625 0.5 0.09790039 0.5 0.09765625 1 0.0974121 0.5 0.09765625 0.5 0.0974121 1 0.09716796 0.5 0.0974121 0.5 0.09716796 1 0.09692382 0.5 0.09716796 0.5 0.09692382 1 0.09667968 0.5 0.09692382 0.5 0.09667968 1 0.09643554 0.5 0.09667968 0.5 0.09643554 1 0.0961914 0.5 0.09643554 0.5 0.0961914 1 0.09594726 0.5 0.0961914 0.5 0.09594726 1 0.09570312 0.5 0.09594726 0.5 0.09570312 1 0.09545898 0.5 0.09570312 0.5 0.09545898 1 0.09521484 0.5 0.09545898 0.5 0.09521484 1 0.0949707 0.5 0.09521484 0.5 0.0949707 1 0.09472656 0.5 0.0949707 0.5 0.09472656 1 0.09448242 0.5 0.09472656 0.5 0.09448242 1 0.09423828 0.5 0.09448242 0.5 0.09423828 1 0.09399414 0.5 0.09423828 0.5 0.09399414 1 0.09375 0.5 0.09399414 0.5 0.09375 1 0.09350585 0.5 0.09375 0.5 0.09350585 1 0.09326171 0.5 0.09350585 0.5 0.09326171 1 0.09301757 0.5 0.09326171 0.5 0.09301757 1 0.09277343 0.5 0.09301757 0.5 0.09277343 1 0.09252929 0.5 0.09277343 0.5 0.09252929 1 0.09228515 0.5 0.09252929 0.5 0.09228515 1 0.09204101 0.5 0.09228515 0.5 0.09204101 1 0.09179687 0.5 0.09204101 0.5 0.09179687 1 0.09155273 0.5 0.09179687 0.5 0.09155273 1 0.09130859 0.5 0.09155273 0.5 0.09130859 1 0.09106445 0.5 0.09130859 0.5 0.09106445 1 0.09082031 0.5 0.09106445 0.5 0.09082031 1 0.09057617 0.5 0.09082031 0.5 0.09057617 1 0.09033203 0.5 0.09057617 0.5 0.09033203 1 0.09008789 0.5 0.09033203 0.5 0.09008789 1 0.08984375 0.5 0.09008789 0.5 0.08984375 1 0.0895996 0.5 0.08984375 0.5 0.0895996 1 0.08935546 0.5 0.0895996 0.5 0.08935546 1 0.08911132 0.5 0.08935546 0.5 0.08911132 1 0.08886718 0.5 0.08911132 0.5 0.08886718 1 0.08862304 0.5 0.08886718 0.5 0.08862304 1 0.0883789 0.5 0.08862304 0.5 0.0883789 1 0.08813476 0.5 0.0883789 0.5 0.08813476 1 0.08789062 0.5 0.08813476 0.5 0.08789062 1 0.08764648 0.5 0.08789062 0.5 0.08764648 1 0.08740234 0.5 0.08764648 0.5 0.08740234 1 0.0871582 0.5 0.08740234 0.5 0.0871582 1 0.08691406 0.5 0.0871582 0.5 0.08691406 1 0.08666992 0.5 0.08691406 0.5 0.08666992 1 0.08642578 0.5 0.08666992 0.5 0.08642578 1 0.08618164 0.5 0.08642578 0.5 0.08618164 1 0.0859375 0.5 0.08618164 0.5 0.0859375 1 0.08569335 0.5 0.0859375 0.5 0.08569335 1 0.08544921 0.5 0.08569335 0.5 0.08544921 1 0.08520507 0.5 0.08544921 0.5 0.08520507 1 0.08496093 0.5 0.08520507 0.5 0.08496093 1 0.08471679 0.5 0.08496093 0.5 0.08471679 1 0.08447265 0.5 0.08471679 0.5 0.08447265 1 0.08422851 0.5 0.08447265 0.5 0.08422851 1 0.08398437 0.5 0.08422851 0.5 0.08398437 1 0.08374023 0.5 0.08398437 0.5 0.08374023 1 0.08349609 0.5 0.08374023 0.5 0.08349609 1 0.08325195 0.5 0.08349609 0.5 0.08325195 1 0.08300781 0.5 0.08325195 0.5 0.08300781 1 0.08276367 0.5 0.08300781 0.5 0.08276367 1 0.08251953 0.5 0.08276367 0.5 0.08251953 1 0.08227539 0.5 0.08251953 0.5 0.08227539 1 0.08203125 0.5 0.08227539 0.5 0.08203125 1 0.0817871 0.5 0.08203125 0.5 0.0817871 1 0.08154296 0.5 0.0817871 0.5 0.08154296 1 0.08129882 0.5 0.08154296 0.5 0.08129882 1 0.08105468 0.5 0.08129882 0.5 0.08105468 1 0.08081054 0.5 0.08105468 0.5 0.08081054 1 0.0805664 0.5 0.08081054 0.5 0.0805664 1 0.08032226 0.5 0.0805664 0.5 0.08032226 1 0.08007812 0.5 0.08032226 0.5 0.08007812 1 0.07983398 0.5 0.08007812 0.5 0.07983398 1 0.07958984 0.5 0.07983398 0.5 0.07958984 1 0.0793457 0.5 0.07958984 0.5 0.0793457 1 0.07910156 0.5 0.0793457 0.5 0.07910156 1 0.07885742 0.5 0.07910156 0.5 0.07885742 1 0.07861328 0.5 0.07885742 0.5 0.07861328 1 0.07836914 0.5 0.07861328 0.5 0.07836914 1 0.078125 0.5 0.07836914 0.5 0.078125 1 0.07788085 0.5 0.078125 0.5 0.07788085 1 0.07763671 0.5 0.07788085 0.5 0.07763671 1 0.07739257 0.5 0.07763671 0.5 0.07739257 1 0.07714843 0.5 0.07739257 0.5 0.07714843 1 0.07690429 0.5 0.07714843 0.5 0.07690429 1 0.07666015 0.5 0.07690429 0.5 0.07666015 1 0.07641601 0.5 0.07666015 0.5 0.07641601 1 0.07617187 0.5 0.07641601 0.5 0.07617187 1 0.07592773 0.5 0.07617187 0.5 0.07592773 1 0.07568359 0.5 0.07592773 0.5 0.07568359 1 0.07543945 0.5 0.07568359 0.5 0.07543945 1 0.07519531 0.5 0.07543945 0.5 0.07519531 1 0.07495117 0.5 0.07519531 0.5 0.07495117 1 0.07470703 0.5 0.07495117 0.5 0.07470703 1 0.07446289 0.5 0.07470703 0.5 0.07446289 1 0.07421875 0.5 0.07446289 0.5 0.07421875 1 0.0739746 0.5 0.07421875 0.5 0.0739746 1 0.07373046 0.5 0.0739746 0.5 0.07373046 1 0.07348632 0.5 0.07373046 0.5 0.07348632 1 0.07324218 0.5 0.07348632 0.5 0.07324218 1 0.07299804 0.5 0.07324218 0.5 0.07299804 1 0.0727539 0.5 0.07299804 0.5 0.0727539 1 0.07250976 0.5 0.0727539 0.5 0.07250976 1 0.07226562 0.5 0.07250976 0.5 0.07226562 1 0.07202148 0.5 0.07226562 0.5 0.07202148 1 0.07177734 0.5 0.07202148 0.5 0.07177734 1 0.0715332 0.5 0.07177734 0.5 0.0715332 1 0.07128906 0.5 0.0715332 0.5 0.07128906 1 0.07104492 0.5 0.07128906 0.5 0.07104492 1 0.07080078 0.5 0.07104492 0.5 0.07080078 1 0.07055664 0.5 0.07080078 0.5 0.07055664 1 0.0703125 0.5 0.07055664 0.5 0.0703125 1 0.07006835 0.5 0.0703125 0.5 0.07006835 1 0.06982421 0.5 0.07006835 0.5 0.06982421 1 0.06958007 0.5 0.06982421 0.5 0.06958007 1 0.06933593 0.5 0.06958007 0.5 0.06933593 1 0.06909179 0.5 0.06933593 0.5 0.06909179 1 0.06884765 0.5 0.06909179 0.5 0.06884765 1 0.06860351 0.5 0.06884765 0.5 0.06860351 1 0.06835937 0.5 0.06860351 0.5 0.06835937 1 0.06811523 0.5 0.06835937 0.5 0.06811523 1 0.06787109 0.5 0.06811523 0.5 0.06787109 1 0.06762695 0.5 0.06787109 0.5 0.06762695 1 0.06738281 0.5 0.06762695 0.5 0.06738281 1 0.06713867 0.5 0.06738281 0.5 0.06713867 1 0.06689453 0.5 0.06713867 0.5 0.06689453 1 0.06665039 0.5 0.06689453 0.5 0.06665039 1 0.06640625 0.5 0.06665039 0.5 0.06640625 1 0.0661621 0.5 0.06640625 0.5 0.0661621 1 0.06591796 0.5 0.0661621 0.5 0.06591796 1 0.06567382 0.5 0.06591796 0.5 0.06567382 1 0.06542968 0.5 0.06567382 0.5 0.06542968 1 0.06518554 0.5 0.06542968 0.5 0.06518554 1 0.0649414 0.5 0.06518554 0.5 0.0649414 1 0.06469726 0.5 0.0649414 0.5 0.06469726 1 0.06445312 0.5 0.06469726 0.5 0.06445312 1 0.06420898 0.5 0.06445312 0.5 0.06420898 1 0.06396484 0.5 0.06420898 0.5 0.06396484 1 0.0637207 0.5 0.06396484 0.5 0.0637207 1 0.06347656 0.5 0.0637207 0.5 0.06347656 1 0.06323242 0.5 0.06347656 0.5 0.06323242 1 0.06298828 0.5 0.06323242 0.5 0.06298828 1 0.06274414 0.5 0.06298828 0.5 0.06274414 1 0.0625 0.5 0.06274414 0.5 0.0625 1 0.06225585 0.5 0.0625 0.5 0.06225585 1 0.06201171 0.5 0.06225585 0.5 0.06201171 1 0.06176757 0.5 0.06201171 0.5 0.06176757 1 0.06152343 0.5 0.06176757 0.5 0.06152343 1 0.06127929 0.5 0.06152343 0.5 0.06127929 1 0.06103515 0.5 0.06127929 0.5 0.06103515 1 0.06079101 0.5 0.06103515 0.5 0.06079101 1 0.06054687 0.5 0.06079101 0.5 0.06054687 1 0.06030273 0.5 0.06054687 0.5 0.06030273 1 0.06005859 0.5 0.06030273 0.5 0.06005859 1 0.05981445 0.5 0.06005859 0.5 0.05981445 1 0.05957031 0.5 0.05981445 0.5 0.05957031 1 0.05932617 0.5 0.05957031 0.5 0.05932617 1 0.05908203 0.5 0.05932617 0.5 0.05908203 1 0.05883789 0.5 0.05908203 0.5 0.05883789 1 0.05859375 0.5 0.05883789 0.5 0.05859375 1 0.0583496 0.5 0.05859375 0.5 0.0583496 1 0.05810546 0.5 0.0583496 0.5 0.05810546 1 0.05786132 0.5 0.05810546 0.5 0.05786132 1 0.05761718 0.5 0.05786132 0.5 0.05761718 1 0.05737304 0.5 0.05761718 0.5 0.05737304 1 0.0571289 0.5 0.05737304 0.5 0.0571289 1 0.05688476 0.5 0.0571289 0.5 0.05688476 1 0.05664062 0.5 0.05688476 0.5 0.05664062 1 0.05639648 0.5 0.05664062 0.5 0.05639648 1 0.05615234 0.5 0.05639648 0.5 0.05615234 1 0.0559082 0.5 0.05615234 0.5 0.0559082 1 0.05566406 0.5 0.0559082 0.5 0.05566406 1 0.05541992 0.5 0.05566406 0.5 0.05541992 1 0.05517578 0.5 0.05541992 0.5 0.05517578 1 0.05493164 0.5 0.05517578 0.5 0.05493164 1 0.0546875 0.5 0.05493164 0.5 0.0546875 1 0.05444335 0.5 0.0546875 0.5 0.05444335 1 0.05419921 0.5 0.05444335 0.5 0.05419921 1 0.05395507 0.5 0.05419921 0.5 0.05395507 1 0.05371093 0.5 0.05395507 0.5 0.05371093 1 0.05346679 0.5 0.05371093 0.5 0.05346679 1 0.05322265 0.5 0.05346679 0.5 0.05322265 1 0.05297851 0.5 0.05322265 0.5 0.05297851 1 0.05273437 0.5 0.05297851 0.5 0.05273437 1 0.05249023 0.5 0.05273437 0.5 0.05249023 1 0.05224609 0.5 0.05249023 0.5 0.05224609 1 0.05200195 0.5 0.05224609 0.5 0.05200195 1 0.05175781 0.5 0.05200195 0.5 0.05175781 1 0.05151367 0.5 0.05175781 0.5 0.05151367 1 0.05126953 0.5 0.05151367 0.5 0.05126953 1 0.05102539 0.5 0.05126953 0.5 0.05102539 1 0.05078125 0.5 0.05102539 0.5 0.05078125 1 0.0505371 0.5 0.05078125 0.5 0.0505371 1 0.05029296 0.5 0.0505371 0.5 0.05029296 1 0.05004882 0.5 0.05029296 0.5 0.05004882 1 0.04980468 0.5 0.05004882 0.5 0.04980468 1 0.04956054 0.5 0.04980468 0.5 0.04956054 1 0.0493164 0.5 0.04956054 0.5 0.0493164 1 0.04907226 0.5 0.0493164 0.5 0.04907226 1 0.04882812 0.5 0.04907226 0.5 0.04882812 1 0.04858398 0.5 0.04882812 0.5 0.04858398 1 0.04833984 0.5 0.04858398 0.5 0.04833984 1 0.0480957 0.5 0.04833984 0.5 0.0480957 1 0.04785156 0.5 0.0480957 0.5 0.04785156 1 0.04760742 0.5 0.04785156 0.5 0.04760742 1 0.04736328 0.5 0.04760742 0.5 0.04736328 1 0.04711914 0.5 0.04736328 0.5 0.04711914 1 0.046875 0.5 0.04711914 0.5 0.046875 1 0.04663085 0.5 0.046875 0.5 0.04663085 1 0.04638671 0.5 0.04663085 0.5 0.04638671 1 0.04614257 0.5 0.04638671 0.5 0.04614257 1 0.04589843 0.5 0.04614257 0.5 0.04589843 1 0.04565429 0.5 0.04589843 0.5 0.04565429 1 0.04541015 0.5 0.04565429 0.5 0.04541015 1 0.04516601 0.5 0.04541015 0.5 0.04516601 1 0.04492187 0.5 0.04516601 0.5 0.04492187 1 0.04467773 0.5 0.04492187 0.5 0.04467773 1 0.04443359 0.5 0.04467773 0.5 0.04443359 1 0.04418945 0.5 0.04443359 0.5 0.04418945 1 0.04394531 0.5 0.04418945 0.5 0.04394531 1 0.04370117 0.5 0.04394531 0.5 0.04370117 1 0.04345703 0.5 0.04370117 0.5 0.04345703 1 0.04321289 0.5 0.04345703 0.5 0.04321289 1 0.04296875 0.5 0.04321289 0.5 0.04296875 1 0.0427246 0.5 0.04296875 0.5 0.0427246 1 0.04248046 0.5 0.0427246 0.5 0.04248046 1 0.04223632 0.5 0.04248046 0.5 0.04223632 1 0.04199218 0.5 0.04223632 0.5 0.04199218 1 0.04174804 0.5 0.04199218 0.5 0.04174804 1 0.0415039 0.5 0.04174804 0.5 0.0415039 1 0.04125976 0.5 0.0415039 0.5 0.04125976 1 0.04101562 0.5 0.04125976 0.5 0.04101562 1 0.04077148 0.5 0.04101562 0.5 0.04077148 1 0.04052734 0.5 0.04077148 0.5 0.04052734 1 0.0402832 0.5 0.04052734 0.5 0.0402832 1 0.04003906 0.5 0.0402832 0.5 0.04003906 1 0.03979492 0.5 0.04003906 0.5 0.03979492 1 0.03955078 0.5 0.03979492 0.5 0.03955078 1 0.03930664 0.5 0.03955078 0.5 0.03930664 1 0.0390625 0.5 0.03930664 0.5 0.0390625 1 0.03881835 0.5 0.0390625 0.5 0.03881835 1 0.03857421 0.5 0.03881835 0.5 0.03857421 1 0.03833007 0.5 0.03857421 0.5 0.03833007 1 0.03808593 0.5 0.03833007 0.5 0.03808593 1 0.03784179 0.5 0.03808593 0.5 0.03784179 1 0.03759765 0.5 0.03784179 0.5 0.03759765 1 0.03735351 0.5 0.03759765 0.5 0.03735351 1 0.03710937 0.5 0.03735351 0.5 0.03710937 1 0.03686523 0.5 0.03710937 0.5 0.03686523 1 0.03662109 0.5 0.03686523 0.5 0.03662109 1 0.03637695 0.5 0.03662109 0.5 0.03637695 1 0.03613281 0.5 0.03637695 0.5 0.03613281 1 0.03588867 0.5 0.03613281 0.5 0.03588867 1 0.03564453 0.5 0.03588867 0.5 0.03564453 1 0.03540039 0.5 0.03564453 0.5 0.03540039 1 0.03515625 0.5 0.03540039 0.5 0.03515625 1 0.0349121 0.5 0.03515625 0.5 0.0349121 1 0.03466796 0.5 0.0349121 0.5 0.03466796 1 0.03442382 0.5 0.03466796 0.5 0.03442382 1 0.03417968 0.5 0.03442382 0.5 0.03417968 1 0.03393554 0.5 0.03417968 0.5 0.03393554 1 0.0336914 0.5 0.03393554 0.5 0.0336914 1 0.03344726 0.5 0.0336914 0.5 0.03344726 1 0.03320312 0.5 0.03344726 0.5 0.03320312 1 0.03295898 0.5 0.03320312 0.5 0.03295898 1 0.03271484 0.5 0.03295898 0.5 0.03271484 1 0.0324707 0.5 0.03271484 0.5 0.0324707 1 0.03222656 0.5 0.0324707 0.5 0.03222656 1 0.03198242 0.5 0.03222656 0.5 0.03198242 1 0.03173828 0.5 0.03198242 0.5 0.03173828 1 0.03149414 0.5 0.03173828 0.5 0.03149414 1 0.03125 0.5 0.03149414 0.5 0.03125 1 0.03100585 0.5 0.03125 0.5 0.03100585 1 0.03076171 0.5 0.03100585 0.5 0.03076171 1 0.03051757 0.5 0.03076171 0.5 0.03051757 1 0.03027343 0.5 0.03051757 0.5 0.03027343 1 0.03002929 0.5 0.03027343 0.5 0.03002929 1 0.02978515 0.5 0.03002929 0.5 0.02978515 1 0.02954101 0.5 0.02978515 0.5 0.02954101 1 0.02929687 0.5 0.02954101 0.5 0.02929687 1 0.02905273 0.5 0.02929687 0.5 0.02905273 1 0.02880859 0.5 0.02905273 0.5 0.02880859 1 0.02856445 0.5 0.02880859 0.5 0.02856445 1 0.02832031 0.5 0.02856445 0.5 0.02832031 1 0.02807617 0.5 0.02832031 0.5 0.02807617 1 0.02783203 0.5 0.02807617 0.5 0.02783203 1 0.02758789 0.5 0.02783203 0.5 0.02758789 1 0.02734375 0.5 0.02758789 0.5 0.02734375 1 0.0270996 0.5 0.02734375 0.5 0.0270996 1 0.02685546 0.5 0.0270996 0.5 0.02685546 1 0.02661132 0.5 0.02685546 0.5 0.02661132 1 0.02636718 0.5 0.02661132 0.5 0.02636718 1 0.02612304 0.5 0.02636718 0.5 0.02612304 1 0.0258789 0.5 0.02612304 0.5 0.0258789 1 0.02563476 0.5 0.0258789 0.5 0.02563476 1 0.02539062 0.5 0.02563476 0.5 0.02539062 1 0.02514648 0.5 0.02539062 0.5 0.02514648 1 0.02490234 0.5 0.02514648 0.5 0.02490234 1 0.0246582 0.5 0.02490234 0.5 0.0246582 1 0.02441406 0.5 0.0246582 0.5 0.02441406 1 0.02416992 0.5 0.02441406 0.5 0.02416992 1 0.02392578 0.5 0.02416992 0.5 0.02392578 1 0.02368164 0.5 0.02392578 0.5 0.02368164 1 0.0234375 0.5 0.02368164 0.5 0.0234375 1 0.02319335 0.5 0.0234375 0.5 0.02319335 1 0.02294921 0.5 0.02319335 0.5 0.02294921 1 0.02270507 0.5 0.02294921 0.5 0.02270507 1 0.02246093 0.5 0.02270507 0.5 0.02246093 1 0.02221679 0.5 0.02246093 0.5 0.02221679 1 0.02197265 0.5 0.02221679 0.5 0.02197265 1 0.02172851 0.5 0.02197265 0.5 0.02172851 1 0.02148437 0.5 0.02172851 0.5 0.02148437 1 0.02124023 0.5 0.02148437 0.5 0.02124023 1 0.02099609 0.5 0.02124023 0.5 0.02099609 1 0.02075195 0.5 0.02099609 0.5 0.02075195 1 0.02050781 0.5 0.02075195 0.5 0.02050781 1 0.02026367 0.5 0.02050781 0.5 0.02026367 1 0.02001953 0.5 0.02026367 0.5 0.02001953 1 0.01977539 0.5 0.02001953 0.5 0.01977539 1 0.01953125 0.5 0.01977539 0.5 0.01953125 1 0.0192871 0.5 0.01953125 0.5 0.0192871 1 0.01904296 0.5 0.0192871 0.5 0.01904296 1 0.01879882 0.5 0.01904296 0.5 0.01879882 1 0.01855468 0.5 0.01879882 0.5 0.01855468 1 0.01831054 0.5 0.01855468 0.5 0.01831054 1 0.0180664 0.5 0.01831054 0.5 0.0180664 1 0.01782226 0.5 0.0180664 0.5 0.01782226 1 0.01757812 0.5 0.01782226 0.5 0.01757812 1 0.01733398 0.5 0.01757812 0.5 0.01733398 1 0.01708984 0.5 0.01733398 0.5 0.01708984 1 0.0168457 0.5 0.01708984 0.5 0.0168457 1 0.01660156 0.5 0.0168457 0.5 0.01660156 1 0.01635742 0.5 0.01660156 0.5 0.01635742 1 0.01611328 0.5 0.01635742 0.5 0.01611328 1 0.01586914 0.5 0.01611328 0.5 0.01586914 1 0.015625 0.5 0.01586914 0.5 0.015625 1 0.01538085 0.5 0.015625 0.5 0.01538085 1 0.01513671 0.5 0.01538085 0.5 0.01513671 1 0.01489257 0.5 0.01513671 0.5 0.01489257 1 0.01464843 0.5 0.01489257 0.5 0.01464843 1 0.01440429 0.5 0.01464843 0.5 0.01440429 1 0.01416015 0.5 0.01440429 0.5 0.01416015 1 0.01391601 0.5 0.01416015 0.5 0.01391601 1 0.01367187 0.5 0.01391601 0.5 0.01367187 1 0.01342773 0.5 0.01367187 0.5 0.01342773 1 0.01318359 0.5 0.01342773 0.5 0.01318359 1 0.01293945 0.5 0.01318359 0.5 0.01293945 1 0.01269531 0.5 0.01293945 0.5 0.01269531 1 0.01245117 0.5 0.01269531 0.5 0.01245117 1 0.01220703 0.5 0.01245117 0.5 0.01220703 1 0.01196289 0.5 0.01220703 0.5 0.01196289 1 0.01171875 0.5 0.01196289 0.5 0.01171875 1 0.0114746 0.5 0.01171875 0.5 0.0114746 1 0.01123046 0.5 0.0114746 0.5 0.01123046 1 0.01098632 0.5 0.01123046 0.5 0.01098632 1 0.01074218 0.5 0.01098632 0.5 0.01074218 1 0.01049804 0.5 0.01074218 0.5 0.01049804 1 0.0102539 0.5 0.01049804 0.5 0.0102539 1 0.01000976 0.5 0.0102539 0.5 0.01000976 1 0.009765625 0.5 0.01000976 0.5 0.009765625 1 0.009521484 0.5 0.009765625 0.5 0.009521484 1 0.009277343 0.5 0.009521484 0.5 0.009277343 1 0.009033203 0.5 0.009277343 0.5 0.009033203 1 0.008789062 0.5 0.009033203 0.5 0.008789062 1 0.008544921 0.5 0.008789062 0.5 0.008544921 1 0.008300781 0.5 0.008544921 0.5 0.008300781 1 0.00805664 0.5 0.008300781 0.5 0.00805664 1 0.0078125 0.5 0.00805664 0.5 0.0078125 1 0.007568359 0.5 0.0078125 0.5 0.007568359 1 0.007324218 0.5 0.007568359 0.5 0.007324218 1 0.007080078 0.5 0.007324218 0.5 0.007080078 1 0.006835937 0.5 0.007080078 0.5 0.006835937 1 0.006591796 0.5 0.006835937 0.5 0.006591796 1 0.006347656 0.5 0.006591796 0.5 0.006347656 1 0.006103515 0.5 0.006347656 0.5 0.006103515 1 0.005859375 0.5 0.006103515 0.5 0.005859375 1 0.005615234 0.5 0.005859375 0.5 0.005615234 1 0.005371093 0.5 0.005615234 0.5 0.005371093 1 0.005126953 0.5 0.005371093 0.5 0.005126953 1 0.004882812 0.5 0.005126953 0.5 0.004882812 1 0.004638671 0.5 0.004882812 0.5 0.004638671 1 0.004394531 0.5 0.004638671 0.5 0.004394531 1 0.00415039 0.5 0.004394531 0.5 0.00415039 1 0.00390625 0.5 0.00415039 0.5 0.00390625 1 0.003662109 0.5 0.00390625 0.5 0.003662109 1 0.003417968 0.5 0.003662109 0.5 0.003417968 1 0.003173828 0.5 0.003417968 0.5 0.003173828 1 0.002929687 0.5 0.003173828 0.5 0.002929687 1 0.002685546 0.5 0.002929687 0.5 0.002685546 1 0.002441406 0.5 0.002685546 0.5 0.002441406 1 0.002197265 0.5 0.002441406 0.5 0.002197265 1 0.001953125 0.5 0.002197265 0.5 0.001953125 1 0.001708984 0.5 0.001953125 0.5 0.001708984 1 0.001464843 0.5 0.001708984 0.5 0.001464843 1 0.001220703 0.5 0.001464843 0.5 0.001220703 1 9.76562e-4 0.5 0.001220703 0.5 9.76562e-4 1 7.32422e-4 0.5 9.76562e-4 0.5 7.32422e-4 1 4.88281e-4 0.5 7.32422e-4 0.5 0.4202255 0.4191842 0.2507363 0.4899989 0.2492637 0.01000112 4.88281e-4 1 2.44141e-4 0.5 4.88281e-4 0.5 2.44141e-4 1 0 0.5 2.44141e-4 0.5 0.7503682 0.01000028 0.5100003 0.2496318 0.7496318 0.4899997 1 1 0.9997559 1 0.9997559 0.5 0.9997559 1 0.9995117 1 0.9995117 0.5 0.9995117 1 0.9992676 1 0.9992676 0.5 0.9992676 1 0.9990234 1 0.9990234 0.5 0.9990234 1 0.9987793 1 0.9987793 0.5 0.9987793 1 0.9985352 1 0.9985352 0.5 0.9985352 1 0.998291 1 0.998291 0.5 0.998291 1 0.9980469 1 0.9980469 0.5 0.9980469 1 0.9978027 1 0.9978027 0.5 0.9978027 1 0.9975586 1 0.9975586 0.5 0.9975586 1 0.9973145 1 0.9973145 0.5 0.9973145 1 0.9970703 1 0.9970703 0.5 0.9970703 1 0.9968262 1 0.9968262 0.5 0.9968262 1 0.996582 1 0.996582 0.5 0.996582 1 0.9963379 1 0.9963379 0.5 0.9963379 1 0.9960938 1 0.9960938 0.5 0.9960938 1 0.9958496 1 0.9958496 0.5 0.9958496 1 0.9956055 1 0.9956055 0.5 0.9956055 1 0.9953613 1 0.9953613 0.5 0.9953613 1 0.9951172 1 0.9951172 0.5 0.9951172 1 0.9948731 1 0.9948731 0.5 0.9948731 1 0.9946289 1 0.9946289 0.5 0.9946289 1 0.9943848 1 0.9943848 0.5 0.9943848 1 0.9941406 1 0.9941406 0.5 0.9941406 1 0.9938965 1 0.9938965 0.5 0.9938965 1 0.9936524 1 0.9936524 0.5 0.9936524 1 0.9934082 1 0.9934082 0.5 0.9934082 1 0.9931641 1 0.9931641 0.5 0.9931641 1 0.9929199 1 0.9929199 0.5 0.9929199 1 0.9926758 1 0.9926758 0.5 0.9926758 1 0.9924317 1 0.9924317 0.5 0.9924317 1 0.9921875 1 0.9921875 0.5 0.9921875 1 0.9919434 1 0.9919434 0.5 0.9919434 1 0.9916992 1 0.9916992 0.5 0.9916992 1 0.9914551 1 0.9914551 0.5 0.9914551 1 0.9912109 1 0.9912109 0.5 0.9912109 1 0.9909668 1 0.9909668 0.5 0.9909668 1 0.9907227 1 0.9907227 0.5 0.9907227 1 0.9904785 1 0.9904785 0.5 0.9904785 1 0.9902344 1 0.9902344 0.5 0.9902344 1 0.9899902 1 0.9899902 0.5 0.9899902 1 0.9897461 1 0.9897461 0.5 0.9897461 1 0.989502 1 0.989502 0.5 0.989502 1 0.9892578 1 0.9892578 0.5 0.9892578 1 0.9890137 1 0.9890137 0.5 0.9890137 1 0.9887695 1 0.9887695 0.5 0.9887695 1 0.9885254 1 0.9885254 0.5 0.9885254 1 0.9882813 1 0.9882813 0.5 0.9882813 1 0.9880371 1 0.9880371 0.5 0.9880371 1 0.987793 1 0.987793 0.5 0.987793 1 0.9875488 1 0.9875488 0.5 0.9875488 1 0.9873047 1 0.9873047 0.5 0.9873047 1 0.9870606 1 0.9870606 0.5 0.9870606 1 0.9868164 1 0.9868164 0.5 0.9868164 1 0.9865723 1 0.9865723 0.5 0.9865723 1 0.9863281 1 0.9863281 0.5 0.9863281 1 0.986084 1 0.986084 0.5 0.986084 1 0.9858399 1 0.9858399 0.5 0.9858399 1 0.9855957 1 0.9855957 0.5 0.9855957 1 0.9853516 1 0.9853516 0.5 0.9853516 1 0.9851074 1 0.9851074 0.5 0.9851074 1 0.9848633 1 0.9848633 0.5 0.9848633 1 0.9846192 1 0.9846192 0.5 0.9846192 1 0.984375 1 0.984375 0.5 0.984375 1 0.9841309 1 0.9841309 0.5 0.9841309 1 0.9838867 1 0.9838867 0.5 0.9838867 1 0.9836426 1 0.9836426 0.5 0.9836426 1 0.9833984 1 0.9833984 0.5 0.9833984 1 0.9831543 1 0.9831543 0.5 0.9831543 1 0.9829102 1 0.9829102 0.5 0.9829102 1 0.982666 1 0.982666 0.5 0.982666 1 0.9824219 1 0.9824219 0.5 0.9824219 1 0.9821777 1 0.9821777 0.5 0.9821777 1 0.9819336 1 0.9819336 0.5 0.9819336 1 0.9816895 1 0.9816895 0.5 0.9816895 1 0.9814453 1 0.9814453 0.5 0.9814453 1 0.9812012 1 0.9812012 0.5 0.9812012 1 0.980957 1 0.980957 0.5 0.980957 1 0.9807129 1 0.9807129 0.5 0.9807129 1 0.9804688 1 0.9804688 0.5 0.9804688 1 0.9802246 1 0.9802246 0.5 0.9802246 1 0.9799805 1 0.9799805 0.5 0.9799805 1 0.9797363 1 0.9797363 0.5 0.9797363 1 0.9794922 1 0.9794922 0.5 0.9794922 1 0.9792481 1 0.9792481 0.5 0.9792481 1 0.9790039 1 0.9790039 0.5 0.9790039 1 0.9787598 1 0.9787598 0.5 0.9787598 1 0.9785156 1 0.9785156 0.5 0.9785156 1 0.9782715 1 0.9782715 0.5 0.9782715 1 0.9780274 1 0.9780274 0.5 0.9780274 1 0.9777832 1 0.9777832 0.5 0.9777832 1 0.9775391 1 0.9775391 0.5 0.9775391 1 0.9772949 1 0.9772949 0.5 0.9772949 1 0.9770508 1 0.9770508 0.5 0.9770508 1 0.9768067 1 0.9768067 0.5 0.9768067 1 0.9765625 1 0.9765625 0.5 0.9765625 1 0.9763184 1 0.9763184 0.5 0.9763184 1 0.9760742 1 0.9760742 0.5 0.9760742 1 0.9758301 1 0.9758301 0.5 0.9758301 1 0.9755859 1 0.9755859 0.5 0.9755859 1 0.9753418 1 0.9753418 0.5 0.9753418 1 0.9750977 1 0.9750977 0.5 0.9750977 1 0.9748535 1 0.9748535 0.5 0.9748535 1 0.9746094 1 0.9746094 0.5 0.9746094 1 0.9743652 1 0.9743652 0.5 0.9743652 1 0.9741211 1 0.9741211 0.5 0.9741211 1 0.973877 1 0.973877 0.5 0.973877 1 0.9736328 1 0.9736328 0.5 0.9736328 1 0.9733887 1 0.9733887 0.5 0.9733887 1 0.9731445 1 0.9731445 0.5 0.9731445 1 0.9729004 1 0.9729004 0.5 0.9729004 1 0.9726563 1 0.9726563 0.5 0.9726563 1 0.9724121 1 0.9724121 0.5 0.9724121 1 0.972168 1 0.972168 0.5 0.972168 1 0.9719238 1 0.9719238 0.5 0.9719238 1 0.9716797 1 0.9716797 0.5 0.9716797 1 0.9714356 1 0.9714356 0.5 0.9714356 1 0.9711914 1 0.9711914 0.5 0.9711914 1 0.9709473 1 0.9709473 0.5 0.9709473 1 0.9707031 1 0.9707031 0.5 0.9707031 1 0.970459 1 0.970459 0.5 0.970459 1 0.9702149 1 0.9702149 0.5 0.9702149 1 0.9699707 1 0.9699707 0.5 0.9699707 1 0.9697266 1 0.9697266 0.5 0.9697266 1 0.9694824 1 0.9694824 0.5 0.9694824 1 0.9692383 1 0.9692383 0.5 0.9692383 1 0.9689942 1 0.9689942 0.5 0.9689942 1 0.96875 1 0.96875 0.5 0.96875 1 0.9685059 1 0.9685059 0.5 0.9685059 1 0.9682617 1 0.9682617 0.5 0.9682617 1 0.9680176 1 0.9680176 0.5 0.9680176 1 0.9677734 1 0.9677734 0.5 0.9677734 1 0.9675293 1 0.9675293 0.5 0.9675293 1 0.9672852 1 0.9672852 0.5 0.9672852 1 0.967041 1 0.967041 0.5 0.967041 1 0.9667969 1 0.9667969 0.5 0.9667969 1 0.9665527 1 0.9665527 0.5 0.9665527 1 0.9663086 1 0.9663086 0.5 0.9663086 1 0.9660645 1 0.9660645 0.5 0.9660645 1 0.9658203 1 0.9658203 0.5 0.9658203 1 0.9655762 1 0.9655762 0.5 0.9655762 1 0.965332 1 0.965332 0.5 0.965332 1 0.9650879 1 0.9650879 0.5 0.9650879 1 0.9648438 1 0.9648438 0.5 0.9648438 1 0.9645996 1 0.9645996 0.5 0.9645996 1 0.9643555 1 0.9643555 0.5 0.9643555 1 0.9641113 1 0.9641113 0.5 0.9641113 1 0.9638672 1 0.9638672 0.5 0.9638672 1 0.9636231 1 0.9636231 0.5 0.9636231 1 0.9633789 1 0.9633789 0.5 0.9633789 1 0.9631348 1 0.9631348 0.5 0.9631348 1 0.9628906 1 0.9628906 0.5 0.9628906 1 0.9626465 1 0.9626465 0.5 0.9626465 1 0.9624024 1 0.9624024 0.5 0.9624024 1 0.9621582 1 0.9621582 0.5 0.9621582 1 0.9619141 1 0.9619141 0.5 0.9619141 1 0.9616699 1 0.9616699 0.5 0.9616699 1 0.9614258 1 0.9614258 0.5 0.9614258 1 0.9611817 1 0.9611817 0.5 0.9611817 1 0.9609375 1 0.9609375 0.5 0.9609375 1 0.9606934 1 0.9606934 0.5 0.9606934 1 0.9604492 1 0.9604492 0.5 0.9604492 1 0.9602051 1 0.9602051 0.5 0.9602051 1 0.9599609 1 0.9599609 0.5 0.9599609 1 0.9597168 1 0.9597168 0.5 0.9597168 1 0.9594727 1 0.9594727 0.5 0.9594727 1 0.9592285 1 0.9592285 0.5 0.9592285 1 0.9589844 1 0.9589844 0.5 0.9589844 1 0.9587402 1 0.9587402 0.5 0.9587402 1 0.9584961 1 0.9584961 0.5 0.9584961 1 0.958252 1 0.958252 0.5 0.958252 1 0.9580078 1 0.9580078 0.5 0.9580078 1 0.9577637 1 0.9577637 0.5 0.9577637 1 0.9575195 1 0.9575195 0.5 0.9575195 1 0.9572754 1 0.9572754 0.5 0.9572754 1 0.9570313 1 0.9570313 0.5 0.9570313 1 0.9567871 1 0.9567871 0.5 0.9567871 1 0.956543 1 0.956543 0.5 0.956543 1 0.9562988 1 0.9562988 0.5 0.9562988 1 0.9560547 1 0.9560547 0.5 0.9560547 1 0.9558106 1 0.9558106 0.5 0.9558106 1 0.9555664 1 0.9555664 0.5 0.9555664 1 0.9553223 1 0.9553223 0.5 0.9553223 1 0.9550781 1 0.9550781 0.5 0.9550781 1 0.954834 1 0.954834 0.5 0.954834 1 0.9545899 1 0.9545899 0.5 0.9545899 1 0.9543457 1 0.9543457 0.5 0.9543457 1 0.9541016 1 0.9541016 0.5 0.9541016 1 0.9538574 1 0.9538574 0.5 0.9538574 1 0.9536133 1 0.9536133 0.5 0.9536133 1 0.9533692 1 0.9533692 0.5 0.9533692 1 0.953125 1 0.953125 0.5 0.953125 1 0.9528809 1 0.9528809 0.5 0.9528809 1 0.9526367 1 0.9526367 0.5 0.9526367 1 0.9523926 1 0.9523926 0.5 0.9523926 1 0.9521484 1 0.9521484 0.5 0.9521484 1 0.9519043 1 0.9519043 0.5 0.9519043 1 0.9516602 1 0.9516602 0.5 0.9516602 1 0.951416 1 0.951416 0.5 0.951416 1 0.9511719 1 0.9511719 0.5 0.9511719 1 0.9509277 1 0.9509277 0.5 0.9509277 1 0.9506836 1 0.9506836 0.5 0.9506836 1 0.9504395 1 0.9504395 0.5 0.9504395 1 0.9501953 1 0.9501953 0.5 0.9501953 1 0.9499512 1 0.9499512 0.5 0.9499512 1 0.949707 1 0.949707 0.5 0.949707 1 0.9494629 1 0.9494629 0.5 0.9494629 1 0.9492188 1 0.9492188 0.5 0.9492188 1 0.9489746 1 0.9489746 0.5 0.9489746 1 0.9487305 1 0.9487305 0.5 0.9487305 1 0.9484863 1 0.9484863 0.5 0.9484863 1 0.9482422 1 0.9482422 0.5 0.9482422 1 0.9479981 1 0.9479981 0.5 0.9479981 1 0.9477539 1 0.9477539 0.5 0.9477539 1 0.9475098 1 0.9475098 0.5 0.9475098 1 0.9472656 1 0.9472656 0.5 0.9472656 1 0.9470215 1 0.9470215 0.5 0.9470215 1 0.9467774 1 0.9467774 0.5 0.9467774 1 0.9465332 1 0.9465332 0.5 0.9465332 1 0.9462891 1 0.9462891 0.5 0.9462891 1 0.9460449 1 0.9460449 0.5 0.9460449 1 0.9458008 1 0.9458008 0.5 0.9458008 1 0.9455567 1 0.9455567 0.5 0.9455567 1 0.9453125 1 0.9453125 0.5 0.9453125 1 0.9450684 1 0.9450684 0.5 0.9450684 1 0.9448242 1 0.9448242 0.5 0.9448242 1 0.9445801 1 0.9445801 0.5 0.9445801 1 0.9443359 1 0.9443359 0.5 0.9443359 1 0.9440918 1 0.9440918 0.5 0.9440918 1 0.9438477 1 0.9438477 0.5 0.9438477 1 0.9436035 1 0.9436035 0.5 0.9436035 1 0.9433594 1 0.9433594 0.5 0.9433594 1 0.9431152 1 0.9431152 0.5 0.9431152 1 0.9428711 1 0.9428711 0.5 0.9428711 1 0.942627 1 0.942627 0.5 0.942627 1 0.9423828 1 0.9423828 0.5 0.9423828 1 0.9421387 1 0.9421387 0.5 0.9421387 1 0.9418945 1 0.9418945 0.5 0.9418945 1 0.9416504 1 0.9416504 0.5 0.9416504 1 0.9414063 1 0.9414063 0.5 0.9414063 1 0.9411621 1 0.9411621 0.5 0.9411621 1 0.940918 1 0.940918 0.5 0.940918 1 0.9406738 1 0.9406738 0.5 0.9406738 1 0.9404297 1 0.9404297 0.5 0.9404297 1 0.9401856 1 0.9401856 0.5 0.9401856 1 0.9399414 1 0.9399414 0.5 0.9399414 1 0.9396973 1 0.9396973 0.5 0.9396973 1 0.9394531 1 0.9394531 0.5 0.9394531 1 0.939209 1 0.939209 0.5 0.939209 1 0.9389649 1 0.9389649 0.5 0.9389649 1 0.9387207 1 0.9387207 0.5 0.9387207 1 0.9384766 1 0.9384766 0.5 0.9384766 1 0.9382324 1 0.9382324 0.5 0.9382324 1 0.9379883 1 0.9379883 0.5 0.9379883 1 0.9377442 1 0.9377442 0.5 0.9377442 1 0.9375 1 0.9375 0.5 0.9375 1 0.9372559 1 0.9372559 0.5 0.9372559 1 0.9370117 1 0.9370117 0.5 0.9370117 1 0.9367676 1 0.9367676 0.5 0.9367676 1 0.9365234 1 0.9365234 0.5 0.9365234 1 0.9362793 1 0.9362793 0.5 0.9362793 1 0.9360352 1 0.9360352 0.5 0.9360352 1 0.935791 1 0.935791 0.5 0.935791 1 0.9355469 1 0.9355469 0.5 0.9355469 1 0.9353027 1 0.9353027 0.5 0.9353027 1 0.9350586 1 0.9350586 0.5 0.9350586 1 0.9348145 1 0.9348145 0.5 0.9348145 1 0.9345703 1 0.9345703 0.5 0.9345703 1 0.9343262 1 0.9343262 0.5 0.9343262 1 0.934082 1 0.934082 0.5 0.934082 1 0.9338379 1 0.9338379 0.5 0.9338379 1 0.9335938 1 0.9335938 0.5 0.9335938 1 0.9333496 1 0.9333496 0.5 0.9333496 1 0.9331055 1 0.9331055 0.5 0.9331055 1 0.9328613 1 0.9328613 0.5 0.9328613 1 0.9326172 1 0.9326172 0.5 0.9326172 1 0.9323731 1 0.9323731 0.5 0.9323731 1 0.9321289 1 0.9321289 0.5 0.9321289 1 0.9318848 1 0.9318848 0.5 0.9318848 1 0.9316406 1 0.9316406 0.5 0.9316406 1 0.9313965 1 0.9313965 0.5 0.9313965 1 0.9311524 1 0.9311524 0.5 0.9311524 1 0.9309082 1 0.9309082 0.5 0.9309082 1 0.9306641 1 0.9306641 0.5 0.9306641 1 0.9304199 1 0.9304199 0.5 0.9304199 1 0.9301758 1 0.9301758 0.5 0.9301758 1 0.9299317 1 0.9299317 0.5 0.9299317 1 0.9296875 1 0.9296875 0.5 0.9296875 1 0.9294434 1 0.9294434 0.5 0.9294434 1 0.9291992 1 0.9291992 0.5 0.9291992 1 0.9289551 1 0.9289551 0.5 0.9289551 1 0.9287109 1 0.9287109 0.5 0.9287109 1 0.9284668 1 0.9284668 0.5 0.9284668 1 0.9282227 1 0.9282227 0.5 0.9282227 1 0.9279785 1 0.9279785 0.5 0.9279785 1 0.9277344 1 0.9277344 0.5 0.9277344 1 0.9274902 1 0.9274902 0.5 0.9274902 1 0.9272461 1 0.9272461 0.5 0.9272461 1 0.927002 1 0.927002 0.5 0.927002 1 0.9267578 1 0.9267578 0.5 0.9267578 1 0.9265137 1 0.9265137 0.5 0.9265137 1 0.9262695 1 0.9262695 0.5 0.9262695 1 0.9260254 1 0.9260254 0.5 0.9260254 1 0.9257813 1 0.9257813 0.5 0.9257813 1 0.9255371 1 0.9255371 0.5 0.9255371 1 0.925293 1 0.925293 0.5 0.925293 1 0.9250488 1 0.9250488 0.5 0.9250488 1 0.9248047 1 0.9248047 0.5 0.9248047 1 0.9245606 1 0.9245606 0.5 0.9245606 1 0.9243164 1 0.9243164 0.5 0.9243164 1 0.9240723 1 0.9240723 0.5 0.9240723 1 0.9238281 1 0.9238281 0.5 0.9238281 1 0.923584 1 0.923584 0.5 0.923584 1 0.9233399 1 0.9233399 0.5 0.9233399 1 0.9230957 1 0.9230957 0.5 0.9230957 1 0.9228516 1 0.9228516 0.5 0.9228516 1 0.9226074 1 0.9226074 0.5 0.9226074 1 0.9223633 1 0.9223633 0.5 0.9223633 1 0.9221192 1 0.9221192 0.5 0.9221192 1 0.921875 1 0.921875 0.5 0.921875 1 0.9216309 1 0.9216309 0.5 0.9216309 1 0.9213867 1 0.9213867 0.5 0.9213867 1 0.9211426 1 0.9211426 0.5 0.9211426 1 0.9208984 1 0.9208984 0.5 0.9208984 1 0.9206543 1 0.9206543 0.5 0.9206543 1 0.9204102 1 0.9204102 0.5 0.9204102 1 0.920166 1 0.920166 0.5 0.920166 1 0.9199219 1 0.9199219 0.5 0.9199219 1 0.9196777 1 0.9196777 0.5 0.9196777 1 0.9194336 1 0.9194336 0.5 0.9194336 1 0.9191895 1 0.9191895 0.5 0.9191895 1 0.9189453 1 0.9189453 0.5 0.9189453 1 0.9187012 1 0.9187012 0.5 0.9187012 1 0.918457 1 0.918457 0.5 0.918457 1 0.9182129 1 0.9182129 0.5 0.9182129 1 0.9179688 1 0.9179688 0.5 0.9179688 1 0.9177246 1 0.9177246 0.5 0.9177246 1 0.9174805 1 0.9174805 0.5 0.9174805 1 0.9172363 1 0.9172363 0.5 0.9172363 1 0.9169922 1 0.9169922 0.5 0.9169922 1 0.9167481 1 0.9167481 0.5 0.9167481 1 0.9165039 1 0.9165039 0.5 0.9165039 1 0.9162598 1 0.9162598 0.5 0.9162598 1 0.9160156 1 0.9160156 0.5 0.9160156 1 0.9157715 1 0.9157715 0.5 0.9157715 1 0.9155274 1 0.9155274 0.5 0.9155274 1 0.9152832 1 0.9152832 0.5 0.9152832 1 0.9150391 1 0.9150391 0.5 0.9150391 1 0.9147949 1 0.9147949 0.5 0.9147949 1 0.9145508 1 0.9145508 0.5 0.9145508 1 0.9143067 1 0.9143067 0.5 0.9143067 1 0.9140625 1 0.9140625 0.5 0.9140625 1 0.9138184 1 0.9138184 0.5 0.9138184 1 0.9135742 1 0.9135742 0.5 0.9135742 1 0.9133301 1 0.9133301 0.5 0.9133301 1 0.9130859 1 0.9130859 0.5 0.9130859 1 0.9128418 1 0.9128418 0.5 0.9128418 1 0.9125977 1 0.9125977 0.5 0.9125977 1 0.9123535 1 0.9123535 0.5 0.9123535 1 0.9121094 1 0.9121094 0.5 0.9121094 1 0.9118652 1 0.9118652 0.5 0.9118652 1 0.9116211 1 0.9116211 0.5 0.9116211 1 0.911377 1 0.911377 0.5 0.911377 1 0.9111328 1 0.9111328 0.5 0.9111328 1 0.9108887 1 0.9108887 0.5 0.9108887 1 0.9106445 1 0.9106445 0.5 0.9106445 1 0.9104004 1 0.9104004 0.5 0.9104004 1 0.9101563 1 0.9101563 0.5 0.9101563 1 0.9099121 1 0.9099121 0.5 0.9099121 1 0.909668 1 0.909668 0.5 0.909668 1 0.9094238 1 0.9094238 0.5 0.9094238 1 0.9091797 1 0.9091797 0.5 0.9091797 1 0.9089356 1 0.9089356 0.5 0.9089356 1 0.9086914 1 0.9086914 0.5 0.9086914 1 0.9084473 1 0.9084473 0.5 0.9084473 1 0.9082031 1 0.9082031 0.5 0.9082031 1 0.907959 1 0.907959 0.5 0.907959 1 0.9077149 1 0.9077149 0.5 0.9077149 1 0.9074707 1 0.9074707 0.5 0.9074707 1 0.9072266 1 0.9072266 0.5 0.9072266 1 0.9069824 1 0.9069824 0.5 0.9069824 1 0.9067383 1 0.9067383 0.5 0.9067383 1 0.9064942 1 0.9064942 0.5 0.9064942 1 0.90625 1 0.90625 0.5 0.90625 1 0.9060059 1 0.9060059 0.5 0.9060059 1 0.9057617 1 0.9057617 0.5 0.9057617 1 0.9055176 1 0.9055176 0.5 0.9055176 1 0.9052734 1 0.9052734 0.5 0.9052734 1 0.9050293 1 0.9050293 0.5 0.9050293 1 0.9047852 1 0.9047852 0.5 0.9047852 1 0.904541 1 0.904541 0.5 0.904541 1 0.9042969 1 0.9042969 0.5 0.9042969 1 0.9040527 1 0.9040527 0.5 0.9040527 1 0.9038086 1 0.9038086 0.5 0.9038086 1 0.9035645 1 0.9035645 0.5 0.9035645 1 0.9033203 1 0.9033203 0.5 0.9033203 1 0.9030762 1 0.9030762 0.5 0.9030762 1 0.902832 1 0.902832 0.5 0.902832 1 0.9025879 1 0.9025879 0.5 0.9025879 1 0.9023438 1 0.9023438 0.5 0.9023438 1 0.9020996 1 0.9020996 0.5 0.9020996 1 0.9018555 1 0.9018555 0.5 0.9018555 1 0.9016113 1 0.9016113 0.5 0.9016113 1 0.9013672 1 0.9013672 0.5 0.9013672 1 0.9011231 1 0.9011231 0.5 0.9011231 1 0.9008789 1 0.9008789 0.5 0.9008789 1 0.9006348 1 0.9006348 0.5 0.9006348 1 0.9003906 1 0.9003906 0.5 0.9003906 1 0.9001465 1 0.9001465 0.5 0.9001465 1 0.8999024 1 0.8999024 0.5 0.8999024 1 0.8996582 1 0.8996582 0.5 0.8996582 1 0.8994141 1 0.8994141 0.5 0.8994141 1 0.8991699 1 0.8991699 0.5 0.8991699 1 0.8989258 1 0.8989258 0.5 0.8989258 1 0.8986817 1 0.8986817 0.5 0.8986817 1 0.8984375 1 0.8984375 0.5 0.8984375 1 0.8981934 1 0.8981934 0.5 0.8981934 1 0.8979492 1 0.8979492 0.5 0.8979492 1 0.8977051 1 0.8977051 0.5 0.8977051 1 0.8974609 1 0.8974609 0.5 0.8974609 1 0.8972168 1 0.8972168 0.5 0.8972168 1 0.8969727 1 0.8969727 0.5 0.8969727 1 0.8967285 1 0.8967285 0.5 0.8967285 1 0.8964844 1 0.8964844 0.5 0.8964844 1 0.8962402 1 0.8962402 0.5 0.8962402 1 0.8959961 1 0.8959961 0.5 0.8959961 1 0.895752 1 0.895752 0.5 0.895752 1 0.8955078 1 0.8955078 0.5 0.8955078 1 0.8952637 1 0.8952637 0.5 0.8952637 1 0.8950195 1 0.8950195 0.5 0.8950195 1 0.8947754 1 0.8947754 0.5 0.8947754 1 0.8945313 1 0.8945313 0.5 0.8945313 1 0.8942871 1 0.8942871 0.5 0.8942871 1 0.894043 1 0.894043 0.5 0.894043 1 0.8937988 1 0.8937988 0.5 0.8937988 1 0.8935547 1 0.8935547 0.5 0.8935547 1 0.8933106 1 0.8933106 0.5 0.8933106 1 0.8930664 1 0.8930664 0.5 0.8930664 1 0.8928223 1 0.8928223 0.5 0.8928223 1 0.8925781 1 0.8925781 0.5 0.8925781 1 0.892334 1 0.892334 0.5 0.892334 1 0.8920899 1 0.8920899 0.5 0.8920899 1 0.8918457 1 0.8918457 0.5 0.8918457 1 0.8916016 1 0.8916016 0.5 0.8916016 1 0.8913574 1 0.8913574 0.5 0.8913574 1 0.8911133 1 0.8911133 0.5 0.8911133 1 0.8908692 1 0.8908692 0.5 0.8908692 1 0.890625 1 0.890625 0.5 0.890625 1 0.8903809 1 0.8903809 0.5 0.8903809 1 0.8901367 1 0.8901367 0.5 0.8901367 1 0.8898926 1 0.8898926 0.5 0.8898926 1 0.8896484 1 0.8896484 0.5 0.8896484 1 0.8894043 1 0.8894043 0.5 0.8894043 1 0.8891602 1 0.8891602 0.5 0.8891602 1 0.888916 1 0.888916 0.5 0.888916 1 0.8886719 1 0.8886719 0.5 0.8886719 1 0.8884277 1 0.8884277 0.5 0.8884277 1 0.8881836 1 0.8881836 0.5 0.8881836 1 0.8879395 1 0.8879395 0.5 0.8879395 1 0.8876953 1 0.8876953 0.5 0.8876953 1 0.8874512 1 0.8874512 0.5 0.8874512 1 0.887207 1 0.887207 0.5 0.887207 1 0.8869629 1 0.8869629 0.5 0.8869629 1 0.8867188 1 0.8867188 0.5 0.8867188 1 0.8864746 1 0.8864746 0.5 0.8864746 1 0.8862305 1 0.8862305 0.5 0.8862305 1 0.8859863 1 0.8859863 0.5 0.8859863 1 0.8857422 1 0.8857422 0.5 0.8857422 1 0.8854981 1 0.8854981 0.5 0.8854981 1 0.8852539 1 0.8852539 0.5 0.8852539 1 0.8850098 1 0.8850098 0.5 0.8850098 1 0.8847656 1 0.8847656 0.5 0.8847656 1 0.8845215 1 0.8845215 0.5 0.8845215 1 0.8842774 1 0.8842774 0.5 0.8842774 1 0.8840332 1 0.8840332 0.5 0.8840332 1 0.8837891 1 0.8837891 0.5 0.8837891 1 0.8835449 1 0.8835449 0.5 0.8835449 1 0.8833008 1 0.8833008 0.5 0.8833008 1 0.8830567 1 0.8830567 0.5 0.8830567 1 0.8828125 1 0.8828125 0.5 0.8828125 1 0.8825684 1 0.8825684 0.5 0.8825684 1 0.8823242 1 0.8823242 0.5 0.8823242 1 0.8820801 1 0.8820801 0.5 0.8820801 1 0.8818359 1 0.8818359 0.5 0.8818359 1 0.8815918 1 0.8815918 0.5 0.8815918 1 0.8813477 1 0.8813477 0.5 0.8813477 1 0.8811035 1 0.8811035 0.5 0.8811035 1 0.8808594 1 0.8808594 0.5 0.8808594 1 0.8806152 1 0.8806152 0.5 0.8806152 1 0.8803711 1 0.8803711 0.5 0.8803711 1 0.880127 1 0.880127 0.5 0.880127 1 0.8798828 1 0.8798828 0.5 0.8798828 1 0.8796387 1 0.8796387 0.5 0.8796387 1 0.8793945 1 0.8793945 0.5 0.8793945 1 0.8791504 1 0.8791504 0.5 0.8791504 1 0.8789063 1 0.8789063 0.5 0.8789063 1 0.8786621 1 0.8786621 0.5 0.8786621 1 0.878418 1 0.878418 0.5 0.878418 1 0.8781738 1 0.8781738 0.5 0.8781738 1 0.8779297 1 0.8779297 0.5 0.8779297 1 0.8776856 1 0.8776856 0.5 0.8776856 1 0.8774414 1 0.8774414 0.5 0.8774414 1 0.8771973 1 0.8771973 0.5 0.8771973 1 0.8769531 1 0.8769531 0.5 0.8769531 1 0.876709 1 0.876709 0.5 0.876709 1 0.8764649 1 0.8764649 0.5 0.8764649 1 0.8762207 1 0.8762207 0.5 0.8762207 1 0.8759766 1 0.8759766 0.5 0.8759766 1 0.8757324 1 0.8757324 0.5 0.8757324 1 0.8754883 1 0.8754883 0.5 0.8754883 1 0.8752442 1 0.8752442 0.5 0.8752442 1 0.875 1 0.875 0.5 0.875 1 0.8747559 1 0.8747559 0.5 0.8747559 1 0.8745117 1 0.8745117 0.5 0.8745117 1 0.8742676 1 0.8742676 0.5 0.8742676 1 0.8740234 1 0.8740234 0.5 0.8740234 1 0.8737793 1 0.8737793 0.5 0.8737793 1 0.8735352 1 0.8735352 0.5 0.8735352 1 0.873291 1 0.873291 0.5 0.873291 1 0.8730469 1 0.8730469 0.5 0.8730469 1 0.8728027 1 0.8728027 0.5 0.8728027 1 0.8725586 1 0.8725586 0.5 0.8725586 1 0.8723145 1 0.8723145 0.5 0.8723145 1 0.8720703 1 0.8720703 0.5 0.8720703 1 0.8718262 1 0.8718262 0.5 0.8718262 1 0.871582 1 0.871582 0.5 0.871582 1 0.8713379 1 0.8713379 0.5 0.8713379 1 0.8710938 1 0.8710938 0.5 0.8710938 1 0.8708496 1 0.8708496 0.5 0.8708496 1 0.8706055 1 0.8706055 0.5 0.8706055 1 0.8703613 1 0.8703613 0.5 0.8703613 1 0.8701172 1 0.8701172 0.5 0.8701172 1 0.8698731 1 0.8698731 0.5 0.8698731 1 0.8696289 1 0.8696289 0.5 0.8696289 1 0.8693848 1 0.8693848 0.5 0.8693848 1 0.8691406 1 0.8691406 0.5 0.8691406 1 0.8688965 1 0.8688965 0.5 0.8688965 1 0.8686524 1 0.8686524 0.5 0.8686524 1 0.8684082 1 0.8684082 0.5 0.8684082 1 0.8681641 1 0.8681641 0.5 0.8681641 1 0.8679199 1 0.8679199 0.5 0.8679199 1 0.8676758 1 0.8676758 0.5 0.8676758 1 0.8674317 1 0.8674317 0.5 0.8674317 1 0.8671875 1 0.8671875 0.5 0.8671875 1 0.8669434 1 0.8669434 0.5 0.8669434 1 0.8666992 1 0.8666992 0.5 0.8666992 1 0.8664551 1 0.8664551 0.5 0.8664551 1 0.8662109 1 0.8662109 0.5 0.8662109 1 0.8659668 1 0.8659668 0.5 0.8659668 1 0.8657227 1 0.8657227 0.5 0.8657227 1 0.8654785 1 0.8654785 0.5 0.8654785 1 0.8652344 1 0.8652344 0.5 0.8652344 1 0.8649902 1 0.8649902 0.5 0.8649902 1 0.8647461 1 0.8647461 0.5 0.8647461 1 0.864502 1 0.864502 0.5 0.864502 1 0.8642578 1 0.8642578 0.5 0.8642578 1 0.8640137 1 0.8640137 0.5 0.8640137 1 0.8637695 1 0.8637695 0.5 0.8637695 1 0.8635254 1 0.8635254 0.5 0.8635254 1 0.8632813 1 0.8632813 0.5 0.8632813 1 0.8630371 1 0.8630371 0.5 0.8630371 1 0.862793 1 0.862793 0.5 0.862793 1 0.8625488 1 0.8625488 0.5 0.8625488 1 0.8623047 1 0.8623047 0.5 0.8623047 1 0.8620606 1 0.8620606 0.5 0.8620606 1 0.8618164 1 0.8618164 0.5 0.8618164 1 0.8615723 1 0.8615723 0.5 0.8615723 1 0.8613281 1 0.8613281 0.5 0.8613281 1 0.861084 1 0.861084 0.5 0.861084 1 0.8608399 1 0.8608399 0.5 0.8608399 1 0.8605957 1 0.8605957 0.5 0.8605957 1 0.8603516 1 0.8603516 0.5 0.8603516 1 0.8601074 1 0.8601074 0.5 0.8601074 1 0.8598633 1 0.8598633 0.5 0.8598633 1 0.8596192 1 0.8596192 0.5 0.8596192 1 0.859375 1 0.859375 0.5 0.859375 1 0.8591309 1 0.8591309 0.5 0.8591309 1 0.8588867 1 0.8588867 0.5 0.8588867 1 0.8586426 1 0.8586426 0.5 0.8586426 1 0.8583984 1 0.8583984 0.5 0.8583984 1 0.8581543 1 0.8581543 0.5 0.8581543 1 0.8579102 1 0.8579102 0.5 0.8579102 1 0.857666 1 0.857666 0.5 0.857666 1 0.8574219 1 0.8574219 0.5 0.8574219 1 0.8571777 1 0.8571777 0.5 0.8571777 1 0.8569336 1 0.8569336 0.5 0.8569336 1 0.8566895 1 0.8566895 0.5 0.8566895 1 0.8564453 1 0.8564453 0.5 0.8564453 1 0.8562012 1 0.8562012 0.5 0.8562012 1 0.855957 1 0.855957 0.5 0.855957 1 0.8557129 1 0.8557129 0.5 0.8557129 1 0.8554688 1 0.8554688 0.5 0.8554688 1 0.8552246 1 0.8552246 0.5 0.8552246 1 0.8549805 1 0.8549805 0.5 0.8549805 1 0.8547363 1 0.8547363 0.5 0.8547363 1 0.8544922 1 0.8544922 0.5 0.8544922 1 0.8542481 1 0.8542481 0.5 0.8542481 1 0.8540039 1 0.8540039 0.5 0.8540039 1 0.8537598 1 0.8537598 0.5 0.8537598 1 0.8535156 1 0.8535156 0.5 0.8535156 1 0.8532715 1 0.8532715 0.5 0.8532715 1 0.8530274 1 0.8530274 0.5 0.8530274 1 0.8527832 1 0.8527832 0.5 0.8527832 1 0.8525391 1 0.8525391 0.5 0.8525391 1 0.8522949 1 0.8522949 0.5 0.8522949 1 0.8520508 1 0.8520508 0.5 0.8520508 1 0.8518067 1 0.8518067 0.5 0.8518067 1 0.8515625 1 0.8515625 0.5 0.8515625 1 0.8513184 1 0.8513184 0.5 0.8513184 1 0.8510742 1 0.8510742 0.5 0.8510742 1 0.8508301 1 0.8508301 0.5 0.8508301 1 0.8505859 1 0.8505859 0.5 0.8505859 1 0.8503418 1 0.8503418 0.5 0.8503418 1 0.8500977 1 0.8500977 0.5 0.8500977 1 0.8498535 1 0.8498535 0.5 0.8498535 1 0.8496094 1 0.8496094 0.5 0.8496094 1 0.8493652 1 0.8493652 0.5 0.8493652 1 0.8491211 1 0.8491211 0.5 0.8491211 1 0.848877 1 0.848877 0.5 0.848877 1 0.8486328 1 0.8486328 0.5 0.8486328 1 0.8483887 1 0.8483887 0.5 0.8483887 1 0.8481445 1 0.8481445 0.5 0.8481445 1 0.8479004 1 0.8479004 0.5 0.8479004 1 0.8476563 1 0.8476563 0.5 0.8476563 1 0.8474121 1 0.8474121 0.5 0.8474121 1 0.847168 1 0.847168 0.5 0.847168 1 0.8469238 1 0.8469238 0.5 0.8469238 1 0.8466797 1 0.8466797 0.5 0.8466797 1 0.8464356 1 0.8464356 0.5 0.8464356 1 0.8461914 1 0.8461914 0.5 0.8461914 1 0.8459473 1 0.8459473 0.5 0.8459473 1 0.8457031 1 0.8457031 0.5 0.8457031 1 0.845459 1 0.845459 0.5 0.845459 1 0.8452149 1 0.8452149 0.5 0.8452149 1 0.8449707 1 0.8449707 0.5 0.8449707 1 0.8447266 1 0.8447266 0.5 0.8447266 1 0.8444824 1 0.8444824 0.5 0.8444824 1 0.8442383 1 0.8442383 0.5 0.8442383 1 0.8439942 1 0.8439942 0.5 0.8439942 1 0.84375 1 0.84375 0.5 0.84375 1 0.8435059 1 0.8435059 0.5 0.8435059 1 0.8432617 1 0.8432617 0.5 0.8432617 1 0.8430176 1 0.8430176 0.5 0.8430176 1 0.8427734 1 0.8427734 0.5 0.8427734 1 0.8425293 1 0.8425293 0.5 0.8425293 1 0.8422852 1 0.8422852 0.5 0.8422852 1 0.842041 1 0.842041 0.5 0.842041 1 0.8417969 1 0.8417969 0.5 0.8417969 1 0.8415527 1 0.8415527 0.5 0.8415527 1 0.8413086 1 0.8413086 0.5 0.8413086 1 0.8410645 1 0.8410645 0.5 0.8410645 1 0.8408203 1 0.8408203 0.5 0.8408203 1 0.8405762 1 0.8405762 0.5 0.8405762 1 0.840332 1 0.840332 0.5 0.840332 1 0.8400879 1 0.8400879 0.5 0.8400879 1 0.8398438 1 0.8398438 0.5 0.8398438 1 0.8395996 1 0.8395996 0.5 0.8395996 1 0.8393555 1 0.8393555 0.5 0.8393555 1 0.8391113 1 0.8391113 0.5 0.8391113 1 0.8388672 1 0.8388672 0.5 0.8388672 1 0.8386231 1 0.8386231 0.5 0.8386231 1 0.8383789 1 0.8383789 0.5 0.8383789 1 0.8381348 1 0.8381348 0.5 0.8381348 1 0.8378906 1 0.8378906 0.5 0.8378906 1 0.8376465 1 0.8376465 0.5 0.8376465 1 0.8374024 1 0.8374024 0.5 0.8374024 1 0.8371582 1 0.8371582 0.5 0.8371582 1 0.8369141 1 0.8369141 0.5 0.8369141 1 0.8366699 1 0.8366699 0.5 0.8366699 1 0.8364258 1 0.8364258 0.5 0.8364258 1 0.8361817 1 0.8361817 0.5 0.8361817 1 0.8359375 1 0.8359375 0.5 0.8359375 1 0.8356934 1 0.8356934 0.5 0.8356934 1 0.8354492 1 0.8354492 0.5 0.8354492 1 0.8352051 1 0.8352051 0.5 0.8352051 1 0.8349609 1 0.8349609 0.5 0.8349609 1 0.8347168 1 0.8347168 0.5 0.8347168 1 0.8344727 1 0.8344727 0.5 0.8344727 1 0.8342285 1 0.8342285 0.5 0.8342285 1 0.8339844 1 0.8339844 0.5 0.8339844 1 0.8337402 1 0.8337402 0.5 0.8337402 1 0.8334961 1 0.8334961 0.5 0.8334961 1 0.833252 1 0.833252 0.5 0.833252 1 0.8330078 1 0.8330078 0.5 0.8330078 1 0.8327637 1 0.8327637 0.5 0.8327637 1 0.8325195 1 0.8325195 0.5 0.8325195 1 0.8322754 1 0.8322754 0.5 0.8322754 1 0.8320313 1 0.8320313 0.5 0.8320313 1 0.8317871 1 0.8317871 0.5 0.8317871 1 0.831543 1 0.831543 0.5 0.831543 1 0.8312988 1 0.8312988 0.5 0.8312988 1 0.8310547 1 0.8310547 0.5 0.8310547 1 0.8308106 1 0.8308106 0.5 0.8308106 1 0.8305664 1 0.8305664 0.5 0.8305664 1 0.8303223 1 0.8303223 0.5 0.8303223 1 0.8300781 1 0.8300781 0.5 0.8300781 1 0.829834 1 0.829834 0.5 0.829834 1 0.8295899 1 0.8295899 0.5 0.8295899 1 0.8293457 1 0.8293457 0.5 0.8293457 1 0.8291016 1 0.8291016 0.5 0.8291016 1 0.8288574 1 0.8288574 0.5 0.8288574 1 0.8286133 1 0.8286133 0.5 0.8286133 1 0.8283692 1 0.8283692 0.5 0.8283692 1 0.828125 1 0.828125 0.5 0.828125 1 0.8278809 1 0.8278809 0.5 0.8278809 1 0.8276367 1 0.8276367 0.5 0.8276367 1 0.8273926 1 0.8273926 0.5 0.8273926 1 0.8271484 1 0.8271484 0.5 0.8271484 1 0.8269043 1 0.8269043 0.5 0.8269043 1 0.8266602 1 0.8266602 0.5 0.8266602 1 0.826416 1 0.826416 0.5 0.826416 1 0.8261719 1 0.8261719 0.5 0.8261719 1 0.8259277 1 0.8259277 0.5 0.8259277 1 0.8256836 1 0.8256836 0.5 0.8256836 1 0.8254395 1 0.8254395 0.5 0.8254395 1 0.8251953 1 0.8251953 0.5 0.8251953 1 0.8249512 1 0.8249512 0.5 0.8249512 1 0.824707 1 0.824707 0.5 0.824707 1 0.8244629 1 0.8244629 0.5 0.8244629 1 0.8242188 1 0.8242188 0.5 0.8242188 1 0.8239746 1 0.8239746 0.5 0.8239746 1 0.8237305 1 0.8237305 0.5 0.8237305 1 0.8234863 1 0.8234863 0.5 0.8234863 1 0.8232422 1 0.8232422 0.5 0.8232422 1 0.8229981 1 0.8229981 0.5 0.8229981 1 0.8227539 1 0.8227539 0.5 0.8227539 1 0.8225098 1 0.8225098 0.5 0.8225098 1 0.8222656 1 0.8222656 0.5 0.8222656 1 0.8220215 1 0.8220215 0.5 0.8220215 1 0.8217774 1 0.8217774 0.5 0.8217774 1 0.8215332 1 0.8215332 0.5 0.8215332 1 0.8212891 1 0.8212891 0.5 0.8212891 1 0.8210449 1 0.8210449 0.5 0.8210449 1 0.8208008 1 0.8208008 0.5 0.8208008 1 0.8205567 1 0.8205567 0.5 0.8205567 1 0.8203125 1 0.8203125 0.5 0.8203125 1 0.8200684 1 0.8200684 0.5 0.8200684 1 0.8198242 1 0.8198242 0.5 0.8198242 1 0.8195801 1 0.8195801 0.5 0.8195801 1 0.8193359 1 0.8193359 0.5 0.8193359 1 0.8190918 1 0.8190918 0.5 0.8190918 1 0.8188477 1 0.8188477 0.5 0.8188477 1 0.8186035 1 0.8186035 0.5 0.8186035 1 0.8183594 1 0.8183594 0.5 0.8183594 1 0.8181152 1 0.8181152 0.5 0.8181152 1 0.8178711 1 0.8178711 0.5 0.8178711 1 0.817627 1 0.817627 0.5 0.817627 1 0.8173828 1 0.8173828 0.5 0.8173828 1 0.8171387 1 0.8171387 0.5 0.8171387 1 0.8168945 1 0.8168945 0.5 0.8168945 1 0.8166504 1 0.8166504 0.5 0.8166504 1 0.8164063 1 0.8164063 0.5 0.8164063 1 0.8161621 1 0.8161621 0.5 0.8161621 1 0.815918 1 0.815918 0.5 0.815918 1 0.8156738 1 0.8156738 0.5 0.8156738 1 0.8154297 1 0.8154297 0.5 0.8154297 1 0.8151856 1 0.8151856 0.5 0.8151856 1 0.8149414 1 0.8149414 0.5 0.8149414 1 0.8146973 1 0.8146973 0.5 0.8146973 1 0.8144531 1 0.8144531 0.5 0.8144531 1 0.814209 1 0.814209 0.5 0.814209 1 0.8139649 1 0.8139649 0.5 0.8139649 1 0.8137207 1 0.8137207 0.5 0.8137207 1 0.8134766 1 0.8134766 0.5 0.8134766 1 0.8132324 1 0.8132324 0.5 0.8132324 1 0.8129883 1 0.8129883 0.5 0.8129883 1 0.8127442 1 0.8127442 0.5 0.8127442 1 0.8125 1 0.8125 0.5 0.8125 1 0.8122559 1 0.8122559 0.5 0.8122559 1 0.8120117 1 0.8120117 0.5 0.8120117 1 0.8117676 1 0.8117676 0.5 0.8117676 1 0.8115234 1 0.8115234 0.5 0.8115234 1 0.8112793 1 0.8112793 0.5 0.8112793 1 0.8110352 1 0.8110352 0.5 0.8110352 1 0.810791 1 0.810791 0.5 0.810791 1 0.8105469 1 0.8105469 0.5 0.8105469 1 0.8103027 1 0.8103027 0.5 0.8103027 1 0.8100586 1 0.8100586 0.5 0.8100586 1 0.8098145 1 0.8098145 0.5 0.8098145 1 0.8095703 1 0.8095703 0.5 0.8095703 1 0.8093262 1 0.8093262 0.5 0.8093262 1 0.809082 1 0.809082 0.5 0.809082 1 0.8088379 1 0.8088379 0.5 0.8088379 1 0.8085938 1 0.8085938 0.5 0.8085938 1 0.8083496 1 0.8083496 0.5 0.8083496 1 0.8081055 1 0.8081055 0.5 0.8081055 1 0.8078613 1 0.8078613 0.5 0.8078613 1 0.8076172 1 0.8076172 0.5 0.8076172 1 0.8073731 1 0.8073731 0.5 0.8073731 1 0.8071289 1 0.8071289 0.5 0.8071289 1 0.8068848 1 0.8068848 0.5 0.8068848 1 0.8066406 1 0.8066406 0.5 0.8066406 1 0.8063965 1 0.8063965 0.5 0.8063965 1 0.8061524 1 0.8061524 0.5 0.8061524 1 0.8059082 1 0.8059082 0.5 0.8059082 1 0.8056641 1 0.8056641 0.5 0.8056641 1 0.8054199 1 0.8054199 0.5 0.8054199 1 0.8051758 1 0.8051758 0.5 0.8051758 1 0.8049317 1 0.8049317 0.5 0.8049317 1 0.8046875 1 0.8046875 0.5 0.8046875 1 0.8044434 1 0.8044434 0.5 0.8044434 1 0.8041992 1 0.8041992 0.5 0.8041992 1 0.8039551 1 0.8039551 0.5 0.8039551 1 0.8037109 1 0.8037109 0.5 0.8037109 1 0.8034668 1 0.8034668 0.5 0.8034668 1 0.8032227 1 0.8032227 0.5 0.8032227 1 0.8029785 1 0.8029785 0.5 0.8029785 1 0.8027344 1 0.8027344 0.5 0.8027344 1 0.8024902 1 0.8024902 0.5 0.8024902 1 0.8022461 1 0.8022461 0.5 0.8022461 1 0.802002 1 0.802002 0.5 0.802002 1 0.8017578 1 0.8017578 0.5 0.8017578 1 0.8015137 1 0.8015137 0.5 0.8015137 1 0.8012695 1 0.8012695 0.5 0.8012695 1 0.8010254 1 0.8010254 0.5 0.8010254 1 0.8007813 1 0.8007813 0.5 0.8007813 1 0.8005371 1 0.8005371 0.5 0.8005371 1 0.800293 1 0.800293 0.5 0.800293 1 0.8000488 1 0.8000488 0.5 0.8000488 1 0.7998047 1 0.7998047 0.5 0.7998047 1 0.7995606 1 0.7995606 0.5 0.7995606 1 0.7993164 1 0.7993164 0.5 0.7993164 1 0.7990723 1 0.7990723 0.5 0.7990723 1 0.7988281 1 0.7988281 0.5 0.7988281 1 0.798584 1 0.798584 0.5 0.798584 1 0.7983399 1 0.7983399 0.5 0.7983399 1 0.7980957 1 0.7980957 0.5 0.7980957 1 0.7978516 1 0.7978516 0.5 0.7978516 1 0.7976074 1 0.7976074 0.5 0.7976074 1 0.7973633 1 0.7973633 0.5 0.7973633 1 0.7971192 1 0.7971192 0.5 0.7971192 1 0.796875 1 0.796875 0.5 0.796875 1 0.7966309 1 0.7966309 0.5 0.7966309 1 0.7963867 1 0.7963867 0.5 0.7963867 1 0.7961426 1 0.7961426 0.5 0.7961426 1 0.7958984 1 0.7958984 0.5 0.7958984 1 0.7956543 1 0.7956543 0.5 0.7956543 1 0.7954102 1 0.7954102 0.5 0.7954102 1 0.795166 1 0.795166 0.5 0.795166 1 0.7949219 1 0.7949219 0.5 0.7949219 1 0.7946777 1 0.7946777 0.5 0.7946777 1 0.7944336 1 0.7944336 0.5 0.7944336 1 0.7941895 1 0.7941895 0.5 0.7941895 1 0.7939453 1 0.7939453 0.5 0.7939453 1 0.7937012 1 0.7937012 0.5 0.7937012 1 0.793457 1 0.793457 0.5 0.793457 1 0.7932129 1 0.7932129 0.5 0.7932129 1 0.7929688 1 0.7929688 0.5 0.7929688 1 0.7927246 1 0.7927246 0.5 0.7927246 1 0.7924805 1 0.7924805 0.5 0.7924805 1 0.7922363 1 0.7922363 0.5 0.7922363 1 0.7919922 1 0.7919922 0.5 0.7919922 1 0.7917481 1 0.7917481 0.5 0.7917481 1 0.7915039 1 0.7915039 0.5 0.7915039 1 0.7912598 1 0.7912598 0.5 0.7912598 1 0.7910156 1 0.7910156 0.5 0.7910156 1 0.7907715 1 0.7907715 0.5 0.7907715 1 0.7905274 1 0.7905274 0.5 0.7905274 1 0.7902832 1 0.7902832 0.5 0.7902832 1 0.7900391 1 0.7900391 0.5 0.7900391 1 0.7897949 1 0.7897949 0.5 0.7897949 1 0.7895508 1 0.7895508 0.5 0.7895508 1 0.7893067 1 0.7893067 0.5 0.7893067 1 0.7890625 1 0.7890625 0.5 0.7890625 1 0.7888184 1 0.7888184 0.5 0.7888184 1 0.7885742 1 0.7885742 0.5 0.7885742 1 0.7883301 1 0.7883301 0.5 0.7883301 1 0.7880859 1 0.7880859 0.5 0.7880859 1 0.7878418 1 0.7878418 0.5 0.7878418 1 0.7875977 1 0.7875977 0.5 0.7875977 1 0.7873535 1 0.7873535 0.5 0.7873535 1 0.7871094 1 0.7871094 0.5 0.7871094 1 0.7868652 1 0.7868652 0.5 0.7868652 1 0.7866211 1 0.7866211 0.5 0.7866211 1 0.786377 1 0.786377 0.5 0.786377 1 0.7861328 1 0.7861328 0.5 0.7861328 1 0.7858887 1 0.7858887 0.5 0.7858887 1 0.7856445 1 0.7856445 0.5 0.7856445 1 0.7854004 1 0.7854004 0.5 0.7854004 1 0.7851563 1 0.7851563 0.5 0.7851563 1 0.7849121 1 0.7849121 0.5 0.7849121 1 0.784668 1 0.784668 0.5 0.784668 1 0.7844238 1 0.7844238 0.5 0.7844238 1 0.7841797 1 0.7841797 0.5 0.7841797 1 0.7839356 1 0.7839356 0.5 0.7839356 1 0.7836914 1 0.7836914 0.5 0.7836914 1 0.7834473 1 0.7834473 0.5 0.7834473 1 0.7832031 1 0.7832031 0.5 0.7832031 1 0.782959 1 0.782959 0.5 0.782959 1 0.7827149 1 0.7827149 0.5 0.7827149 1 0.7824707 1 0.7824707 0.5 0.7824707 1 0.7822266 1 0.7822266 0.5 0.7822266 1 0.7819824 1 0.7819824 0.5 0.7819824 1 0.7817383 1 0.7817383 0.5 0.7817383 1 0.7814942 1 0.7814942 0.5 0.7814942 1 0.78125 1 0.78125 0.5 0.78125 1 0.7810059 1 0.7810059 0.5 0.7810059 1 0.7807617 1 0.7807617 0.5 0.7807617 1 0.7805176 1 0.7805176 0.5 0.7805176 1 0.7802734 1 0.7802734 0.5 0.7802734 1 0.7800293 1 0.7800293 0.5 0.7800293 1 0.7797852 1 0.7797852 0.5 0.7797852 1 0.779541 1 0.779541 0.5 0.779541 1 0.7792969 1 0.7792969 0.5 0.7792969 1 0.7790527 1 0.7790527 0.5 0.7790527 1 0.7788086 1 0.7788086 0.5 0.7788086 1 0.7785645 1 0.7785645 0.5 0.7785645 1 0.7783203 1 0.7783203 0.5 0.7783203 1 0.7780762 1 0.7780762 0.5 0.7780762 1 0.777832 1 0.777832 0.5 0.777832 1 0.7775879 1 0.7775879 0.5 0.7775879 1 0.7773438 1 0.7773438 0.5 0.7773438 1 0.7770996 1 0.7770996 0.5 0.7770996 1 0.7768555 1 0.7768555 0.5 0.7768555 1 0.7766113 1 0.7766113 0.5 0.7766113 1 0.7763672 1 0.7763672 0.5 0.7763672 1 0.7761231 1 0.7761231 0.5 0.7761231 1 0.7758789 1 0.7758789 0.5 0.7758789 1 0.7756348 1 0.7756348 0.5 0.7756348 1 0.7753906 1 0.7753906 0.5 0.7753906 1 0.7751465 1 0.7751465 0.5 0.7751465 1 0.7749024 1 0.7749024 0.5 0.7749024 1 0.7746582 1 0.7746582 0.5 0.7746582 1 0.7744141 1 0.7744141 0.5 0.7744141 1 0.7741699 1 0.7741699 0.5 0.7741699 1 0.7739258 1 0.7739258 0.5 0.7739258 1 0.7736817 1 0.7736817 0.5 0.7736817 1 0.7734375 1 0.7734375 0.5 0.7734375 1 0.7731934 1 0.7731934 0.5 0.7731934 1 0.7729492 1 0.7729492 0.5 0.7729492 1 0.7727051 1 0.7727051 0.5 0.7727051 1 0.7724609 1 0.7724609 0.5 0.7724609 1 0.7722168 1 0.7722168 0.5 0.7722168 1 0.7719727 1 0.7719727 0.5 0.7719727 1 0.7717285 1 0.7717285 0.5 0.7717285 1 0.7714844 1 0.7714844 0.5 0.7714844 1 0.7712402 1 0.7712402 0.5 0.7712402 1 0.7709961 1 0.7709961 0.5 0.7709961 1 0.770752 1 0.770752 0.5 0.770752 1 0.7705078 1 0.7705078 0.5 0.7705078 1 0.7702637 1 0.7702637 0.5 0.7702637 1 0.7700195 1 0.7700195 0.5 0.7700195 1 0.7697754 1 0.7697754 0.5 0.7697754 1 0.7695313 1 0.7695313 0.5 0.7695313 1 0.7692871 1 0.7692871 0.5 0.7692871 1 0.769043 1 0.769043 0.5 0.769043 1 0.7687988 1 0.7687988 0.5 0.7687988 1 0.7685547 1 0.7685547 0.5 0.7685547 1 0.7683106 1 0.7683106 0.5 0.7683106 1 0.7680664 1 0.7680664 0.5 0.7680664 1 0.7678223 1 0.7678223 0.5 0.7678223 1 0.7675781 1 0.7675781 0.5 0.7675781 1 0.767334 1 0.767334 0.5 0.767334 1 0.7670899 1 0.7670899 0.5 0.7670899 1 0.7668457 1 0.7668457 0.5 0.7668457 1 0.7666016 1 0.7666016 0.5 0.7666016 1 0.7663574 1 0.7663574 0.5 0.7663574 1 0.7661133 1 0.7661133 0.5 0.7661133 1 0.7658692 1 0.7658692 0.5 0.7658692 1 0.765625 1 0.765625 0.5 0.765625 1 0.7653809 1 0.7653809 0.5 0.7653809 1 0.7651367 1 0.7651367 0.5 0.7651367 1 0.7648926 1 0.7648926 0.5 0.7648926 1 0.7646484 1 0.7646484 0.5 0.7646484 1 0.7644043 1 0.7644043 0.5 0.7644043 1 0.7641602 1 0.7641602 0.5 0.7641602 1 0.763916 1 0.763916 0.5 0.763916 1 0.7636719 1 0.7636719 0.5 0.7636719 1 0.7634277 1 0.7634277 0.5 0.7634277 1 0.7631836 1 0.7631836 0.5 0.7631836 1 0.7629395 1 0.7629395 0.5 0.7629395 1 0.7626953 1 0.7626953 0.5 0.7626953 1 0.7624512 1 0.7624512 0.5 0.7624512 1 0.762207 1 0.762207 0.5 0.762207 1 0.7619629 1 0.7619629 0.5 0.7619629 1 0.7617188 1 0.7617188 0.5 0.7617188 1 0.7614746 1 0.7614746 0.5 0.7614746 1 0.7612305 1 0.7612305 0.5 0.7612305 1 0.7609863 1 0.7609863 0.5 0.7609863 1 0.7607422 1 0.7607422 0.5 0.7607422 1 0.7604981 1 0.7604981 0.5 0.7604981 1 0.7602539 1 0.7602539 0.5 0.7602539 1 0.7600098 1 0.7600098 0.5 0.7600098 1 0.7597656 1 0.7597656 0.5 0.7597656 1 0.7595215 1 0.7595215 0.5 0.7595215 1 0.7592774 1 0.7592774 0.5 0.7592774 1 0.7590332 1 0.7590332 0.5 0.7590332 1 0.7587891 1 0.7587891 0.5 0.7587891 1 0.7585449 1 0.7585449 0.5 0.7585449 1 0.7583008 1 0.7583008 0.5 0.7583008 1 0.7580567 1 0.7580567 0.5 0.7580567 1 0.7578125 1 0.7578125 0.5 0.7578125 1 0.7575684 1 0.7575684 0.5 0.7575684 1 0.7573242 1 0.7573242 0.5 0.7573242 1 0.7570801 1 0.7570801 0.5 0.7570801 1 0.7568359 1 0.7568359 0.5 0.7568359 1 0.7565918 1 0.7565918 0.5 0.7565918 1 0.7563477 1 0.7563477 0.5 0.7563477 1 0.7561035 1 0.7561035 0.5 0.7561035 1 0.7558594 1 0.7558594 0.5 0.7558594 1 0.7556152 1 0.7556152 0.5 0.7556152 1 0.7553711 1 0.7553711 0.5 0.7553711 1 0.755127 1 0.755127 0.5 0.755127 1 0.7548828 1 0.7548828 0.5 0.7548828 1 0.7546387 1 0.7546387 0.5 0.7546387 1 0.7543945 1 0.7543945 0.5 0.7543945 1 0.7541504 1 0.7541504 0.5 0.7541504 1 0.7539063 1 0.7539063 0.5 0.7539063 1 0.7536621 1 0.7536621 0.5 0.7536621 1 0.753418 1 0.753418 0.5 0.753418 1 0.7531738 1 0.7531738 0.5 0.7531738 1 0.7529297 1 0.7529297 0.5 0.7529297 1 0.7526856 1 0.7526856 0.5 0.7526856 1 0.7524414 1 0.7524414 0.5 0.7524414 1 0.7521973 1 0.7521973 0.5 0.7521973 1 0.7519531 1 0.7519531 0.5 0.7519531 1 0.751709 1 0.751709 0.5 0.751709 1 0.7514649 1 0.7514649 0.5 0.7514649 1 0.7512207 1 0.7512207 0.5 0.7512207 1 0.7509766 1 0.7509766 0.5 0.7509766 1 0.7507324 1 0.7507324 0.5 0.7507324 1 0.7504883 1 0.7504883 0.5 0.7504883 1 0.7502442 1 0.7502442 0.5 0.7502442 1 0.75 1 0.75 0.5 0.75 1 0.7497559 1 0.7497559 0.5 0.7497559 1 0.7495117 1 0.7495117 0.5 0.7495117 1 0.7492676 1 0.7492676 0.5 0.7492676 1 0.7490234 1 0.7490234 0.5 0.7490234 1 0.7487793 1 0.7487793 0.5 0.7487793 1 0.7485352 1 0.7485352 0.5 0.7485352 1 0.748291 1 0.748291 0.5 0.748291 1 0.7480469 1 0.7480469 0.5 0.7480469 1 0.7478027 1 0.7478027 0.5 0.7478027 1 0.7475586 1 0.7475586 0.5 0.7475586 1 0.7473145 1 0.7473145 0.5 0.7473145 1 0.7470703 1 0.7470703 0.5 0.7470703 1 0.7468262 1 0.7468262 0.5 0.7468262 1 0.746582 1 0.746582 0.5 0.746582 1 0.7463379 1 0.7463379 0.5 0.7463379 1 0.7460938 1 0.7460938 0.5 0.7460938 1 0.7458496 1 0.7458496 0.5 0.7458496 1 0.7456055 1 0.7456055 0.5 0.7456055 1 0.7453613 1 0.7453613 0.5 0.7453613 1 0.7451172 1 0.7451172 0.5 0.7451172 1 0.7448731 1 0.7448731 0.5 0.7448731 1 0.7446289 1 0.7446289 0.5 0.7446289 1 0.7443848 1 0.7443848 0.5 0.7443848 1 0.7441406 1 0.7441406 0.5 0.7441406 1 0.7438965 1 0.7438965 0.5 0.7438965 1 0.7436524 1 0.7436524 0.5 0.7436524 1 0.7434082 1 0.7434082 0.5 0.7434082 1 0.7431641 1 0.7431641 0.5 0.7431641 1 0.7429199 1 0.7429199 0.5 0.7429199 1 0.7426758 1 0.7426758 0.5 0.7426758 1 0.7424317 1 0.7424317 0.5 0.7424317 1 0.7421875 1 0.7421875 0.5 0.7421875 1 0.7419434 1 0.7419434 0.5 0.7419434 1 0.7416992 1 0.7416992 0.5 0.7416992 1 0.7414551 1 0.7414551 0.5 0.7414551 1 0.7412109 1 0.7412109 0.5 0.7412109 1 0.7409668 1 0.7409668 0.5 0.7409668 1 0.7407227 1 0.7407227 0.5 0.7407227 1 0.7404785 1 0.7404785 0.5 0.7404785 1 0.7402344 1 0.7402344 0.5 0.7402344 1 0.7399902 1 0.7399902 0.5 0.7399902 1 0.7397461 1 0.7397461 0.5 0.7397461 1 0.739502 1 0.739502 0.5 0.739502 1 0.7392578 1 0.7392578 0.5 0.7392578 1 0.7390137 1 0.7390137 0.5 0.7390137 1 0.7387695 1 0.7387695 0.5 0.7387695 1 0.7385254 1 0.7385254 0.5 0.7385254 1 0.7382813 1 0.7382813 0.5 0.7382813 1 0.7380371 1 0.7380371 0.5 0.7380371 1 0.737793 1 0.737793 0.5 0.737793 1 0.7375488 1 0.7375488 0.5 0.7375488 1 0.7373047 1 0.7373047 0.5 0.7373047 1 0.7370606 1 0.7370606 0.5 0.7370606 1 0.7368164 1 0.7368164 0.5 0.7368164 1 0.7365723 1 0.7365723 0.5 0.7365723 1 0.7363281 1 0.7363281 0.5 0.7363281 1 0.736084 1 0.736084 0.5 0.736084 1 0.7358399 1 0.7358399 0.5 0.7358399 1 0.7355957 1 0.7355957 0.5 0.7355957 1 0.7353516 1 0.7353516 0.5 0.7353516 1 0.7351074 1 0.7351074 0.5 0.7351074 1 0.7348633 1 0.7348633 0.5 0.7348633 1 0.7346192 1 0.7346192 0.5 0.7346192 1 0.734375 1 0.734375 0.5 0.734375 1 0.7341309 1 0.7341309 0.5 0.7341309 1 0.7338867 1 0.7338867 0.5 0.7338867 1 0.7336426 1 0.7336426 0.5 0.7336426 1 0.7333984 1 0.7333984 0.5 0.7333984 1 0.7331543 1 0.7331543 0.5 0.7331543 1 0.7329102 1 0.7329102 0.5 0.7329102 1 0.732666 1 0.732666 0.5 0.732666 1 0.7324219 1 0.7324219 0.5 0.7324219 1 0.7321777 1 0.7321777 0.5 0.7321777 1 0.7319336 1 0.7319336 0.5 0.7319336 1 0.7316895 1 0.7316895 0.5 0.7316895 1 0.7314453 1 0.7314453 0.5 0.7314453 1 0.7312012 1 0.7312012 0.5 0.7312012 1 0.730957 1 0.730957 0.5 0.730957 1 0.7307129 1 0.7307129 0.5 0.7307129 1 0.7304688 1 0.7304688 0.5 0.7304688 1 0.7302246 1 0.7302246 0.5 0.7302246 1 0.7299805 1 0.7299805 0.5 0.7299805 1 0.7297363 1 0.7297363 0.5 0.7297363 1 0.7294922 1 0.7294922 0.5 0.7294922 1 0.7292481 1 0.7292481 0.5 0.7292481 1 0.7290039 1 0.7290039 0.5 0.7290039 1 0.7287598 1 0.7287598 0.5 0.7287598 1 0.7285156 1 0.7285156 0.5 0.7285156 1 0.7282715 1 0.7282715 0.5 0.7282715 1 0.7280274 1 0.7280274 0.5 0.7280274 1 0.7277832 1 0.7277832 0.5 0.7277832 1 0.7275391 1 0.7275391 0.5 0.7275391 1 0.7272949 1 0.7272949 0.5 0.7272949 1 0.7270508 1 0.7270508 0.5 0.7270508 1 0.7268067 1 0.7268067 0.5 0.7268067 1 0.7265625 1 0.7265625 0.5 0.7265625 1 0.7263184 1 0.7263184 0.5 0.7263184 1 0.7260742 1 0.7260742 0.5 0.7260742 1 0.7258301 1 0.7258301 0.5 0.7258301 1 0.7255859 1 0.7255859 0.5 0.7255859 1 0.7253418 1 0.7253418 0.5 0.7253418 1 0.7250977 1 0.7250977 0.5 0.7250977 1 0.7248535 1 0.7248535 0.5 0.7248535 1 0.7246094 1 0.7246094 0.5 0.7246094 1 0.7243652 1 0.7243652 0.5 0.7243652 1 0.7241211 1 0.7241211 0.5 0.7241211 1 0.723877 1 0.723877 0.5 0.723877 1 0.7236328 1 0.7236328 0.5 0.7236328 1 0.7233887 1 0.7233887 0.5 0.7233887 1 0.7231445 1 0.7231445 0.5 0.7231445 1 0.7229004 1 0.7229004 0.5 0.7229004 1 0.7226563 1 0.7226563 0.5 0.7226563 1 0.7224121 1 0.7224121 0.5 0.7224121 1 0.722168 1 0.722168 0.5 0.722168 1 0.7219238 1 0.7219238 0.5 0.7219238 1 0.7216797 1 0.7216797 0.5 0.7216797 1 0.7214356 1 0.7214356 0.5 0.7214356 1 0.7211914 1 0.7211914 0.5 0.7211914 1 0.7209473 1 0.7209473 0.5 0.7209473 1 0.7207031 1 0.7207031 0.5 0.7207031 1 0.720459 1 0.720459 0.5 0.720459 1 0.7202149 1 0.7202149 0.5 0.7202149 1 0.7199707 1 0.7199707 0.5 0.7199707 1 0.7197266 1 0.7197266 0.5 0.7197266 1 0.7194824 1 0.7194824 0.5 0.7194824 1 0.7192383 1 0.7192383 0.5 0.7192383 1 0.7189942 1 0.7189942 0.5 0.7189942 1 0.71875 1 0.71875 0.5 0.71875 1 0.7185059 1 0.7185059 0.5 0.7185059 1 0.7182617 1 0.7182617 0.5 0.7182617 1 0.7180176 1 0.7180176 0.5 0.7180176 1 0.7177734 1 0.7177734 0.5 0.7177734 1 0.7175293 1 0.7175293 0.5 0.7175293 1 0.7172852 1 0.7172852 0.5 0.7172852 1 0.717041 1 0.717041 0.5 0.717041 1 0.7167969 1 0.7167969 0.5 0.7167969 1 0.7165527 1 0.7165527 0.5 0.7165527 1 0.7163086 1 0.7163086 0.5 0.7163086 1 0.7160645 1 0.7160645 0.5 0.7160645 1 0.7158203 1 0.7158203 0.5 0.7158203 1 0.7155762 1 0.7155762 0.5 0.7155762 1 0.715332 1 0.715332 0.5 0.715332 1 0.7150879 1 0.7150879 0.5 0.7150879 1 0.7148438 1 0.7148438 0.5 0.7148438 1 0.7145996 1 0.7145996 0.5 0.7145996 1 0.7143555 1 0.7143555 0.5 0.7143555 1 0.7141113 1 0.7141113 0.5 0.7141113 1 0.7138672 1 0.7138672 0.5 0.7138672 1 0.7136231 1 0.7136231 0.5 0.7136231 1 0.7133789 1 0.7133789 0.5 0.7133789 1 0.7131348 1 0.7131348 0.5 0.7131348 1 0.7128906 1 0.7128906 0.5 0.7128906 1 0.7126465 1 0.7126465 0.5 0.7126465 1 0.7124024 1 0.7124024 0.5 0.7124024 1 0.7121582 1 0.7121582 0.5 0.7121582 1 0.7119141 1 0.7119141 0.5 0.7119141 1 0.7116699 1 0.7116699 0.5 0.7116699 1 0.7114258 1 0.7114258 0.5 0.7114258 1 0.7111817 1 0.7111817 0.5 0.7111817 1 0.7109375 1 0.7109375 0.5 0.7109375 1 0.7106934 1 0.7106934 0.5 0.7106934 1 0.7104492 1 0.7104492 0.5 0.7104492 1 0.7102051 1 0.7102051 0.5 0.7102051 1 0.7099609 1 0.7099609 0.5 0.7099609 1 0.7097168 1 0.7097168 0.5 0.7097168 1 0.7094727 1 0.7094727 0.5 0.7094727 1 0.7092285 1 0.7092285 0.5 0.7092285 1 0.7089844 1 0.7089844 0.5 0.7089844 1 0.7087402 1 0.7087402 0.5 0.7087402 1 0.7084961 1 0.7084961 0.5 0.7084961 1 0.708252 1 0.708252 0.5 0.708252 1 0.7080078 1 0.7080078 0.5 0.7080078 1 0.7077637 1 0.7077637 0.5 0.7077637 1 0.7075195 1 0.7075195 0.5 0.7075195 1 0.7072754 1 0.7072754 0.5 0.7072754 1 0.7070313 1 0.7070313 0.5 0.7070313 1 0.7067871 1 0.7067871 0.5 0.7067871 1 0.706543 1 0.706543 0.5 0.706543 1 0.7062988 1 0.7062988 0.5 0.7062988 1 0.7060547 1 0.7060547 0.5 0.7060547 1 0.7058106 1 0.7058106 0.5 0.7058106 1 0.7055664 1 0.7055664 0.5 0.7055664 1 0.7053223 1 0.7053223 0.5 0.7053223 1 0.7050781 1 0.7050781 0.5 0.7050781 1 0.704834 1 0.704834 0.5 0.704834 1 0.7045899 1 0.7045899 0.5 0.7045899 1 0.7043457 1 0.7043457 0.5 0.7043457 1 0.7041016 1 0.7041016 0.5 0.7041016 1 0.7038574 1 0.7038574 0.5 0.7038574 1 0.7036133 1 0.7036133 0.5 0.7036133 1 0.7033692 1 0.7033692 0.5 0.7033692 1 0.703125 1 0.703125 0.5 0.703125 1 0.7028809 1 0.7028809 0.5 0.7028809 1 0.7026367 1 0.7026367 0.5 0.7026367 1 0.7023926 1 0.7023926 0.5 0.7023926 1 0.7021484 1 0.7021484 0.5 0.7021484 1 0.7019043 1 0.7019043 0.5 0.7019043 1 0.7016602 1 0.7016602 0.5 0.7016602 1 0.701416 1 0.701416 0.5 0.701416 1 0.7011719 1 0.7011719 0.5 0.7011719 1 0.7009277 1 0.7009277 0.5 0.7009277 1 0.7006836 1 0.7006836 0.5 0.7006836 1 0.7004395 1 0.7004395 0.5 0.7004395 1 0.7001953 1 0.7001953 0.5 0.7001953 1 0.6999512 1 0.6999512 0.5 0.6999512 1 0.699707 1 0.699707 0.5 0.699707 1 0.6994629 1 0.6994629 0.5 0.6994629 1 0.6992188 1 0.6992188 0.5 0.6992188 1 0.6989746 1 0.6989746 0.5 0.6989746 1 0.6987305 1 0.6987305 0.5 0.6987305 1 0.6984863 1 0.6984863 0.5 0.6984863 1 0.6982422 1 0.6982422 0.5 0.6982422 1 0.6979981 1 0.6979981 0.5 0.6979981 1 0.6977539 1 0.6977539 0.5 0.6977539 1 0.6975098 1 0.6975098 0.5 0.6975098 1 0.6972656 1 0.6972656 0.5 0.6972656 1 0.6970215 1 0.6970215 0.5 0.6970215 1 0.6967774 1 0.6967774 0.5 0.6967774 1 0.6965332 1 0.6965332 0.5 0.6965332 1 0.6962891 1 0.6962891 0.5 0.6962891 1 0.6960449 1 0.6960449 0.5 0.6960449 1 0.6958008 1 0.6958008 0.5 0.6958008 1 0.6955567 1 0.6955567 0.5 0.6955567 1 0.6953125 1 0.6953125 0.5 0.6953125 1 0.6950684 1 0.6950684 0.5 0.6950684 1 0.6948242 1 0.6948242 0.5 0.6948242 1 0.6945801 1 0.6945801 0.5 0.6945801 1 0.6943359 1 0.6943359 0.5 0.6943359 1 0.6940918 1 0.6940918 0.5 0.6940918 1 0.6938477 1 0.6938477 0.5 0.6938477 1 0.6936035 1 0.6936035 0.5 0.6936035 1 0.6933594 1 0.6933594 0.5 0.6933594 1 0.6931152 1 0.6931152 0.5 0.6931152 1 0.6928711 1 0.6928711 0.5 0.6928711 1 0.692627 1 0.692627 0.5 0.692627 1 0.6923828 1 0.6923828 0.5 0.6923828 1 0.6921387 1 0.6921387 0.5 0.6921387 1 0.6918945 1 0.6918945 0.5 0.6918945 1 0.6916504 1 0.6916504 0.5 0.6916504 1 0.6914063 1 0.6914063 0.5 0.6914063 1 0.6911621 1 0.6911621 0.5 0.6911621 1 0.690918 1 0.690918 0.5 0.690918 1 0.6906738 1 0.6906738 0.5 0.6906738 1 0.6904297 1 0.6904297 0.5 0.6904297 1 0.6901856 1 0.6901856 0.5 0.6901856 1 0.6899414 1 0.6899414 0.5 0.6899414 1 0.6896973 1 0.6896973 0.5 0.6896973 1 0.6894531 1 0.6894531 0.5 0.6894531 1 0.689209 1 0.689209 0.5 0.689209 1 0.6889649 1 0.6889649 0.5 0.6889649 1 0.6887207 1 0.6887207 0.5 0.6887207 1 0.6884766 1 0.6884766 0.5 0.6884766 1 0.6882324 1 0.6882324 0.5 0.6882324 1 0.6879883 1 0.6879883 0.5 0.6879883 1 0.6877442 1 0.6877442 0.5 0.6877442 1 0.6875 1 0.6875 0.5 0.6875 1 0.6872559 1 0.6872559 0.5 0.6872559 1 0.6870117 1 0.6870117 0.5 0.6870117 1 0.6867676 1 0.6867676 0.5 0.6867676 1 0.6865234 1 0.6865234 0.5 0.6865234 1 0.6862793 1 0.6862793 0.5 0.6862793 1 0.6860352 1 0.6860352 0.5 0.6860352 1 0.685791 1 0.685791 0.5 0.685791 1 0.6855469 1 0.6855469 0.5 0.6855469 1 0.6853027 1 0.6853027 0.5 0.6853027 1 0.6850586 1 0.6850586 0.5 0.6850586 1 0.6848145 1 0.6848145 0.5 0.6848145 1 0.6845703 1 0.6845703 0.5 0.6845703 1 0.6843262 1 0.6843262 0.5 0.6843262 1 0.684082 1 0.684082 0.5 0.684082 1 0.6838379 1 0.6838379 0.5 0.6838379 1 0.6835938 1 0.6835938 0.5 0.6835938 1 0.6833496 1 0.6833496 0.5 0.6833496 1 0.6831055 1 0.6831055 0.5 0.6831055 1 0.6828613 1 0.6828613 0.5 0.6828613 1 0.6826172 1 0.6826172 0.5 0.6826172 1 0.6823731 1 0.6823731 0.5 0.6823731 1 0.6821289 1 0.6821289 0.5 0.6821289 1 0.6818848 1 0.6818848 0.5 0.6818848 1 0.6816406 1 0.6816406 0.5 0.6816406 1 0.6813965 1 0.6813965 0.5 0.6813965 1 0.6811524 1 0.6811524 0.5 0.6811524 1 0.6809082 1 0.6809082 0.5 0.6809082 1 0.6806641 1 0.6806641 0.5 0.6806641 1 0.6804199 1 0.6804199 0.5 0.6804199 1 0.6801758 1 0.6801758 0.5 0.6801758 1 0.6799317 1 0.6799317 0.5 0.6799317 1 0.6796875 1 0.6796875 0.5 0.6796875 1 0.6794434 1 0.6794434 0.5 0.6794434 1 0.6791992 1 0.6791992 0.5 0.6791992 1 0.6789551 1 0.6789551 0.5 0.6789551 1 0.6787109 1 0.6787109 0.5 0.6787109 1 0.6784668 1 0.6784668 0.5 0.6784668 1 0.6782227 1 0.6782227 0.5 0.6782227 1 0.6779785 1 0.6779785 0.5 0.6779785 1 0.6777344 1 0.6777344 0.5 0.6777344 1 0.6774902 1 0.6774902 0.5 0.6774902 1 0.6772461 1 0.6772461 0.5 0.6772461 1 0.677002 1 0.677002 0.5 0.677002 1 0.6767578 1 0.6767578 0.5 0.6767578 1 0.6765137 1 0.6765137 0.5 0.6765137 1 0.6762695 1 0.6762695 0.5 0.6762695 1 0.6760254 1 0.6760254 0.5 0.6760254 1 0.6757813 1 0.6757813 0.5 0.6757813 1 0.6755371 1 0.6755371 0.5 0.6755371 1 0.675293 1 0.675293 0.5 0.675293 1 0.6750488 1 0.6750488 0.5 0.6750488 1 0.6748047 1 0.6748047 0.5 0.6748047 1 0.6745606 1 0.6745606 0.5 0.6745606 1 0.6743164 1 0.6743164 0.5 0.6743164 1 0.6740723 1 0.6740723 0.5 0.6740723 1 0.6738281 1 0.6738281 0.5 0.6738281 1 0.673584 1 0.673584 0.5 0.673584 1 0.6733399 1 0.6733399 0.5 0.6733399 1 0.6730957 1 0.6730957 0.5 0.6730957 1 0.6728516 1 0.6728516 0.5 0.6728516 1 0.6726074 1 0.6726074 0.5 0.6726074 1 0.6723633 1 0.6723633 0.5 0.6723633 1 0.6721192 1 0.6721192 0.5 0.6721192 1 0.671875 1 0.671875 0.5 0.671875 1 0.6716309 1 0.6716309 0.5 0.6716309 1 0.6713867 1 0.6713867 0.5 0.6713867 1 0.6711426 1 0.6711426 0.5 0.6711426 1 0.6708984 1 0.6708984 0.5 0.6708984 1 0.6706543 1 0.6706543 0.5 0.6706543 1 0.6704102 1 0.6704102 0.5 0.6704102 1 0.670166 1 0.670166 0.5 0.670166 1 0.6699219 1 0.6699219 0.5 0.6699219 1 0.6696777 1 0.6696777 0.5 0.6696777 1 0.6694336 1 0.6694336 0.5 0.6694336 1 0.6691895 1 0.6691895 0.5 0.6691895 1 0.6689453 1 0.6689453 0.5 0.6689453 1 0.6687012 1 0.6687012 0.5 0.6687012 1 0.668457 1 0.668457 0.5 0.668457 1 0.6682129 1 0.6682129 0.5 0.6682129 1 0.6679688 1 0.6679688 0.5 0.6679688 1 0.6677246 1 0.6677246 0.5 0.6677246 1 0.6674805 1 0.6674805 0.5 0.6674805 1 0.6672363 1 0.6672363 0.5 0.6672363 1 0.6669922 1 0.6669922 0.5 0.6669922 1 0.6667481 1 0.6667481 0.5 0.6667481 1 0.6665039 1 0.6665039 0.5 0.6665039 1 0.6662598 1 0.6662598 0.5 0.6662598 1 0.6660156 1 0.6660156 0.5 0.6660156 1 0.6657715 1 0.6657715 0.5 0.6657715 1 0.6655274 1 0.6655274 0.5 0.6655274 1 0.6652832 1 0.6652832 0.5 0.6652832 1 0.6650391 1 0.6650391 0.5 0.6650391 1 0.6647949 1 0.6647949 0.5 0.6647949 1 0.6645508 1 0.6645508 0.5 0.6645508 1 0.6643067 1 0.6643067 0.5 0.6643067 1 0.6640625 1 0.6640625 0.5 0.6640625 1 0.6638184 1 0.6638184 0.5 0.6638184 1 0.6635742 1 0.6635742 0.5 0.6635742 1 0.6633301 1 0.6633301 0.5 0.6633301 1 0.6630859 1 0.6630859 0.5 0.6630859 1 0.6628418 1 0.6628418 0.5 0.6628418 1 0.6625977 1 0.6625977 0.5 0.6625977 1 0.6623535 1 0.6623535 0.5 0.6623535 1 0.6621094 1 0.6621094 0.5 0.6621094 1 0.6618652 1 0.6618652 0.5 0.6618652 1 0.6616211 1 0.6616211 0.5 0.6616211 1 0.661377 1 0.661377 0.5 0.661377 1 0.6611328 1 0.6611328 0.5 0.6611328 1 0.6608887 1 0.6608887 0.5 0.6608887 1 0.6606445 1 0.6606445 0.5 0.6606445 1 0.6604004 1 0.6604004 0.5 0.6604004 1 0.6601563 1 0.6601563 0.5 0.6601563 1 0.6599121 1 0.6599121 0.5 0.6599121 1 0.659668 1 0.659668 0.5 0.659668 1 0.6594238 1 0.6594238 0.5 0.6594238 1 0.6591797 1 0.6591797 0.5 0.6591797 1 0.6589356 1 0.6589356 0.5 0.6589356 1 0.6586914 1 0.6586914 0.5 0.6586914 1 0.6584473 1 0.6584473 0.5 0.6584473 1 0.6582031 1 0.6582031 0.5 0.6582031 1 0.657959 1 0.657959 0.5 0.657959 1 0.6577149 1 0.6577149 0.5 0.6577149 1 0.6574707 1 0.6574707 0.5 0.6574707 1 0.6572266 1 0.6572266 0.5 0.6572266 1 0.6569824 1 0.6569824 0.5 0.6569824 1 0.6567383 1 0.6567383 0.5 0.6567383 1 0.6564942 1 0.6564942 0.5 0.6564942 1 0.65625 1 0.65625 0.5 0.65625 1 0.6560059 1 0.6560059 0.5 0.6560059 1 0.6557617 1 0.6557617 0.5 0.6557617 1 0.6555176 1 0.6555176 0.5 0.6555176 1 0.6552734 1 0.6552734 0.5 0.6552734 1 0.6550293 1 0.6550293 0.5 0.6550293 1 0.6547852 1 0.6547852 0.5 0.6547852 1 0.654541 1 0.654541 0.5 0.654541 1 0.6542969 1 0.6542969 0.5 0.6542969 1 0.6540527 1 0.6540527 0.5 0.6540527 1 0.6538086 1 0.6538086 0.5 0.6538086 1 0.6535645 1 0.6535645 0.5 0.6535645 1 0.6533203 1 0.6533203 0.5 0.6533203 1 0.6530762 1 0.6530762 0.5 0.6530762 1 0.652832 1 0.652832 0.5 0.652832 1 0.6525879 1 0.6525879 0.5 0.6525879 1 0.6523438 1 0.6523438 0.5 0.6523438 1 0.6520996 1 0.6520996 0.5 0.6520996 1 0.6518555 1 0.6518555 0.5 0.6518555 1 0.6516113 1 0.6516113 0.5 0.6516113 1 0.6513672 1 0.6513672 0.5 0.6513672 1 0.6511231 1 0.6511231 0.5 0.6511231 1 0.6508789 1 0.6508789 0.5 0.6508789 1 0.6506348 1 0.6506348 0.5 0.6506348 1 0.6503906 1 0.6503906 0.5 0.6503906 1 0.6501465 1 0.6501465 0.5 0.6501465 1 0.6499024 1 0.6499024 0.5 0.6499024 1 0.6496582 1 0.6496582 0.5 0.6496582 1 0.6494141 1 0.6494141 0.5 0.6494141 1 0.6491699 1 0.6491699 0.5 0.6491699 1 0.6489258 1 0.6489258 0.5 0.6489258 1 0.6486817 1 0.6486817 0.5 0.6486817 1 0.6484375 1 0.6484375 0.5 0.6484375 1 0.6481934 1 0.6481934 0.5 0.6481934 1 0.6479492 1 0.6479492 0.5 0.6479492 1 0.6477051 1 0.6477051 0.5 0.6477051 1 0.6474609 1 0.6474609 0.5 0.6474609 1 0.6472168 1 0.6472168 0.5 0.6472168 1 0.6469727 1 0.6469727 0.5 0.6469727 1 0.6467285 1 0.6467285 0.5 0.6467285 1 0.6464844 1 0.6464844 0.5 0.6464844 1 0.6462402 1 0.6462402 0.5 0.6462402 1 0.6459961 1 0.6459961 0.5 0.6459961 1 0.645752 1 0.645752 0.5 0.645752 1 0.6455078 1 0.6455078 0.5 0.6455078 1 0.6452637 1 0.6452637 0.5 0.6452637 1 0.6450195 1 0.6450195 0.5 0.6450195 1 0.6447754 1 0.6447754 0.5 0.6447754 1 0.6445313 1 0.6445313 0.5 0.6445313 1 0.6442871 1 0.6442871 0.5 0.6442871 1 0.644043 1 0.644043 0.5 0.644043 1 0.6437988 1 0.6437988 0.5 0.6437988 1 0.6435547 1 0.6435547 0.5 0.6435547 1 0.6433106 1 0.6433106 0.5 0.6433106 1 0.6430664 1 0.6430664 0.5 0.6430664 1 0.6428223 1 0.6428223 0.5 0.6428223 1 0.6425781 1 0.6425781 0.5 0.6425781 1 0.642334 1 0.642334 0.5 0.642334 1 0.6420899 1 0.6420899 0.5 0.6420899 1 0.6418457 1 0.6418457 0.5 0.6418457 1 0.6416016 1 0.6416016 0.5 0.6416016 1 0.6413574 1 0.6413574 0.5 0.6413574 1 0.6411133 1 0.6411133 0.5 0.6411133 1 0.6408692 1 0.6408692 0.5 0.6408692 1 0.640625 1 0.640625 0.5 0.640625 1 0.6403809 1 0.6403809 0.5 0.6403809 1 0.6401367 1 0.6401367 0.5 0.6401367 1 0.6398926 1 0.6398926 0.5 0.6398926 1 0.6396484 1 0.6396484 0.5 0.6396484 1 0.6394043 1 0.6394043 0.5 0.6394043 1 0.6391602 1 0.6391602 0.5 0.6391602 1 0.638916 1 0.638916 0.5 0.638916 1 0.6386719 1 0.6386719 0.5 0.6386719 1 0.6384277 1 0.6384277 0.5 0.6384277 1 0.6381836 1 0.6381836 0.5 0.6381836 1 0.6379395 1 0.6379395 0.5 0.6379395 1 0.6376953 1 0.6376953 0.5 0.6376953 1 0.6374512 1 0.6374512 0.5 0.6374512 1 0.637207 1 0.637207 0.5 0.637207 1 0.6369629 1 0.6369629 0.5 0.6369629 1 0.6367188 1 0.6367188 0.5 0.6367188 1 0.6364746 1 0.6364746 0.5 0.6364746 1 0.6362305 1 0.6362305 0.5 0.6362305 1 0.6359863 1 0.6359863 0.5 0.6359863 1 0.6357422 1 0.6357422 0.5 0.6357422 1 0.6354981 1 0.6354981 0.5 0.6354981 1 0.6352539 1 0.6352539 0.5 0.6352539 1 0.6350098 1 0.6350098 0.5 0.6350098 1 0.6347656 1 0.6347656 0.5 0.6347656 1 0.6345215 1 0.6345215 0.5 0.6345215 1 0.6342774 1 0.6342774 0.5 0.6342774 1 0.6340332 1 0.6340332 0.5 0.6340332 1 0.6337891 1 0.6337891 0.5 0.6337891 1 0.6335449 1 0.6335449 0.5 0.6335449 1 0.6333008 1 0.6333008 0.5 0.6333008 1 0.6330567 1 0.6330567 0.5 0.6330567 1 0.6328125 1 0.6328125 0.5 0.6328125 1 0.6325684 1 0.6325684 0.5 0.6325684 1 0.6323242 1 0.6323242 0.5 0.6323242 1 0.6320801 1 0.6320801 0.5 0.6320801 1 0.6318359 1 0.6318359 0.5 0.6318359 1 0.6315918 1 0.6315918 0.5 0.6315918 1 0.6313477 1 0.6313477 0.5 0.6313477 1 0.6311035 1 0.6311035 0.5 0.6311035 1 0.6308594 1 0.6308594 0.5 0.6308594 1 0.6306152 1 0.6306152 0.5 0.6306152 1 0.6303711 1 0.6303711 0.5 0.6303711 1 0.630127 1 0.630127 0.5 0.630127 1 0.6298828 1 0.6298828 0.5 0.6298828 1 0.6296387 1 0.6296387 0.5 0.6296387 1 0.6293945 1 0.6293945 0.5 0.6293945 1 0.6291504 1 0.6291504 0.5 0.6291504 1 0.6289063 1 0.6289063 0.5 0.6289063 1 0.6286621 1 0.6286621 0.5 0.6286621 1 0.628418 1 0.628418 0.5 0.628418 1 0.6281738 1 0.6281738 0.5 0.6281738 1 0.6279297 1 0.6279297 0.5 0.6279297 1 0.6276856 1 0.6276856 0.5 0.6276856 1 0.6274414 1 0.6274414 0.5 0.6274414 1 0.6271973 1 0.6271973 0.5 0.6271973 1 0.6269531 1 0.6269531 0.5 0.6269531 1 0.626709 1 0.626709 0.5 0.626709 1 0.6264649 1 0.6264649 0.5 0.6264649 1 0.6262207 1 0.6262207 0.5 0.6262207 1 0.6259766 1 0.6259766 0.5 0.6259766 1 0.6257324 1 0.6257324 0.5 0.6257324 1 0.6254883 1 0.6254883 0.5 0.6254883 1 0.6252442 1 0.6252442 0.5 0.6252442 1 0.625 1 0.625 0.5 0.625 1 0.6247559 1 0.6247559 0.5 0.6247559 1 0.6245117 1 0.6245117 0.5 0.6245117 1 0.6242676 1 0.6242676 0.5 0.6242676 1 0.6240234 1 0.6240234 0.5 0.6240234 1 0.6237793 1 0.6237793 0.5 0.6237793 1 0.6235352 1 0.6235352 0.5 0.6235352 1 0.623291 1 0.623291 0.5 0.623291 1 0.6230469 1 0.6230469 0.5 0.6230469 1 0.6228027 1 0.6228027 0.5 0.6228027 1 0.6225586 1 0.6225586 0.5 0.6225586 1 0.6223145 1 0.6223145 0.5 0.6223145 1 0.6220703 1 0.6220703 0.5 0.6220703 1 0.6218262 1 0.6218262 0.5 0.6218262 1 0.621582 1 0.621582 0.5 0.621582 1 0.6213379 1 0.6213379 0.5 0.6213379 1 0.6210938 1 0.6210938 0.5 0.6210938 1 0.6208496 1 0.6208496 0.5 0.6208496 1 0.6206055 1 0.6206055 0.5 0.6206055 1 0.6203613 1 0.6203613 0.5 0.6203613 1 0.6201172 1 0.6201172 0.5 0.6201172 1 0.6198731 1 0.6198731 0.5 0.6198731 1 0.6196289 1 0.6196289 0.5 0.6196289 1 0.6193848 1 0.6193848 0.5 0.6193848 1 0.6191406 1 0.6191406 0.5 0.6191406 1 0.6188965 1 0.6188965 0.5 0.6188965 1 0.6186524 1 0.6186524 0.5 0.6186524 1 0.6184082 1 0.6184082 0.5 0.6184082 1 0.6181641 1 0.6181641 0.5 0.6181641 1 0.6179199 1 0.6179199 0.5 0.6179199 1 0.6176758 1 0.6176758 0.5 0.6176758 1 0.6174317 1 0.6174317 0.5 0.6174317 1 0.6171875 1 0.6171875 0.5 0.6171875 1 0.6169434 1 0.6169434 0.5 0.6169434 1 0.6166992 1 0.6166992 0.5 0.6166992 1 0.6164551 1 0.6164551 0.5 0.6164551 1 0.6162109 1 0.6162109 0.5 0.6162109 1 0.6159668 1 0.6159668 0.5 0.6159668 1 0.6157227 1 0.6157227 0.5 0.6157227 1 0.6154785 1 0.6154785 0.5 0.6154785 1 0.6152344 1 0.6152344 0.5 0.6152344 1 0.6149902 1 0.6149902 0.5 0.6149902 1 0.6147461 1 0.6147461 0.5 0.6147461 1 0.614502 1 0.614502 0.5 0.614502 1 0.6142578 1 0.6142578 0.5 0.6142578 1 0.6140137 1 0.6140137 0.5 0.6140137 1 0.6137695 1 0.6137695 0.5 0.6137695 1 0.6135254 1 0.6135254 0.5 0.6135254 1 0.6132813 1 0.6132813 0.5 0.6132813 1 0.6130371 1 0.6130371 0.5 0.6130371 1 0.612793 1 0.612793 0.5 0.612793 1 0.6125488 1 0.6125488 0.5 0.6125488 1 0.6123047 1 0.6123047 0.5 0.6123047 1 0.6120606 1 0.6120606 0.5 0.6120606 1 0.6118164 1 0.6118164 0.5 0.6118164 1 0.6115723 1 0.6115723 0.5 0.6115723 1 0.6113281 1 0.6113281 0.5 0.6113281 1 0.611084 1 0.611084 0.5 0.611084 1 0.6108399 1 0.6108399 0.5 0.6108399 1 0.6105957 1 0.6105957 0.5 0.6105957 1 0.6103516 1 0.6103516 0.5 0.6103516 1 0.6101074 1 0.6101074 0.5 0.6101074 1 0.6098633 1 0.6098633 0.5 0.6098633 1 0.6096192 1 0.6096192 0.5 0.6096192 1 0.609375 1 0.609375 0.5 0.609375 1 0.6091309 1 0.6091309 0.5 0.6091309 1 0.6088867 1 0.6088867 0.5 0.6088867 1 0.6086426 1 0.6086426 0.5 0.6086426 1 0.6083984 1 0.6083984 0.5 0.6083984 1 0.6081543 1 0.6081543 0.5 0.6081543 1 0.6079102 1 0.6079102 0.5 0.6079102 1 0.607666 1 0.607666 0.5 0.607666 1 0.6074219 1 0.6074219 0.5 0.6074219 1 0.6071777 1 0.6071777 0.5 0.6071777 1 0.6069336 1 0.6069336 0.5 0.6069336 1 0.6066895 1 0.6066895 0.5 0.6066895 1 0.6064453 1 0.6064453 0.5 0.6064453 1 0.6062012 1 0.6062012 0.5 0.6062012 1 0.605957 1 0.605957 0.5 0.605957 1 0.6057129 1 0.6057129 0.5 0.6057129 1 0.6054688 1 0.6054688 0.5 0.6054688 1 0.6052246 1 0.6052246 0.5 0.6052246 1 0.6049805 1 0.6049805 0.5 0.6049805 1 0.6047363 1 0.6047363 0.5 0.6047363 1 0.6044922 1 0.6044922 0.5 0.6044922 1 0.6042481 1 0.6042481 0.5 0.6042481 1 0.6040039 1 0.6040039 0.5 0.6040039 1 0.6037598 1 0.6037598 0.5 0.6037598 1 0.6035156 1 0.6035156 0.5 0.6035156 1 0.6032715 1 0.6032715 0.5 0.6032715 1 0.6030274 1 0.6030274 0.5 0.6030274 1 0.6027832 1 0.6027832 0.5 0.6027832 1 0.6025391 1 0.6025391 0.5 0.6025391 1 0.6022949 1 0.6022949 0.5 0.6022949 1 0.6020508 1 0.6020508 0.5 0.6020508 1 0.6018067 1 0.6018067 0.5 0.6018067 1 0.6015625 1 0.6015625 0.5 0.6015625 1 0.6013184 1 0.6013184 0.5 0.6013184 1 0.6010742 1 0.6010742 0.5 0.6010742 1 0.6008301 1 0.6008301 0.5 0.6008301 1 0.6005859 1 0.6005859 0.5 0.6005859 1 0.6003418 1 0.6003418 0.5 0.6003418 1 0.6000977 1 0.6000977 0.5 0.6000977 1 0.5998535 1 0.5998535 0.5 0.5998535 1 0.5996094 1 0.5996094 0.5 0.5996094 1 0.5993652 1 0.5993652 0.5 0.5993652 1 0.5991211 1 0.5991211 0.5 0.5991211 1 0.598877 1 0.598877 0.5 0.598877 1 0.5986328 1 0.5986328 0.5 0.5986328 1 0.5983887 1 0.5983887 0.5 0.5983887 1 0.5981445 1 0.5981445 0.5 0.5981445 1 0.5979004 1 0.5979004 0.5 0.5979004 1 0.5976563 1 0.5976563 0.5 0.5976563 1 0.5974121 1 0.5974121 0.5 0.5974121 1 0.597168 1 0.597168 0.5 0.597168 1 0.5969238 1 0.5969238 0.5 0.5969238 1 0.5966797 1 0.5966797 0.5 0.5966797 1 0.5964356 1 0.5964356 0.5 0.5964356 1 0.5961914 1 0.5961914 0.5 0.5961914 1 0.5959473 1 0.5959473 0.5 0.5959473 1 0.5957031 1 0.5957031 0.5 0.5957031 1 0.595459 1 0.595459 0.5 0.595459 1 0.5952149 1 0.5952149 0.5 0.5952149 1 0.5949707 1 0.5949707 0.5 0.5949707 1 0.5947266 1 0.5947266 0.5 0.5947266 1 0.5944824 1 0.5944824 0.5 0.5944824 1 0.5942383 1 0.5942383 0.5 0.5942383 1 0.5939942 1 0.5939942 0.5 0.5939942 1 0.59375 1 0.59375 0.5 0.59375 1 0.5935059 1 0.5935059 0.5 0.5935059 1 0.5932617 1 0.5932617 0.5 0.5932617 1 0.5930176 1 0.5930176 0.5 0.5930176 1 0.5927734 1 0.5927734 0.5 0.5927734 1 0.5925293 1 0.5925293 0.5 0.5925293 1 0.5922852 1 0.5922852 0.5 0.5922852 1 0.592041 1 0.592041 0.5 0.592041 1 0.5917969 1 0.5917969 0.5 0.5917969 1 0.5915527 1 0.5915527 0.5 0.5915527 1 0.5913086 1 0.5913086 0.5 0.5913086 1 0.5910645 1 0.5910645 0.5 0.5910645 1 0.5908203 1 0.5908203 0.5 0.5908203 1 0.5905762 1 0.5905762 0.5 0.5905762 1 0.590332 1 0.590332 0.5 0.590332 1 0.5900879 1 0.5900879 0.5 0.5900879 1 0.5898438 1 0.5898438 0.5 0.5898438 1 0.5895996 1 0.5895996 0.5 0.5895996 1 0.5893555 1 0.5893555 0.5 0.5893555 1 0.5891113 1 0.5891113 0.5 0.5891113 1 0.5888672 1 0.5888672 0.5 0.5888672 1 0.5886231 1 0.5886231 0.5 0.5886231 1 0.5883789 1 0.5883789 0.5 0.5883789 1 0.5881348 1 0.5881348 0.5 0.5881348 1 0.5878906 1 0.5878906 0.5 0.5878906 1 0.5876465 1 0.5876465 0.5 0.5876465 1 0.5874024 1 0.5874024 0.5 0.5874024 1 0.5871582 1 0.5871582 0.5 0.5871582 1 0.5869141 1 0.5869141 0.5 0.5869141 1 0.5866699 1 0.5866699 0.5 0.5866699 1 0.5864258 1 0.5864258 0.5 0.5864258 1 0.5861817 1 0.5861817 0.5 0.5861817 1 0.5859375 1 0.5859375 0.5 0.5859375 1 0.5856934 1 0.5856934 0.5 0.5856934 1 0.5854492 1 0.5854492 0.5 0.5854492 1 0.5852051 1 0.5852051 0.5 0.5852051 1 0.5849609 1 0.5849609 0.5 0.5849609 1 0.5847168 1 0.5847168 0.5 0.5847168 1 0.5844727 1 0.5844727 0.5 0.5844727 1 0.5842285 1 0.5842285 0.5 0.5842285 1 0.5839844 1 0.5839844 0.5 0.5839844 1 0.5837402 1 0.5837402 0.5 0.5837402 1 0.5834961 1 0.5834961 0.5 0.5834961 1 0.583252 1 0.583252 0.5 0.583252 1 0.5830078 1 0.5830078 0.5 0.5830078 1 0.5827637 1 0.5827637 0.5 0.5827637 1 0.5825195 1 0.5825195 0.5 0.5825195 1 0.5822754 1 0.5822754 0.5 0.5822754 1 0.5820313 1 0.5820313 0.5 0.5820313 1 0.5817871 1 0.5817871 0.5 0.5817871 1 0.581543 1 0.581543 0.5 0.581543 1 0.5812988 1 0.5812988 0.5 0.5812988 1 0.5810547 1 0.5810547 0.5 0.5810547 1 0.5808106 1 0.5808106 0.5 0.5808106 1 0.5805664 1 0.5805664 0.5 0.5805664 1 0.5803223 1 0.5803223 0.5 0.5803223 1 0.5800781 1 0.5800781 0.5 0.5800781 1 0.579834 1 0.579834 0.5 0.579834 1 0.5795899 1 0.5795899 0.5 0.5795899 1 0.5793457 1 0.5793457 0.5 0.5793457 1 0.5791016 1 0.5791016 0.5 0.5791016 1 0.5788574 1 0.5788574 0.5 0.5788574 1 0.5786133 1 0.5786133 0.5 0.5786133 1 0.5783692 1 0.5783692 0.5 0.5783692 1 0.578125 1 0.578125 0.5 0.578125 1 0.5778809 1 0.5778809 0.5 0.5778809 1 0.5776367 1 0.5776367 0.5 0.5776367 1 0.5773926 1 0.5773926 0.5 0.5773926 1 0.5771484 1 0.5771484 0.5 0.5771484 1 0.5769043 1 0.5769043 0.5 0.5769043 1 0.5766602 1 0.5766602 0.5 0.5766602 1 0.576416 1 0.576416 0.5 0.576416 1 0.5761719 1 0.5761719 0.5 0.5761719 1 0.5759277 1 0.5759277 0.5 0.5759277 1 0.5756836 1 0.5756836 0.5 0.5756836 1 0.5754395 1 0.5754395 0.5 0.5754395 1 0.5751953 1 0.5751953 0.5 0.5751953 1 0.5749512 1 0.5749512 0.5 0.5749512 1 0.574707 1 0.574707 0.5 0.574707 1 0.5744629 1 0.5744629 0.5 0.5744629 1 0.5742188 1 0.5742188 0.5 0.5742188 1 0.5739746 1 0.5739746 0.5 0.5739746 1 0.5737305 1 0.5737305 0.5 0.5737305 1 0.5734863 1 0.5734863 0.5 0.5734863 1 0.5732422 1 0.5732422 0.5 0.5732422 1 0.5729981 1 0.5729981 0.5 0.5729981 1 0.5727539 1 0.5727539 0.5 0.5727539 1 0.5725098 1 0.5725098 0.5 0.5725098 1 0.5722656 1 0.5722656 0.5 0.5722656 1 0.5720215 1 0.5720215 0.5 0.5720215 1 0.5717774 1 0.5717774 0.5 0.5717774 1 0.5715332 1 0.5715332 0.5 0.5715332 1 0.5712891 1 0.5712891 0.5 0.5712891 1 0.5710449 1 0.5710449 0.5 0.5710449 1 0.5708008 1 0.5708008 0.5 0.5708008 1 0.5705567 1 0.5705567 0.5 0.5705567 1 0.5703125 1 0.5703125 0.5 0.5703125 1 0.5700684 1 0.5700684 0.5 0.5700684 1 0.5698242 1 0.5698242 0.5 0.5698242 1 0.5695801 1 0.5695801 0.5 0.5695801 1 0.5693359 1 0.5693359 0.5 0.5693359 1 0.5690918 1 0.5690918 0.5 0.5690918 1 0.5688477 1 0.5688477 0.5 0.5688477 1 0.5686035 1 0.5686035 0.5 0.5686035 1 0.5683594 1 0.5683594 0.5 0.5683594 1 0.5681152 1 0.5681152 0.5 0.5681152 1 0.5678711 1 0.5678711 0.5 0.5678711 1 0.567627 1 0.567627 0.5 0.567627 1 0.5673828 1 0.5673828 0.5 0.5673828 1 0.5671387 1 0.5671387 0.5 0.5671387 1 0.5668945 1 0.5668945 0.5 0.5668945 1 0.5666504 1 0.5666504 0.5 0.5666504 1 0.5664063 1 0.5664063 0.5 0.5664063 1 0.5661621 1 0.5661621 0.5 0.5661621 1 0.565918 1 0.565918 0.5 0.565918 1 0.5656738 1 0.5656738 0.5 0.5656738 1 0.5654297 1 0.5654297 0.5 0.5654297 1 0.5651856 1 0.5651856 0.5 0.5651856 1 0.5649414 1 0.5649414 0.5 0.5649414 1 0.5646973 1 0.5646973 0.5 0.5646973 1 0.5644531 1 0.5644531 0.5 0.5644531 1 0.564209 1 0.564209 0.5 0.564209 1 0.5639649 1 0.5639649 0.5 0.5639649 1 0.5637207 1 0.5637207 0.5 0.5637207 1 0.5634766 1 0.5634766 0.5 0.5634766 1 0.5632324 1 0.5632324 0.5 0.5632324 1 0.5629883 1 0.5629883 0.5 0.5629883 1 0.5627442 1 0.5627442 0.5 0.5627442 1 0.5625 1 0.5625 0.5 0.5625 1 0.5622559 1 0.5622559 0.5 0.5622559 1 0.5620117 1 0.5620117 0.5 0.5620117 1 0.5617676 1 0.5617676 0.5 0.5617676 1 0.5615234 1 0.5615234 0.5 0.5615234 1 0.5612793 1 0.5612793 0.5 0.5612793 1 0.5610352 1 0.5610352 0.5 0.5610352 1 0.560791 1 0.560791 0.5 0.560791 1 0.5605469 1 0.5605469 0.5 0.5605469 1 0.5603027 1 0.5603027 0.5 0.5603027 1 0.5600586 1 0.5600586 0.5 0.5600586 1 0.5598145 1 0.5598145 0.5 0.5598145 1 0.5595703 1 0.5595703 0.5 0.5595703 1 0.5593262 1 0.5593262 0.5 0.5593262 1 0.559082 1 0.559082 0.5 0.559082 1 0.5588379 1 0.5588379 0.5 0.5588379 1 0.5585938 1 0.5585938 0.5 0.5585938 1 0.5583496 1 0.5583496 0.5 0.5583496 1 0.5581055 1 0.5581055 0.5 0.5581055 1 0.5578613 1 0.5578613 0.5 0.5578613 1 0.5576172 1 0.5576172 0.5 0.5576172 1 0.5573731 1 0.5573731 0.5 0.5573731 1 0.5571289 1 0.5571289 0.5 0.5571289 1 0.5568848 1 0.5568848 0.5 0.5568848 1 0.5566406 1 0.5566406 0.5 0.5566406 1 0.5563965 1 0.5563965 0.5 0.5563965 1 0.5561524 1 0.5561524 0.5 0.5561524 1 0.5559082 1 0.5559082 0.5 0.5559082 1 0.5556641 1 0.5556641 0.5 0.5556641 1 0.5554199 1 0.5554199 0.5 0.5554199 1 0.5551758 1 0.5551758 0.5 0.5551758 1 0.5549317 1 0.5549317 0.5 0.5549317 1 0.5546875 1 0.5546875 0.5 0.5546875 1 0.5544434 1 0.5544434 0.5 0.5544434 1 0.5541992 1 0.5541992 0.5 0.5541992 1 0.5539551 1 0.5539551 0.5 0.5539551 1 0.5537109 1 0.5537109 0.5 0.5537109 1 0.5534668 1 0.5534668 0.5 0.5534668 1 0.5532227 1 0.5532227 0.5 0.5532227 1 0.5529785 1 0.5529785 0.5 0.5529785 1 0.5527344 1 0.5527344 0.5 0.5527344 1 0.5524902 1 0.5524902 0.5 0.5524902 1 0.5522461 1 0.5522461 0.5 0.5522461 1 0.552002 1 0.552002 0.5 0.552002 1 0.5517578 1 0.5517578 0.5 0.5517578 1 0.5515137 1 0.5515137 0.5 0.5515137 1 0.5512695 1 0.5512695 0.5 0.5512695 1 0.5510254 1 0.5510254 0.5 0.5510254 1 0.5507813 1 0.5507813 0.5 0.5507813 1 0.5505371 1 0.5505371 0.5 0.5505371 1 0.550293 1 0.550293 0.5 0.550293 1 0.5500488 1 0.5500488 0.5 0.5500488 1 0.5498047 1 0.5498047 0.5 0.5498047 1 0.5495606 1 0.5495606 0.5 0.5495606 1 0.5493164 1 0.5493164 0.5 0.5493164 1 0.5490723 1 0.5490723 0.5 0.5490723 1 0.5488281 1 0.5488281 0.5 0.5488281 1 0.548584 1 0.548584 0.5 0.548584 1 0.5483399 1 0.5483399 0.5 0.5483399 1 0.5480957 1 0.5480957 0.5 0.5480957 1 0.5478516 1 0.5478516 0.5 0.5478516 1 0.5476074 1 0.5476074 0.5 0.5476074 1 0.5473633 1 0.5473633 0.5 0.5473633 1 0.5471192 1 0.5471192 0.5 0.5471192 1 0.546875 1 0.546875 0.5 0.546875 1 0.5466309 1 0.5466309 0.5 0.5466309 1 0.5463867 1 0.5463867 0.5 0.5463867 1 0.5461426 1 0.5461426 0.5 0.5461426 1 0.5458984 1 0.5458984 0.5 0.5458984 1 0.5456543 1 0.5456543 0.5 0.5456543 1 0.5454102 1 0.5454102 0.5 0.5454102 1 0.545166 1 0.545166 0.5 0.545166 1 0.5449219 1 0.5449219 0.5 0.5449219 1 0.5446777 1 0.5446777 0.5 0.5446777 1 0.5444336 1 0.5444336 0.5 0.5444336 1 0.5441895 1 0.5441895 0.5 0.5441895 1 0.5439453 1 0.5439453 0.5 0.5439453 1 0.5437012 1 0.5437012 0.5 0.5437012 1 0.543457 1 0.543457 0.5 0.543457 1 0.5432129 1 0.5432129 0.5 0.5432129 1 0.5429688 1 0.5429688 0.5 0.5429688 1 0.5427246 1 0.5427246 0.5 0.5427246 1 0.5424805 1 0.5424805 0.5 0.5424805 1 0.5422363 1 0.5422363 0.5 0.5422363 1 0.5419922 1 0.5419922 0.5 0.5419922 1 0.5417481 1 0.5417481 0.5 0.5417481 1 0.5415039 1 0.5415039 0.5 0.5415039 1 0.5412598 1 0.5412598 0.5 0.5412598 1 0.5410156 1 0.5410156 0.5 0.5410156 1 0.5407715 1 0.5407715 0.5 0.5407715 1 0.5405274 1 0.5405274 0.5 0.5405274 1 0.5402832 1 0.5402832 0.5 0.5402832 1 0.5400391 1 0.5400391 0.5 0.5400391 1 0.5397949 1 0.5397949 0.5 0.5397949 1 0.5395508 1 0.5395508 0.5 0.5395508 1 0.5393067 1 0.5393067 0.5 0.5393067 1 0.5390625 1 0.5390625 0.5 0.5390625 1 0.5388184 1 0.5388184 0.5 0.5388184 1 0.5385742 1 0.5385742 0.5 0.5385742 1 0.5383301 1 0.5383301 0.5 0.5383301 1 0.5380859 1 0.5380859 0.5 0.5380859 1 0.5378418 1 0.5378418 0.5 0.5378418 1 0.5375977 1 0.5375977 0.5 0.5375977 1 0.5373535 1 0.5373535 0.5 0.5373535 1 0.5371094 1 0.5371094 0.5 0.5371094 1 0.5368652 1 0.5368652 0.5 0.5368652 1 0.5366211 1 0.5366211 0.5 0.5366211 1 0.536377 1 0.536377 0.5 0.536377 1 0.5361328 1 0.5361328 0.5 0.5361328 1 0.5358887 1 0.5358887 0.5 0.5358887 1 0.5356445 1 0.5356445 0.5 0.5356445 1 0.5354004 1 0.5354004 0.5 0.5354004 1 0.5351563 1 0.5351563 0.5 0.5351563 1 0.5349121 1 0.5349121 0.5 0.5349121 1 0.534668 1 0.534668 0.5 0.534668 1 0.5344238 1 0.5344238 0.5 0.5344238 1 0.5341797 1 0.5341797 0.5 0.5341797 1 0.5339356 1 0.5339356 0.5 0.5339356 1 0.5336914 1 0.5336914 0.5 0.5336914 1 0.5334473 1 0.5334473 0.5 0.5334473 1 0.5332031 1 0.5332031 0.5 0.5332031 1 0.532959 1 0.532959 0.5 0.532959 1 0.5327149 1 0.5327149 0.5 0.5327149 1 0.5324707 1 0.5324707 0.5 0.5324707 1 0.5322266 1 0.5322266 0.5 0.5322266 1 0.5319824 1 0.5319824 0.5 0.5319824 1 0.5317383 1 0.5317383 0.5 0.5317383 1 0.5314942 1 0.5314942 0.5 0.5314942 1 0.53125 1 0.53125 0.5 0.53125 1 0.5310059 1 0.5310059 0.5 0.5310059 1 0.5307617 1 0.5307617 0.5 0.5307617 1 0.5305176 1 0.5305176 0.5 0.5305176 1 0.5302734 1 0.5302734 0.5 0.5302734 1 0.5300293 1 0.5300293 0.5 0.5300293 1 0.5297852 1 0.5297852 0.5 0.5297852 1 0.529541 1 0.529541 0.5 0.529541 1 0.5292969 1 0.5292969 0.5 0.5292969 1 0.5290527 1 0.5290527 0.5 0.5290527 1 0.5288086 1 0.5288086 0.5 0.5288086 1 0.5285645 1 0.5285645 0.5 0.5285645 1 0.5283203 1 0.5283203 0.5 0.5283203 1 0.5280762 1 0.5280762 0.5 0.5280762 1 0.527832 1 0.527832 0.5 0.527832 1 0.5275879 1 0.5275879 0.5 0.5275879 1 0.5273438 1 0.5273438 0.5 0.5273438 1 0.5270996 1 0.5270996 0.5 0.5270996 1 0.5268555 1 0.5268555 0.5 0.5268555 1 0.5266113 1 0.5266113 0.5 0.5266113 1 0.5263672 1 0.5263672 0.5 0.5263672 1 0.5261231 1 0.5261231 0.5 0.5261231 1 0.5258789 1 0.5258789 0.5 0.5258789 1 0.5256348 1 0.5256348 0.5 0.5256348 1 0.5253906 1 0.5253906 0.5 0.5253906 1 0.5251465 1 0.5251465 0.5 0.5251465 1 0.5249024 1 0.5249024 0.5 0.5249024 1 0.5246582 1 0.5246582 0.5 0.5246582 1 0.5244141 1 0.5244141 0.5 0.5244141 1 0.5241699 1 0.5241699 0.5 0.5241699 1 0.5239258 1 0.5239258 0.5 0.5239258 1 0.5236817 1 0.5236817 0.5 0.5236817 1 0.5234375 1 0.5234375 0.5 0.5234375 1 0.5231934 1 0.5231934 0.5 0.5231934 1 0.5229492 1 0.5229492 0.5 0.5229492 1 0.5227051 1 0.5227051 0.5 0.5227051 1 0.5224609 1 0.5224609 0.5 0.5224609 1 0.5222168 1 0.5222168 0.5 0.5222168 1 0.5219727 1 0.5219727 0.5 0.5219727 1 0.5217285 1 0.5217285 0.5 0.5217285 1 0.5214844 1 0.5214844 0.5 0.5214844 1 0.5212402 1 0.5212402 0.5 0.5212402 1 0.5209961 1 0.5209961 0.5 0.5209961 1 0.520752 1 0.520752 0.5 0.520752 1 0.5205078 1 0.5205078 0.5 0.5205078 1 0.5202637 1 0.5202637 0.5 0.5202637 1 0.5200195 1 0.5200195 0.5 0.5200195 1 0.5197754 1 0.5197754 0.5 0.5197754 1 0.5195313 1 0.5195313 0.5 0.5195313 1 0.5192871 1 0.5192871 0.5 0.5192871 1 0.519043 1 0.519043 0.5 0.519043 1 0.5187988 1 0.5187988 0.5 0.5187988 1 0.5185547 1 0.5185547 0.5 0.5185547 1 0.5183106 1 0.5183106 0.5 0.5183106 1 0.5180664 1 0.5180664 0.5 0.5180664 1 0.5178223 1 0.5178223 0.5 0.5178223 1 0.5175781 1 0.5175781 0.5 0.5175781 1 0.517334 1 0.517334 0.5 0.517334 1 0.5170899 1 0.5170899 0.5 0.5170899 1 0.5168457 1 0.5168457 0.5 0.5168457 1 0.5166016 1 0.5166016 0.5 0.5166016 1 0.5163574 1 0.5163574 0.5 0.5163574 1 0.5161133 1 0.5161133 0.5 0.5161133 1 0.5158692 1 0.5158692 0.5 0.5158692 1 0.515625 1 0.515625 0.5 0.515625 1 0.5153809 1 0.5153809 0.5 0.5153809 1 0.5151367 1 0.5151367 0.5 0.5151367 1 0.5148926 1 0.5148926 0.5 0.5148926 1 0.5146484 1 0.5146484 0.5 0.5146484 1 0.5144043 1 0.5144043 0.5 0.5144043 1 0.5141602 1 0.5141602 0.5 0.5141602 1 0.513916 1 0.513916 0.5 0.513916 1 0.5136719 1 0.5136719 0.5 0.5136719 1 0.5134277 1 0.5134277 0.5 0.5134277 1 0.5131836 1 0.5131836 0.5 0.5131836 1 0.5129395 1 0.5129395 0.5 0.5129395 1 0.5126953 1 0.5126953 0.5 0.5126953 1 0.5124512 1 0.5124512 0.5 0.5124512 1 0.512207 1 0.512207 0.5 0.512207 1 0.5119629 1 0.5119629 0.5 0.5119629 1 0.5117188 1 0.5117188 0.5 0.5117188 1 0.5114746 1 0.5114746 0.5 0.5114746 1 0.5112305 1 0.5112305 0.5 0.5112305 1 0.5109863 1 0.5109863 0.5 0.5109863 1 0.5107422 1 0.5107422 0.5 0.5107422 1 0.5104981 1 0.5104981 0.5 0.5104981 1 0.5102539 1 0.5102539 0.5 0.5102539 1 0.5100098 1 0.5100098 0.5 0.5100098 1 0.5097656 1 0.5097656 0.5 0.5097656 1 0.5095215 1 0.5095215 0.5 0.5095215 1 0.5092774 1 0.5092774 0.5 0.5092774 1 0.5090332 1 0.5090332 0.5 0.5090332 1 0.5087891 1 0.5087891 0.5 0.5087891 1 0.5085449 1 0.5085449 0.5 0.5085449 1 0.5083008 1 0.5083008 0.5 0.5083008 1 0.5080567 1 0.5080567 0.5 0.5080567 1 0.5078125 1 0.5078125 0.5 0.5078125 1 0.5075684 1 0.5075684 0.5 0.5075684 1 0.5073242 1 0.5073242 0.5 0.5073242 1 0.5070801 1 0.5070801 0.5 0.5070801 1 0.5068359 1 0.5068359 0.5 0.5068359 1 0.5065918 1 0.5065918 0.5 0.5065918 1 0.5063477 1 0.5063477 0.5 0.5063477 1 0.5061035 1 0.5061035 0.5 0.5061035 1 0.5058594 1 0.5058594 0.5 0.5058594 1 0.5056152 1 0.5056152 0.5 0.5056152 1 0.5053711 1 0.5053711 0.5 0.5053711 1 0.505127 1 0.505127 0.5 0.505127 1 0.5048828 1 0.5048828 0.5 0.5048828 1 0.5046387 1 0.5046387 0.5 0.5046387 1 0.5043945 1 0.5043945 0.5 0.5043945 1 0.5041504 1 0.5041504 0.5 0.5041504 1 0.5039063 1 0.5039063 0.5 0.5039063 1 0.5036621 1 0.5036621 0.5 0.5036621 1 0.503418 1 0.503418 0.5 0.503418 1 0.5031738 1 0.5031738 0.5 0.5031738 1 0.5029297 1 0.5029297 0.5 0.5029297 1 0.5026856 1 0.5026856 0.5 0.5026856 1 0.5024414 1 0.5024414 0.5 0.5024414 1 0.5021973 1 0.5021973 0.5 0.5021973 1 0.5019531 1 0.5019531 0.5 0.5019531 1 0.501709 1 0.501709 0.5 0.501709 1 0.5014649 1 0.5014649 0.5 0.5014649 1 0.5012207 1 0.5012207 0.5 0.5012207 1 0.5009766 1 0.5009766 0.5 0.5009766 1 0.5007324 1 0.5007324 0.5 0.5007324 1 0.5004883 1 0.5004883 0.5 0.5004883 1 0.5002442 1 0.5002442 0.5 0.5002442 1 0.5 1 0.5 0.5 0.5 1 0.4997559 1 0.4997559 0.5 0.4997559 1 0.4995117 1 0.4995117 0.5 0.4995117 1 0.4992676 1 0.4992676 0.5 0.4992676 1 0.4990234 1 0.4990234 0.5 0.4990234 1 0.4987793 1 0.4987793 0.5 0.4987793 1 0.4985352 1 0.4985352 0.5 0.4985352 1 0.498291 1 0.498291 0.5 0.498291 1 0.4980469 1 0.4980469 0.5 0.4980469 1 0.4978027 1 0.4978027 0.5 0.4978027 1 0.4975586 1 0.4975586 0.5 0.4975586 1 0.4973145 1 0.4973145 0.5 0.4973145 1 0.4970703 1 0.4970703 0.5 0.4970703 1 0.4968262 1 0.4968262 0.5 0.4968262 1 0.496582 1 0.496582 0.5 0.496582 1 0.4963379 1 0.4963379 0.5 0.4963379 1 0.4960938 1 0.4960938 0.5 0.4960938 1 0.4958496 1 0.4958496 0.5 0.4958496 1 0.4956055 1 0.4956055 0.5 0.4956055 1 0.4953613 1 0.4953613 0.5 0.4953613 1 0.4951172 1 0.4951172 0.5 0.4951172 1 0.4948731 1 0.4948731 0.5 0.4948731 1 0.4946289 1 0.4946289 0.5 0.4946289 1 0.4943848 1 0.4943848 0.5 0.4943848 1 0.4941406 1 0.4941406 0.5 0.4941406 1 0.4938965 1 0.4938965 0.5 0.4938965 1 0.4936524 1 0.4936524 0.5 0.4936524 1 0.4934082 1 0.4934082 0.5 0.4934082 1 0.4931641 1 0.4931641 0.5 0.4931641 1 0.4929199 1 0.4929199 0.5 0.4929199 1 0.4926758 1 0.4926758 0.5 0.4926758 1 0.4924317 1 0.4924317 0.5 0.4924317 1 0.4921875 1 0.4921875 0.5 0.4921875 1 0.4919434 1 0.4919434 0.5 0.4919434 1 0.4916992 1 0.4916992 0.5 0.4916992 1 0.4914551 1 0.4914551 0.5 0.4914551 1 0.4912109 1 0.4912109 0.5 0.4912109 1 0.4909668 1 0.4909668 0.5 0.4909668 1 0.4907227 1 0.4907227 0.5 0.4907227 1 0.4904785 1 0.4904785 0.5 0.4904785 1 0.4902344 1 0.4902344 0.5 0.4902344 1 0.4899902 1 0.4899902 0.5 0.4899902 1 0.4897461 1 0.4897461 0.5 0.4897461 1 0.489502 1 0.489502 0.5 0.489502 1 0.4892578 1 0.4892578 0.5 0.4892578 1 0.4890137 1 0.4890137 0.5 0.4890137 1 0.4887695 1 0.4887695 0.5 0.4887695 1 0.4885254 1 0.4885254 0.5 0.4885254 1 0.4882813 1 0.4882813 0.5 0.4882813 1 0.4880371 1 0.4880371 0.5 0.4880371 1 0.487793 1 0.487793 0.5 0.487793 1 0.4875488 1 0.4875488 0.5 0.4875488 1 0.4873047 1 0.4873047 0.5 0.4873047 1 0.4870606 1 0.4870606 0.5 0.4870606 1 0.4868164 1 0.4868164 0.5 0.4868164 1 0.4865723 1 0.4865723 0.5 0.4865723 1 0.4863281 1 0.4863281 0.5 0.4863281 1 0.486084 1 0.486084 0.5 0.486084 1 0.4858399 1 0.4858399 0.5 0.4858399 1 0.4855957 1 0.4855957 0.5 0.4855957 1 0.4853516 1 0.4853516 0.5 0.4853516 1 0.4851074 1 0.4851074 0.5 0.4851074 1 0.4848633 1 0.4848633 0.5 0.4848633 1 0.4846192 1 0.4846192 0.5 0.4846192 1 0.484375 1 0.484375 0.5 0.484375 1 0.4841309 1 0.4841309 0.5 0.4841309 1 0.4838867 1 0.4838867 0.5 0.4838867 1 0.4836426 1 0.4836426 0.5 0.4836426 1 0.4833984 1 0.4833984 0.5 0.4833984 1 0.4831543 1 0.4831543 0.5 0.4831543 1 0.4829102 1 0.4829102 0.5 0.4829102 1 0.482666 1 0.482666 0.5 0.482666 1 0.4824219 1 0.4824219 0.5 0.4824219 1 0.4821777 1 0.4821777 0.5 0.4821777 1 0.4819336 1 0.4819336 0.5 0.4819336 1 0.4816895 1 0.4816895 0.5 0.4816895 1 0.4814453 1 0.4814453 0.5 0.4814453 1 0.4812012 1 0.4812012 0.5 0.4812012 1 0.480957 1 0.480957 0.5 0.480957 1 0.4807129 1 0.4807129 0.5 0.4807129 1 0.4804688 1 0.4804688 0.5 0.4804688 1 0.4802246 1 0.4802246 0.5 0.4802246 1 0.4799805 1 0.4799805 0.5 0.4799805 1 0.4797363 1 0.4797363 0.5 0.4797363 1 0.4794922 1 0.4794922 0.5 0.4794922 1 0.4792481 1 0.4792481 0.5 0.4792481 1 0.4790039 1 0.4790039 0.5 0.4790039 1 0.4787598 1 0.4787598 0.5 0.4787598 1 0.4785156 1 0.4785156 0.5 0.4785156 1 0.4782715 1 0.4782715 0.5 0.4782715 1 0.4780274 1 0.4780274 0.5 0.4780274 1 0.4777832 1 0.4777832 0.5 0.4777832 1 0.4775391 1 0.4775391 0.5 0.4775391 1 0.4772949 1 0.4772949 0.5 0.4772949 1 0.4770508 1 0.4770508 0.5 0.4770508 1 0.4768067 1 0.4768067 0.5 0.4768067 1 0.4765625 1 0.4765625 0.5 0.4765625 1 0.4763184 1 0.4763184 0.5 0.4763184 1 0.4760742 1 0.4760742 0.5 0.4760742 1 0.4758301 1 0.4758301 0.5 0.4758301 1 0.4755859 1 0.4755859 0.5 0.4755859 1 0.4753418 1 0.4753418 0.5 0.4753418 1 0.4750977 1 0.4750977 0.5 0.4750977 1 0.4748535 1 0.4748535 0.5 0.4748535 1 0.4746094 1 0.4746094 0.5 0.4746094 1 0.4743652 1 0.4743652 0.5 0.4743652 1 0.4741211 1 0.4741211 0.5 0.4741211 1 0.473877 1 0.473877 0.5 0.473877 1 0.4736328 1 0.4736328 0.5 0.4736328 1 0.4733887 1 0.4733887 0.5 0.4733887 1 0.4731445 1 0.4731445 0.5 0.4731445 1 0.4729004 1 0.4729004 0.5 0.4729004 1 0.4726563 1 0.4726563 0.5 0.4726563 1 0.4724121 1 0.4724121 0.5 0.4724121 1 0.472168 1 0.472168 0.5 0.472168 1 0.4719238 1 0.4719238 0.5 0.4719238 1 0.4716797 1 0.4716797 0.5 0.4716797 1 0.4714356 1 0.4714356 0.5 0.4714356 1 0.4711914 1 0.4711914 0.5 0.4711914 1 0.4709473 1 0.4709473 0.5 0.4709473 1 0.4707031 1 0.4707031 0.5 0.4707031 1 0.470459 1 0.470459 0.5 0.470459 1 0.4702149 1 0.4702149 0.5 0.4702149 1 0.4699707 1 0.4699707 0.5 0.4699707 1 0.4697266 1 0.4697266 0.5 0.4697266 1 0.4694824 1 0.4694824 0.5 0.4694824 1 0.4692383 1 0.4692383 0.5 0.4692383 1 0.4689942 1 0.4689942 0.5 0.4689942 1 0.46875 1 0.46875 0.5 0.46875 1 0.4685059 1 0.4685059 0.5 0.4685059 1 0.4682617 1 0.4682617 0.5 0.4682617 1 0.4680176 1 0.4680176 0.5 0.4680176 1 0.4677734 1 0.4677734 0.5 0.4677734 1 0.4675293 1 0.4675293 0.5 0.4675293 1 0.4672852 1 0.4672852 0.5 0.4672852 1 0.467041 1 0.467041 0.5 0.467041 1 0.4667969 1 0.4667969 0.5 0.4667969 1 0.4665527 1 0.4665527 0.5 0.4665527 1 0.4663086 1 0.4663086 0.5 0.4663086 1 0.4660645 1 0.4660645 0.5 0.4660645 1 0.4658203 1 0.4658203 0.5 0.4658203 1 0.4655762 1 0.4655762 0.5 0.4655762 1 0.465332 1 0.465332 0.5 0.465332 1 0.4650879 1 0.4650879 0.5 0.4650879 1 0.4648438 1 0.4648438 0.5 0.4648438 1 0.4645996 1 0.4645996 0.5 0.4645996 1 0.4643555 1 0.4643555 0.5 0.4643555 1 0.4641113 1 0.4641113 0.5 0.4641113 1 0.4638672 1 0.4638672 0.5 0.4638672 1 0.4636231 1 0.4636231 0.5 0.4636231 1 0.4633789 1 0.4633789 0.5 0.4633789 1 0.4631348 1 0.4631348 0.5 0.4631348 1 0.4628906 1 0.4628906 0.5 0.4628906 1 0.4626465 1 0.4626465 0.5 0.4626465 1 0.4624024 1 0.4624024 0.5 0.4624024 1 0.4621582 1 0.4621582 0.5 0.4621582 1 0.4619141 1 0.4619141 0.5 0.4619141 1 0.4616699 1 0.4616699 0.5 0.4616699 1 0.4614258 1 0.4614258 0.5 0.4614258 1 0.4611817 1 0.4611817 0.5 0.4611817 1 0.4609375 1 0.4609375 0.5 0.4609375 1 0.4606934 1 0.4606934 0.5 0.4606934 1 0.4604492 1 0.4604492 0.5 0.4604492 1 0.4602051 1 0.4602051 0.5 0.4602051 1 0.4599609 1 0.4599609 0.5 0.4599609 1 0.4597168 1 0.4597168 0.5 0.4597168 1 0.4594727 1 0.4594727 0.5 0.4594727 1 0.4592285 1 0.4592285 0.5 0.4592285 1 0.4589844 1 0.4589844 0.5 0.4589844 1 0.4587402 1 0.4587402 0.5 0.4587402 1 0.4584961 1 0.4584961 0.5 0.4584961 1 0.458252 1 0.458252 0.5 0.458252 1 0.4580078 1 0.4580078 0.5 0.4580078 1 0.4577637 1 0.4577637 0.5 0.4577637 1 0.4575195 1 0.4575195 0.5 0.4575195 1 0.4572754 1 0.4572754 0.5 0.4572754 1 0.4570313 1 0.4570313 0.5 0.4570313 1 0.4567871 1 0.4567871 0.5 0.4567871 1 0.456543 1 0.456543 0.5 0.456543 1 0.4562988 1 0.4562988 0.5 0.4562988 1 0.4560547 1 0.4560547 0.5 0.4560547 1 0.4558106 1 0.4558106 0.5 0.4558106 1 0.4555664 1 0.4555664 0.5 0.4555664 1 0.4553223 1 0.4553223 0.5 0.4553223 1 0.4550781 1 0.4550781 0.5 0.4550781 1 0.454834 1 0.454834 0.5 0.454834 1 0.4545899 1 0.4545899 0.5 0.4545899 1 0.4543457 1 0.4543457 0.5 0.4543457 1 0.4541016 1 0.4541016 0.5 0.4541016 1 0.4538574 1 0.4538574 0.5 0.4538574 1 0.4536133 1 0.4536133 0.5 0.4536133 1 0.4533692 1 0.4533692 0.5 0.4533692 1 0.453125 1 0.453125 0.5 0.453125 1 0.4528809 1 0.4528809 0.5 0.4528809 1 0.4526367 1 0.4526367 0.5 0.4526367 1 0.4523926 1 0.4523926 0.5 0.4523926 1 0.4521484 1 0.4521484 0.5 0.4521484 1 0.4519043 1 0.4519043 0.5 0.4519043 1 0.4516602 1 0.4516602 0.5 0.4516602 1 0.451416 1 0.451416 0.5 0.451416 1 0.4511719 1 0.4511719 0.5 0.4511719 1 0.4509277 1 0.4509277 0.5 0.4509277 1 0.4506836 1 0.4506836 0.5 0.4506836 1 0.4504395 1 0.4504395 0.5 0.4504395 1 0.4501953 1 0.4501953 0.5 0.4501953 1 0.4499512 1 0.4499512 0.5 0.4499512 1 0.449707 1 0.449707 0.5 0.449707 1 0.4494629 1 0.4494629 0.5 0.4494629 1 0.4492188 1 0.4492188 0.5 0.4492188 1 0.4489746 1 0.4489746 0.5 0.4489746 1 0.4487305 1 0.4487305 0.5 0.4487305 1 0.4484863 1 0.4484863 0.5 0.4484863 1 0.4482422 1 0.4482422 0.5 0.4482422 1 0.4479981 1 0.4479981 0.5 0.4479981 1 0.4477539 1 0.4477539 0.5 0.4477539 1 0.4475098 1 0.4475098 0.5 0.4475098 1 0.4472656 1 0.4472656 0.5 0.4472656 1 0.4470215 1 0.4470215 0.5 0.4470215 1 0.4467774 1 0.4467774 0.5 0.4467774 1 0.4465332 1 0.4465332 0.5 0.4465332 1 0.4462891 1 0.4462891 0.5 0.4462891 1 0.4460449 1 0.4460449 0.5 0.4460449 1 0.4458008 1 0.4458008 0.5 0.4458008 1 0.4455567 1 0.4455567 0.5 0.4455567 1 0.4453125 1 0.4453125 0.5 0.4453125 1 0.4450684 1 0.4450684 0.5 0.4450684 1 0.4448242 1 0.4448242 0.5 0.4448242 1 0.4445801 1 0.4445801 0.5 0.4445801 1 0.4443359 1 0.4443359 0.5 0.4443359 1 0.4440918 1 0.4440918 0.5 0.4440918 1 0.4438477 1 0.4438477 0.5 0.4438477 1 0.4436035 1 0.4436035 0.5 0.4436035 1 0.4433594 1 0.4433594 0.5 0.4433594 1 0.4431152 1 0.4431152 0.5 0.4431152 1 0.4428711 1 0.4428711 0.5 0.4428711 1 0.442627 1 0.442627 0.5 0.442627 1 0.4423828 1 0.4423828 0.5 0.4423828 1 0.4421387 1 0.4421387 0.5 0.4421387 1 0.4418945 1 0.4418945 0.5 0.4418945 1 0.4416504 1 0.4416504 0.5 0.4416504 1 0.4414063 1 0.4414063 0.5 0.4414063 1 0.4411621 1 0.4411621 0.5 0.4411621 1 0.440918 1 0.440918 0.5 0.440918 1 0.4406738 1 0.4406738 0.5 0.4406738 1 0.4404297 1 0.4404297 0.5 0.4404297 1 0.4401856 1 0.4401856 0.5 0.4401856 1 0.4399414 1 0.4399414 0.5 0.4399414 1 0.4396973 1 0.4396973 0.5 0.4396973 1 0.4394531 1 0.4394531 0.5 0.4394531 1 0.439209 1 0.439209 0.5 0.439209 1 0.4389649 1 0.4389649 0.5 0.4389649 1 0.4387207 1 0.4387207 0.5 0.4387207 1 0.4384766 1 0.4384766 0.5 0.4384766 1 0.4382324 1 0.4382324 0.5 0.4382324 1 0.4379883 1 0.4379883 0.5 0.4379883 1 0.4377442 1 0.4377442 0.5 0.4377442 1 0.4375 1 0.4375 0.5 0.4375 1 0.4372559 1 0.4372559 0.5 0.4372559 1 0.4370117 1 0.4370117 0.5 0.4370117 1 0.4367676 1 0.4367676 0.5 0.4367676 1 0.4365234 1 0.4365234 0.5 0.4365234 1 0.4362793 1 0.4362793 0.5 0.4362793 1 0.4360352 1 0.4360352 0.5 0.4360352 1 0.435791 1 0.435791 0.5 0.435791 1 0.4355469 1 0.4355469 0.5 0.4355469 1 0.4353027 1 0.4353027 0.5 0.4353027 1 0.4350586 1 0.4350586 0.5 0.4350586 1 0.4348145 1 0.4348145 0.5 0.4348145 1 0.4345703 1 0.4345703 0.5 0.4345703 1 0.4343262 1 0.4343262 0.5 0.4343262 1 0.434082 1 0.434082 0.5 0.434082 1 0.4338379 1 0.4338379 0.5 0.4338379 1 0.4335938 1 0.4335938 0.5 0.4335938 1 0.4333496 1 0.4333496 0.5 0.4333496 1 0.4331055 1 0.4331055 0.5 0.4331055 1 0.4328613 1 0.4328613 0.5 0.4328613 1 0.4326172 1 0.4326172 0.5 0.4326172 1 0.4323731 1 0.4323731 0.5 0.4323731 1 0.4321289 1 0.4321289 0.5 0.4321289 1 0.4318848 1 0.4318848 0.5 0.4318848 1 0.4316406 1 0.4316406 0.5 0.4316406 1 0.4313965 1 0.4313965 0.5 0.4313965 1 0.4311524 1 0.4311524 0.5 0.4311524 1 0.4309082 1 0.4309082 0.5 0.4309082 1 0.4306641 1 0.4306641 0.5 0.4306641 1 0.4304199 1 0.4304199 0.5 0.4304199 1 0.4301758 1 0.4301758 0.5 0.4301758 1 0.4299317 1 0.4299317 0.5 0.4299317 1 0.4296875 1 0.4296875 0.5 0.4296875 1 0.4294434 1 0.4294434 0.5 0.4294434 1 0.4291992 1 0.4291992 0.5 0.4291992 1 0.4289551 1 0.4289551 0.5 0.4289551 1 0.4287109 1 0.4287109 0.5 0.4287109 1 0.4284668 1 0.4284668 0.5 0.4284668 1 0.4282227 1 0.4282227 0.5 0.4282227 1 0.4279785 1 0.4279785 0.5 0.4279785 1 0.4277344 1 0.4277344 0.5 0.4277344 1 0.4274902 1 0.4274902 0.5 0.4274902 1 0.4272461 1 0.4272461 0.5 0.4272461 1 0.427002 1 0.427002 0.5 0.427002 1 0.4267578 1 0.4267578 0.5 0.4267578 1 0.4265137 1 0.4265137 0.5 0.4265137 1 0.4262695 1 0.4262695 0.5 0.4262695 1 0.4260254 1 0.4260254 0.5 0.4260254 1 0.4257813 1 0.4257813 0.5 0.4257813 1 0.4255371 1 0.4255371 0.5 0.4255371 1 0.425293 1 0.425293 0.5 0.425293 1 0.4250488 1 0.4250488 0.5 0.4250488 1 0.4248047 1 0.4248047 0.5 0.4248047 1 0.4245606 1 0.4245606 0.5 0.4245606 1 0.4243164 1 0.4243164 0.5 0.4243164 1 0.4240723 1 0.4240723 0.5 0.4240723 1 0.4238281 1 0.4238281 0.5 0.4238281 1 0.423584 1 0.423584 0.5 0.423584 1 0.4233399 1 0.4233399 0.5 0.4233399 1 0.4230957 1 0.4230957 0.5 0.4230957 1 0.4228516 1 0.4228516 0.5 0.4228516 1 0.4226074 1 0.4226074 0.5 0.4226074 1 0.4223633 1 0.4223633 0.5 0.4223633 1 0.4221192 1 0.4221192 0.5 0.4221192 1 0.421875 1 0.421875 0.5 0.421875 1 0.4216309 1 0.4216309 0.5 0.4216309 1 0.4213867 1 0.4213867 0.5 0.4213867 1 0.4211426 1 0.4211426 0.5 0.4211426 1 0.4208984 1 0.4208984 0.5 0.4208984 1 0.4206543 1 0.4206543 0.5 0.4206543 1 0.4204102 1 0.4204102 0.5 0.4204102 1 0.420166 1 0.420166 0.5 0.420166 1 0.4199219 1 0.4199219 0.5 0.4199219 1 0.4196777 1 0.4196777 0.5 0.4196777 1 0.4194336 1 0.4194336 0.5 0.4194336 1 0.4191895 1 0.4191895 0.5 0.4191895 1 0.4189453 1 0.4189453 0.5 0.4189453 1 0.4187012 1 0.4187012 0.5 0.4187012 1 0.418457 1 0.418457 0.5 0.418457 1 0.4182129 1 0.4182129 0.5 0.4182129 1 0.4179688 1 0.4179688 0.5 0.4179688 1 0.4177246 1 0.4177246 0.5 0.4177246 1 0.4174805 1 0.4174805 0.5 0.4174805 1 0.4172363 1 0.4172363 0.5 0.4172363 1 0.4169922 1 0.4169922 0.5 0.4169922 1 0.4167481 1 0.4167481 0.5 0.4167481 1 0.4165039 1 0.4165039 0.5 0.4165039 1 0.4162598 1 0.4162598 0.5 0.4162598 1 0.4160156 1 0.4160156 0.5 0.4160156 1 0.4157715 1 0.4157715 0.5 0.4157715 1 0.4155274 1 0.4155274 0.5 0.4155274 1 0.4152832 1 0.4152832 0.5 0.4152832 1 0.4150391 1 0.4150391 0.5 0.4150391 1 0.4147949 1 0.4147949 0.5 0.4147949 1 0.4145508 1 0.4145508 0.5 0.4145508 1 0.4143067 1 0.4143067 0.5 0.4143067 1 0.4140625 1 0.4140625 0.5 0.4140625 1 0.4138184 1 0.4138184 0.5 0.4138184 1 0.4135742 1 0.4135742 0.5 0.4135742 1 0.4133301 1 0.4133301 0.5 0.4133301 1 0.4130859 1 0.4130859 0.5 0.4130859 1 0.4128418 1 0.4128418 0.5 0.4128418 1 0.4125977 1 0.4125977 0.5 0.4125977 1 0.4123535 1 0.4123535 0.5 0.4123535 1 0.4121094 1 0.4121094 0.5 0.4121094 1 0.4118652 1 0.4118652 0.5 0.4118652 1 0.4116211 1 0.4116211 0.5 0.4116211 1 0.411377 1 0.411377 0.5 0.411377 1 0.4111328 1 0.4111328 0.5 0.4111328 1 0.4108887 1 0.4108887 0.5 0.4108887 1 0.4106445 1 0.4106445 0.5 0.4106445 1 0.4104004 1 0.4104004 0.5 0.4104004 1 0.4101563 1 0.4101563 0.5 0.4101563 1 0.4099121 1 0.4099121 0.5 0.4099121 1 0.409668 1 0.409668 0.5 0.409668 1 0.4094238 1 0.4094238 0.5 0.4094238 1 0.4091797 1 0.4091797 0.5 0.4091797 1 0.4089356 1 0.4089356 0.5 0.4089356 1 0.4086914 1 0.4086914 0.5 0.4086914 1 0.4084473 1 0.4084473 0.5 0.4084473 1 0.4082031 1 0.4082031 0.5 0.4082031 1 0.407959 1 0.407959 0.5 0.407959 1 0.4077149 1 0.4077149 0.5 0.4077149 1 0.4074707 1 0.4074707 0.5 0.4074707 1 0.4072266 1 0.4072266 0.5 0.4072266 1 0.4069824 1 0.4069824 0.5 0.4069824 1 0.4067383 1 0.4067383 0.5 0.4067383 1 0.4064942 1 0.4064942 0.5 0.4064942 1 0.40625 1 0.40625 0.5 0.40625 1 0.4060059 1 0.4060059 0.5 0.4060059 1 0.4057617 1 0.4057617 0.5 0.4057617 1 0.4055176 1 0.4055176 0.5 0.4055176 1 0.4052734 1 0.4052734 0.5 0.4052734 1 0.4050293 1 0.4050293 0.5 0.4050293 1 0.4047852 1 0.4047852 0.5 0.4047852 1 0.404541 1 0.404541 0.5 0.404541 1 0.4042969 1 0.4042969 0.5 0.4042969 1 0.4040527 1 0.4040527 0.5 0.4040527 1 0.4038086 1 0.4038086 0.5 0.4038086 1 0.4035645 1 0.4035645 0.5 0.4035645 1 0.4033203 1 0.4033203 0.5 0.4033203 1 0.4030762 1 0.4030762 0.5 0.4030762 1 0.402832 1 0.402832 0.5 0.402832 1 0.4025879 1 0.4025879 0.5 0.4025879 1 0.4023438 1 0.4023438 0.5 0.4023438 1 0.4020996 1 0.4020996 0.5 0.4020996 1 0.4018555 1 0.4018555 0.5 0.4018555 1 0.4016113 1 0.4016113 0.5 0.4016113 1 0.4013672 1 0.4013672 0.5 0.4013672 1 0.4011231 1 0.4011231 0.5 0.4011231 1 0.4008789 1 0.4008789 0.5 0.4008789 1 0.4006348 1 0.4006348 0.5 0.4006348 1 0.4003906 1 0.4003906 0.5 0.4003906 1 0.4001465 1 0.4001465 0.5 0.4001465 1 0.3999024 1 0.3999024 0.5 0.3999024 1 0.3996582 1 0.3996582 0.5 0.3996582 1 0.3994141 1 0.3994141 0.5 0.3994141 1 0.3991699 1 0.3991699 0.5 0.3991699 1 0.3989258 1 0.3989258 0.5 0.3989258 1 0.3986817 1 0.3986817 0.5 0.3986817 1 0.3984375 1 0.3984375 0.5 0.3984375 1 0.3981934 1 0.3981934 0.5 0.3981934 1 0.3979492 1 0.3979492 0.5 0.3979492 1 0.3977051 1 0.3977051 0.5 0.3977051 1 0.3974609 1 0.3974609 0.5 0.3974609 1 0.3972168 1 0.3972168 0.5 0.3972168 1 0.3969727 1 0.3969727 0.5 0.3969727 1 0.3967285 1 0.3967285 0.5 0.3967285 1 0.3964844 1 0.3964844 0.5 0.3964844 1 0.3962402 1 0.3962402 0.5 0.3962402 1 0.3959961 1 0.3959961 0.5 0.3959961 1 0.395752 1 0.395752 0.5 0.395752 1 0.3955078 1 0.3955078 0.5 0.3955078 1 0.3952637 1 0.3952637 0.5 0.3952637 1 0.3950195 1 0.3950195 0.5 0.3950195 1 0.3947754 1 0.3947754 0.5 0.3947754 1 0.3945313 1 0.3945313 0.5 0.3945313 1 0.3942871 1 0.3942871 0.5 0.3942871 1 0.394043 1 0.394043 0.5 0.394043 1 0.3937988 1 0.3937988 0.5 0.3937988 1 0.3935547 1 0.3935547 0.5 0.3935547 1 0.3933106 1 0.3933106 0.5 0.3933106 1 0.3930664 1 0.3930664 0.5 0.3930664 1 0.3928223 1 0.3928223 0.5 0.3928223 1 0.3925781 1 0.3925781 0.5 0.3925781 1 0.392334 1 0.392334 0.5 0.392334 1 0.3920899 1 0.3920899 0.5 0.3920899 1 0.3918457 1 0.3918457 0.5 0.3918457 1 0.3916016 1 0.3916016 0.5 0.3916016 1 0.3913574 1 0.3913574 0.5 0.3913574 1 0.3911133 1 0.3911133 0.5 0.3911133 1 0.3908692 1 0.3908692 0.5 0.3908692 1 0.390625 1 0.390625 0.5 0.390625 1 0.3903809 1 0.3903809 0.5 0.3903809 1 0.3901367 1 0.3901367 0.5 0.3901367 1 0.3898926 1 0.3898926 0.5 0.3898926 1 0.3896484 1 0.3896484 0.5 0.3896484 1 0.3894043 1 0.3894043 0.5 0.3894043 1 0.3891602 1 0.3891602 0.5 0.3891602 1 0.388916 1 0.388916 0.5 0.388916 1 0.3886719 1 0.3886719 0.5 0.3886719 1 0.3884277 1 0.3884277 0.5 0.3884277 1 0.3881836 1 0.3881836 0.5 0.3881836 1 0.3879395 1 0.3879395 0.5 0.3879395 1 0.3876953 1 0.3876953 0.5 0.3876953 1 0.3874512 1 0.3874512 0.5 0.3874512 1 0.387207 1 0.387207 0.5 0.387207 1 0.3869629 1 0.3869629 0.5 0.3869629 1 0.3867188 1 0.3867188 0.5 0.3867188 1 0.3864746 1 0.3864746 0.5 0.3864746 1 0.3862305 1 0.3862305 0.5 0.3862305 1 0.3859863 1 0.3859863 0.5 0.3859863 1 0.3857422 1 0.3857422 0.5 0.3857422 1 0.3854981 1 0.3854981 0.5 0.3854981 1 0.3852539 1 0.3852539 0.5 0.3852539 1 0.3850098 1 0.3850098 0.5 0.3850098 1 0.3847656 1 0.3847656 0.5 0.3847656 1 0.3845215 1 0.3845215 0.5 0.3845215 1 0.3842774 1 0.3842774 0.5 0.3842774 1 0.3840332 1 0.3840332 0.5 0.3840332 1 0.3837891 1 0.3837891 0.5 0.3837891 1 0.3835449 1 0.3835449 0.5 0.3835449 1 0.3833008 1 0.3833008 0.5 0.3833008 1 0.3830567 1 0.3830567 0.5 0.3830567 1 0.3828125 1 0.3828125 0.5 0.3828125 1 0.3825684 1 0.3825684 0.5 0.3825684 1 0.3823242 1 0.3823242 0.5 0.3823242 1 0.3820801 1 0.3820801 0.5 0.3820801 1 0.3818359 1 0.3818359 0.5 0.3818359 1 0.3815918 1 0.3815918 0.5 0.3815918 1 0.3813477 1 0.3813477 0.5 0.3813477 1 0.3811035 1 0.3811035 0.5 0.3811035 1 0.3808594 1 0.3808594 0.5 0.3808594 1 0.3806152 1 0.3806152 0.5 0.3806152 1 0.3803711 1 0.3803711 0.5 0.3803711 1 0.380127 1 0.380127 0.5 0.380127 1 0.3798828 1 0.3798828 0.5 0.3798828 1 0.3796387 1 0.3796387 0.5 0.3796387 1 0.3793945 1 0.3793945 0.5 0.3793945 1 0.3791504 1 0.3791504 0.5 0.3791504 1 0.3789063 1 0.3789063 0.5 0.3789063 1 0.3786621 1 0.3786621 0.5 0.3786621 1 0.378418 1 0.378418 0.5 0.378418 1 0.3781738 1 0.3781738 0.5 0.3781738 1 0.3779297 1 0.3779297 0.5 0.3779297 1 0.3776856 1 0.3776856 0.5 0.3776856 1 0.3774414 1 0.3774414 0.5 0.3774414 1 0.3771973 1 0.3771973 0.5 0.3771973 1 0.3769531 1 0.3769531 0.5 0.3769531 1 0.376709 1 0.376709 0.5 0.376709 1 0.3764649 1 0.3764649 0.5 0.3764649 1 0.3762207 1 0.3762207 0.5 0.3762207 1 0.3759766 1 0.3759766 0.5 0.3759766 1 0.3757324 1 0.3757324 0.5 0.3757324 1 0.3754883 1 0.3754883 0.5 0.3754883 1 0.3752442 1 0.3752442 0.5 0.3752442 1 0.375 1 0.375 0.5 0.375 1 0.3747559 1 0.3747559 0.5 0.3747559 1 0.3745117 1 0.3745117 0.5 0.3745117 1 0.3742676 1 0.3742676 0.5 0.3742676 1 0.3740234 1 0.3740234 0.5 0.3740234 1 0.3737793 1 0.3737793 0.5 0.3737793 1 0.3735352 1 0.3735352 0.5 0.3735352 1 0.373291 1 0.373291 0.5 0.373291 1 0.3730469 1 0.3730469 0.5 0.3730469 1 0.3728027 1 0.3728027 0.5 0.3728027 1 0.3725586 1 0.3725586 0.5 0.3725586 1 0.3723145 1 0.3723145 0.5 0.3723145 1 0.3720703 1 0.3720703 0.5 0.3720703 1 0.3718262 1 0.3718262 0.5 0.3718262 1 0.371582 1 0.371582 0.5 0.371582 1 0.3713379 1 0.3713379 0.5 0.3713379 1 0.3710938 1 0.3710938 0.5 0.3710938 1 0.3708496 1 0.3708496 0.5 0.3708496 1 0.3706055 1 0.3706055 0.5 0.3706055 1 0.3703613 1 0.3703613 0.5 0.3703613 1 0.3701172 1 0.3701172 0.5 0.3701172 1 0.3698731 1 0.3698731 0.5 0.3698731 1 0.3696289 1 0.3696289 0.5 0.3696289 1 0.3693848 1 0.3693848 0.5 0.3693848 1 0.3691406 1 0.3691406 0.5 0.3691406 1 0.3688965 1 0.3688965 0.5 0.3688965 1 0.3686524 1 0.3686524 0.5 0.3686524 1 0.3684082 1 0.3684082 0.5 0.3684082 1 0.3681641 1 0.3681641 0.5 0.3681641 1 0.3679199 1 0.3679199 0.5 0.3679199 1 0.3676758 1 0.3676758 0.5 0.3676758 1 0.3674317 1 0.3674317 0.5 0.3674317 1 0.3671875 1 0.3671875 0.5 0.3671875 1 0.3669434 1 0.3669434 0.5 0.3669434 1 0.3666992 1 0.3666992 0.5 0.3666992 1 0.3664551 1 0.3664551 0.5 0.3664551 1 0.3662109 1 0.3662109 0.5 0.3662109 1 0.3659668 1 0.3659668 0.5 0.3659668 1 0.3657227 1 0.3657227 0.5 0.3657227 1 0.3654785 1 0.3654785 0.5 0.3654785 1 0.3652344 1 0.3652344 0.5 0.3652344 1 0.3649902 1 0.3649902 0.5 0.3649902 1 0.3647461 1 0.3647461 0.5 0.3647461 1 0.364502 1 0.364502 0.5 0.364502 1 0.3642578 1 0.3642578 0.5 0.3642578 1 0.3640137 1 0.3640137 0.5 0.3640137 1 0.3637695 1 0.3637695 0.5 0.3637695 1 0.3635254 1 0.3635254 0.5 0.3635254 1 0.3632813 1 0.3632813 0.5 0.3632813 1 0.3630371 1 0.3630371 0.5 0.3630371 1 0.362793 1 0.362793 0.5 0.362793 1 0.3625488 1 0.3625488 0.5 0.3625488 1 0.3623047 1 0.3623047 0.5 0.3623047 1 0.3620606 1 0.3620606 0.5 0.3620606 1 0.3618164 1 0.3618164 0.5 0.3618164 1 0.3615723 1 0.3615723 0.5 0.3615723 1 0.3613281 1 0.3613281 0.5 0.3613281 1 0.361084 1 0.361084 0.5 0.361084 1 0.3608399 1 0.3608399 0.5 0.3608399 1 0.3605957 1 0.3605957 0.5 0.3605957 1 0.3603516 1 0.3603516 0.5 0.3603516 1 0.3601074 1 0.3601074 0.5 0.3601074 1 0.3598633 1 0.3598633 0.5 0.3598633 1 0.3596192 1 0.3596192 0.5 0.3596192 1 0.359375 1 0.359375 0.5 0.359375 1 0.3591309 1 0.3591309 0.5 0.3591309 1 0.3588867 1 0.3588867 0.5 0.3588867 1 0.3586426 1 0.3586426 0.5 0.3586426 1 0.3583984 1 0.3583984 0.5 0.3583984 1 0.3581543 1 0.3581543 0.5 0.3581543 1 0.3579102 1 0.3579102 0.5 0.3579102 1 0.357666 1 0.357666 0.5 0.357666 1 0.3574219 1 0.3574219 0.5 0.3574219 1 0.3571777 1 0.3571777 0.5 0.3571777 1 0.3569336 1 0.3569336 0.5 0.3569336 1 0.3566895 1 0.3566895 0.5 0.3566895 1 0.3564453 1 0.3564453 0.5 0.3564453 1 0.3562012 1 0.3562012 0.5 0.3562012 1 0.355957 1 0.355957 0.5 0.355957 1 0.3557129 1 0.3557129 0.5 0.3557129 1 0.3554688 1 0.3554688 0.5 0.3554688 1 0.3552246 1 0.3552246 0.5 0.3552246 1 0.3549805 1 0.3549805 0.5 0.3549805 1 0.3547363 1 0.3547363 0.5 0.3547363 1 0.3544922 1 0.3544922 0.5 0.3544922 1 0.3542481 1 0.3542481 0.5 0.3542481 1 0.3540039 1 0.3540039 0.5 0.3540039 1 0.3537598 1 0.3537598 0.5 0.3537598 1 0.3535156 1 0.3535156 0.5 0.3535156 1 0.3532715 1 0.3532715 0.5 0.3532715 1 0.3530274 1 0.3530274 0.5 0.3530274 1 0.3527832 1 0.3527832 0.5 0.3527832 1 0.3525391 1 0.3525391 0.5 0.3525391 1 0.3522949 1 0.3522949 0.5 0.3522949 1 0.3520508 1 0.3520508 0.5 0.3520508 1 0.3518067 1 0.3518067 0.5 0.3518067 1 0.3515625 1 0.3515625 0.5 0.3515625 1 0.3513184 1 0.3513184 0.5 0.3513184 1 0.3510742 1 0.3510742 0.5 0.3510742 1 0.3508301 1 0.3508301 0.5 0.3508301 1 0.3505859 1 0.3505859 0.5 0.3505859 1 0.3503418 1 0.3503418 0.5 0.3503418 1 0.3500977 1 0.3500977 0.5 0.3500977 1 0.3498535 1 0.3498535 0.5 0.3498535 1 0.3496094 1 0.3496094 0.5 0.3496094 1 0.3493652 1 0.3493652 0.5 0.3493652 1 0.3491211 1 0.3491211 0.5 0.3491211 1 0.348877 1 0.348877 0.5 0.348877 1 0.3486328 1 0.3486328 0.5 0.3486328 1 0.3483887 1 0.3483887 0.5 0.3483887 1 0.3481445 1 0.3481445 0.5 0.3481445 1 0.3479004 1 0.3479004 0.5 0.3479004 1 0.3476563 1 0.3476563 0.5 0.3476563 1 0.3474121 1 0.3474121 0.5 0.3474121 1 0.347168 1 0.347168 0.5 0.347168 1 0.3469238 1 0.3469238 0.5 0.3469238 1 0.3466797 1 0.3466797 0.5 0.3466797 1 0.3464356 1 0.3464356 0.5 0.3464356 1 0.3461914 1 0.3461914 0.5 0.3461914 1 0.3459473 1 0.3459473 0.5 0.3459473 1 0.3457031 1 0.3457031 0.5 0.3457031 1 0.345459 1 0.345459 0.5 0.345459 1 0.3452149 1 0.3452149 0.5 0.3452149 1 0.3449707 1 0.3449707 0.5 0.3449707 1 0.3447266 1 0.3447266 0.5 0.3447266 1 0.3444824 1 0.3444824 0.5 0.3444824 1 0.3442383 1 0.3442383 0.5 0.3442383 1 0.3439942 1 0.3439942 0.5 0.3439942 1 0.34375 1 0.34375 0.5 0.34375 1 0.3435059 1 0.3435059 0.5 0.3435059 1 0.3432617 1 0.3432617 0.5 0.3432617 1 0.3430176 1 0.3430176 0.5 0.3430176 1 0.3427734 1 0.3427734 0.5 0.3427734 1 0.3425293 1 0.3425293 0.5 0.3425293 1 0.3422852 1 0.3422852 0.5 0.3422852 1 0.342041 1 0.342041 0.5 0.342041 1 0.3417969 1 0.3417969 0.5 0.3417969 1 0.3415527 1 0.3415527 0.5 0.3415527 1 0.3413086 1 0.3413086 0.5 0.3413086 1 0.3410645 1 0.3410645 0.5 0.3410645 1 0.3408203 1 0.3408203 0.5 0.3408203 1 0.3405762 1 0.3405762 0.5 0.3405762 1 0.340332 1 0.340332 0.5 0.340332 1 0.3400879 1 0.3400879 0.5 0.3400879 1 0.3398438 1 0.3398438 0.5 0.3398438 1 0.3395996 1 0.3395996 0.5 0.3395996 1 0.3393555 1 0.3393555 0.5 0.3393555 1 0.3391113 1 0.3391113 0.5 0.3391113 1 0.3388672 1 0.3388672 0.5 0.3388672 1 0.3386231 1 0.3386231 0.5 0.3386231 1 0.3383789 1 0.3383789 0.5 0.3383789 1 0.3381348 1 0.3381348 0.5 0.3381348 1 0.3378906 1 0.3378906 0.5 0.3378906 1 0.3376465 1 0.3376465 0.5 0.3376465 1 0.3374024 1 0.3374024 0.5 0.3374024 1 0.3371582 1 0.3371582 0.5 0.3371582 1 0.3369141 1 0.3369141 0.5 0.3369141 1 0.3366699 1 0.3366699 0.5 0.3366699 1 0.3364258 1 0.3364258 0.5 0.3364258 1 0.3361817 1 0.3361817 0.5 0.3361817 1 0.3359375 1 0.3359375 0.5 0.3359375 1 0.3356934 1 0.3356934 0.5 0.3356934 1 0.3354492 1 0.3354492 0.5 0.3354492 1 0.3352051 1 0.3352051 0.5 0.3352051 1 0.3349609 1 0.3349609 0.5 0.3349609 1 0.3347168 1 0.3347168 0.5 0.3347168 1 0.3344727 1 0.3344727 0.5 0.3344727 1 0.3342285 1 0.3342285 0.5 0.3342285 1 0.3339844 1 0.3339844 0.5 0.3339844 1 0.3337402 1 0.3337402 0.5 0.3337402 1 0.3334961 1 0.3334961 0.5 0.3334961 1 0.333252 1 0.333252 0.5 0.333252 1 0.3330078 1 0.3330078 0.5 0.3330078 1 0.3327637 1 0.3327637 0.5 0.3327637 1 0.3325195 1 0.3325195 0.5 0.3325195 1 0.3322754 1 0.3322754 0.5 0.3322754 1 0.3320313 1 0.3320313 0.5 0.3320313 1 0.3317871 1 0.3317871 0.5 0.3317871 1 0.331543 1 0.331543 0.5 0.331543 1 0.3312988 1 0.3312988 0.5 0.3312988 1 0.3310547 1 0.3310547 0.5 0.3310547 1 0.3308106 1 0.3308106 0.5 0.3308106 1 0.3305664 1 0.3305664 0.5 0.3305664 1 0.3303223 1 0.3303223 0.5 0.3303223 1 0.3300781 1 0.3300781 0.5 0.3300781 1 0.329834 1 0.329834 0.5 0.329834 1 0.3295899 1 0.3295899 0.5 0.3295899 1 0.3293457 1 0.3293457 0.5 0.3293457 1 0.3291016 1 0.3291016 0.5 0.3291016 1 0.3288574 1 0.3288574 0.5 0.3288574 1 0.3286133 1 0.3286133 0.5 0.3286133 1 0.3283692 1 0.3283692 0.5 0.3283692 1 0.328125 1 0.328125 0.5 0.328125 1 0.3278809 1 0.3278809 0.5 0.3278809 1 0.3276367 1 0.3276367 0.5 0.3276367 1 0.3273926 1 0.3273926 0.5 0.3273926 1 0.3271484 1 0.3271484 0.5 0.3271484 1 0.3269043 1 0.3269043 0.5 0.3269043 1 0.3266602 1 0.3266602 0.5 0.3266602 1 0.326416 1 0.326416 0.5 0.326416 1 0.3261719 1 0.3261719 0.5 0.3261719 1 0.3259277 1 0.3259277 0.5 0.3259277 1 0.3256836 1 0.3256836 0.5 0.3256836 1 0.3254395 1 0.3254395 0.5 0.3254395 1 0.3251953 1 0.3251953 0.5 0.3251953 1 0.3249512 1 0.3249512 0.5 0.3249512 1 0.324707 1 0.324707 0.5 0.324707 1 0.3244629 1 0.3244629 0.5 0.3244629 1 0.3242188 1 0.3242188 0.5 0.3242188 1 0.3239746 1 0.3239746 0.5 0.3239746 1 0.3237305 1 0.3237305 0.5 0.3237305 1 0.3234863 1 0.3234863 0.5 0.3234863 1 0.3232422 1 0.3232422 0.5 0.3232422 1 0.3229981 1 0.3229981 0.5 0.3229981 1 0.3227539 1 0.3227539 0.5 0.3227539 1 0.3225098 1 0.3225098 0.5 0.3225098 1 0.3222656 1 0.3222656 0.5 0.3222656 1 0.3220215 1 0.3220215 0.5 0.3220215 1 0.3217774 1 0.3217774 0.5 0.3217774 1 0.3215332 1 0.3215332 0.5 0.3215332 1 0.3212891 1 0.3212891 0.5 0.3212891 1 0.3210449 1 0.3210449 0.5 0.3210449 1 0.3208008 1 0.3208008 0.5 0.3208008 1 0.3205567 1 0.3205567 0.5 0.3205567 1 0.3203125 1 0.3203125 0.5 0.3203125 1 0.3200684 1 0.3200684 0.5 0.3200684 1 0.3198242 1 0.3198242 0.5 0.3198242 1 0.3195801 1 0.3195801 0.5 0.3195801 1 0.3193359 1 0.3193359 0.5 0.3193359 1 0.3190918 1 0.3190918 0.5 0.3190918 1 0.3188477 1 0.3188477 0.5 0.3188477 1 0.3186035 1 0.3186035 0.5 0.3186035 1 0.3183594 1 0.3183594 0.5 0.3183594 1 0.3181152 1 0.3181152 0.5 0.3181152 1 0.3178711 1 0.3178711 0.5 0.3178711 1 0.317627 1 0.317627 0.5 0.317627 1 0.3173828 1 0.3173828 0.5 0.3173828 1 0.3171387 1 0.3171387 0.5 0.3171387 1 0.3168945 1 0.3168945 0.5 0.3168945 1 0.3166504 1 0.3166504 0.5 0.3166504 1 0.3164063 1 0.3164063 0.5 0.3164063 1 0.3161621 1 0.3161621 0.5 0.3161621 1 0.315918 1 0.315918 0.5 0.315918 1 0.3156738 1 0.3156738 0.5 0.3156738 1 0.3154297 1 0.3154297 0.5 0.3154297 1 0.3151856 1 0.3151856 0.5 0.3151856 1 0.3149414 1 0.3149414 0.5 0.3149414 1 0.3146973 1 0.3146973 0.5 0.3146973 1 0.3144531 1 0.3144531 0.5 0.3144531 1 0.314209 1 0.314209 0.5 0.314209 1 0.3139649 1 0.3139649 0.5 0.3139649 1 0.3137207 1 0.3137207 0.5 0.3137207 1 0.3134766 1 0.3134766 0.5 0.3134766 1 0.3132324 1 0.3132324 0.5 0.3132324 1 0.3129883 1 0.3129883 0.5 0.3129883 1 0.3127442 1 0.3127442 0.5 0.3127442 1 0.3125 1 0.3125 0.5 0.3125 1 0.3122559 1 0.3122559 0.5 0.3122559 1 0.3120117 1 0.3120117 0.5 0.3120117 1 0.3117676 1 0.3117676 0.5 0.3117676 1 0.3115234 1 0.3115234 0.5 0.3115234 1 0.3112793 1 0.3112793 0.5 0.3112793 1 0.3110352 1 0.3110352 0.5 0.3110352 1 0.310791 1 0.310791 0.5 0.310791 1 0.3105469 1 0.3105469 0.5 0.3105469 1 0.3103027 1 0.3103027 0.5 0.3103027 1 0.3100586 1 0.3100586 0.5 0.3100586 1 0.3098145 1 0.3098145 0.5 0.3098145 1 0.3095703 1 0.3095703 0.5 0.3095703 1 0.3093262 1 0.3093262 0.5 0.3093262 1 0.309082 1 0.309082 0.5 0.309082 1 0.3088379 1 0.3088379 0.5 0.3088379 1 0.3085938 1 0.3085938 0.5 0.3085938 1 0.3083496 1 0.3083496 0.5 0.3083496 1 0.3081055 1 0.3081055 0.5 0.3081055 1 0.3078613 1 0.3078613 0.5 0.3078613 1 0.3076172 1 0.3076172 0.5 0.3076172 1 0.3073731 1 0.3073731 0.5 0.3073731 1 0.3071289 1 0.3071289 0.5 0.3071289 1 0.3068848 1 0.3068848 0.5 0.3068848 1 0.3066406 1 0.3066406 0.5 0.3066406 1 0.3063965 1 0.3063965 0.5 0.3063965 1 0.3061524 1 0.3061524 0.5 0.3061524 1 0.3059082 1 0.3059082 0.5 0.3059082 1 0.3056641 1 0.3056641 0.5 0.3056641 1 0.3054199 1 0.3054199 0.5 0.3054199 1 0.3051758 1 0.3051758 0.5 0.3051758 1 0.3049317 1 0.3049317 0.5 0.3049317 1 0.3046875 1 0.3046875 0.5 0.3046875 1 0.3044434 1 0.3044434 0.5 0.3044434 1 0.3041992 1 0.3041992 0.5 0.3041992 1 0.3039551 1 0.3039551 0.5 0.3039551 1 0.3037109 1 0.3037109 0.5 0.3037109 1 0.3034668 1 0.3034668 0.5 0.3034668 1 0.3032227 1 0.3032227 0.5 0.3032227 1 0.3029785 1 0.3029785 0.5 0.3029785 1 0.3027344 1 0.3027344 0.5 0.3027344 1 0.3024902 1 0.3024902 0.5 0.3024902 1 0.3022461 1 0.3022461 0.5 0.3022461 1 0.302002 1 0.302002 0.5 0.302002 1 0.3017578 1 0.3017578 0.5 0.3017578 1 0.3015137 1 0.3015137 0.5 0.3015137 1 0.3012695 1 0.3012695 0.5 0.3012695 1 0.3010254 1 0.3010254 0.5 0.3010254 1 0.3007813 1 0.3007813 0.5 0.3007813 1 0.3005371 1 0.3005371 0.5 0.3005371 1 0.300293 1 0.300293 0.5 0.300293 1 0.3000488 1 0.3000488 0.5 0.3000488 1 0.2998047 1 0.2998047 0.5 0.2998047 1 0.2995606 1 0.2995606 0.5 0.2995606 1 0.2993164 1 0.2993164 0.5 0.2993164 1 0.2990723 1 0.2990723 0.5 0.2990723 1 0.2988281 1 0.2988281 0.5 0.2988281 1 0.298584 1 0.298584 0.5 0.298584 1 0.2983399 1 0.2983399 0.5 0.2983399 1 0.2980957 1 0.2980957 0.5 0.2980957 1 0.2978516 1 0.2978516 0.5 0.2978516 1 0.2976074 1 0.2976074 0.5 0.2976074 1 0.2973633 1 0.2973633 0.5 0.2973633 1 0.2971192 1 0.2971192 0.5 0.2971192 1 0.296875 1 0.296875 0.5 0.296875 1 0.2966309 1 0.2966309 0.5 0.2966309 1 0.2963867 1 0.2963867 0.5 0.2963867 1 0.2961426 1 0.2961426 0.5 0.2961426 1 0.2958984 1 0.2958984 0.5 0.2958984 1 0.2956543 1 0.2956543 0.5 0.2956543 1 0.2954102 1 0.2954102 0.5 0.2954102 1 0.295166 1 0.295166 0.5 0.295166 1 0.2949219 1 0.2949219 0.5 0.2949219 1 0.2946777 1 0.2946777 0.5 0.2946777 1 0.2944336 1 0.2944336 0.5 0.2944336 1 0.2941895 1 0.2941895 0.5 0.2941895 1 0.2939453 1 0.2939453 0.5 0.2939453 1 0.2937012 1 0.2937012 0.5 0.2937012 1 0.293457 1 0.293457 0.5 0.293457 1 0.2932129 1 0.2932129 0.5 0.2932129 1 0.2929688 1 0.2929688 0.5 0.2929688 1 0.2927246 1 0.2927246 0.5 0.2927246 1 0.2924805 1 0.2924805 0.5 0.2924805 1 0.2922363 1 0.2922363 0.5 0.2922363 1 0.2919922 1 0.2919922 0.5 0.2919922 1 0.2917481 1 0.2917481 0.5 0.2917481 1 0.2915039 1 0.2915039 0.5 0.2915039 1 0.2912598 1 0.2912598 0.5 0.2912598 1 0.2910156 1 0.2910156 0.5 0.2910156 1 0.2907715 1 0.2907715 0.5 0.2907715 1 0.2905274 1 0.2905274 0.5 0.2905274 1 0.2902832 1 0.2902832 0.5 0.2902832 1 0.2900391 1 0.2900391 0.5 0.2900391 1 0.2897949 1 0.2897949 0.5 0.2897949 1 0.2895508 1 0.2895508 0.5 0.2895508 1 0.2893067 1 0.2893067 0.5 0.2893067 1 0.2890625 1 0.2890625 0.5 0.2890625 1 0.2888184 1 0.2888184 0.5 0.2888184 1 0.2885742 1 0.2885742 0.5 0.2885742 1 0.2883301 1 0.2883301 0.5 0.2883301 1 0.2880859 1 0.2880859 0.5 0.2880859 1 0.2878418 1 0.2878418 0.5 0.2878418 1 0.2875977 1 0.2875977 0.5 0.2875977 1 0.2873535 1 0.2873535 0.5 0.2873535 1 0.2871094 1 0.2871094 0.5 0.2871094 1 0.2868652 1 0.2868652 0.5 0.2868652 1 0.2866211 1 0.2866211 0.5 0.2866211 1 0.286377 1 0.286377 0.5 0.286377 1 0.2861328 1 0.2861328 0.5 0.2861328 1 0.2858887 1 0.2858887 0.5 0.2858887 1 0.2856445 1 0.2856445 0.5 0.2856445 1 0.2854004 1 0.2854004 0.5 0.2854004 1 0.2851563 1 0.2851563 0.5 0.2851563 1 0.2849121 1 0.2849121 0.5 0.2849121 1 0.284668 1 0.284668 0.5 0.284668 1 0.2844238 1 0.2844238 0.5 0.2844238 1 0.2841797 1 0.2841797 0.5 0.2841797 1 0.2839356 1 0.2839356 0.5 0.2839356 1 0.2836914 1 0.2836914 0.5 0.2836914 1 0.2834473 1 0.2834473 0.5 0.2834473 1 0.2832031 1 0.2832031 0.5 0.2832031 1 0.282959 1 0.282959 0.5 0.282959 1 0.2827149 1 0.2827149 0.5 0.2827149 1 0.2824707 1 0.2824707 0.5 0.2824707 1 0.2822266 1 0.2822266 0.5 0.2822266 1 0.2819824 1 0.2819824 0.5 0.2819824 1 0.2817383 1 0.2817383 0.5 0.2817383 1 0.2814942 1 0.2814942 0.5 0.2814942 1 0.28125 1 0.28125 0.5 0.28125 1 0.2810059 1 0.2810059 0.5 0.2810059 1 0.2807617 1 0.2807617 0.5 0.2807617 1 0.2805176 1 0.2805176 0.5 0.2805176 1 0.2802734 1 0.2802734 0.5 0.2802734 1 0.2800293 1 0.2800293 0.5 0.2800293 1 0.2797852 1 0.2797852 0.5 0.2797852 1 0.279541 1 0.279541 0.5 0.279541 1 0.2792969 1 0.2792969 0.5 0.2792969 1 0.2790527 1 0.2790527 0.5 0.2790527 1 0.2788086 1 0.2788086 0.5 0.2788086 1 0.2785645 1 0.2785645 0.5 0.2785645 1 0.2783203 1 0.2783203 0.5 0.2783203 1 0.2780762 1 0.2780762 0.5 0.2780762 1 0.277832 1 0.277832 0.5 0.277832 1 0.2775879 1 0.2775879 0.5 0.2775879 1 0.2773438 1 0.2773438 0.5 0.2773438 1 0.2770996 1 0.2770996 0.5 0.2770996 1 0.2768555 1 0.2768555 0.5 0.2768555 1 0.2766113 1 0.2766113 0.5 0.2766113 1 0.2763672 1 0.2763672 0.5 0.2763672 1 0.2761231 1 0.2761231 0.5 0.2761231 1 0.2758789 1 0.2758789 0.5 0.2758789 1 0.2756348 1 0.2756348 0.5 0.2756348 1 0.2753906 1 0.2753906 0.5 0.2753906 1 0.2751465 1 0.2751465 0.5 0.2751465 1 0.2749024 1 0.2749024 0.5 0.2749024 1 0.2746582 1 0.2746582 0.5 0.2746582 1 0.2744141 1 0.2744141 0.5 0.2744141 1 0.2741699 1 0.2741699 0.5 0.2741699 1 0.2739258 1 0.2739258 0.5 0.2739258 1 0.2736817 1 0.2736817 0.5 0.2736817 1 0.2734375 1 0.2734375 0.5 0.2734375 1 0.2731934 1 0.2731934 0.5 0.2731934 1 0.2729492 1 0.2729492 0.5 0.2729492 1 0.2727051 1 0.2727051 0.5 0.2727051 1 0.2724609 1 0.2724609 0.5 0.2724609 1 0.2722168 1 0.2722168 0.5 0.2722168 1 0.2719727 1 0.2719727 0.5 0.2719727 1 0.2717285 1 0.2717285 0.5 0.2717285 1 0.2714844 1 0.2714844 0.5 0.2714844 1 0.2712402 1 0.2712402 0.5 0.2712402 1 0.2709961 1 0.2709961 0.5 0.2709961 1 0.270752 1 0.270752 0.5 0.270752 1 0.2705078 1 0.2705078 0.5 0.2705078 1 0.2702637 1 0.2702637 0.5 0.2702637 1 0.2700195 1 0.2700195 0.5 0.2700195 1 0.2697754 1 0.2697754 0.5 0.2697754 1 0.2695313 1 0.2695313 0.5 0.2695313 1 0.2692871 1 0.2692871 0.5 0.2692871 1 0.269043 1 0.269043 0.5 0.269043 1 0.2687988 1 0.2687988 0.5 0.2687988 1 0.2685547 1 0.2685547 0.5 0.2685547 1 0.2683106 1 0.2683106 0.5 0.2683106 1 0.2680664 1 0.2680664 0.5 0.2680664 1 0.2678223 1 0.2678223 0.5 0.2678223 1 0.2675781 1 0.2675781 0.5 0.2675781 1 0.267334 1 0.267334 0.5 0.267334 1 0.2670899 1 0.2670899 0.5 0.2670899 1 0.2668457 1 0.2668457 0.5 0.2668457 1 0.2666016 1 0.2666016 0.5 0.2666016 1 0.2663574 1 0.2663574 0.5 0.2663574 1 0.2661133 1 0.2661133 0.5 0.2661133 1 0.2658692 1 0.2658692 0.5 0.2658692 1 0.265625 1 0.265625 0.5 0.265625 1 0.2653809 1 0.2653809 0.5 0.2653809 1 0.2651367 1 0.2651367 0.5 0.2651367 1 0.2648926 1 0.2648926 0.5 0.2648926 1 0.2646484 1 0.2646484 0.5 0.2646484 1 0.2644043 1 0.2644043 0.5 0.2644043 1 0.2641602 1 0.2641602 0.5 0.2641602 1 0.263916 1 0.263916 0.5 0.263916 1 0.2636719 1 0.2636719 0.5 0.2636719 1 0.2634277 1 0.2634277 0.5 0.2634277 1 0.2631836 1 0.2631836 0.5 0.2631836 1 0.2629395 1 0.2629395 0.5 0.2629395 1 0.2626953 1 0.2626953 0.5 0.2626953 1 0.2624512 1 0.2624512 0.5 0.2624512 1 0.262207 1 0.262207 0.5 0.262207 1 0.2619629 1 0.2619629 0.5 0.2619629 1 0.2617188 1 0.2617188 0.5 0.2617188 1 0.2614746 1 0.2614746 0.5 0.2614746 1 0.2612305 1 0.2612305 0.5 0.2612305 1 0.2609863 1 0.2609863 0.5 0.2609863 1 0.2607422 1 0.2607422 0.5 0.2607422 1 0.2604981 1 0.2604981 0.5 0.2604981 1 0.2602539 1 0.2602539 0.5 0.2602539 1 0.2600098 1 0.2600098 0.5 0.2600098 1 0.2597656 1 0.2597656 0.5 0.2597656 1 0.2595215 1 0.2595215 0.5 0.2595215 1 0.2592774 1 0.2592774 0.5 0.2592774 1 0.2590332 1 0.2590332 0.5 0.2590332 1 0.2587891 1 0.2587891 0.5 0.2587891 1 0.2585449 1 0.2585449 0.5 0.2585449 1 0.2583008 1 0.2583008 0.5 0.2583008 1 0.2580567 1 0.2580567 0.5 0.2580567 1 0.2578125 1 0.2578125 0.5 0.2578125 1 0.2575684 1 0.2575684 0.5 0.2575684 1 0.2573242 1 0.2573242 0.5 0.2573242 1 0.2570801 1 0.2570801 0.5 0.2570801 1 0.2568359 1 0.2568359 0.5 0.2568359 1 0.2565918 1 0.2565918 0.5 0.2565918 1 0.2563477 1 0.2563477 0.5 0.2563477 1 0.2561035 1 0.2561035 0.5 0.2561035 1 0.2558594 1 0.2558594 0.5 0.2558594 1 0.2556152 1 0.2556152 0.5 0.2556152 1 0.2553711 1 0.2553711 0.5 0.2553711 1 0.255127 1 0.255127 0.5 0.255127 1 0.2548828 1 0.2548828 0.5 0.2548828 1 0.2546387 1 0.2546387 0.5 0.2546387 1 0.2543945 1 0.2543945 0.5 0.2543945 1 0.2541504 1 0.2541504 0.5 0.2541504 1 0.2539063 1 0.2539063 0.5 0.2539063 1 0.2536621 1 0.2536621 0.5 0.2536621 1 0.253418 1 0.253418 0.5 0.253418 1 0.2531738 1 0.2531738 0.5 0.2531738 1 0.2529297 1 0.2529297 0.5 0.2529297 1 0.2526856 1 0.2526856 0.5 0.2526856 1 0.2524414 1 0.2524414 0.5 0.2524414 1 0.2521973 1 0.2521973 0.5 0.2521973 1 0.2519531 1 0.2519531 0.5 0.2519531 1 0.251709 1 0.251709 0.5 0.251709 1 0.2514649 1 0.2514649 0.5 0.2514649 1 0.2512207 1 0.2512207 0.5 0.2512207 1 0.2509766 1 0.2509766 0.5 0.2509766 1 0.2507324 1 0.2507324 0.5 0.2507324 1 0.2504883 1 0.2504883 0.5 0.2504883 1 0.2502442 1 0.2502442 0.5 0.2502442 1 0.25 1 0.25 0.5 0.25 1 0.2497558 1 0.2497558 0.5 0.2497558 1 0.2495117 1 0.2495117 0.5 0.2495117 1 0.2492675 1 0.2492675 0.5 0.2492675 1 0.2490234 1 0.2490234 0.5 0.2490234 1 0.2487792 1 0.2487792 0.5 0.2487792 1 0.2485351 1 0.2485351 0.5 0.2485351 1 0.248291 1 0.248291 0.5 0.248291 1 0.2480468 1 0.2480468 0.5 0.2480468 1 0.2478027 1 0.2478027 0.5 0.2478027 1 0.2475585 1 0.2475585 0.5 0.2475585 1 0.2473144 1 0.2473144 0.5 0.2473144 1 0.2470703 1 0.2470703 0.5 0.2470703 1 0.2468261 1 0.2468261 0.5 0.2468261 1 0.246582 1 0.246582 0.5 0.246582 1 0.2463378 1 0.2463378 0.5 0.2463378 1 0.2460937 1 0.2460937 0.5 0.2460937 1 0.2458496 1 0.2458496 0.5 0.2458496 1 0.2456054 1 0.2456054 0.5 0.2456054 1 0.2453613 1 0.2453613 0.5 0.2453613 1 0.2451171 1 0.2451171 0.5 0.2451171 1 0.244873 1 0.244873 0.5 0.244873 1 0.2446289 1 0.2446289 0.5 0.2446289 1 0.2443847 1 0.2443847 0.5 0.2443847 1 0.2441406 1 0.2441406 0.5 0.2441406 1 0.2438964 1 0.2438964 0.5 0.2438964 1 0.2436523 1 0.2436523 0.5 0.2436523 1 0.2434082 1 0.2434082 0.5 0.2434082 1 0.243164 1 0.243164 0.5 0.243164 1 0.2429199 1 0.2429199 0.5 0.2429199 1 0.2426757 1 0.2426757 0.5 0.2426757 1 0.2424316 1 0.2424316 0.5 0.2424316 1 0.2421875 1 0.2421875 0.5 0.2421875 1 0.2419433 1 0.2419433 0.5 0.2419433 1 0.2416992 1 0.2416992 0.5 0.2416992 1 0.241455 1 0.241455 0.5 0.241455 1 0.2412109 1 0.2412109 0.5 0.2412109 1 0.2409667 1 0.2409667 0.5 0.2409667 1 0.2407226 1 0.2407226 0.5 0.2407226 1 0.2404785 1 0.2404785 0.5 0.2404785 1 0.2402343 1 0.2402343 0.5 0.2402343 1 0.2399902 1 0.2399902 0.5 0.2399902 1 0.239746 1 0.239746 0.5 0.239746 1 0.2395019 1 0.2395019 0.5 0.2395019 1 0.2392578 1 0.2392578 0.5 0.2392578 1 0.2390136 1 0.2390136 0.5 0.2390136 1 0.2387695 1 0.2387695 0.5 0.2387695 1 0.2385253 1 0.2385253 0.5 0.2385253 1 0.2382812 1 0.2382812 0.5 0.2382812 1 0.2380371 1 0.2380371 0.5 0.2380371 1 0.2377929 1 0.2377929 0.5 0.2377929 1 0.2375488 1 0.2375488 0.5 0.2375488 1 0.2373046 1 0.2373046 0.5 0.2373046 1 0.2370605 1 0.2370605 0.5 0.2370605 1 0.2368164 1 0.2368164 0.5 0.2368164 1 0.2365722 1 0.2365722 0.5 0.2365722 1 0.2363281 1 0.2363281 0.5 0.2363281 1 0.2360839 1 0.2360839 0.5 0.2360839 1 0.2358398 1 0.2358398 0.5 0.2358398 1 0.2355957 1 0.2355957 0.5 0.2355957 1 0.2353515 1 0.2353515 0.5 0.2353515 1 0.2351074 1 0.2351074 0.5 0.2351074 1 0.2348632 1 0.2348632 0.5 0.2348632 1 0.2346191 1 0.2346191 0.5 0.2346191 1 0.234375 1 0.234375 0.5 0.234375 1 0.2341308 1 0.2341308 0.5 0.2341308 1 0.2338867 1 0.2338867 0.5 0.2338867 1 0.2336425 1 0.2336425 0.5 0.2336425 1 0.2333984 1 0.2333984 0.5 0.2333984 1 0.2331542 1 0.2331542 0.5 0.2331542 1 0.2329101 1 0.2329101 0.5 0.2329101 1 0.232666 1 0.232666 0.5 0.232666 1 0.2324218 1 0.2324218 0.5 0.2324218 1 0.2321777 1 0.2321777 0.5 0.2321777 1 0.2319335 1 0.2319335 0.5 0.2319335 1 0.2316894 1 0.2316894 0.5 0.2316894 1 0.2314453 1 0.2314453 0.5 0.2314453 1 0.2312011 1 0.2312011 0.5 0.2312011 1 0.230957 1 0.230957 0.5 0.230957 1 0.2307128 1 0.2307128 0.5 0.2307128 1 0.2304687 1 0.2304687 0.5 0.2304687 1 0.2302246 1 0.2302246 0.5 0.2302246 1 0.2299804 1 0.2299804 0.5 0.2299804 1 0.2297363 1 0.2297363 0.5 0.2297363 1 0.2294921 1 0.2294921 0.5 0.2294921 1 0.229248 1 0.229248 0.5 0.229248 1 0.2290039 1 0.2290039 0.5 0.2290039 1 0.2287597 1 0.2287597 0.5 0.2287597 1 0.2285156 1 0.2285156 0.5 0.2285156 1 0.2282714 1 0.2282714 0.5 0.2282714 1 0.2280273 1 0.2280273 0.5 0.2280273 1 0.2277832 1 0.2277832 0.5 0.2277832 1 0.227539 1 0.227539 0.5 0.227539 1 0.2272949 1 0.2272949 0.5 0.2272949 1 0.2270507 1 0.2270507 0.5 0.2270507 1 0.2268066 1 0.2268066 0.5 0.2268066 1 0.2265625 1 0.2265625 0.5 0.2265625 1 0.2263183 1 0.2263183 0.5 0.2263183 1 0.2260742 1 0.2260742 0.5 0.2260742 1 0.22583 1 0.22583 0.5 0.22583 1 0.2255859 1 0.2255859 0.5 0.2255859 1 0.2253417 1 0.2253417 0.5 0.2253417 1 0.2250976 1 0.2250976 0.5 0.2250976 1 0.2248535 1 0.2248535 0.5 0.2248535 1 0.2246093 1 0.2246093 0.5 0.2246093 1 0.2243652 1 0.2243652 0.5 0.2243652 1 0.224121 1 0.224121 0.5 0.224121 1 0.2238769 1 0.2238769 0.5 0.2238769 1 0.2236328 1 0.2236328 0.5 0.2236328 1 0.2233886 1 0.2233886 0.5 0.2233886 1 0.2231445 1 0.2231445 0.5 0.2231445 1 0.2229003 1 0.2229003 0.5 0.2229003 1 0.2226562 1 0.2226562 0.5 0.2226562 1 0.2224121 1 0.2224121 0.5 0.2224121 1 0.2221679 1 0.2221679 0.5 0.2221679 1 0.2219238 1 0.2219238 0.5 0.2219238 1 0.2216796 1 0.2216796 0.5 0.2216796 1 0.2214355 1 0.2214355 0.5 0.2214355 1 0.2211914 1 0.2211914 0.5 0.2211914 1 0.2209472 1 0.2209472 0.5 0.2209472 1 0.2207031 1 0.2207031 0.5 0.2207031 1 0.2204589 1 0.2204589 0.5 0.2204589 1 0.2202148 1 0.2202148 0.5 0.2202148 1 0.2199707 1 0.2199707 0.5 0.2199707 1 0.2197265 1 0.2197265 0.5 0.2197265 1 0.2194824 1 0.2194824 0.5 0.2194824 1 0.2192382 1 0.2192382 0.5 0.2192382 1 0.2189941 1 0.2189941 0.5 0.2189941 1 0.21875 1 0.21875 0.5 0.21875 1 0.2185058 1 0.2185058 0.5 0.2185058 1 0.2182617 1 0.2182617 0.5 0.2182617 1 0.2180175 1 0.2180175 0.5 0.2180175 1 0.2177734 1 0.2177734 0.5 0.2177734 1 0.2175292 1 0.2175292 0.5 0.2175292 1 0.2172851 1 0.2172851 0.5 0.2172851 1 0.217041 1 0.217041 0.5 0.217041 1 0.2167968 1 0.2167968 0.5 0.2167968 1 0.2165527 1 0.2165527 0.5 0.2165527 1 0.2163085 1 0.2163085 0.5 0.2163085 1 0.2160644 1 0.2160644 0.5 0.2160644 1 0.2158203 1 0.2158203 0.5 0.2158203 1 0.2155761 1 0.2155761 0.5 0.2155761 1 0.215332 1 0.215332 0.5 0.215332 1 0.2150878 1 0.2150878 0.5 0.2150878 1 0.2148437 1 0.2148437 0.5 0.2148437 1 0.2145996 1 0.2145996 0.5 0.2145996 1 0.2143554 1 0.2143554 0.5 0.2143554 1 0.2141113 1 0.2141113 0.5 0.2141113 1 0.2138671 1 0.2138671 0.5 0.2138671 1 0.213623 1 0.213623 0.5 0.213623 1 0.2133789 1 0.2133789 0.5 0.2133789 1 0.2131347 1 0.2131347 0.5 0.2131347 1 0.2128906 1 0.2128906 0.5 0.2128906 1 0.2126464 1 0.2126464 0.5 0.2126464 1 0.2124023 1 0.2124023 0.5 0.2124023 1 0.2121582 1 0.2121582 0.5 0.2121582 1 0.211914 1 0.211914 0.5 0.211914 1 0.2116699 1 0.2116699 0.5 0.2116699 1 0.2114257 1 0.2114257 0.5 0.2114257 1 0.2111816 1 0.2111816 0.5 0.2111816 1 0.2109375 1 0.2109375 0.5 0.2109375 1 0.2106933 1 0.2106933 0.5 0.2106933 1 0.2104492 1 0.2104492 0.5 0.2104492 1 0.210205 1 0.210205 0.5 0.210205 1 0.2099609 1 0.2099609 0.5 0.2099609 1 0.2097167 1 0.2097167 0.5 0.2097167 1 0.2094726 1 0.2094726 0.5 0.2094726 1 0.2092285 1 0.2092285 0.5 0.2092285 1 0.2089843 1 0.2089843 0.5 0.2089843 1 0.2087402 1 0.2087402 0.5 0.2087402 1 0.208496 1 0.208496 0.5 0.208496 1 0.2082519 1 0.2082519 0.5 0.2082519 1 0.2080078 1 0.2080078 0.5 0.2080078 1 0.2077636 1 0.2077636 0.5 0.2077636 1 0.2075195 1 0.2075195 0.5 0.2075195 1 0.2072753 1 0.2072753 0.5 0.2072753 1 0.2070312 1 0.2070312 0.5 0.2070312 1 0.2067871 1 0.2067871 0.5 0.2067871 1 0.2065429 1 0.2065429 0.5 0.2065429 1 0.2062988 1 0.2062988 0.5 0.2062988 1 0.2060546 1 0.2060546 0.5 0.2060546 1 0.2058105 1 0.2058105 0.5 0.2058105 1 0.2055664 1 0.2055664 0.5 0.2055664 1 0.2053222 1 0.2053222 0.5 0.2053222 1 0.2050781 1 0.2050781 0.5 0.2050781 1 0.2048339 1 0.2048339 0.5 0.2048339 1 0.2045898 1 0.2045898 0.5 0.2045898 1 0.2043457 1 0.2043457 0.5 0.2043457 1 0.2041015 1 0.2041015 0.5 0.2041015 1 0.2038574 1 0.2038574 0.5 0.2038574 1 0.2036132 1 0.2036132 0.5 0.2036132 1 0.2033691 1 0.2033691 0.5 0.2033691 1 0.203125 1 0.203125 0.5 0.203125 1 0.2028808 1 0.2028808 0.5 0.2028808 1 0.2026367 1 0.2026367 0.5 0.2026367 1 0.2023925 1 0.2023925 0.5 0.2023925 1 0.2021484 1 0.2021484 0.5 0.2021484 1 0.2019042 1 0.2019042 0.5 0.2019042 1 0.2016601 1 0.2016601 0.5 0.2016601 1 0.201416 1 0.201416 0.5 0.201416 1 0.2011718 1 0.2011718 0.5 0.2011718 1 0.2009277 1 0.2009277 0.5 0.2009277 1 0.2006835 1 0.2006835 0.5 0.2006835 1 0.2004394 1 0.2004394 0.5 0.2004394 1 0.2001953 1 0.2001953 0.5 0.2001953 1 0.1999511 1 0.1999511 0.5 0.1999511 1 0.199707 1 0.199707 0.5 0.199707 1 0.1994628 1 0.1994628 0.5 0.1994628 1 0.1992187 1 0.1992187 0.5 0.1992187 1 0.1989746 1 0.1989746 0.5 0.1989746 1 0.1987304 1 0.1987304 0.5 0.1987304 1 0.1984863 1 0.1984863 0.5 0.1984863 1 0.1982421 1 0.1982421 0.5 0.1982421 1 0.197998 1 0.197998 0.5 0.197998 1 0.1977539 1 0.1977539 0.5 0.1977539 1 0.1975097 1 0.1975097 0.5 0.1975097 1 0.1972656 1 0.1972656 0.5 0.1972656 1 0.1970214 1 0.1970214 0.5 0.1970214 1 0.1967773 1 0.1967773 0.5 0.1967773 1 0.1965332 1 0.1965332 0.5 0.1965332 1 0.196289 1 0.196289 0.5 0.196289 1 0.1960449 1 0.1960449 0.5 0.1960449 1 0.1958007 1 0.1958007 0.5 0.1958007 1 0.1955566 1 0.1955566 0.5 0.1955566 1 0.1953125 1 0.1953125 0.5 0.1953125 1 0.1950683 1 0.1950683 0.5 0.1950683 1 0.1948242 1 0.1948242 0.5 0.1948242 1 0.19458 1 0.19458 0.5 0.19458 1 0.1943359 1 0.1943359 0.5 0.1943359 1 0.1940917 1 0.1940917 0.5 0.1940917 1 0.1938476 1 0.1938476 0.5 0.1938476 1 0.1936035 1 0.1936035 0.5 0.1936035 1 0.1933593 1 0.1933593 0.5 0.1933593 1 0.1931152 1 0.1931152 0.5 0.1931152 1 0.192871 1 0.192871 0.5 0.192871 1 0.1926269 1 0.1926269 0.5 0.1926269 1 0.1923828 1 0.1923828 0.5 0.1923828 1 0.1921386 1 0.1921386 0.5 0.1921386 1 0.1918945 1 0.1918945 0.5 0.1918945 1 0.1916503 1 0.1916503 0.5 0.1916503 1 0.1914062 1 0.1914062 0.5 0.1914062 1 0.1911621 1 0.1911621 0.5 0.1911621 1 0.1909179 1 0.1909179 0.5 0.1909179 1 0.1906738 1 0.1906738 0.5 0.1906738 1 0.1904296 1 0.1904296 0.5 0.1904296 1 0.1901855 1 0.1901855 0.5 0.1901855 1 0.1899414 1 0.1899414 0.5 0.1899414 1 0.1896972 1 0.1896972 0.5 0.1896972 1 0.1894531 1 0.1894531 0.5 0.1894531 1 0.1892089 1 0.1892089 0.5 0.1892089 1 0.1889648 1 0.1889648 0.5 0.1889648 1 0.1887207 1 0.1887207 0.5 0.1887207 1 0.1884765 1 0.1884765 0.5 0.1884765 1 0.1882324 1 0.1882324 0.5 0.1882324 1 0.1879882 1 0.1879882 0.5 0.1879882 1 0.1877441 1 0.1877441 0.5 0.1877441 1 0.1875 1 0.1875 0.5 0.1875 1 0.1872558 1 0.1872558 0.5 0.1872558 1 0.1870117 1 0.1870117 0.5 0.1870117 1 0.1867675 1 0.1867675 0.5 0.1867675 1 0.1865234 1 0.1865234 0.5 0.1865234 1 0.1862792 1 0.1862792 0.5 0.1862792 1 0.1860351 1 0.1860351 0.5 0.1860351 1 0.185791 1 0.185791 0.5 0.185791 1 0.1855468 1 0.1855468 0.5 0.1855468 1 0.1853027 1 0.1853027 0.5 0.1853027 1 0.1850585 1 0.1850585 0.5 0.1850585 1 0.1848144 1 0.1848144 0.5 0.1848144 1 0.1845703 1 0.1845703 0.5 0.1845703 1 0.1843261 1 0.1843261 0.5 0.1843261 1 0.184082 1 0.184082 0.5 0.184082 1 0.1838378 1 0.1838378 0.5 0.1838378 1 0.1835937 1 0.1835937 0.5 0.1835937 1 0.1833496 1 0.1833496 0.5 0.1833496 1 0.1831054 1 0.1831054 0.5 0.1831054 1 0.1828613 1 0.1828613 0.5 0.1828613 1 0.1826171 1 0.1826171 0.5 0.1826171 1 0.182373 1 0.182373 0.5 0.182373 1 0.1821289 1 0.1821289 0.5 0.1821289 1 0.1818847 1 0.1818847 0.5 0.1818847 1 0.1816406 1 0.1816406 0.5 0.1816406 1 0.1813964 1 0.1813964 0.5 0.1813964 1 0.1811523 1 0.1811523 0.5 0.1811523 1 0.1809082 1 0.1809082 0.5 0.1809082 1 0.180664 1 0.180664 0.5 0.180664 1 0.1804199 1 0.1804199 0.5 0.1804199 1 0.1801757 1 0.1801757 0.5 0.1801757 1 0.1799316 1 0.1799316 0.5 0.1799316 1 0.1796875 1 0.1796875 0.5 0.1796875 1 0.1794433 1 0.1794433 0.5 0.1794433 1 0.1791992 1 0.1791992 0.5 0.1791992 1 0.178955 1 0.178955 0.5 0.178955 1 0.1787109 1 0.1787109 0.5 0.1787109 1 0.1784667 1 0.1784667 0.5 0.1784667 1 0.1782226 1 0.1782226 0.5 0.1782226 1 0.1779785 1 0.1779785 0.5 0.1779785 1 0.1777343 1 0.1777343 0.5 0.1777343 1 0.1774902 1 0.1774902 0.5 0.1774902 1 0.177246 1 0.177246 0.5 0.177246 1 0.1770019 1 0.1770019 0.5 0.1770019 1 0.1767578 1 0.1767578 0.5 0.1767578 1 0.1765136 1 0.1765136 0.5 0.1765136 1 0.1762695 1 0.1762695 0.5 0.1762695 1 0.1760253 1 0.1760253 0.5 0.1760253 1 0.1757812 1 0.1757812 0.5 0.1757812 1 0.1755371 1 0.1755371 0.5 0.1755371 1 0.1752929 1 0.1752929 0.5 0.1752929 1 0.1750488 1 0.1750488 0.5 0.1750488 1 0.1748046 1 0.1748046 0.5 0.1748046 1 0.1745605 1 0.1745605 0.5 0.1745605 1 0.1743164 1 0.1743164 0.5 0.1743164 1 0.1740722 1 0.1740722 0.5 0.1740722 1 0.1738281 1 0.1738281 0.5 0.1738281 1 0.1735839 1 0.1735839 0.5 0.1735839 1 0.1733398 1 0.1733398 0.5 0.1733398 1 0.1730957 1 0.1730957 0.5 0.1730957 1 0.1728515 1 0.1728515 0.5 0.1728515 1 0.1726074 1 0.1726074 0.5 0.1726074 1 0.1723632 1 0.1723632 0.5 0.1723632 1 0.1721191 1 0.1721191 0.5 0.1721191 1 0.171875 1 0.171875 0.5 0.171875 1 0.1716308 1 0.1716308 0.5 0.1716308 1 0.1713867 1 0.1713867 0.5 0.1713867 1 0.1711425 1 0.1711425 0.5 0.1711425 1 0.1708984 1 0.1708984 0.5 0.1708984 1 0.1706542 1 0.1706542 0.5 0.1706542 1 0.1704101 1 0.1704101 0.5 0.1704101 1 0.170166 1 0.170166 0.5 0.170166 1 0.1699218 1 0.1699218 0.5 0.1699218 1 0.1696777 1 0.1696777 0.5 0.1696777 1 0.1694335 1 0.1694335 0.5 0.1694335 1 0.1691894 1 0.1691894 0.5 0.1691894 1 0.1689453 1 0.1689453 0.5 0.1689453 1 0.1687011 1 0.1687011 0.5 0.1687011 1 0.168457 1 0.168457 0.5 0.168457 1 0.1682128 1 0.1682128 0.5 0.1682128 1 0.1679687 1 0.1679687 0.5 0.1679687 1 0.1677246 1 0.1677246 0.5 0.1677246 1 0.1674804 1 0.1674804 0.5 0.1674804 1 0.1672363 1 0.1672363 0.5 0.1672363 1 0.1669921 1 0.1669921 0.5 0.1669921 1 0.166748 1 0.166748 0.5 0.166748 1 0.1665039 1 0.1665039 0.5 0.1665039 1 0.1662597 1 0.1662597 0.5 0.1662597 1 0.1660156 1 0.1660156 0.5 0.1660156 1 0.1657714 1 0.1657714 0.5 0.1657714 1 0.1655273 1 0.1655273 0.5 0.1655273 1 0.1652832 1 0.1652832 0.5 0.1652832 1 0.165039 1 0.165039 0.5 0.165039 1 0.1647949 1 0.1647949 0.5 0.1647949 1 0.1645507 1 0.1645507 0.5 0.1645507 1 0.1643066 1 0.1643066 0.5 0.1643066 1 0.1640625 1 0.1640625 0.5 0.1640625 1 0.1638183 1 0.1638183 0.5 0.1638183 1 0.1635742 1 0.1635742 0.5 0.1635742 1 0.16333 1 0.16333 0.5 0.16333 1 0.1630859 1 0.1630859 0.5 0.1630859 1 0.1628417 1 0.1628417 0.5 0.1628417 1 0.1625976 1 0.1625976 0.5 0.1625976 1 0.1623535 1 0.1623535 0.5 0.1623535 1 0.1621093 1 0.1621093 0.5 0.1621093 1 0.1618652 1 0.1618652 0.5 0.1618652 1 0.161621 1 0.161621 0.5 0.161621 1 0.1613769 1 0.1613769 0.5 0.1613769 1 0.1611328 1 0.1611328 0.5 0.1611328 1 0.1608886 1 0.1608886 0.5 0.1608886 1 0.1606445 1 0.1606445 0.5 0.1606445 1 0.1604003 1 0.1604003 0.5 0.1604003 1 0.1601562 1 0.1601562 0.5 0.1601562 1 0.1599121 1 0.1599121 0.5 0.1599121 1 0.1596679 1 0.1596679 0.5 0.1596679 1 0.1594238 1 0.1594238 0.5 0.1594238 1 0.1591796 1 0.1591796 0.5 0.1591796 1 0.1589355 1 0.1589355 0.5 0.1589355 1 0.1586914 1 0.1586914 0.5 0.1586914 1 0.1584472 1 0.1584472 0.5 0.1584472 1 0.1582031 1 0.1582031 0.5 0.1582031 1 0.1579589 1 0.1579589 0.5 0.1579589 1 0.1577148 1 0.1577148 0.5 0.1577148 1 0.1574707 1 0.1574707 0.5 0.1574707 1 0.1572265 1 0.1572265 0.5 0.1572265 1 0.1569824 1 0.1569824 0.5 0.1569824 1 0.1567382 1 0.1567382 0.5 0.1567382 1 0.1564941 1 0.1564941 0.5 0.1564941 1 0.15625 1 0.15625 0.5 0.15625 1 0.1560058 1 0.1560058 0.5 0.1560058 1 0.1557617 1 0.1557617 0.5 0.1557617 1 0.1555175 1 0.1555175 0.5 0.1555175 1 0.1552734 1 0.1552734 0.5 0.1552734 1 0.1550292 1 0.1550292 0.5 0.1550292 1 0.1547851 1 0.1547851 0.5 0.1547851 1 0.154541 1 0.154541 0.5 0.154541 1 0.1542968 1 0.1542968 0.5 0.1542968 1 0.1540527 1 0.1540527 0.5 0.1540527 1 0.1538085 1 0.1538085 0.5 0.1538085 1 0.1535644 1 0.1535644 0.5 0.1535644 1 0.1533203 1 0.1533203 0.5 0.1533203 1 0.1530761 1 0.1530761 0.5 0.1530761 1 0.152832 1 0.152832 0.5 0.152832 1 0.1525878 1 0.1525878 0.5 0.1525878 1 0.1523437 1 0.1523437 0.5 0.1523437 1 0.1520996 1 0.1520996 0.5 0.1520996 1 0.1518554 1 0.1518554 0.5 0.1518554 1 0.1516113 1 0.1516113 0.5 0.1516113 1 0.1513671 1 0.1513671 0.5 0.1513671 1 0.151123 1 0.151123 0.5 0.151123 1 0.1508789 1 0.1508789 0.5 0.1508789 1 0.1506347 1 0.1506347 0.5 0.1506347 1 0.1503906 1 0.1503906 0.5 0.1503906 1 0.1501464 1 0.1501464 0.5 0.1501464 1 0.1499023 1 0.1499023 0.5 0.1499023 1 0.1496582 1 0.1496582 0.5 0.1496582 1 0.149414 1 0.149414 0.5 0.149414 1 0.1491699 1 0.1491699 0.5 0.1491699 1 0.1489257 1 0.1489257 0.5 0.1489257 1 0.1486816 1 0.1486816 0.5 0.1486816 1 0.1484375 1 0.1484375 0.5 0.1484375 1 0.1481933 1 0.1481933 0.5 0.1481933 1 0.1479492 1 0.1479492 0.5 0.1479492 1 0.147705 1 0.147705 0.5 0.147705 1 0.1474609 1 0.1474609 0.5 0.1474609 1 0.1472167 1 0.1472167 0.5 0.1472167 1 0.1469726 1 0.1469726 0.5 0.1469726 1 0.1467285 1 0.1467285 0.5 0.1467285 1 0.1464843 1 0.1464843 0.5 0.1464843 1 0.1462402 1 0.1462402 0.5 0.1462402 1 0.145996 1 0.145996 0.5 0.145996 1 0.1457519 1 0.1457519 0.5 0.1457519 1 0.1455078 1 0.1455078 0.5 0.1455078 1 0.1452636 1 0.1452636 0.5 0.1452636 1 0.1450195 1 0.1450195 0.5 0.1450195 1 0.1447753 1 0.1447753 0.5 0.1447753 1 0.1445312 1 0.1445312 0.5 0.1445312 1 0.1442871 1 0.1442871 0.5 0.1442871 1 0.1440429 1 0.1440429 0.5 0.1440429 1 0.1437988 1 0.1437988 0.5 0.1437988 1 0.1435546 1 0.1435546 0.5 0.1435546 1 0.1433105 1 0.1433105 0.5 0.1433105 1 0.1430664 1 0.1430664 0.5 0.1430664 1 0.1428222 1 0.1428222 0.5 0.1428222 1 0.1425781 1 0.1425781 0.5 0.1425781 1 0.1423339 1 0.1423339 0.5 0.1423339 1 0.1420898 1 0.1420898 0.5 0.1420898 1 0.1418457 1 0.1418457 0.5 0.1418457 1 0.1416015 1 0.1416015 0.5 0.1416015 1 0.1413574 1 0.1413574 0.5 0.1413574 1 0.1411132 1 0.1411132 0.5 0.1411132 1 0.1408691 1 0.1408691 0.5 0.1408691 1 0.140625 1 0.140625 0.5 0.140625 1 0.1403808 1 0.1403808 0.5 0.1403808 1 0.1401367 1 0.1401367 0.5 0.1401367 1 0.1398925 1 0.1398925 0.5 0.1398925 1 0.1396484 1 0.1396484 0.5 0.1396484 1 0.1394042 1 0.1394042 0.5 0.1394042 1 0.1391601 1 0.1391601 0.5 0.1391601 1 0.138916 1 0.138916 0.5 0.138916 1 0.1386718 1 0.1386718 0.5 0.1386718 1 0.1384277 1 0.1384277 0.5 0.1384277 1 0.1381835 1 0.1381835 0.5 0.1381835 1 0.1379394 1 0.1379394 0.5 0.1379394 1 0.1376953 1 0.1376953 0.5 0.1376953 1 0.1374511 1 0.1374511 0.5 0.1374511 1 0.137207 1 0.137207 0.5 0.137207 1 0.1369628 1 0.1369628 0.5 0.1369628 1 0.1367187 1 0.1367187 0.5 0.1367187 1 0.1364746 1 0.1364746 0.5 0.1364746 1 0.1362304 1 0.1362304 0.5 0.1362304 1 0.1359863 1 0.1359863 0.5 0.1359863 1 0.1357421 1 0.1357421 0.5 0.1357421 1 0.135498 1 0.135498 0.5 0.135498 1 0.1352539 1 0.1352539 0.5 0.1352539 1 0.1350097 1 0.1350097 0.5 0.1350097 1 0.1347656 1 0.1347656 0.5 0.1347656 1 0.1345214 1 0.1345214 0.5 0.1345214 1 0.1342773 1 0.1342773 0.5 0.1342773 1 0.1340332 1 0.1340332 0.5 0.1340332 1 0.133789 1 0.133789 0.5 0.133789 1 0.1335449 1 0.1335449 0.5 0.1335449 1 0.1333007 1 0.1333007 0.5 0.1333007 1 0.1330566 1 0.1330566 0.5 0.1330566 1 0.1328125 1 0.1328125 0.5 0.1328125 1 0.1325683 1 0.1325683 0.5 0.1325683 1 0.1323242 1 0.1323242 0.5 0.1323242 1 0.13208 1 0.13208 0.5 0.13208 1 0.1318359 1 0.1318359 0.5 0.1318359 1 0.1315917 1 0.1315917 0.5 0.1315917 1 0.1313476 1 0.1313476 0.5 0.1313476 1 0.1311035 1 0.1311035 0.5 0.1311035 1 0.1308593 1 0.1308593 0.5 0.1308593 1 0.1306152 1 0.1306152 0.5 0.1306152 1 0.130371 1 0.130371 0.5 0.130371 1 0.1301269 1 0.1301269 0.5 0.1301269 1 0.1298828 1 0.1298828 0.5 0.1298828 1 0.1296386 1 0.1296386 0.5 0.1296386 1 0.1293945 1 0.1293945 0.5 0.1293945 1 0.1291503 1 0.1291503 0.5 0.1291503 1 0.1289062 1 0.1289062 0.5 0.1289062 1 0.1286621 1 0.1286621 0.5 0.1286621 1 0.1284179 1 0.1284179 0.5 0.1284179 1 0.1281738 1 0.1281738 0.5 0.1281738 1 0.1279296 1 0.1279296 0.5 0.1279296 1 0.1276855 1 0.1276855 0.5 0.1276855 1 0.1274414 1 0.1274414 0.5 0.1274414 1 0.1271972 1 0.1271972 0.5 0.1271972 1 0.1269531 1 0.1269531 0.5 0.1269531 1 0.1267089 1 0.1267089 0.5 0.1267089 1 0.1264648 1 0.1264648 0.5 0.1264648 1 0.1262207 1 0.1262207 0.5 0.1262207 1 0.1259765 1 0.1259765 0.5 0.1259765 1 0.1257324 1 0.1257324 0.5 0.1257324 1 0.1254882 1 0.1254882 0.5 0.1254882 1 0.1252441 1 0.1252441 0.5 0.1252441 1 0.125 1 0.125 0.5 0.125 1 0.1247558 1 0.1247558 0.5 0.1247558 1 0.1245117 1 0.1245117 0.5 0.1245117 1 0.1242675 1 0.1242675 0.5 0.1242675 1 0.1240234 1 0.1240234 0.5 0.1240234 1 0.1237792 1 0.1237792 0.5 0.1237792 1 0.1235351 1 0.1235351 0.5 0.1235351 1 0.123291 1 0.123291 0.5 0.123291 1 0.1230468 1 0.1230468 0.5 0.1230468 1 0.1228027 1 0.1228027 0.5 0.1228027 1 0.1225585 1 0.1225585 0.5 0.1225585 1 0.1223144 1 0.1223144 0.5 0.1223144 1 0.1220703 1 0.1220703 0.5 0.1220703 1 0.1218261 1 0.1218261 0.5 0.1218261 1 0.121582 1 0.121582 0.5 0.121582 1 0.1213378 1 0.1213378 0.5 0.1213378 1 0.1210937 1 0.1210937 0.5 0.1210937 1 0.1208496 1 0.1208496 0.5 0.1208496 1 0.1206054 1 0.1206054 0.5 0.1206054 1 0.1203613 1 0.1203613 0.5 0.1203613 1 0.1201171 1 0.1201171 0.5 0.1201171 1 0.119873 1 0.119873 0.5 0.119873 1 0.1196289 1 0.1196289 0.5 0.1196289 1 0.1193847 1 0.1193847 0.5 0.1193847 1 0.1191406 1 0.1191406 0.5 0.1191406 1 0.1188964 1 0.1188964 0.5 0.1188964 1 0.1186523 1 0.1186523 0.5 0.1186523 1 0.1184082 1 0.1184082 0.5 0.1184082 1 0.118164 1 0.118164 0.5 0.118164 1 0.1179199 1 0.1179199 0.5 0.1179199 1 0.1176757 1 0.1176757 0.5 0.1176757 1 0.1174316 1 0.1174316 0.5 0.1174316 1 0.1171875 1 0.1171875 0.5 0.1171875 1 0.1169433 1 0.1169433 0.5 0.1169433 1 0.1166992 1 0.1166992 0.5 0.1166992 1 0.116455 1 0.116455 0.5 0.116455 1 0.1162109 1 0.1162109 0.5 0.1162109 1 0.1159667 1 0.1159667 0.5 0.1159667 1 0.1157226 1 0.1157226 0.5 0.1157226 1 0.1154785 1 0.1154785 0.5 0.1154785 1 0.1152343 1 0.1152343 0.5 0.1152343 1 0.1149902 1 0.1149902 0.5 0.1149902 1 0.114746 1 0.114746 0.5 0.114746 1 0.1145019 1 0.1145019 0.5 0.1145019 1 0.1142578 1 0.1142578 0.5 0.1142578 1 0.1140136 1 0.1140136 0.5 0.1140136 1 0.1137695 1 0.1137695 0.5 0.1137695 1 0.1135253 1 0.1135253 0.5 0.1135253 1 0.1132812 1 0.1132812 0.5 0.1132812 1 0.1130371 1 0.1130371 0.5 0.1130371 1 0.1127929 1 0.1127929 0.5 0.1127929 1 0.1125488 1 0.1125488 0.5 0.1125488 1 0.1123046 1 0.1123046 0.5 0.1123046 1 0.1120605 1 0.1120605 0.5 0.1120605 1 0.1118164 1 0.1118164 0.5 0.1118164 1 0.1115722 1 0.1115722 0.5 0.1115722 1 0.1113281 1 0.1113281 0.5 0.1113281 1 0.1110839 1 0.1110839 0.5 0.1110839 1 0.1108398 1 0.1108398 0.5 0.1108398 1 0.1105957 1 0.1105957 0.5 0.1105957 1 0.1103515 1 0.1103515 0.5 0.1103515 1 0.1101074 1 0.1101074 0.5 0.1101074 1 0.1098632 1 0.1098632 0.5 0.1098632 1 0.1096191 1 0.1096191 0.5 0.1096191 1 0.109375 1 0.109375 0.5 0.109375 1 0.1091308 1 0.1091308 0.5 0.1091308 1 0.1088867 1 0.1088867 0.5 0.1088867 1 0.1086425 1 0.1086425 0.5 0.1086425 1 0.1083984 1 0.1083984 0.5 0.1083984 1 0.1081542 1 0.1081542 0.5 0.1081542 1 0.1079101 1 0.1079101 0.5 0.1079101 1 0.107666 1 0.107666 0.5 0.107666 1 0.1074218 1 0.1074218 0.5 0.1074218 1 0.1071777 1 0.1071777 0.5 0.1071777 1 0.1069335 1 0.1069335 0.5 0.1069335 1 0.1066894 1 0.1066894 0.5 0.1066894 1 0.1064453 1 0.1064453 0.5 0.1064453 1 0.1062011 1 0.1062011 0.5 0.1062011 1 0.105957 1 0.105957 0.5 0.105957 1 0.1057128 1 0.1057128 0.5 0.1057128 1 0.1054687 1 0.1054687 0.5 0.1054687 1 0.1052246 1 0.1052246 0.5 0.1052246 1 0.1049804 1 0.1049804 0.5 0.1049804 1 0.1047363 1 0.1047363 0.5 0.1047363 1 0.1044921 1 0.1044921 0.5 0.1044921 1 0.104248 1 0.104248 0.5 0.104248 1 0.1040039 1 0.1040039 0.5 0.1040039 1 0.1037597 1 0.1037597 0.5 0.1037597 1 0.1035156 1 0.1035156 0.5 0.1035156 1 0.1032714 1 0.1032714 0.5 0.1032714 1 0.1030273 1 0.1030273 0.5 0.1030273 1 0.1027832 1 0.1027832 0.5 0.1027832 1 0.102539 1 0.102539 0.5 0.102539 1 0.1022949 1 0.1022949 0.5 0.1022949 1 0.1020507 1 0.1020507 0.5 0.1020507 1 0.1018066 1 0.1018066 0.5 0.1018066 1 0.1015625 1 0.1015625 0.5 0.1015625 1 0.1013183 1 0.1013183 0.5 0.1013183 1 0.1010742 1 0.1010742 0.5 0.1010742 1 0.10083 1 0.10083 0.5 0.10083 1 0.1005859 1 0.1005859 0.5 0.1005859 1 0.1003417 1 0.1003417 0.5 0.1003417 1 0.1000976 1 0.1000976 0.5 0.1000976 1 0.09985351 1 0.09985351 0.5 0.09985351 1 0.09960937 1 0.09960937 0.5 0.09960937 1 0.09936523 1 0.09936523 0.5 0.09936523 1 0.09912109 1 0.09912109 0.5 0.09912109 1 0.09887695 1 0.09887695 0.5 0.09887695 1 0.09863281 1 0.09863281 0.5 0.09863281 1 0.09838867 1 0.09838867 0.5 0.09838867 1 0.09814453 1 0.09814453 0.5 0.09814453 1 0.09790039 1 0.09790039 0.5 0.09790039 1 0.09765625 1 0.09765625 0.5 0.09765625 1 0.0974121 1 0.0974121 0.5 0.0974121 1 0.09716796 1 0.09716796 0.5 0.09716796 1 0.09692382 1 0.09692382 0.5 0.09692382 1 0.09667968 1 0.09667968 0.5 0.09667968 1 0.09643554 1 0.09643554 0.5 0.09643554 1 0.0961914 1 0.0961914 0.5 0.0961914 1 0.09594726 1 0.09594726 0.5 0.09594726 1 0.09570312 1 0.09570312 0.5 0.09570312 1 0.09545898 1 0.09545898 0.5 0.09545898 1 0.09521484 1 0.09521484 0.5 0.09521484 1 0.0949707 1 0.0949707 0.5 0.0949707 1 0.09472656 1 0.09472656 0.5 0.09472656 1 0.09448242 1 0.09448242 0.5 0.09448242 1 0.09423828 1 0.09423828 0.5 0.09423828 1 0.09399414 1 0.09399414 0.5 0.09399414 1 0.09375 1 0.09375 0.5 0.09375 1 0.09350585 1 0.09350585 0.5 0.09350585 1 0.09326171 1 0.09326171 0.5 0.09326171 1 0.09301757 1 0.09301757 0.5 0.09301757 1 0.09277343 1 0.09277343 0.5 0.09277343 1 0.09252929 1 0.09252929 0.5 0.09252929 1 0.09228515 1 0.09228515 0.5 0.09228515 1 0.09204101 1 0.09204101 0.5 0.09204101 1 0.09179687 1 0.09179687 0.5 0.09179687 1 0.09155273 1 0.09155273 0.5 0.09155273 1 0.09130859 1 0.09130859 0.5 0.09130859 1 0.09106445 1 0.09106445 0.5 0.09106445 1 0.09082031 1 0.09082031 0.5 0.09082031 1 0.09057617 1 0.09057617 0.5 0.09057617 1 0.09033203 1 0.09033203 0.5 0.09033203 1 0.09008789 1 0.09008789 0.5 0.09008789 1 0.08984375 1 0.08984375 0.5 0.08984375 1 0.0895996 1 0.0895996 0.5 0.0895996 1 0.08935546 1 0.08935546 0.5 0.08935546 1 0.08911132 1 0.08911132 0.5 0.08911132 1 0.08886718 1 0.08886718 0.5 0.08886718 1 0.08862304 1 0.08862304 0.5 0.08862304 1 0.0883789 1 0.0883789 0.5 0.0883789 1 0.08813476 1 0.08813476 0.5 0.08813476 1 0.08789062 1 0.08789062 0.5 0.08789062 1 0.08764648 1 0.08764648 0.5 0.08764648 1 0.08740234 1 0.08740234 0.5 0.08740234 1 0.0871582 1 0.0871582 0.5 0.0871582 1 0.08691406 1 0.08691406 0.5 0.08691406 1 0.08666992 1 0.08666992 0.5 0.08666992 1 0.08642578 1 0.08642578 0.5 0.08642578 1 0.08618164 1 0.08618164 0.5 0.08618164 1 0.0859375 1 0.0859375 0.5 0.0859375 1 0.08569335 1 0.08569335 0.5 0.08569335 1 0.08544921 1 0.08544921 0.5 0.08544921 1 0.08520507 1 0.08520507 0.5 0.08520507 1 0.08496093 1 0.08496093 0.5 0.08496093 1 0.08471679 1 0.08471679 0.5 0.08471679 1 0.08447265 1 0.08447265 0.5 0.08447265 1 0.08422851 1 0.08422851 0.5 0.08422851 1 0.08398437 1 0.08398437 0.5 0.08398437 1 0.08374023 1 0.08374023 0.5 0.08374023 1 0.08349609 1 0.08349609 0.5 0.08349609 1 0.08325195 1 0.08325195 0.5 0.08325195 1 0.08300781 1 0.08300781 0.5 0.08300781 1 0.08276367 1 0.08276367 0.5 0.08276367 1 0.08251953 1 0.08251953 0.5 0.08251953 1 0.08227539 1 0.08227539 0.5 0.08227539 1 0.08203125 1 0.08203125 0.5 0.08203125 1 0.0817871 1 0.0817871 0.5 0.0817871 1 0.08154296 1 0.08154296 0.5 0.08154296 1 0.08129882 1 0.08129882 0.5 0.08129882 1 0.08105468 1 0.08105468 0.5 0.08105468 1 0.08081054 1 0.08081054 0.5 0.08081054 1 0.0805664 1 0.0805664 0.5 0.0805664 1 0.08032226 1 0.08032226 0.5 0.08032226 1 0.08007812 1 0.08007812 0.5 0.08007812 1 0.07983398 1 0.07983398 0.5 0.07983398 1 0.07958984 1 0.07958984 0.5 0.07958984 1 0.0793457 1 0.0793457 0.5 0.0793457 1 0.07910156 1 0.07910156 0.5 0.07910156 1 0.07885742 1 0.07885742 0.5 0.07885742 1 0.07861328 1 0.07861328 0.5 0.07861328 1 0.07836914 1 0.07836914 0.5 0.07836914 1 0.078125 1 0.078125 0.5 0.078125 1 0.07788085 1 0.07788085 0.5 0.07788085 1 0.07763671 1 0.07763671 0.5 0.07763671 1 0.07739257 1 0.07739257 0.5 0.07739257 1 0.07714843 1 0.07714843 0.5 0.07714843 1 0.07690429 1 0.07690429 0.5 0.07690429 1 0.07666015 1 0.07666015 0.5 0.07666015 1 0.07641601 1 0.07641601 0.5 0.07641601 1 0.07617187 1 0.07617187 0.5 0.07617187 1 0.07592773 1 0.07592773 0.5 0.07592773 1 0.07568359 1 0.07568359 0.5 0.07568359 1 0.07543945 1 0.07543945 0.5 0.07543945 1 0.07519531 1 0.07519531 0.5 0.07519531 1 0.07495117 1 0.07495117 0.5 0.07495117 1 0.07470703 1 0.07470703 0.5 0.07470703 1 0.07446289 1 0.07446289 0.5 0.07446289 1 0.07421875 1 0.07421875 0.5 0.07421875 1 0.0739746 1 0.0739746 0.5 0.0739746 1 0.07373046 1 0.07373046 0.5 0.07373046 1 0.07348632 1 0.07348632 0.5 0.07348632 1 0.07324218 1 0.07324218 0.5 0.07324218 1 0.07299804 1 0.07299804 0.5 0.07299804 1 0.0727539 1 0.0727539 0.5 0.0727539 1 0.07250976 1 0.07250976 0.5 0.07250976 1 0.07226562 1 0.07226562 0.5 0.07226562 1 0.07202148 1 0.07202148 0.5 0.07202148 1 0.07177734 1 0.07177734 0.5 0.07177734 1 0.0715332 1 0.0715332 0.5 0.0715332 1 0.07128906 1 0.07128906 0.5 0.07128906 1 0.07104492 1 0.07104492 0.5 0.07104492 1 0.07080078 1 0.07080078 0.5 0.07080078 1 0.07055664 1 0.07055664 0.5 0.07055664 1 0.0703125 1 0.0703125 0.5 0.0703125 1 0.07006835 1 0.07006835 0.5 0.07006835 1 0.06982421 1 0.06982421 0.5 0.06982421 1 0.06958007 1 0.06958007 0.5 0.06958007 1 0.06933593 1 0.06933593 0.5 0.06933593 1 0.06909179 1 0.06909179 0.5 0.06909179 1 0.06884765 1 0.06884765 0.5 0.06884765 1 0.06860351 1 0.06860351 0.5 0.06860351 1 0.06835937 1 0.06835937 0.5 0.06835937 1 0.06811523 1 0.06811523 0.5 0.06811523 1 0.06787109 1 0.06787109 0.5 0.06787109 1 0.06762695 1 0.06762695 0.5 0.06762695 1 0.06738281 1 0.06738281 0.5 0.06738281 1 0.06713867 1 0.06713867 0.5 0.06713867 1 0.06689453 1 0.06689453 0.5 0.06689453 1 0.06665039 1 0.06665039 0.5 0.06665039 1 0.06640625 1 0.06640625 0.5 0.06640625 1 0.0661621 1 0.0661621 0.5 0.0661621 1 0.06591796 1 0.06591796 0.5 0.06591796 1 0.06567382 1 0.06567382 0.5 0.06567382 1 0.06542968 1 0.06542968 0.5 0.06542968 1 0.06518554 1 0.06518554 0.5 0.06518554 1 0.0649414 1 0.0649414 0.5 0.0649414 1 0.06469726 1 0.06469726 0.5 0.06469726 1 0.06445312 1 0.06445312 0.5 0.06445312 1 0.06420898 1 0.06420898 0.5 0.06420898 1 0.06396484 1 0.06396484 0.5 0.06396484 1 0.0637207 1 0.0637207 0.5 0.0637207 1 0.06347656 1 0.06347656 0.5 0.06347656 1 0.06323242 1 0.06323242 0.5 0.06323242 1 0.06298828 1 0.06298828 0.5 0.06298828 1 0.06274414 1 0.06274414 0.5 0.06274414 1 0.0625 1 0.0625 0.5 0.0625 1 0.06225585 1 0.06225585 0.5 0.06225585 1 0.06201171 1 0.06201171 0.5 0.06201171 1 0.06176757 1 0.06176757 0.5 0.06176757 1 0.06152343 1 0.06152343 0.5 0.06152343 1 0.06127929 1 0.06127929 0.5 0.06127929 1 0.06103515 1 0.06103515 0.5 0.06103515 1 0.06079101 1 0.06079101 0.5 0.06079101 1 0.06054687 1 0.06054687 0.5 0.06054687 1 0.06030273 1 0.06030273 0.5 0.06030273 1 0.06005859 1 0.06005859 0.5 0.06005859 1 0.05981445 1 0.05981445 0.5 0.05981445 1 0.05957031 1 0.05957031 0.5 0.05957031 1 0.05932617 1 0.05932617 0.5 0.05932617 1 0.05908203 1 0.05908203 0.5 0.05908203 1 0.05883789 1 0.05883789 0.5 0.05883789 1 0.05859375 1 0.05859375 0.5 0.05859375 1 0.0583496 1 0.0583496 0.5 0.0583496 1 0.05810546 1 0.05810546 0.5 0.05810546 1 0.05786132 1 0.05786132 0.5 0.05786132 1 0.05761718 1 0.05761718 0.5 0.05761718 1 0.05737304 1 0.05737304 0.5 0.05737304 1 0.0571289 1 0.0571289 0.5 0.0571289 1 0.05688476 1 0.05688476 0.5 0.05688476 1 0.05664062 1 0.05664062 0.5 0.05664062 1 0.05639648 1 0.05639648 0.5 0.05639648 1 0.05615234 1 0.05615234 0.5 0.05615234 1 0.0559082 1 0.0559082 0.5 0.0559082 1 0.05566406 1 0.05566406 0.5 0.05566406 1 0.05541992 1 0.05541992 0.5 0.05541992 1 0.05517578 1 0.05517578 0.5 0.05517578 1 0.05493164 1 0.05493164 0.5 0.05493164 1 0.0546875 1 0.0546875 0.5 0.0546875 1 0.05444335 1 0.05444335 0.5 0.05444335 1 0.05419921 1 0.05419921 0.5 0.05419921 1 0.05395507 1 0.05395507 0.5 0.05395507 1 0.05371093 1 0.05371093 0.5 0.05371093 1 0.05346679 1 0.05346679 0.5 0.05346679 1 0.05322265 1 0.05322265 0.5 0.05322265 1 0.05297851 1 0.05297851 0.5 0.05297851 1 0.05273437 1 0.05273437 0.5 0.05273437 1 0.05249023 1 0.05249023 0.5 0.05249023 1 0.05224609 1 0.05224609 0.5 0.05224609 1 0.05200195 1 0.05200195 0.5 0.05200195 1 0.05175781 1 0.05175781 0.5 0.05175781 1 0.05151367 1 0.05151367 0.5 0.05151367 1 0.05126953 1 0.05126953 0.5 0.05126953 1 0.05102539 1 0.05102539 0.5 0.05102539 1 0.05078125 1 0.05078125 0.5 0.05078125 1 0.0505371 1 0.0505371 0.5 0.0505371 1 0.05029296 1 0.05029296 0.5 0.05029296 1 0.05004882 1 0.05004882 0.5 0.05004882 1 0.04980468 1 0.04980468 0.5 0.04980468 1 0.04956054 1 0.04956054 0.5 0.04956054 1 0.0493164 1 0.0493164 0.5 0.0493164 1 0.04907226 1 0.04907226 0.5 0.04907226 1 0.04882812 1 0.04882812 0.5 0.04882812 1 0.04858398 1 0.04858398 0.5 0.04858398 1 0.04833984 1 0.04833984 0.5 0.04833984 1 0.0480957 1 0.0480957 0.5 0.0480957 1 0.04785156 1 0.04785156 0.5 0.04785156 1 0.04760742 1 0.04760742 0.5 0.04760742 1 0.04736328 1 0.04736328 0.5 0.04736328 1 0.04711914 1 0.04711914 0.5 0.04711914 1 0.046875 1 0.046875 0.5 0.046875 1 0.04663085 1 0.04663085 0.5 0.04663085 1 0.04638671 1 0.04638671 0.5 0.04638671 1 0.04614257 1 0.04614257 0.5 0.04614257 1 0.04589843 1 0.04589843 0.5 0.04589843 1 0.04565429 1 0.04565429 0.5 0.04565429 1 0.04541015 1 0.04541015 0.5 0.04541015 1 0.04516601 1 0.04516601 0.5 0.04516601 1 0.04492187 1 0.04492187 0.5 0.04492187 1 0.04467773 1 0.04467773 0.5 0.04467773 1 0.04443359 1 0.04443359 0.5 0.04443359 1 0.04418945 1 0.04418945 0.5 0.04418945 1 0.04394531 1 0.04394531 0.5 0.04394531 1 0.04370117 1 0.04370117 0.5 0.04370117 1 0.04345703 1 0.04345703 0.5 0.04345703 1 0.04321289 1 0.04321289 0.5 0.04321289 1 0.04296875 1 0.04296875 0.5 0.04296875 1 0.0427246 1 0.0427246 0.5 0.0427246 1 0.04248046 1 0.04248046 0.5 0.04248046 1 0.04223632 1 0.04223632 0.5 0.04223632 1 0.04199218 1 0.04199218 0.5 0.04199218 1 0.04174804 1 0.04174804 0.5 0.04174804 1 0.0415039 1 0.0415039 0.5 0.0415039 1 0.04125976 1 0.04125976 0.5 0.04125976 1 0.04101562 1 0.04101562 0.5 0.04101562 1 0.04077148 1 0.04077148 0.5 0.04077148 1 0.04052734 1 0.04052734 0.5 0.04052734 1 0.0402832 1 0.0402832 0.5 0.0402832 1 0.04003906 1 0.04003906 0.5 0.04003906 1 0.03979492 1 0.03979492 0.5 0.03979492 1 0.03955078 1 0.03955078 0.5 0.03955078 1 0.03930664 1 0.03930664 0.5 0.03930664 1 0.0390625 1 0.0390625 0.5 0.0390625 1 0.03881835 1 0.03881835 0.5 0.03881835 1 0.03857421 1 0.03857421 0.5 0.03857421 1 0.03833007 1 0.03833007 0.5 0.03833007 1 0.03808593 1 0.03808593 0.5 0.03808593 1 0.03784179 1 0.03784179 0.5 0.03784179 1 0.03759765 1 0.03759765 0.5 0.03759765 1 0.03735351 1 0.03735351 0.5 0.03735351 1 0.03710937 1 0.03710937 0.5 0.03710937 1 0.03686523 1 0.03686523 0.5 0.03686523 1 0.03662109 1 0.03662109 0.5 0.03662109 1 0.03637695 1 0.03637695 0.5 0.03637695 1 0.03613281 1 0.03613281 0.5 0.03613281 1 0.03588867 1 0.03588867 0.5 0.03588867 1 0.03564453 1 0.03564453 0.5 0.03564453 1 0.03540039 1 0.03540039 0.5 0.03540039 1 0.03515625 1 0.03515625 0.5 0.03515625 1 0.0349121 1 0.0349121 0.5 0.0349121 1 0.03466796 1 0.03466796 0.5 0.03466796 1 0.03442382 1 0.03442382 0.5 0.03442382 1 0.03417968 1 0.03417968 0.5 0.03417968 1 0.03393554 1 0.03393554 0.5 0.03393554 1 0.0336914 1 0.0336914 0.5 0.0336914 1 0.03344726 1 0.03344726 0.5 0.03344726 1 0.03320312 1 0.03320312 0.5 0.03320312 1 0.03295898 1 0.03295898 0.5 0.03295898 1 0.03271484 1 0.03271484 0.5 0.03271484 1 0.0324707 1 0.0324707 0.5 0.0324707 1 0.03222656 1 0.03222656 0.5 0.03222656 1 0.03198242 1 0.03198242 0.5 0.03198242 1 0.03173828 1 0.03173828 0.5 0.03173828 1 0.03149414 1 0.03149414 0.5 0.03149414 1 0.03125 1 0.03125 0.5 0.03125 1 0.03100585 1 0.03100585 0.5 0.03100585 1 0.03076171 1 0.03076171 0.5 0.03076171 1 0.03051757 1 0.03051757 0.5 0.03051757 1 0.03027343 1 0.03027343 0.5 0.03027343 1 0.03002929 1 0.03002929 0.5 0.03002929 1 0.02978515 1 0.02978515 0.5 0.02978515 1 0.02954101 1 0.02954101 0.5 0.02954101 1 0.02929687 1 0.02929687 0.5 0.02929687 1 0.02905273 1 0.02905273 0.5 0.02905273 1 0.02880859 1 0.02880859 0.5 0.02880859 1 0.02856445 1 0.02856445 0.5 0.02856445 1 0.02832031 1 0.02832031 0.5 0.02832031 1 0.02807617 1 0.02807617 0.5 0.02807617 1 0.02783203 1 0.02783203 0.5 0.02783203 1 0.02758789 1 0.02758789 0.5 0.02758789 1 0.02734375 1 0.02734375 0.5 0.02734375 1 0.0270996 1 0.0270996 0.5 0.0270996 1 0.02685546 1 0.02685546 0.5 0.02685546 1 0.02661132 1 0.02661132 0.5 0.02661132 1 0.02636718 1 0.02636718 0.5 0.02636718 1 0.02612304 1 0.02612304 0.5 0.02612304 1 0.0258789 1 0.0258789 0.5 0.0258789 1 0.02563476 1 0.02563476 0.5 0.02563476 1 0.02539062 1 0.02539062 0.5 0.02539062 1 0.02514648 1 0.02514648 0.5 0.02514648 1 0.02490234 1 0.02490234 0.5 0.02490234 1 0.0246582 1 0.0246582 0.5 0.0246582 1 0.02441406 1 0.02441406 0.5 0.02441406 1 0.02416992 1 0.02416992 0.5 0.02416992 1 0.02392578 1 0.02392578 0.5 0.02392578 1 0.02368164 1 0.02368164 0.5 0.02368164 1 0.0234375 1 0.0234375 0.5 0.0234375 1 0.02319335 1 0.02319335 0.5 0.02319335 1 0.02294921 1 0.02294921 0.5 0.02294921 1 0.02270507 1 0.02270507 0.5 0.02270507 1 0.02246093 1 0.02246093 0.5 0.02246093 1 0.02221679 1 0.02221679 0.5 0.02221679 1 0.02197265 1 0.02197265 0.5 0.02197265 1 0.02172851 1 0.02172851 0.5 0.02172851 1 0.02148437 1 0.02148437 0.5 0.02148437 1 0.02124023 1 0.02124023 0.5 0.02124023 1 0.02099609 1 0.02099609 0.5 0.02099609 1 0.02075195 1 0.02075195 0.5 0.02075195 1 0.02050781 1 0.02050781 0.5 0.02050781 1 0.02026367 1 0.02026367 0.5 0.02026367 1 0.02001953 1 0.02001953 0.5 0.02001953 1 0.01977539 1 0.01977539 0.5 0.01977539 1 0.01953125 1 0.01953125 0.5 0.01953125 1 0.0192871 1 0.0192871 0.5 0.0192871 1 0.01904296 1 0.01904296 0.5 0.01904296 1 0.01879882 1 0.01879882 0.5 0.01879882 1 0.01855468 1 0.01855468 0.5 0.01855468 1 0.01831054 1 0.01831054 0.5 0.01831054 1 0.0180664 1 0.0180664 0.5 0.0180664 1 0.01782226 1 0.01782226 0.5 0.01782226 1 0.01757812 1 0.01757812 0.5 0.01757812 1 0.01733398 1 0.01733398 0.5 0.01733398 1 0.01708984 1 0.01708984 0.5 0.01708984 1 0.0168457 1 0.0168457 0.5 0.0168457 1 0.01660156 1 0.01660156 0.5 0.01660156 1 0.01635742 1 0.01635742 0.5 0.01635742 1 0.01611328 1 0.01611328 0.5 0.01611328 1 0.01586914 1 0.01586914 0.5 0.01586914 1 0.015625 1 0.015625 0.5 0.015625 1 0.01538085 1 0.01538085 0.5 0.01538085 1 0.01513671 1 0.01513671 0.5 0.01513671 1 0.01489257 1 0.01489257 0.5 0.01489257 1 0.01464843 1 0.01464843 0.5 0.01464843 1 0.01440429 1 0.01440429 0.5 0.01440429 1 0.01416015 1 0.01416015 0.5 0.01416015 1 0.01391601 1 0.01391601 0.5 0.01391601 1 0.01367187 1 0.01367187 0.5 0.01367187 1 0.01342773 1 0.01342773 0.5 0.01342773 1 0.01318359 1 0.01318359 0.5 0.01318359 1 0.01293945 1 0.01293945 0.5 0.01293945 1 0.01269531 1 0.01269531 0.5 0.01269531 1 0.01245117 1 0.01245117 0.5 0.01245117 1 0.01220703 1 0.01220703 0.5 0.01220703 1 0.01196289 1 0.01196289 0.5 0.01196289 1 0.01171875 1 0.01171875 0.5 0.01171875 1 0.0114746 1 0.0114746 0.5 0.0114746 1 0.01123046 1 0.01123046 0.5 0.01123046 1 0.01098632 1 0.01098632 0.5 0.01098632 1 0.01074218 1 0.01074218 0.5 0.01074218 1 0.01049804 1 0.01049804 0.5 0.01049804 1 0.0102539 1 0.0102539 0.5 0.0102539 1 0.01000976 1 0.01000976 0.5 0.01000976 1 0.009765625 1 0.009765625 0.5 0.009765625 1 0.009521484 1 0.009521484 0.5 0.009521484 1 0.009277343 1 0.009277343 0.5 0.009277343 1 0.009033203 1 0.009033203 0.5 0.009033203 1 0.008789062 1 0.008789062 0.5 0.008789062 1 0.008544921 1 0.008544921 0.5 0.008544921 1 0.008300781 1 0.008300781 0.5 0.008300781 1 0.00805664 1 0.00805664 0.5 0.00805664 1 0.0078125 1 0.0078125 0.5 0.0078125 1 0.007568359 1 0.007568359 0.5 0.007568359 1 0.007324218 1 0.007324218 0.5 0.007324218 1 0.007080078 1 0.007080078 0.5 0.007080078 1 0.006835937 1 0.006835937 0.5 0.006835937 1 0.006591796 1 0.006591796 0.5 0.006591796 1 0.006347656 1 0.006347656 0.5 0.006347656 1 0.006103515 1 0.006103515 0.5 0.006103515 1 0.005859375 1 0.005859375 0.5 0.005859375 1 0.005615234 1 0.005615234 0.5 0.005615234 1 0.005371093 1 0.005371093 0.5 0.005371093 1 0.005126953 1 0.005126953 0.5 0.005126953 1 0.004882812 1 0.004882812 0.5 0.004882812 1 0.004638671 1 0.004638671 0.5 0.004638671 1 0.004394531 1 0.004394531 0.5 0.004394531 1 0.00415039 1 0.00415039 0.5 0.00415039 1 0.00390625 1 0.00390625 0.5 0.00390625 1 0.003662109 1 0.003662109 0.5 0.003662109 1 0.003417968 1 0.003417968 0.5 0.003417968 1 0.003173828 1 0.003173828 0.5 0.003173828 1 0.002929687 1 0.002929687 0.5 0.002929687 1 0.002685546 1 0.002685546 0.5 0.002685546 1 0.002441406 1 0.002441406 0.5 0.002441406 1 0.002197265 1 0.002197265 0.5 0.002197265 1 0.001953125 1 0.001953125 0.5 0.001953125 1 0.001708984 1 0.001708984 0.5 0.001708984 1 0.001464843 1 0.001464843 0.5 0.001464843 1 0.001220703 1 0.001220703 0.5 0.001220703 1 9.76562e-4 1 9.76562e-4 0.5 9.76562e-4 1 7.32422e-4 1 7.32422e-4 0.5 7.32422e-4 1 4.88281e-4 1 4.88281e-4 0.5 0.2507363 0.4899989 0.2503681 0.4899997 0.2492637 0.4899989 0.2503681 0.4899997 0.25 0.49 0.2492637 0.4899989 0.25 0.49 0.2496318 0.4899997 0.2492637 0.4899989 0.2492637 0.4899989 0.2488955 0.4899975 0.2477911 0.4899898 0.2488955 0.4899975 0.2485274 0.4899955 0.2477911 0.4899898 0.2485274 0.4899955 0.2481592 0.4899929 0.2477911 0.4899898 0.2477911 0.4899898 0.2474229 0.4899862 0.2470548 0.489982 0.2470548 0.489982 0.2466867 0.4899771 0.2477911 0.4899898 0.2466867 0.4899771 0.2463186 0.4899718 0.2477911 0.4899898 0.2463186 0.4899718 0.2459505 0.4899659 0.2455824 0.4899594 0.2455824 0.4899594 0.2452143 0.4899523 0.2463186 0.4899718 0.2452143 0.4899523 0.2448462 0.4899446 0.2463186 0.4899718 0.2448462 0.4899446 0.2444781 0.4899365 0.2441101 0.4899277 0.2441101 0.4899277 0.2437421 0.4899184 0.243374 0.4899085 0.243374 0.4899085 0.243006 0.4898981 0.242638 0.4898871 0.242638 0.4898871 0.2422701 0.4898755 0.2419021 0.4898633 0.2419021 0.4898633 0.2415342 0.4898506 0.2411662 0.4898374 0.2411662 0.4898374 0.2407984 0.4898235 0.2404305 0.4898092 0.2404305 0.4898092 0.2400626 0.4897942 0.2389592 0.4897459 0.2400626 0.4897942 0.2396948 0.4897786 0.2389592 0.4897459 0.2396948 0.4897786 0.239327 0.4897626 0.2389592 0.4897459 0.2389592 0.4897459 0.2385914 0.4897287 0.2374883 0.4896737 0.2385914 0.4897287 0.2382237 0.4897109 0.2374883 0.4896737 0.2382237 0.4897109 0.237856 0.4896926 0.2374883 0.4896737 0.2374883 0.4896737 0.2371207 0.4896542 0.2367531 0.4896341 0.2367531 0.4896341 0.2363855 0.4896135 0.236018 0.4895924 0.236018 0.4895924 0.2356505 0.4895706 0.235283 0.4895483 0.235283 0.4895483 0.2349156 0.4895255 0.2345482 0.4895021 0.2345482 0.4895021 0.2341808 0.4894781 0.2330788 0.4894027 0.2341808 0.4894781 0.2338134 0.4894535 0.2330788 0.4894027 0.2338134 0.4894535 0.2334461 0.4894284 0.2330788 0.4894027 0.2330788 0.4894027 0.2327117 0.4893765 0.2323445 0.4893497 0.2323445 0.4893497 0.2319774 0.4893223 0.2316102 0.4892944 0.2316102 0.4892944 0.2312432 0.4892659 0.2301423 0.4891771 0.2312432 0.4892659 0.2308762 0.4892368 0.2301423 0.4891771 0.2308762 0.4892368 0.2305092 0.4892073 0.2301423 0.4891771 0.2301423 0.4891771 0.2297754 0.4891463 0.2286751 0.4890507 0.2297754 0.4891463 0.2294086 0.489115 0.2286751 0.4890507 0.2294086 0.489115 0.2290418 0.4890832 0.2286751 0.4890507 0.2286751 0.4890507 0.2283084 0.4890177 0.2279418 0.4889842 0.2279418 0.4889842 0.2275753 0.4889501 0.2286751 0.4890507 0.2275753 0.4889501 0.2272087 0.4889154 0.2286751 0.4890507 0.2272087 0.4889154 0.2268423 0.4888801 0.2257432 0.488771 0.2268423 0.4888801 0.2264758 0.4888443 0.2257432 0.488771 0.2264758 0.4888443 0.2261095 0.488808 0.2257432 0.488771 0.2257432 0.488771 0.225377 0.4887335 0.2250108 0.4886955 0.2250108 0.4886955 0.2246447 0.4886569 0.2257432 0.488771 0.2246447 0.4886569 0.2242786 0.4886177 0.2257432 0.488771 0.2242786 0.4886177 0.2239126 0.488578 0.2228149 0.4884554 0.2239126 0.488578 0.2235466 0.4885377 0.2228149 0.4884554 0.2235466 0.4885377 0.2231808 0.4884968 0.2228149 0.4884554 0.2228149 0.4884554 0.2224492 0.4884134 0.2220835 0.4883708 0.2220835 0.4883708 0.2217179 0.4883278 0.2213523 0.4882841 0.2213523 0.4882841 0.2209869 0.4882399 0.2198908 0.4881038 0.2209869 0.4882399 0.2206214 0.4881951 0.2198908 0.4881038 0.2206214 0.4881951 0.220256 0.4881498 0.2198908 0.4881038 0.2198908 0.4881038 0.2195256 0.4880574 0.2191604 0.4880104 0.2191604 0.4880104 0.2187954 0.4879627 0.2198908 0.4881038 0.2187954 0.4879627 0.2184303 0.4879146 0.2198908 0.4881038 0.2184303 0.4879146 0.2180655 0.4878659 0.2177006 0.4878166 0.2177006 0.4878166 0.2173358 0.4877668 0.2184303 0.4879146 0.2173358 0.4877668 0.2169712 0.4877164 0.2184303 0.4879146 0.2169712 0.4877164 0.2166065 0.4876655 0.216242 0.487614 0.216242 0.487614 0.2158775 0.4875619 0.2155132 0.4875093 0.2155132 0.4875093 0.2151489 0.4874561 0.2147846 0.4874024 0.2147846 0.4874024 0.2144205 0.487348 0.2155132 0.4875093 0.2144205 0.487348 0.2140565 0.4872932 0.2155132 0.4875093 0.2140565 0.4872932 0.2136925 0.4872378 0.2133287 0.4871818 0.2133287 0.4871818 0.2129648 0.4871253 0.2140565 0.4872932 0.2129648 0.4871253 0.2126011 0.4870682 0.2140565 0.4872932 0.2126011 0.4870682 0.2122375 0.4870105 0.2111473 0.4868342 0.2122375 0.4870105 0.211874 0.4869523 0.2111473 0.4868342 0.211874 0.4869523 0.2115106 0.4868935 0.2111473 0.4868342 0.2111473 0.4868342 0.210784 0.4867744 0.2104208 0.486714 0.2104208 0.486714 0.2100577 0.4866529 0.2111473 0.4868342 0.2100577 0.4866529 0.2096948 0.4865914 0.2111473 0.4868342 0.2096948 0.4865914 0.2093319 0.4865293 0.2082439 0.4863396 0.2093319 0.4865293 0.2089691 0.4864667 0.2082439 0.4863396 0.2089691 0.4864667 0.2086064 0.4864034 0.2082439 0.4863396 0.2082439 0.4863396 0.2078813 0.4862753 0.2075189 0.4862104 0.2075189 0.4862104 0.2071567 0.486145 0.2067945 0.486079 0.2067945 0.486079 0.2064324 0.4860124 0.2053467 0.4858095 0.2064324 0.4860124 0.2060704 0.4859453 0.2053467 0.4858095 0.2060704 0.4859453 0.2057085 0.4858776 0.2053467 0.4858095 0.2053467 0.4858095 0.2049851 0.4857407 0.2039006 0.485531 0.2049851 0.4857407 0.2046235 0.4856714 0.2039006 0.485531 0.2046235 0.4856714 0.204262 0.4856014 0.2039006 0.485531 0.2039006 0.485531 0.2035394 0.48546 0.2031783 0.4853885 0.2031783 0.4853885 0.2028173 0.4853163 0.2024564 0.4852437 0.2024564 0.4852437 0.2020956 0.4851705 0.2010138 0.4849476 0.2020956 0.4851705 0.2017349 0.4850968 0.2010138 0.4849476 0.2017349 0.4850968 0.2013743 0.4850224 0.2010138 0.4849476 0.2010138 0.4849476 0.2006534 0.4848722 0.2002933 0.4847962 0.2002933 0.4847962 0.1999331 0.4847196 0.2010138 0.4849476 0.1999331 0.4847196 0.1995731 0.4846426 0.2010138 0.4849476 0.1995731 0.4846426 0.1992133 0.4845649 0.1981343 0.4843288 0.1992133 0.4845649 0.1988535 0.4844868 0.1981343 0.4843288 0.1988535 0.4844868 0.1984938 0.484408 0.1981343 0.4843288 0.1981343 0.4843288 0.197775 0.4842489 0.1974157 0.4841685 0.1974157 0.4841685 0.1970565 0.4840875 0.1966975 0.4840061 0.1966975 0.4840061 0.1963386 0.483924 0.1959798 0.4838414 0.1959798 0.4838414 0.1956212 0.4837583 0.1966975 0.4840061 0.1956212 0.4837583 0.1952627 0.4836746 0.1966975 0.4840061 0.1952627 0.4836746 0.1949043 0.4835904 0.1938299 0.4833344 0.1949043 0.4835904 0.194546 0.4835056 0.1938299 0.4833344 0.194546 0.4835056 0.1941879 0.4834203 0.1938299 0.4833344 0.1938299 0.4833344 0.193472 0.4832479 0.1923993 0.4829853 0.193472 0.4832479 0.1931143 0.4831609 0.1923993 0.4829853 0.1931143 0.4831609 0.1927567 0.4830734 0.1923993 0.4829853 0.1923993 0.4829853 0.1920419 0.4828967 0.1916847 0.4828075 0.1916847 0.4828075 0.1913277 0.4827178 0.1923993 0.4829853 0.1913277 0.4827178 0.1909708 0.4826275 0.1923993 0.4829853 0.1909708 0.4826275 0.190614 0.4825367 0.1902573 0.4824453 0.1902573 0.4824453 0.1899008 0.4823534 0.1895445 0.4822609 0.1895445 0.4822609 0.1891883 0.4821679 0.1881205 0.4818856 0.1891883 0.4821679 0.1888322 0.4820743 0.1881205 0.4818856 0.1888322 0.4820743 0.1884763 0.4819803 0.1881205 0.4818856 0.1881205 0.4818856 0.1877649 0.4817904 0.1874094 0.4816946 0.1874094 0.4816946 0.187054 0.4815984 0.1881205 0.4818856 0.187054 0.4815984 0.1866989 0.4815015 0.1881205 0.4818856 0.1866989 0.4815015 0.1863438 0.4814042 0.1859889 0.4813063 0.1859889 0.4813063 0.1856341 0.4812078 0.1852796 0.4811088 0.1852796 0.4811088 0.1849251 0.4810093 0.1845709 0.4809091 0.1845709 0.4809091 0.1842167 0.4808085 0.1852796 0.4811088 0.1842167 0.4808085 0.1838628 0.4807073 0.1852796 0.4811088 0.1838628 0.4807073 0.1835089 0.4806056 0.1831552 0.4805033 0.1831552 0.4805033 0.1828017 0.4804005 0.1838628 0.4807073 0.1828017 0.4804005 0.1824484 0.4802972 0.1838628 0.4807073 0.1824484 0.4802972 0.1820952 0.4801933 0.1817421 0.4800888 0.1817421 0.4800888 0.1813893 0.4799839 0.1810365 0.4798783 0.1810365 0.4798783 0.180684 0.4797723 0.1803317 0.4796657 0.1803317 0.4796657 0.1799794 0.4795585 0.1810365 0.4798783 0.1799794 0.4795585 0.1796274 0.4794509 0.1810365 0.4798783 0.1796274 0.4794509 0.1792755 0.4793426 0.1782208 0.4790148 0.1792755 0.4793426 0.1789237 0.4792339 0.1782208 0.4790148 0.1789237 0.4792339 0.1785722 0.4791246 0.1782208 0.4790148 0.1782208 0.4790148 0.1778696 0.4789044 0.1775186 0.4787935 0.1775186 0.4787935 0.1771677 0.478682 0.1768169 0.47857 0.1768169 0.47857 0.1764664 0.4784575 0.1761161 0.4783444 0.1761161 0.4783444 0.1757659 0.4782308 0.1768169 0.47857 0.1757659 0.4782308 0.1754159 0.4781166 0.1768169 0.47857 0.1754159 0.4781166 0.175066 0.478002 0.1747164 0.4778867 0.1747164 0.4778867 0.1743668 0.477771 0.1740176 0.4776547 0.1740176 0.4776547 0.1736685 0.4775379 0.1726222 0.4771842 0.1736685 0.4775379 0.1733195 0.4774205 0.1726222 0.4771842 0.1733195 0.4774205 0.1729707 0.4773026 0.1726222 0.4771842 0.1726222 0.4771842 0.1722737 0.4770653 0.1719255 0.4769458 0.1719255 0.4769458 0.1715775 0.4768257 0.1726222 0.4771842 0.1715775 0.4768257 0.1712296 0.4767051 0.1726222 0.4771842 0.1712296 0.4767051 0.1708819 0.4765841 0.1705344 0.4764624 0.1705344 0.4764624 0.1701872 0.4763402 0.1712296 0.4767051 0.1701872 0.4763402 0.16984 0.4762176 0.1712296 0.4767051 0.16984 0.4762176 0.1694931 0.4760943 0.1691464 0.4759706 0.1691464 0.4759706 0.1687999 0.4758463 0.16984 0.4762176 0.1687999 0.4758463 0.1684535 0.4757214 0.16984 0.4762176 0.1684535 0.4757214 0.1681073 0.4755961 0.1677614 0.4754702 0.1677614 0.4754702 0.1674156 0.4753438 0.1684535 0.4757214 0.1674156 0.4753438 0.16707 0.4752169 0.1684535 0.4757214 0.16707 0.4752169 0.1667247 0.4750894 0.1656897 0.4747037 0.1667247 0.4750894 0.1663795 0.4749614 0.1656897 0.4747037 0.1663795 0.4749614 0.1660345 0.4748328 0.1656897 0.4747037 0.1656897 0.4747037 0.1653451 0.4745742 0.1650007 0.474444 0.1650007 0.474444 0.1646565 0.4743134 0.1656897 0.4747037 0.1646565 0.4743134 0.1643126 0.4741822 0.1656897 0.4747037 0.1643126 0.4741822 0.1639688 0.4740505 0.1636251 0.4739183 0.1636251 0.4739183 0.1632818 0.4737855 0.1643126 0.4741822 0.1632818 0.4737855 0.1629386 0.4736523 0.1643126 0.4741822 0.1629386 0.4736523 0.1625956 0.4735184 0.1622529 0.4733841 0.1622529 0.4733841 0.1619103 0.4732492 0.1615679 0.4731138 0.1615679 0.4731138 0.1612258 0.4729779 0.1608839 0.4728415 0.1608839 0.4728415 0.1605421 0.4727045 0.1615679 0.4731138 0.1605421 0.4727045 0.1602006 0.472567 0.1615679 0.4731138 0.1602006 0.472567 0.1598593 0.472429 0.1595182 0.4722905 0.1595182 0.4722905 0.1591773 0.4721514 0.1602006 0.472567 0.1591773 0.4721514 0.1588367 0.4720118 0.1602006 0.472567 0.1588367 0.4720118 0.1584962 0.4718717 0.1581559 0.4717311 0.1581559 0.4717311 0.1578159 0.4715899 0.1574761 0.4714483 0.1574761 0.4714483 0.1571365 0.4713061 0.1567972 0.4711633 0.1567972 0.4711633 0.156458 0.4710201 0.1574761 0.4714483 0.156458 0.4710201 0.1561191 0.4708764 0.1574761 0.4714483 0.1561191 0.4708764 0.1557804 0.4707321 0.1547656 0.4702962 0.1557804 0.4707321 0.1554419 0.4705873 0.1547656 0.4702962 0.1554419 0.4705873 0.1551036 0.470442 0.1547656 0.4702962 0.1547656 0.4702962 0.1544278 0.4701498 0.1534156 0.4697077 0.1544278 0.4701498 0.1540902 0.470003 0.1534156 0.4697077 0.1540902 0.470003 0.1537528 0.4698556 0.1534156 0.4697077 0.1534156 0.4697077 0.1530787 0.4695593 0.152742 0.4694103 0.152742 0.4694103 0.1524056 0.4692609 0.1520694 0.4691109 0.1520694 0.4691109 0.1517333 0.4689604 0.1507267 0.4685059 0.1517333 0.4689604 0.1513976 0.4688094 0.1507267 0.4685059 0.1513976 0.4688094 0.1510621 0.4686579 0.1507267 0.4685059 0.1507267 0.4685059 0.1503917 0.4683533 0.1500568 0.4682003 0.1500568 0.4682003 0.1497223 0.4680467 0.1507267 0.4685059 0.1497223 0.4680467 0.1493879 0.4678927 0.1507267 0.4685059 0.1493879 0.4678927 0.1490538 0.4677381 0.1487199 0.467583 0.1487199 0.467583 0.1483862 0.4674273 0.1493879 0.4678927 0.1483862 0.4674273 0.1480528 0.4672712 0.1493879 0.4678927 0.1480528 0.4672712 0.1477197 0.4671146 0.1467216 0.4666416 0.1477197 0.4671146 0.1473867 0.4669575 0.1467216 0.4666416 0.1473867 0.4669575 0.1470541 0.4667997 0.1467216 0.4666416 0.1467216 0.4666416 0.1463894 0.4664829 0.1453943 0.4660038 0.1463894 0.4664829 0.1460574 0.4663237 0.1453943 0.4660038 0.1460574 0.4663237 0.1457257 0.466164 0.1453943 0.4660038 0.1453943 0.4660038 0.1450631 0.4658431 0.1440709 0.4653579 0.1450631 0.4658431 0.1447321 0.4656819 0.1440709 0.4653579 0.1447321 0.4656819 0.1444013 0.4655202 0.1440709 0.4653579 0.1440709 0.4653579 0.1437407 0.4651951 0.1427515 0.4647039 0.1437407 0.4651951 0.1434106 0.4650319 0.1427515 0.4647039 0.1434106 0.4650319 0.1430809 0.4648681 0.1427515 0.4647039 0.1427515 0.4647039 0.1424222 0.4645391 0.1420933 0.4643738 0.1420933 0.4643738 0.1417645 0.4642081 0.1427515 0.4647039 0.1417645 0.4642081 0.1414361 0.4640418 0.1427515 0.4647039 0.1414361 0.4640418 0.1411079 0.463875 0.1407799 0.4637077 0.1407799 0.4637077 0.1404522 0.4635399 0.1414361 0.4640418 0.1404522 0.4635399 0.1401247 0.4633716 0.1414361 0.4640418 0.1401247 0.4633716 0.1397976 0.4632028 0.1388176 0.4626934 0.1397976 0.4632028 0.1394707 0.4630335 0.1388176 0.4626934 0.1394707 0.4630335 0.139144 0.4628637 0.1388176 0.4626934 0.1388176 0.4626934 0.1384915 0.4625226 0.1375147 0.4620072 0.1384915 0.4625226 0.1381656 0.4623513 0.1375147 0.4620072 0.1381656 0.4623513 0.13784 0.4621795 0.1375147 0.4620072 0.1375147 0.4620072 0.1371896 0.4618344 0.1368647 0.4616611 0.1368647 0.4616611 0.1365402 0.4614873 0.1362159 0.461313 0.1362159 0.461313 0.1358919 0.4611382 0.1349215 0.4606109 0.1358919 0.4611382 0.1355682 0.460963 0.1349215 0.4606109 0.1355682 0.460963 0.1352447 0.4607871 0.1349215 0.4606109 0.1349215 0.4606109 0.1345986 0.4604341 0.1342759 0.4602568 0.1342759 0.4602568 0.1339535 0.460079 0.1349215 0.4606109 0.1339535 0.460079 0.1336314 0.4599008 0.1349215 0.4606109 0.1336314 0.4599008 0.1333095 0.4597221 0.1329879 0.4595428 0.1329879 0.4595428 0.1326667 0.4593631 0.1336314 0.4599008 0.1326667 0.4593631 0.1323456 0.4591828 0.1336314 0.4599008 0.1323456 0.4591828 0.1320249 0.4590021 0.1310643 0.4584569 0.1320249 0.4590021 0.1317044 0.4588209 0.1310643 0.4584569 0.1317044 0.4588209 0.1313842 0.4586392 0.1310643 0.4584569 0.1310643 0.4584569 0.1307446 0.4582743 0.1304253 0.4580911 0.1304253 0.4580911 0.1301063 0.4579074 0.1297875 0.4577233 0.1297875 0.4577233 0.129469 0.4575386 0.1291508 0.4573535 0.1291508 0.4573535 0.1288328 0.4571679 0.1285152 0.4569817 0.1285152 0.4569817 0.1281978 0.4567952 0.1278807 0.4566081 0.1278807 0.4566081 0.127564 0.4564205 0.1272475 0.4562324 0.1272475 0.4562324 0.1269312 0.4560439 0.1266153 0.4558548 0.1266153 0.4558548 0.1262997 0.4556654 0.1272475 0.4562324 0.1262997 0.4556654 0.1259843 0.4554753 0.1272475 0.4562324 0.1259843 0.4554753 0.1256693 0.4552849 0.1247259 0.4547106 0.1256693 0.4552849 0.1253545 0.4550939 0.1247259 0.4547106 0.1253545 0.4550939 0.1250401 0.4549025 0.1247259 0.4547106 0.1247259 0.4547106 0.124412 0.4545181 0.1240984 0.4543253 0.1240984 0.4543253 0.1237851 0.4541319 0.1247259 0.4547106 0.1237851 0.4541319 0.1234722 0.453938 0.1247259 0.4547106 0.1234722 0.453938 0.1231595 0.4537437 0.1228471 0.4535489 0.1228471 0.4535489 0.122535 0.4533536 0.1222232 0.4531578 0.1222232 0.4531578 0.1219117 0.4529616 0.1216006 0.4527649 0.1216006 0.4527649 0.1212897 0.4525676 0.1222232 0.4531578 0.1212897 0.4525676 0.1209791 0.45237 0.1222232 0.4531578 0.1209791 0.45237 0.1206688 0.4521718 0.1203588 0.4519732 0.1203588 0.4519732 0.1200491 0.4517741 0.1209791 0.45237 0.1200491 0.4517741 0.1197398 0.4515745 0.1209791 0.45237 0.1197398 0.4515745 0.1194307 0.4513745 0.119122 0.4511739 0.119122 0.4511739 0.1188135 0.4509729 0.1185054 0.4507715 0.1185054 0.4507715 0.1181976 0.4505695 0.1178901 0.4503671 0.1178901 0.4503671 0.1175829 0.4501642 0.117276 0.4499608 0.117276 0.4499608 0.1169694 0.449757 0.1160515 0.4491427 0.1169694 0.449757 0.1166631 0.4495527 0.1160515 0.4491427 0.1166631 0.4495527 0.1163572 0.4493479 0.1160515 0.4491427 0.1160515 0.4491427 0.1157462 0.448937 0.1154412 0.4487308 0.1154412 0.4487308 0.1151365 0.4485242 0.1148321 0.4483171 0.1148321 0.4483171 0.1145281 0.4481095 0.1136178 0.447484 0.1145281 0.4481095 0.1142243 0.4479014 0.1136178 0.447484 0.1142243 0.4479014 0.1139209 0.4476929 0.1136178 0.447484 0.1136178 0.447484 0.1133151 0.4472745 0.1130126 0.4470646 0.1130126 0.4470646 0.1127105 0.4468542 0.1136178 0.447484 0.1127105 0.4468542 0.1124086 0.4466434 0.1136178 0.447484 0.1124086 0.4466434 0.1121072 0.4464321 0.111806 0.4462203 0.111806 0.4462203 0.1115052 0.4460082 0.1112046 0.4457954 0.1112046 0.4457954 0.1109045 0.4455823 0.1106046 0.4453687 0.1106046 0.4453687 0.1103051 0.4451547 0.1112046 0.4457954 0.1103051 0.4451547 0.1100059 0.4449402 0.1112046 0.4457954 0.1100059 0.4449402 0.109707 0.4447252 0.1088124 0.4440775 0.109707 0.4447252 0.1094085 0.4445097 0.1088124 0.4440775 0.1094085 0.4445097 0.1091103 0.4442939 0.1088124 0.4440775 0.1088124 0.4440775 0.1085149 0.4438607 0.1082177 0.4436434 0.1082177 0.4436434 0.1079208 0.4434257 0.1076242 0.4432075 0.1076242 0.4432075 0.107328 0.4429889 0.1070321 0.4427698 0.1070321 0.4427698 0.1067366 0.4425503 0.1064414 0.4423303 0.1064414 0.4423303 0.1061465 0.4421098 0.105264 0.4414458 0.1061465 0.4421098 0.105852 0.4418889 0.105264 0.4414458 0.105852 0.4418889 0.1055578 0.4416676 0.105264 0.4414458 0.105264 0.4414458 0.1049705 0.4412236 0.104092 0.4405541 0.1049705 0.4412236 0.1046773 0.4410009 0.104092 0.4405541 0.1046773 0.4410009 0.1043845 0.4407777 0.104092 0.4405541 0.104092 0.4405541 0.1037999 0.44033 0.1035081 0.4401056 0.1035081 0.4401056 0.1032167 0.4398806 0.1029255 0.4396553 0.1029255 0.4396553 0.1026348 0.4394294 0.1023444 0.4392032 0.1023444 0.4392032 0.1020543 0.4389764 0.1029255 0.4396553 0.1020543 0.4389764 0.1017646 0.4387493 0.1029255 0.4396553 0.1017646 0.4387493 0.1014752 0.4385216 0.1006093 0.4378361 0.1014752 0.4385216 0.1011862 0.4382936 0.1006093 0.4378361 0.1011862 0.4382936 0.1008976 0.4380651 0.1006093 0.4378361 0.1006093 0.4378361 0.1003213 0.4376068 0.1000337 0.4373769 0.1000337 0.4373769 0.09974646 0.4371467 0.1006093 0.4378361 0.09974646 0.4371467 0.09945952 0.4369159 0.1006093 0.4378361 0.09945952 0.4369159 0.099173 0.4366848 0.09888678 0.4364532 0.09888678 0.4364532 0.09860098 0.4362212 0.09831547 0.4359887 0.09831547 0.4359887 0.09803032 0.4357559 0.09717714 0.4350546 0.09803032 0.4357559 0.09774559 0.4355225 0.09717714 0.4350546 0.09774559 0.4355225 0.09746116 0.4352887 0.09717714 0.4350546 0.09717714 0.4350546 0.09689342 0.4348199 0.09661012 0.4345848 0.09661012 0.4345848 0.09632712 0.4343493 0.09717714 0.4350546 0.09632712 0.4343493 0.09604454 0.4341133 0.09717714 0.4350546 0.09604454 0.4341133 0.09576231 0.4338769 0.09548038 0.4336401 0.09548038 0.4336401 0.09519886 0.4334029 0.09491771 0.4331652 0.09491771 0.4331652 0.09463691 0.4329271 0.09435653 0.4326885 0.09435653 0.4326885 0.09407645 0.4324496 0.09491771 0.4331652 0.09407645 0.4324496 0.09379678 0.4322102 0.09491771 0.4331652 0.09379678 0.4322102 0.09351742 0.4319704 0.09323847 0.4317301 0.09323847 0.4317301 0.09295994 0.4314894 0.09379678 0.4322102 0.09295994 0.4314894 0.0926817 0.4312483 0.09379678 0.4322102 0.0926817 0.4312483 0.09240382 0.4310068 0.09212636 0.4307649 0.09212636 0.4307649 0.09184926 0.4305225 0.0926817 0.4312483 0.09184926 0.4305225 0.09157252 0.4302796 0.0926817 0.4312483 0.09157252 0.4302796 0.09129619 0.4300364 0.09102016 0.4297927 0.09102016 0.4297927 0.09074455 0.4295486 0.09157252 0.4302796 0.09074455 0.4295486 0.09046936 0.4293041 0.09157252 0.4302796 0.09046936 0.4293041 0.09019446 0.4290592 0.08991998 0.4288139 0.08991998 0.4288139 0.08964586 0.4285681 0.08937215 0.4283219 0.08937215 0.4283219 0.08909881 0.4280753 0.08828103 0.4273329 0.08909881 0.4280753 0.08882582 0.4278283 0.08828103 0.4273329 0.08882582 0.4278283 0.08855324 0.4275808 0.08828103 0.4273329 0.08828103 0.4273329 0.08800917 0.4270847 0.08773773 0.426836 0.08773773 0.426836 0.08746665 0.4265869 0.08828103 0.4273329 0.08746665 0.4265869 0.08719593 0.4263373 0.08828103 0.4273329 0.08719593 0.4263373 0.08692568 0.4260874 0.08611702 0.4253351 0.08692568 0.4260874 0.08665573 0.425837 0.08611702 0.4253351 0.08665573 0.425837 0.0863862 0.4255862 0.08611702 0.4253351 0.08611702 0.4253351 0.08584827 0.4250835 0.08557987 0.4248315 0.08557987 0.4248315 0.08531188 0.424579 0.08504432 0.4243262 0.08504432 0.4243262 0.08477705 0.4240729 0.08451026 0.4238193 0.08451026 0.4238193 0.08424383 0.4235652 0.08504432 0.4243262 0.08424383 0.4235652 0.08397775 0.4233108 0.08504432 0.4243262 0.08397775 0.4233108 0.0837121 0.4230559 0.08344686 0.4228006 0.08344686 0.4228006 0.08318191 0.4225449 0.08291745 0.4222888 0.08291745 0.4222888 0.08265334 0.4220323 0.08238965 0.4217754 0.08238965 0.4217754 0.08212637 0.4215181 0.08186346 0.4212604 0.08186346 0.4212604 0.08160096 0.4210023 0.08133882 0.4207437 0.08133882 0.4207437 0.08107709 0.4204848 0.08186346 0.4212604 0.08107709 0.4204848 0.08081579 0.4202255 0.08186346 0.4212604 0.08081579 0.4202255 0.0805549 0.4199658 0.08029437 0.4197056 0.08029437 0.4197056 0.08003425 0.4194451 0.08081579 0.4202255 0.08003425 0.4194451 0.07977449 0.4191842 0.08081579 0.4202255 0.07977449 0.4191842 0.07951515 0.4189229 0.07925623 0.4186611 0.07925623 0.4186611 0.07899773 0.418399 0.07977449 0.4191842 0.07899773 0.418399 0.07873958 0.4181365 0.07977449 0.4191842 0.07873958 0.4181365 0.07848191 0.4178736 0.07822459 0.4176103 0.07822459 0.4176103 0.0779677 0.4173466 0.07873958 0.4181365 0.0779677 0.4173466 0.07771116 0.4170825 0.07873958 0.4181365 0.07771116 0.4170825 0.0774551 0.416818 0.07719939 0.4165531 0.07719939 0.4165531 0.07694411 0.4162879 0.07668924 0.4160223 0.07668924 0.4160223 0.07643473 0.4157562 0.07567381 0.4149557 0.07643473 0.4157562 0.07618069 0.4154897 0.07567381 0.4149557 0.07618069 0.4154897 0.07592701 0.4152229 0.07567381 0.4149557 0.07567381 0.4149557 0.07542097 0.4146881 0.07516855 0.4144201 0.07516855 0.4144201 0.07491654 0.4141517 0.07466495 0.4138829 0.07466495 0.4138829 0.07441371 0.4136138 0.07416296 0.4133442 0.07416296 0.4133442 0.07391262 0.4130743 0.07466495 0.4138829 0.07391262 0.4130743 0.07366263 0.412804 0.07466495 0.4138829 0.07366263 0.412804 0.07341313 0.4125334 0.072667 0.411719 0.07341313 0.4125334 0.07316398 0.4122623 0.072667 0.411719 0.07316398 0.4122623 0.07291531 0.4119908 0.072667 0.411719 0.072667 0.411719 0.07241916 0.4114468 0.07217168 0.4111741 0.07217168 0.4111741 0.07192468 0.4109011 0.072667 0.411719 0.07192468 0.4109011 0.07167804 0.4106279 0.072667 0.411719 0.07167804 0.4106279 0.07143187 0.4103541 0.07118612 0.41008 0.07118612 0.41008 0.07094079 0.4098055 0.07069581 0.4095306 0.07069581 0.4095306 0.07045131 0.4092554 0.06972038 0.4084274 0.07045131 0.4092554 0.07020723 0.4089798 0.06972038 0.4084274 0.07020723 0.4089798 0.06996357 0.4087038 0.06972038 0.4084274 0.06972038 0.4084274 0.06947755 0.4081507 0.06923514 0.4078736 0.06923514 0.4078736 0.06899321 0.4075961 0.06972038 0.4084274 0.06899321 0.4075961 0.06875163 0.4073183 0.06972038 0.4084274 0.06875163 0.4073183 0.06851053 0.4070401 0.06778979 0.4062032 0.06851053 0.4070401 0.06826984 0.4067615 0.06778979 0.4062032 0.06826984 0.4067615 0.06802958 0.4064825 0.06778979 0.4062032 0.06778979 0.4062032 0.06755036 0.4059235 0.06683474 0.4050822 0.06755036 0.4059235 0.0673114 0.4056435 0.06683474 0.4050822 0.0673114 0.4056435 0.06707286 0.405363 0.06683474 0.4050822 0.06683474 0.4050822 0.0665971 0.4048011 0.06635981 0.4045196 0.06635981 0.4045196 0.066123 0.4042377 0.06588661 0.4039555 0.06588661 0.4039555 0.0656507 0.4036728 0.06494545 0.4028229 0.0656507 0.4036728 0.0654152 0.4033899 0.06494545 0.4028229 0.0654152 0.4033899 0.06518012 0.4031065 0.06494545 0.4028229 0.06494545 0.4028229 0.06471127 0.4025388 0.0644775 0.4022544 0.0644775 0.4022544 0.06424415 0.4019696 0.06494545 0.4028229 0.06424415 0.4019696 0.06401121 0.4016845 0.06494545 0.4028229 0.06401121 0.4016845 0.06377875 0.401399 0.06354677 0.4011132 0.06354677 0.4011132 0.06331515 0.400827 0.063084 0.4005404 0.063084 0.4005404 0.06285333 0.4002535 0.06216382 0.3993907 0.06285333 0.4002535 0.06262302 0.3999663 0.06216382 0.3993907 0.06262302 0.3999663 0.06239324 0.3996787 0.06216382 0.3993907 0.06216382 0.3993907 0.06193488 0.3991024 0.06170636 0.3988137 0.06170636 0.3988137 0.06147837 0.3985247 0.06216382 0.3993907 0.06147837 0.3985247 0.06125074 0.3982354 0.06216382 0.3993907 0.06125074 0.3982354 0.06102359 0.3979457 0.06034475 0.3970744 0.06102359 0.3979457 0.06079685 0.3976556 0.06034475 0.3970744 0.06079685 0.3976556 0.06057053 0.3973652 0.06034475 0.3970744 0.06034475 0.3970744 0.06011933 0.3967833 0.05989438 0.3964919 0.05989438 0.3964919 0.05966991 0.3962001 0.05944585 0.3959079 0.05944585 0.3959079 0.05922228 0.3956155 0.05899912 0.3953226 0.05899912 0.3953226 0.05877643 0.3950295 0.05944585 0.3959079 0.05877643 0.3950295 0.05855417 0.394736 0.05944585 0.3959079 0.05855417 0.394736 0.05833238 0.3944422 0.05811107 0.3941479 0.05811107 0.3941479 0.05789011 0.3938534 0.05855417 0.394736 0.05789011 0.3938534 0.05766969 0.3935586 0.05855417 0.394736 0.05766969 0.3935586 0.05744969 0.3932633 0.05723017 0.3929678 0.05723017 0.3929678 0.05701106 0.392672 0.05679249 0.3923758 0.05679249 0.3923758 0.05657428 0.3920792 0.05635654 0.3917824 0.05635654 0.3917824 0.05613929 0.3914851 0.0559225 0.3911876 0.0559225 0.3911876 0.05570614 0.3908897 0.05549025 0.3905915 0.05549025 0.3905915 0.05527484 0.390293 0.0559225 0.3911876 0.05527484 0.390293 0.05505985 0.3899941 0.0559225 0.3911876 0.05505985 0.3899941 0.05484533 0.3896949 0.05420452 0.3887953 0.05484533 0.3896949 0.05463129 0.3893954 0.05420452 0.3887953 0.05463129 0.3893954 0.05441766 0.3890955 0.05420452 0.3887953 0.05420452 0.3887953 0.05399185 0.3884948 0.0537796 0.388194 0.0537796 0.388194 0.05356788 0.3878928 0.05335658 0.3875913 0.05335658 0.3875913 0.05314576 0.3872895 0.05251604 0.3863822 0.05314576 0.3872895 0.05293536 0.3869874 0.05251604 0.3863822 0.05293536 0.3869874 0.05272549 0.3866849 0.05251604 0.3863822 0.05251604 0.3863822 0.05230706 0.3860791 0.05209857 0.3857756 0.05209857 0.3857756 0.05189049 0.3854719 0.05251604 0.3863822 0.05189049 0.3854719 0.05168294 0.3851678 0.05251604 0.3863822 0.05168294 0.3851678 0.05147582 0.3848634 0.05126917 0.3845588 0.05126917 0.3845588 0.051063 0.3842537 0.0508573 0.3839485 0.0508573 0.3839485 0.05065202 0.3836428 0.05044728 0.3833369 0.05044728 0.3833369 0.05024296 0.3830306 0.0508573 0.3839485 0.05024296 0.3830306 0.05003911 0.382724 0.0508573 0.3839485 0.05003911 0.382724 0.0498358 0.3824171 0.0496329 0.3821099 0.0496329 0.3821099 0.04943048 0.3818024 0.04922854 0.3814946 0.04922854 0.3814946 0.04902702 0.3811864 0.04882603 0.380878 0.04882603 0.380878 0.04862552 0.3805692 0.04842549 0.3802602 0.04842549 0.3802602 0.04822587 0.3799508 0.04763001 0.3790209 0.04822587 0.3799508 0.0480268 0.3796412 0.04763001 0.3790209 0.0480268 0.3796412 0.04782813 0.3793312 0.04763001 0.3790209 0.04763001 0.3790209 0.04743236 0.3787103 0.04684215 0.3777768 0.04743236 0.3787103 0.04723513 0.3783994 0.04684215 0.3777768 0.04723513 0.3783994 0.04703837 0.3780882 0.04684215 0.3777768 0.04684215 0.3777768 0.04664641 0.377465 0.04645109 0.3771529 0.04645109 0.3771529 0.0462563 0.3768405 0.04606193 0.3765278 0.04606193 0.3765278 0.04586809 0.3762148 0.04528945 0.3752741 0.04586809 0.3762148 0.04567474 0.3759015 0.04528945 0.3752741 0.04567474 0.3759015 0.04548186 0.3755879 0.04528945 0.3752741 0.04528945 0.3752741 0.04509752 0.3749599 0.04490607 0.3746454 0.04490607 0.3746454 0.0447151 0.3743306 0.04528945 0.3752741 0.0447151 0.3743306 0.04452461 0.3740156 0.04528945 0.3752741 0.04452461 0.3740156 0.04433465 0.3737003 0.04376757 0.3727526 0.04433465 0.3737003 0.0441451 0.3733847 0.04376757 0.3727526 0.0441451 0.3733847 0.0439561 0.3730688 0.04376757 0.3727526 0.04376757 0.3727526 0.04357951 0.3724361 0.04339194 0.3721193 0.04339194 0.3721193 0.04320484 0.3718022 0.04301822 0.3714848 0.04301822 0.3714848 0.04283213 0.3711671 0.04264652 0.3708492 0.04264652 0.3708492 0.04246133 0.370531 0.04227674 0.3702125 0.04227674 0.3702125 0.04209256 0.3698937 0.04190886 0.3695746 0.04190886 0.3695746 0.04172569 0.3692553 0.041543 0.3689357 0.041543 0.3689357 0.04136079 0.3686158 0.04117912 0.3682956 0.04117912 0.3682956 0.04099792 0.3679751 0.041543 0.3689357 0.04099792 0.3679751 0.04081714 0.3676543 0.041543 0.3689357 0.04081714 0.3676543 0.04063695 0.3673334 0.0400992 0.3663686 0.04063695 0.3673334 0.04045718 0.367012 0.0400992 0.3663686 0.04045718 0.367012 0.04027795 0.3666905 0.0400992 0.3663686 0.0400992 0.3663686 0.03992092 0.3660465 0.03974318 0.3657241 0.03974318 0.3657241 0.03956592 0.3654015 0.03938913 0.3650785 0.03938913 0.3650785 0.03921282 0.3647553 0.03903704 0.3644318 0.03903704 0.3644318 0.03886175 0.364108 0.03938913 0.3650785 0.03886175 0.364108 0.03868699 0.363784 0.03938913 0.3650785 0.03868699 0.363784 0.0385127 0.3634598 0.03833889 0.3631352 0.03833889 0.3631352 0.03816556 0.3628104 0.03799277 0.3624853 0.03799277 0.3624853 0.03782045 0.36216 0.03764867 0.3618344 0.03764867 0.3618344 0.03747737 0.3615085 0.03799277 0.3624853 0.03747737 0.3615085 0.03730654 0.3611823 0.03799277 0.3624853 0.03730654 0.3611823 0.03713625 0.3608559 0.03696644 0.3605293 0.03696644 0.3605293 0.03679716 0.3602024 0.03730654 0.3611823 0.03679716 0.3602024 0.03662836 0.3598752 0.03730654 0.3611823 0.03662836 0.3598752 0.0364601 0.3595477 0.03595823 0.3585639 0.0364601 0.3595477 0.03629225 0.35922 0.03595823 0.3585639 0.03629225 0.35922 0.036125 0.3588921 0.03595823 0.3585639 0.03595823 0.3585639 0.03579193 0.3582354 0.03529608 0.3572485 0.03579193 0.3582354 0.03562617 0.3579067 0.03529608 0.3572485 0.03562617 0.3579067 0.03546088 0.3575778 0.03529608 0.3572485 0.03529608 0.3572485 0.03513181 0.3569191 0.03496807 0.3565893 0.03496807 0.3565893 0.03480482 0.3562594 0.03529608 0.3572485 0.03480482 0.3562594 0.0346421 0.3559291 0.03529608 0.3572485 0.0346421 0.3559291 0.03447985 0.3555986 0.03431808 0.3552679 0.03431808 0.3552679 0.03415685 0.3549369 0.0346421 0.3559291 0.03415685 0.3549369 0.03399616 0.3546057 0.0346421 0.3559291 0.03399616 0.3546057 0.03383594 0.3542742 0.03367626 0.3539425 0.03367626 0.3539425 0.03351706 0.3536105 0.03399616 0.3546057 0.03351706 0.3536105 0.03335839 0.3532783 0.03399616 0.3546057 0.03335839 0.3532783 0.0332002 0.3529459 0.03304255 0.3526132 0.03304255 0.3526132 0.03288543 0.3522803 0.03335839 0.3532783 0.03288543 0.3522803 0.03272879 0.3519471 0.03335839 0.3532783 0.03272879 0.3519471 0.03257262 0.3516137 0.03210729 0.3506121 0.03257262 0.3516137 0.03241699 0.35128 0.03210729 0.3506121 0.03241699 0.35128 0.0322619 0.3509462 0.03210729 0.3506121 0.03210729 0.3506121 0.03195321 0.3502777 0.03179967 0.3499431 0.03179967 0.3499431 0.0316466 0.3496083 0.03149408 0.3492732 0.03149408 0.3492732 0.03134202 0.3489379 0.03119051 0.3486024 0.03119051 0.3486024 0.03103953 0.3482666 0.03149408 0.3492732 0.03103953 0.3482666 0.03088903 0.3479306 0.03149408 0.3492732 0.03088903 0.3479306 0.03073906 0.3475944 0.03058964 0.3472579 0.03058964 0.3472579 0.03044068 0.3469212 0.03029227 0.3465843 0.03029227 0.3465843 0.03014439 0.3462471 0.02999699 0.3459098 0.02999699 0.3459098 0.02985012 0.3455722 0.03029227 0.3465843 0.02985012 0.3455722 0.02970379 0.3452344 0.03029227 0.3465843 0.02970379 0.3452344 0.02955794 0.3448964 0.02941262 0.3445581 0.02941262 0.3445581 0.02926784 0.3442196 0.02970379 0.3452344 0.02926784 0.3442196 0.0291236 0.3438809 0.02970379 0.3452344 0.0291236 0.3438809 0.02897983 0.3435419 0.02855169 0.3425239 0.02897983 0.3435419 0.0288366 0.3432028 0.02855169 0.3425239 0.0288366 0.3432028 0.02869391 0.3428635 0.02855169 0.3425239 0.02855169 0.3425239 0.02841007 0.342184 0.02826887 0.341844 0.02826887 0.341844 0.02812826 0.3415038 0.02798813 0.3411633 0.02798813 0.3411633 0.0278486 0.3408226 0.02743297 0.3397994 0.0278486 0.3408226 0.02770954 0.3404818 0.02743297 0.3397994 0.02770954 0.3404818 0.02757096 0.3401407 0.02743297 0.3397994 0.02743297 0.3397994 0.02729547 0.3394579 0.02688616 0.338432 0.02729547 0.3394579 0.02715849 0.3391161 0.02688616 0.338432 0.02715849 0.3391161 0.02702206 0.3387742 0.02688616 0.338432 0.02688616 0.338432 0.0267508 0.3380897 0.02661591 0.3377471 0.02661591 0.3377471 0.02648156 0.3374043 0.02634775 0.3370614 0.02634775 0.3370614 0.02621448 0.3367182 0.02581775 0.3356874 0.02621448 0.3367182 0.02608168 0.3363748 0.02581775 0.3356874 0.02608168 0.3363748 0.02594947 0.3360312 0.02581775 0.3356874 0.02581775 0.3356874 0.02568662 0.3353434 0.02529621 0.3343102 0.02568662 0.3353434 0.0255559 0.3349993 0.02529621 0.3343102 0.0255559 0.3349993 0.02542579 0.3346549 0.02529621 0.3343102 0.02529621 0.3343102 0.02516716 0.3339655 0.02503859 0.3336205 0.02503859 0.3336205 0.02491062 0.3332753 0.02529621 0.3343102 0.02491062 0.3332753 0.02478313 0.3329299 0.02529621 0.3343102 0.02478313 0.3329299 0.02465617 0.3325843 0.02452975 0.3322386 0.02452975 0.3322386 0.02440387 0.3318926 0.02427852 0.3315464 0.02427852 0.3315464 0.0241537 0.3312001 0.02378243 0.3301599 0.0241537 0.3312001 0.02402943 0.3308536 0.02378243 0.3301599 0.02402943 0.3308536 0.02390563 0.3305068 0.02378243 0.3301599 0.02378243 0.3301599 0.0236597 0.3298128 0.02353757 0.3294655 0.02353757 0.3294655 0.02341592 0.329118 0.0232948 0.3287703 0.0232948 0.3287703 0.02317428 0.3284225 0.02281576 0.3273779 0.02317428 0.3284225 0.02305424 0.3280745 0.02281576 0.3273779 0.02305424 0.3280745 0.02293473 0.3277263 0.02281576 0.3273779 0.02281576 0.3273779 0.02269732 0.3270292 0.02257943 0.3266805 0.02257943 0.3266805 0.02246206 0.3263316 0.02234524 0.3259824 0.02234524 0.3259824 0.02222895 0.3256331 0.0221132 0.3252836 0.0221132 0.3252836 0.02199798 0.324934 0.0218833 0.3245841 0.0218833 0.3245841 0.02176916 0.3242341 0.02142995 0.323183 0.02176916 0.3242341 0.02165555 0.3238839 0.02142995 0.323183 0.02165555 0.3238839 0.02154248 0.3235335 0.02142995 0.323183 0.02142995 0.323183 0.02131801 0.3228323 0.02120655 0.3224814 0.02120655 0.3224814 0.02109563 0.3221304 0.02098524 0.3217791 0.02098524 0.3217791 0.02087539 0.3214278 0.02076607 0.3210762 0.02076607 0.3210762 0.02065736 0.3207245 0.02098524 0.3217791 0.02065736 0.3207245 0.02054911 0.3203726 0.02098524 0.3217791 0.02054911 0.3203726 0.02044147 0.3200206 0.02012163 0.3189634 0.02044147 0.3200206 0.0203343 0.3196683 0.02012163 0.3189634 0.0203343 0.3196683 0.02022767 0.3193159 0.02012163 0.3189634 0.02012163 0.3189634 0.02001613 0.3186107 0.01991117 0.3182578 0.01991117 0.3182578 0.01980668 0.3179048 0.01970279 0.3175516 0.01970279 0.3175516 0.01959949 0.3171982 0.01929265 0.3161373 0.01959949 0.3171982 0.01949667 0.3168447 0.01929265 0.3161373 0.01949667 0.3168447 0.01939439 0.3164911 0.01929265 0.3161373 0.01929265 0.3161373 0.0191915 0.3157833 0.01889121 0.3147204 0.0191915 0.3157833 0.01909083 0.3154291 0.01889121 0.3147204 0.01909083 0.3154291 0.01899075 0.3150748 0.01889121 0.3147204 0.01889121 0.3147204 0.01879221 0.3143658 0.01849842 0.3133011 0.01879221 0.3143658 0.01869374 0.314011 0.01849842 0.3133011 0.01869374 0.314011 0.01859581 0.3136562 0.01849842 0.3133011 0.01849842 0.3133011 0.01840162 0.3129459 0.01811438 0.3118795 0.01840162 0.3129459 0.0183053 0.3125906 0.01811438 0.3118795 0.0183053 0.3125906 0.01820957 0.3122351 0.01811438 0.3118795 0.01811438 0.3118795 0.01801973 0.3115237 0.01792562 0.3111678 0.01792562 0.3111678 0.0178321 0.3108117 0.01811438 0.3118795 0.0178321 0.3108117 0.01773905 0.3104555 0.01811438 0.3118795 0.01773905 0.3104555 0.01764661 0.3100991 0.0175547 0.3097426 0.0175547 0.3097426 0.01746332 0.309386 0.01737248 0.3090292 0.01737248 0.3090292 0.01728218 0.3086723 0.01701468 0.3076007 0.01728218 0.3086723 0.01719248 0.3083152 0.01701468 0.3076007 0.01719248 0.3083152 0.01710331 0.3079581 0.01701468 0.3076007 0.01701468 0.3076007 0.01692658 0.3072432 0.01683902 0.3068857 0.01683902 0.3068857 0.01675206 0.3065279 0.01701468 0.3076007 0.01675206 0.3065279 0.01666563 0.3061701 0.01701468 0.3076007 0.01666563 0.3061701 0.01657974 0.3058121 0.01649439 0.305454 0.01649439 0.305454 0.01640957 0.3050957 0.01666563 0.3061701 0.01640957 0.3050957 0.01632535 0.3047373 0.01666563 0.3061701 0.01632535 0.3047373 0.01624166 0.3043788 0.01615852 0.3040201 0.01615852 0.3040201 0.0160759 0.3036614 0.01599389 0.3033025 0.01599389 0.3033025 0.01591241 0.3029434 0.01583147 0.3025843 0.01583147 0.3025843 0.01575106 0.302225 0.01567125 0.3018656 0.01567125 0.3018656 0.01559197 0.3015061 0.01551324 0.3011465 0.01551324 0.3011465 0.01543503 0.3007867 0.01567125 0.3018656 0.01543503 0.3007867 0.01535743 0.3004269 0.01567125 0.3018656 0.01535743 0.3004269 0.01528036 0.3000668 0.01505243 0.2989861 0.01528036 0.3000668 0.01520383 0.2997067 0.01505243 0.2989861 0.01520383 0.2997067 0.01512783 0.2993465 0.01505243 0.2989861 0.01505243 0.2989861 0.01497757 0.2986257 0.01490324 0.2982651 0.01490324 0.2982651 0.01482945 0.2979044 0.01505243 0.2989861 0.01482945 0.2979044 0.01475626 0.2975436 0.01505243 0.2989861 0.01475626 0.2975436 0.0146836 0.2971827 0.01461154 0.2968217 0.01461154 0.2968217 0.01453995 0.2964605 0.01446896 0.2960993 0.01446896 0.2960993 0.01439851 0.2957379 0.01432865 0.2953765 0.01432865 0.2953765 0.01425933 0.2950149 0.01446896 0.2960993 0.01425933 0.2950149 0.01419055 0.2946532 0.01446896 0.2960993 0.01419055 0.2946532 0.0141223 0.2942914 0.01405465 0.2939296 0.01405465 0.2939296 0.01398754 0.2935676 0.01419055 0.2946532 0.01398754 0.2935676 0.01392102 0.2932055 0.01419055 0.2946532 0.01392102 0.2932055 0.01385498 0.2928433 0.01378959 0.292481 0.01378959 0.292481 0.01372468 0.2921186 0.01366037 0.2917561 0.01366037 0.2917561 0.01359653 0.2913935 0.01353335 0.2910308 0.01353335 0.2910308 0.0134707 0.2906681 0.01366037 0.2917561 0.0134707 0.2906681 0.0134086 0.2903052 0.01366037 0.2917561 0.0134086 0.2903052 0.01334702 0.2899422 0.01316571 0.2888527 0.01334702 0.2899422 0.01328605 0.2895792 0.01316571 0.2888527 0.01328605 0.2895792 0.01322561 0.289216 0.01316571 0.2888527 0.01316571 0.2888527 0.0131064 0.2884894 0.01304763 0.2881259 0.01304763 0.2881259 0.01298946 0.2877624 0.01293176 0.2873988 0.01293176 0.2873988 0.01287472 0.2870351 0.01270675 0.2859435 0.01287472 0.2870351 0.01281815 0.2866714 0.01270675 0.2859435 0.01281815 0.2866714 0.01276218 0.2863075 0.01270675 0.2859435 0.01270675 0.2859435 0.01265192 0.2855795 0.01249068 0.2844868 0.01265192 0.2855795 0.01259762 0.2852153 0.01249068 0.2844868 0.01259762 0.2852153 0.01254385 0.2848511 0.01249068 0.2844868 0.01249068 0.2844868 0.01243805 0.2841224 0.01238602 0.283758 0.01238602 0.283758 0.01233452 0.2833935 0.01228356 0.2830289 0.01228356 0.2830289 0.01223319 0.2826641 0.01208537 0.2815696 0.01223319 0.2826641 0.01218336 0.2822993 0.01208537 0.2815696 0.01218336 0.2822993 0.01213407 0.2819345 0.01208537 0.2815696 0.01208537 0.2815696 0.01203721 0.2812046 0.01189613 0.2801092 0.01203721 0.2812046 0.01198965 0.2808396 0.01189613 0.2801092 0.01198965 0.2808396 0.01194262 0.2804744 0.01189613 0.2801092 0.01189613 0.2801092 0.01185023 0.2797439 0.01180487 0.2793785 0.01180487 0.2793785 0.01176011 0.2790132 0.01189613 0.2801092 0.01176011 0.2790132 0.01171588 0.2786477 0.01189613 0.2801092 0.01171588 0.2786477 0.01167219 0.2782821 0.0116291 0.2779164 0.0116291 0.2779164 0.0115866 0.2775508 0.01154458 0.277185 0.01154458 0.277185 0.01150315 0.2768192 0.01146233 0.2764533 0.01146233 0.2764533 0.01142203 0.2760874 0.01154458 0.277185 0.01142203 0.2760874 0.01138228 0.2757214 0.01154458 0.277185 0.01138228 0.2757214 0.01134312 0.2753553 0.01122897 0.2742568 0.01134312 0.2753553 0.01130449 0.2749892 0.01122897 0.2742568 0.01130449 0.2749892 0.01126641 0.274623 0.01122897 0.2742568 0.01122897 0.2742568 0.01119202 0.2738904 0.01115566 0.2735241 0.01115566 0.2735241 0.01111984 0.2731577 0.01122897 0.2742568 0.01111984 0.2731577 0.01108461 0.2727912 0.01122897 0.2742568 0.01108461 0.2727912 0.01104992 0.2724247 0.01101583 0.2720581 0.01101583 0.2720581 0.01098221 0.2716915 0.01094925 0.2713248 0.01094925 0.2713248 0.01091682 0.2709581 0.01088494 0.2705913 0.01088494 0.2705913 0.01085364 0.2702245 0.01094925 0.2713248 0.01085364 0.2702245 0.01082289 0.2698577 0.01094925 0.2713248 0.01082289 0.2698577 0.01079273 0.2694907 0.0107631 0.2691238 0.0107631 0.2691238 0.01073408 0.2687568 0.01082289 0.2698577 0.01073408 0.2687568 0.01070559 0.2683897 0.01082289 0.2698577 0.01070559 0.2683897 0.01067763 0.2680226 0.01059722 0.2669211 0.01067763 0.2680226 0.01065027 0.2676555 0.01059722 0.2669211 0.01065027 0.2676555 0.01062345 0.2672883 0.01059722 0.2669211 0.01059722 0.2669211 0.01057153 0.2665538 0.01054644 0.2661865 0.01054644 0.2661865 0.01052188 0.2658192 0.01049792 0.2654518 0.01049792 0.2654518 0.0104745 0.2650844 0.01040762 0.263982 0.0104745 0.2650844 0.01045161 0.264717 0.01040762 0.263982 0.01045161 0.264717 0.01042932 0.2643495 0.01040762 0.263982 0.01040762 0.263982 0.01038646 0.2636144 0.01036584 0.2632468 0.01036584 0.2632468 0.01034581 0.2628793 0.01032632 0.2625116 0.01032632 0.2625116 0.01030743 0.2621439 0.01028907 0.2617762 0.01028907 0.2617762 0.01027131 0.2614085 0.01025408 0.2610408 0.01025408 0.2610408 0.01023739 0.260673 0.0102213 0.2603052 0.0102213 0.2603052 0.0102058 0.2599374 0.01025408 0.2610408 0.0102058 0.2599374 0.01019084 0.2595695 0.01025408 0.2610408 0.01019084 0.2595695 0.01017642 0.2592016 0.01016259 0.2588337 0.01016259 0.2588337 0.01014935 0.2584658 0.01013666 0.2580979 0.01013666 0.2580979 0.0101245 0.2577299 0.01011294 0.257362 0.01011294 0.257362 0.01010191 0.256994 0.01009148 0.256626 0.01009148 0.256626 0.01008158 0.2562579 0.01007229 0.2558899 0.01007229 0.2558899 0.01006352 0.2555218 0.0100553 0.2551538 0.0100553 0.2551538 0.01004773 0.2547857 0.01002824 0.2536814 0.01004773 0.2547857 0.01004064 0.2544176 0.01002824 0.2536814 0.01004064 0.2544176 0.01003414 0.2540495 0.01002824 0.2536814 0.01002824 0.2536814 0.01002287 0.2533133 0.01001018 0.2522089 0.01002287 0.2533133 0.01001805 0.2529451 0.01001018 0.2522089 0.01001805 0.2529451 0.01001381 0.252577 0.01001018 0.2522089 0.01001018 0.2522089 0.01000702 0.2518408 0.01000452 0.2514726 0.01000452 0.2514726 0.01000255 0.2511045 0.01001018 0.2522089 0.01000255 0.2511045 0.01000112 0.2507363 0.01001018 0.2522089 0.01000112 0.2507363 0.01000028 0.2503681 0.01000112 0.2492637 0.01000028 0.2503681 0.00999999 0.25 0.01000112 0.2492637 0.00999999 0.25 0.01000028 0.2496318 0.01000112 0.2492637 0.01000112 0.2492637 0.01000255 0.2488955 0.01001018 0.2477911 0.01000255 0.2488955 0.01000452 0.2485274 0.01001018 0.2477911 0.01000452 0.2485274 0.01000702 0.2481592 0.01001018 0.2477911 0.01001018 0.2477911 0.01001381 0.2474229 0.01001805 0.2470548 0.01001805 0.2470548 0.01002287 0.2466867 0.01001018 0.2477911 0.01002287 0.2466867 0.01002824 0.2463186 0.01001018 0.2477911 0.01002824 0.2463186 0.01003414 0.2459505 0.01004064 0.2455824 0.01004064 0.2455824 0.01004773 0.2452143 0.01002824 0.2463186 0.01004773 0.2452143 0.0100553 0.2448462 0.01002824 0.2463186 0.0100553 0.2448462 0.01006352 0.2444781 0.01007229 0.2441101 0.01007229 0.2441101 0.01008158 0.2437421 0.01009148 0.243374 0.01009148 0.243374 0.01010191 0.243006 0.01011294 0.242638 0.01011294 0.242638 0.0101245 0.2422701 0.01013666 0.2419021 0.01013666 0.2419021 0.01014935 0.2415342 0.01016259 0.2411662 0.01016259 0.2411662 0.01017642 0.2407984 0.01019084 0.2404305 0.01019084 0.2404305 0.0102058 0.2400626 0.01025408 0.2389592 0.0102058 0.2400626 0.0102213 0.2396948 0.01025408 0.2389592 0.0102213 0.2396948 0.01023739 0.239327 0.01025408 0.2389592 0.01025408 0.2389592 0.01027131 0.2385914 0.01032632 0.2374883 0.01027131 0.2385914 0.01028907 0.2382237 0.01032632 0.2374883 0.01028907 0.2382237 0.01030743 0.237856 0.01032632 0.2374883 0.01032632 0.2374883 0.01034581 0.2371207 0.01036584 0.2367531 0.01036584 0.2367531 0.01038646 0.2363855 0.01040762 0.236018 0.01040762 0.236018 0.01042932 0.2356505 0.01045161 0.235283 0.01045161 0.235283 0.0104745 0.2349156 0.01049792 0.2345482 0.01049792 0.2345482 0.01052188 0.2341808 0.01059722 0.2330788 0.01052188 0.2341808 0.01054644 0.2338134 0.01059722 0.2330788 0.01054644 0.2338134 0.01057153 0.2334461 0.01059722 0.2330788 0.01059722 0.2330788 0.01062345 0.2327117 0.01065027 0.2323445 0.01065027 0.2323445 0.01067763 0.2319774 0.01070559 0.2316102 0.01070559 0.2316102 0.01073408 0.2312432 0.01082289 0.2301423 0.01073408 0.2312432 0.0107631 0.2308762 0.01082289 0.2301423 0.0107631 0.2308762 0.01079273 0.2305092 0.01082289 0.2301423 0.01082289 0.2301423 0.01085364 0.2297754 0.01094925 0.2286751 0.01085364 0.2297754 0.01088494 0.2294086 0.01094925 0.2286751 0.01088494 0.2294086 0.01091682 0.2290418 0.01094925 0.2286751 0.01094925 0.2286751 0.01098221 0.2283084 0.01101583 0.2279418 0.01101583 0.2279418 0.01104992 0.2275753 0.01094925 0.2286751 0.01104992 0.2275753 0.01108461 0.2272087 0.01094925 0.2286751 0.01108461 0.2272087 0.01111984 0.2268423 0.01122897 0.2257432 0.01111984 0.2268423 0.01115566 0.2264758 0.01122897 0.2257432 0.01115566 0.2264758 0.01119202 0.2261095 0.01122897 0.2257432 0.01122897 0.2257432 0.01126641 0.225377 0.01130449 0.2250108 0.01130449 0.2250108 0.01134312 0.2246447 0.01122897 0.2257432 0.01134312 0.2246447 0.01138228 0.2242786 0.01122897 0.2257432 0.01138228 0.2242786 0.01142203 0.2239126 0.01154458 0.2228149 0.01142203 0.2239126 0.01146233 0.2235466 0.01154458 0.2228149 0.01146233 0.2235466 0.01150315 0.2231808 0.01154458 0.2228149 0.01154458 0.2228149 0.0115866 0.2224492 0.0116291 0.2220835 0.0116291 0.2220835 0.01167219 0.2217179 0.01171588 0.2213523 0.01171588 0.2213523 0.01176011 0.2209869 0.01189613 0.2198908 0.01176011 0.2209869 0.01180487 0.2206214 0.01189613 0.2198908 0.01180487 0.2206214 0.01185023 0.220256 0.01189613 0.2198908 0.01189613 0.2198908 0.01194262 0.2195256 0.01198965 0.2191604 0.01198965 0.2191604 0.01203721 0.2187954 0.01189613 0.2198908 0.01203721 0.2187954 0.01208537 0.2184303 0.01189613 0.2198908 0.01208537 0.2184303 0.01213407 0.2180655 0.01218336 0.2177006 0.01218336 0.2177006 0.01223319 0.2173358 0.01208537 0.2184303 0.01223319 0.2173358 0.01228356 0.2169712 0.01208537 0.2184303 0.01228356 0.2169712 0.01233452 0.2166065 0.01238602 0.216242 0.01238602 0.216242 0.01243805 0.2158775 0.01249068 0.2155132 0.01249068 0.2155132 0.01254385 0.2151489 0.01259762 0.2147846 0.01259762 0.2147846 0.01265192 0.2144205 0.01249068 0.2155132 0.01265192 0.2144205 0.01270675 0.2140565 0.01249068 0.2155132 0.01270675 0.2140565 0.01276218 0.2136925 0.01281815 0.2133287 0.01281815 0.2133287 0.01287472 0.2129648 0.01270675 0.2140565 0.01287472 0.2129648 0.01293176 0.2126011 0.01270675 0.2140565 0.01293176 0.2126011 0.01298946 0.2122375 0.01316571 0.2111473 0.01298946 0.2122375 0.01304763 0.211874 0.01316571 0.2111473 0.01304763 0.211874 0.0131064 0.2115106 0.01316571 0.2111473 0.01316571 0.2111473 0.01322561 0.210784 0.01328605 0.2104208 0.01328605 0.2104208 0.01334702 0.2100577 0.01316571 0.2111473 0.01334702 0.2100577 0.0134086 0.2096948 0.01316571 0.2111473 0.0134086 0.2096948 0.0134707 0.2093319 0.01366037 0.2082439 0.0134707 0.2093319 0.01353335 0.2089691 0.01366037 0.2082439 0.01353335 0.2089691 0.01359653 0.2086064 0.01366037 0.2082439 0.01366037 0.2082439 0.01372468 0.2078813 0.01378959 0.2075189 0.01378959 0.2075189 0.01385498 0.2071567 0.01392102 0.2067945 0.01392102 0.2067945 0.01398754 0.2064324 0.01419055 0.2053467 0.01398754 0.2064324 0.01405465 0.2060704 0.01419055 0.2053467 0.01405465 0.2060704 0.0141223 0.2057085 0.01419055 0.2053467 0.01419055 0.2053467 0.01425933 0.2049851 0.01446896 0.2039006 0.01425933 0.2049851 0.01432865 0.2046235 0.01446896 0.2039006 0.01432865 0.2046235 0.01439851 0.204262 0.01446896 0.2039006 0.01446896 0.2039006 0.01453995 0.2035394 0.01461154 0.2031783 0.01461154 0.2031783 0.0146836 0.2028173 0.01475626 0.2024564 0.01475626 0.2024564 0.01482945 0.2020956 0.01505243 0.2010138 0.01482945 0.2020956 0.01490324 0.2017349 0.01505243 0.2010138 0.01490324 0.2017349 0.01497757 0.2013743 0.01505243 0.2010138 0.01505243 0.2010138 0.01512783 0.2006534 0.01520383 0.2002933 0.01520383 0.2002933 0.01528036 0.1999331 0.01505243 0.2010138 0.01528036 0.1999331 0.01535743 0.1995731 0.01505243 0.2010138 0.01535743 0.1995731 0.01543503 0.1992133 0.01567125 0.1981343 0.01543503 0.1992133 0.01551324 0.1988535 0.01567125 0.1981343 0.01551324 0.1988535 0.01559197 0.1984938 0.01567125 0.1981343 0.01567125 0.1981343 0.01575106 0.197775 0.01583147 0.1974157 0.01583147 0.1974157 0.01591241 0.1970565 0.01599389 0.1966975 0.01599389 0.1966975 0.0160759 0.1963386 0.01615852 0.1959798 0.01615852 0.1959798 0.01624166 0.1956212 0.01599389 0.1966975 0.01624166 0.1956212 0.01632535 0.1952627 0.01599389 0.1966975 0.01632535 0.1952627 0.01640957 0.1949043 0.01666563 0.1938299 0.01640957 0.1949043 0.01649439 0.194546 0.01666563 0.1938299 0.01649439 0.194546 0.01657974 0.1941879 0.01666563 0.1938299 0.01666563 0.1938299 0.01675206 0.193472 0.01701468 0.1923993 0.01675206 0.193472 0.01683902 0.1931143 0.01701468 0.1923993 0.01683902 0.1931143 0.01692658 0.1927567 0.01701468 0.1923993 0.01701468 0.1923993 0.01710331 0.1920419 0.01719248 0.1916847 0.01719248 0.1916847 0.01728218 0.1913277 0.01701468 0.1923993 0.01728218 0.1913277 0.01737248 0.1909708 0.01701468 0.1923993 0.01737248 0.1909708 0.01746332 0.190614 0.0175547 0.1902573 0.0175547 0.1902573 0.01764661 0.1899008 0.01773905 0.1895445 0.01773905 0.1895445 0.0178321 0.1891883 0.01811438 0.1881205 0.0178321 0.1891883 0.01792562 0.1888322 0.01811438 0.1881205 0.01792562 0.1888322 0.01801973 0.1884763 0.01811438 0.1881205 0.01811438 0.1881205 0.01820957 0.1877649 0.0183053 0.1874094 0.0183053 0.1874094 0.01840162 0.187054 0.01811438 0.1881205 0.01840162 0.187054 0.01849842 0.1866989 0.01811438 0.1881205 0.01849842 0.1866989 0.01859581 0.1863438 0.01869374 0.1859889 0.01869374 0.1859889 0.01879221 0.1856341 0.01889121 0.1852796 0.01889121 0.1852796 0.01899075 0.1849251 0.01909083 0.1845709 0.01909083 0.1845709 0.0191915 0.1842167 0.01889121 0.1852796 0.0191915 0.1842167 0.01929265 0.1838628 0.01889121 0.1852796 0.01929265 0.1838628 0.01939439 0.1835089 0.01949667 0.1831552 0.01949667 0.1831552 0.01959949 0.1828017 0.01929265 0.1838628 0.01959949 0.1828017 0.01970279 0.1824484 0.01929265 0.1838628 0.01970279 0.1824484 0.01980668 0.1820952 0.01991117 0.1817421 0.01991117 0.1817421 0.02001613 0.1813893 0.02012163 0.1810365 0.02012163 0.1810365 0.02022767 0.180684 0.0203343 0.1803317 0.0203343 0.1803317 0.02044147 0.1799794 0.02012163 0.1810365 0.02044147 0.1799794 0.02054911 0.1796274 0.02012163 0.1810365 0.02054911 0.1796274 0.02065736 0.1792755 0.02098524 0.1782208 0.02065736 0.1792755 0.02076607 0.1789237 0.02098524 0.1782208 0.02076607 0.1789237 0.02087539 0.1785722 0.02098524 0.1782208 0.02098524 0.1782208 0.02109563 0.1778696 0.02120655 0.1775186 0.02120655 0.1775186 0.02131801 0.1771677 0.02142995 0.1768169 0.02142995 0.1768169 0.02154248 0.1764664 0.02165555 0.1761161 0.02165555 0.1761161 0.02176916 0.1757659 0.02142995 0.1768169 0.02176916 0.1757659 0.0218833 0.1754159 0.02142995 0.1768169 0.0218833 0.1754159 0.02199798 0.175066 0.0221132 0.1747164 0.0221132 0.1747164 0.02222895 0.1743668 0.02234524 0.1740176 0.02234524 0.1740176 0.02246206 0.1736685 0.02281576 0.1726222 0.02246206 0.1736685 0.02257943 0.1733195 0.02281576 0.1726222 0.02257943 0.1733195 0.02269732 0.1729707 0.02281576 0.1726222 0.02281576 0.1726222 0.02293473 0.1722737 0.02305424 0.1719255 0.02305424 0.1719255 0.02317428 0.1715775 0.02281576 0.1726222 0.02317428 0.1715775 0.0232948 0.1712296 0.02281576 0.1726222 0.0232948 0.1712296 0.02341592 0.1708819 0.02353757 0.1705344 0.02353757 0.1705344 0.0236597 0.1701872 0.0232948 0.1712296 0.0236597 0.1701872 0.02378243 0.16984 0.0232948 0.1712296 0.02378243 0.16984 0.02390563 0.1694931 0.02402943 0.1691464 0.02402943 0.1691464 0.0241537 0.1687999 0.02378243 0.16984 0.0241537 0.1687999 0.02427852 0.1684535 0.02378243 0.16984 0.02427852 0.1684535 0.02440387 0.1681073 0.02452975 0.1677614 0.02452975 0.1677614 0.02465617 0.1674156 0.02427852 0.1684535 0.02465617 0.1674156 0.02478313 0.16707 0.02427852 0.1684535 0.02478313 0.16707 0.02491062 0.1667247 0.02529621 0.1656897 0.02491062 0.1667247 0.02503859 0.1663795 0.02529621 0.1656897 0.02503859 0.1663795 0.02516716 0.1660345 0.02529621 0.1656897 0.02529621 0.1656897 0.02542579 0.1653451 0.0255559 0.1650007 0.0255559 0.1650007 0.02568662 0.1646565 0.02529621 0.1656897 0.02568662 0.1646565 0.02581775 0.1643126 0.02529621 0.1656897 0.02581775 0.1643126 0.02594947 0.1639688 0.02608168 0.1636251 0.02608168 0.1636251 0.02621448 0.1632818 0.02581775 0.1643126 0.02621448 0.1632818 0.02634775 0.1629386 0.02581775 0.1643126 0.02634775 0.1629386 0.02648156 0.1625956 0.02661591 0.1622529 0.02661591 0.1622529 0.0267508 0.1619103 0.02688616 0.1615679 0.02688616 0.1615679 0.02702206 0.1612258 0.02715849 0.1608839 0.02715849 0.1608839 0.02729547 0.1605421 0.02688616 0.1615679 0.02729547 0.1605421 0.02743297 0.1602006 0.02688616 0.1615679 0.02743297 0.1602006 0.02757096 0.1598593 0.02770954 0.1595182 0.02770954 0.1595182 0.0278486 0.1591773 0.02743297 0.1602006 0.0278486 0.1591773 0.02798813 0.1588367 0.02743297 0.1602006 0.02798813 0.1588367 0.02812826 0.1584962 0.02826887 0.1581559 0.02826887 0.1581559 0.02841007 0.1578159 0.02855169 0.1574761 0.02855169 0.1574761 0.02869391 0.1571365 0.0288366 0.1567972 0.0288366 0.1567972 0.02897983 0.156458 0.02855169 0.1574761 0.02897983 0.156458 0.0291236 0.1561191 0.02855169 0.1574761 0.0291236 0.1561191 0.02926784 0.1557804 0.02970379 0.1547656 0.02926784 0.1557804 0.02941262 0.1554419 0.02970379 0.1547656 0.02941262 0.1554419 0.02955794 0.1551036 0.02970379 0.1547656 0.02970379 0.1547656 0.02985012 0.1544278 0.03029227 0.1534156 0.02985012 0.1544278 0.02999699 0.1540902 0.03029227 0.1534156 0.02999699 0.1540902 0.03014439 0.1537528 0.03029227 0.1534156 0.03029227 0.1534156 0.03044068 0.1530787 0.03058964 0.152742 0.03058964 0.152742 0.03073906 0.1524056 0.03088903 0.1520694 0.03088903 0.1520694 0.03103953 0.1517333 0.03149408 0.1507267 0.03103953 0.1517333 0.03119051 0.1513976 0.03149408 0.1507267 0.03119051 0.1513976 0.03134202 0.1510621 0.03149408 0.1507267 0.03149408 0.1507267 0.0316466 0.1503917 0.03179967 0.1500568 0.03179967 0.1500568 0.03195321 0.1497223 0.03149408 0.1507267 0.03195321 0.1497223 0.03210729 0.1493879 0.03149408 0.1507267 0.03210729 0.1493879 0.0322619 0.1490538 0.03241699 0.1487199 0.03241699 0.1487199 0.03257262 0.1483862 0.03210729 0.1493879 0.03257262 0.1483862 0.03272879 0.1480528 0.03210729 0.1493879 0.03272879 0.1480528 0.03288543 0.1477197 0.03335839 0.1467216 0.03288543 0.1477197 0.03304255 0.1473867 0.03335839 0.1467216 0.03304255 0.1473867 0.0332002 0.1470541 0.03335839 0.1467216 0.03335839 0.1467216 0.03351706 0.1463894 0.03399616 0.1453943 0.03351706 0.1463894 0.03367626 0.1460574 0.03399616 0.1453943 0.03367626 0.1460574 0.03383594 0.1457257 0.03399616 0.1453943 0.03399616 0.1453943 0.03415685 0.1450631 0.0346421 0.1440709 0.03415685 0.1450631 0.03431808 0.1447321 0.0346421 0.1440709 0.03431808 0.1447321 0.03447985 0.1444013 0.0346421 0.1440709 0.0346421 0.1440709 0.03480482 0.1437407 0.03529608 0.1427515 0.03480482 0.1437407 0.03496807 0.1434106 0.03529608 0.1427515 0.03496807 0.1434106 0.03513181 0.1430809 0.03529608 0.1427515 0.03529608 0.1427515 0.03546088 0.1424222 0.03562617 0.1420933 0.03562617 0.1420933 0.03579193 0.1417645 0.03529608 0.1427515 0.03579193 0.1417645 0.03595823 0.1414361 0.03529608 0.1427515 0.03595823 0.1414361 0.036125 0.1411079 0.03629225 0.1407799 0.03629225 0.1407799 0.0364601 0.1404522 0.03595823 0.1414361 0.0364601 0.1404522 0.03662836 0.1401247 0.03595823 0.1414361 0.03662836 0.1401247 0.03679716 0.1397976 0.03730654 0.1388176 0.03679716 0.1397976 0.03696644 0.1394707 0.03730654 0.1388176 0.03696644 0.1394707 0.03713625 0.139144 0.03730654 0.1388176 0.03730654 0.1388176 0.03747737 0.1384915 0.03799277 0.1375147 0.03747737 0.1384915 0.03764867 0.1381656 0.03799277 0.1375147 0.03764867 0.1381656 0.03782045 0.13784 0.03799277 0.1375147 0.03799277 0.1375147 0.03816556 0.1371896 0.03833889 0.1368647 0.03833889 0.1368647 0.0385127 0.1365402 0.03868699 0.1362159 0.03868699 0.1362159 0.03886175 0.1358919 0.03938913 0.1349215 0.03886175 0.1358919 0.03903704 0.1355682 0.03938913 0.1349215 0.03903704 0.1355682 0.03921282 0.1352447 0.03938913 0.1349215 0.03938913 0.1349215 0.03956592 0.1345986 0.03974318 0.1342759 0.03974318 0.1342759 0.03992092 0.1339535 0.03938913 0.1349215 0.03992092 0.1339535 0.0400992 0.1336314 0.03938913 0.1349215 0.0400992 0.1336314 0.04027795 0.1333095 0.04045718 0.1329879 0.04045718 0.1329879 0.04063695 0.1326667 0.0400992 0.1336314 0.04063695 0.1326667 0.04081714 0.1323456 0.0400992 0.1336314 0.04081714 0.1323456 0.04099792 0.1320249 0.041543 0.1310643 0.04099792 0.1320249 0.04117912 0.1317044 0.041543 0.1310643 0.04117912 0.1317044 0.04136079 0.1313842 0.041543 0.1310643 0.041543 0.1310643 0.04172569 0.1307446 0.04190886 0.1304253 0.04190886 0.1304253 0.04209256 0.1301063 0.04227674 0.1297875 0.04227674 0.1297875 0.04246133 0.129469 0.04264652 0.1291508 0.04264652 0.1291508 0.04283213 0.1288328 0.04301822 0.1285152 0.04301822 0.1285152 0.04320484 0.1281978 0.04339194 0.1278807 0.04339194 0.1278807 0.04357951 0.127564 0.04376757 0.1272475 0.04376757 0.1272475 0.0439561 0.1269312 0.0441451 0.1266153 0.0441451 0.1266153 0.04433465 0.1262997 0.04376757 0.1272475 0.04433465 0.1262997 0.04452461 0.1259843 0.04376757 0.1272475 0.04452461 0.1259843 0.0447151 0.1256693 0.04528945 0.1247259 0.0447151 0.1256693 0.04490607 0.1253545 0.04528945 0.1247259 0.04490607 0.1253545 0.04509752 0.1250401 0.04528945 0.1247259 0.04528945 0.1247259 0.04548186 0.124412 0.04567474 0.1240984 0.04567474 0.1240984 0.04586809 0.1237851 0.04528945 0.1247259 0.04586809 0.1237851 0.04606193 0.1234722 0.04528945 0.1247259 0.04606193 0.1234722 0.0462563 0.1231595 0.04645109 0.1228471 0.04645109 0.1228471 0.04664641 0.122535 0.04684215 0.1222232 0.04684215 0.1222232 0.04703837 0.1219117 0.04723513 0.1216006 0.04723513 0.1216006 0.04743236 0.1212897 0.04684215 0.1222232 0.04743236 0.1212897 0.04763001 0.1209791 0.04684215 0.1222232 0.04763001 0.1209791 0.04782813 0.1206688 0.0480268 0.1203588 0.0480268 0.1203588 0.04822587 0.1200491 0.04763001 0.1209791 0.04822587 0.1200491 0.04842549 0.1197398 0.04763001 0.1209791 0.04842549 0.1197398 0.04862552 0.1194307 0.04882603 0.119122 0.04882603 0.119122 0.04902702 0.1188135 0.04922854 0.1185054 0.04922854 0.1185054 0.04943048 0.1181976 0.0496329 0.1178901 0.0496329 0.1178901 0.0498358 0.1175829 0.05003911 0.117276 0.05003911 0.117276 0.05024296 0.1169694 0.0508573 0.1160515 0.05024296 0.1169694 0.05044728 0.1166631 0.0508573 0.1160515 0.05044728 0.1166631 0.05065202 0.1163572 0.0508573 0.1160515 0.0508573 0.1160515 0.051063 0.1157462 0.05126917 0.1154412 0.05126917 0.1154412 0.05147582 0.1151365 0.05168294 0.1148321 0.05168294 0.1148321 0.05189049 0.1145281 0.05251604 0.1136178 0.05189049 0.1145281 0.05209857 0.1142243 0.05251604 0.1136178 0.05209857 0.1142243 0.05230706 0.1139209 0.05251604 0.1136178 0.05251604 0.1136178 0.05272549 0.1133151 0.05293536 0.1130126 0.05293536 0.1130126 0.05314576 0.1127105 0.05251604 0.1136178 0.05314576 0.1127105 0.05335658 0.1124086 0.05251604 0.1136178 0.05335658 0.1124086 0.05356788 0.1121072 0.0537796 0.111806 0.0537796 0.111806 0.05399185 0.1115052 0.05420452 0.1112046 0.05420452 0.1112046 0.05441766 0.1109045 0.05463129 0.1106046 0.05463129 0.1106046 0.05484533 0.1103051 0.05420452 0.1112046 0.05484533 0.1103051 0.05505985 0.1100059 0.05420452 0.1112046 0.05505985 0.1100059 0.05527484 0.109707 0.0559225 0.1088124 0.05527484 0.109707 0.05549025 0.1094085 0.0559225 0.1088124 0.05549025 0.1094085 0.05570614 0.1091103 0.0559225 0.1088124 0.0559225 0.1088124 0.05613929 0.1085149 0.05635654 0.1082177 0.05635654 0.1082177 0.05657428 0.1079208 0.05679249 0.1076242 0.05679249 0.1076242 0.05701106 0.107328 0.05723017 0.1070321 0.05723017 0.1070321 0.05744969 0.1067366 0.05766969 0.1064414 0.05766969 0.1064414 0.05789011 0.1061465 0.05855417 0.105264 0.05789011 0.1061465 0.05811107 0.105852 0.05855417 0.105264 0.05811107 0.105852 0.05833238 0.1055578 0.05855417 0.105264 0.05855417 0.105264 0.05877643 0.1049705 0.05944585 0.104092 0.05877643 0.1049705 0.05899912 0.1046773 0.05944585 0.104092 0.05899912 0.1046773 0.05922228 0.1043845 0.05944585 0.104092 0.05944585 0.104092 0.05966991 0.1037999 0.05989438 0.1035081 0.05989438 0.1035081 0.06011933 0.1032167 0.06034475 0.1029255 0.06034475 0.1029255 0.06057053 0.1026348 0.06079685 0.1023444 0.06079685 0.1023444 0.06102359 0.1020543 0.06034475 0.1029255 0.06102359 0.1020543 0.06125074 0.1017646 0.06034475 0.1029255 0.06125074 0.1017646 0.06147837 0.1014752 0.06216382 0.1006093 0.06147837 0.1014752 0.06170636 0.1011862 0.06216382 0.1006093 0.06170636 0.1011862 0.06193488 0.1008976 0.06216382 0.1006093 0.06216382 0.1006093 0.06239324 0.1003213 0.06262302 0.1000337 0.06262302 0.1000337 0.06285333 0.09974646 0.06216382 0.1006093 0.06285333 0.09974646 0.063084 0.09945952 0.06216382 0.1006093 0.063084 0.09945952 0.06331515 0.099173 0.06354677 0.09888678 0.06354677 0.09888678 0.06377875 0.09860098 0.06401121 0.09831547 0.06401121 0.09831547 0.06424415 0.09803032 0.06494545 0.09717714 0.06424415 0.09803032 0.0644775 0.09774559 0.06494545 0.09717714 0.0644775 0.09774559 0.06471127 0.09746116 0.06494545 0.09717714 0.06494545 0.09717714 0.06518012 0.09689342 0.0654152 0.09661012 0.0654152 0.09661012 0.0656507 0.09632712 0.06494545 0.09717714 0.0656507 0.09632712 0.06588661 0.09604454 0.06494545 0.09717714 0.06588661 0.09604454 0.066123 0.09576231 0.06635981 0.09548038 0.06635981 0.09548038 0.0665971 0.09519886 0.06683474 0.09491771 0.06683474 0.09491771 0.06707286 0.09463691 0.0673114 0.09435653 0.0673114 0.09435653 0.06755036 0.09407645 0.06683474 0.09491771 0.06755036 0.09407645 0.06778979 0.09379678 0.06683474 0.09491771 0.06778979 0.09379678 0.06802958 0.09351742 0.06826984 0.09323847 0.06826984 0.09323847 0.06851053 0.09295994 0.06778979 0.09379678 0.06851053 0.09295994 0.06875163 0.0926817 0.06778979 0.09379678 0.06875163 0.0926817 0.06899321 0.09240382 0.06923514 0.09212636 0.06923514 0.09212636 0.06947755 0.09184926 0.06875163 0.0926817 0.06947755 0.09184926 0.06972038 0.09157252 0.06875163 0.0926817 0.06972038 0.09157252 0.06996357 0.09129619 0.07020723 0.09102016 0.07020723 0.09102016 0.07045131 0.09074455 0.06972038 0.09157252 0.07045131 0.09074455 0.07069581 0.09046936 0.06972038 0.09157252 0.07069581 0.09046936 0.07094079 0.09019446 0.07118612 0.08991998 0.07118612 0.08991998 0.07143187 0.08964586 0.07167804 0.08937215 0.07167804 0.08937215 0.07192468 0.08909881 0.072667 0.08828103 0.07192468 0.08909881 0.07217168 0.08882582 0.072667 0.08828103 0.07217168 0.08882582 0.07241916 0.08855324 0.072667 0.08828103 0.072667 0.08828103 0.07291531 0.08800917 0.07316398 0.08773773 0.07316398 0.08773773 0.07341313 0.08746665 0.072667 0.08828103 0.07341313 0.08746665 0.07366263 0.08719593 0.072667 0.08828103 0.07366263 0.08719593 0.07391262 0.08692568 0.07466495 0.08611702 0.07391262 0.08692568 0.07416296 0.08665573 0.07466495 0.08611702 0.07416296 0.08665573 0.07441371 0.0863862 0.07466495 0.08611702 0.07466495 0.08611702 0.07491654 0.08584827 0.07516855 0.08557987 0.07516855 0.08557987 0.07542097 0.08531188 0.07567381 0.08504432 0.07567381 0.08504432 0.07592701 0.08477705 0.07618069 0.08451026 0.07618069 0.08451026 0.07643473 0.08424383 0.07567381 0.08504432 0.07643473 0.08424383 0.07668924 0.08397775 0.07567381 0.08504432 0.07668924 0.08397775 0.07694411 0.0837121 0.07719939 0.08344686 0.07719939 0.08344686 0.0774551 0.08318191 0.07771116 0.08291745 0.07771116 0.08291745 0.0779677 0.08265334 0.07822459 0.08238965 0.07822459 0.08238965 0.07848191 0.08212637 0.07873958 0.08186346 0.07873958 0.08186346 0.07899773 0.08160096 0.07925623 0.08133882 0.07925623 0.08133882 0.07951515 0.08107709 0.07873958 0.08186346 0.07951515 0.08107709 0.07977449 0.08081579 0.07873958 0.08186346 0.07977449 0.08081579 0.08003425 0.0805549 0.08029437 0.08029437 0.08029437 0.08029437 0.0805549 0.08003425 0.07977449 0.08081579 0.0805549 0.08003425 0.08081579 0.07977449 0.07977449 0.08081579 0.08081579 0.07977449 0.08107709 0.07951515 0.08133882 0.07925623 0.08133882 0.07925623 0.08160096 0.07899773 0.08081579 0.07977449 0.08160096 0.07899773 0.08186346 0.07873958 0.08081579 0.07977449 0.08186346 0.07873958 0.08212637 0.07848191 0.08238965 0.07822459 0.08238965 0.07822459 0.08265334 0.0779677 0.08186346 0.07873958 0.08265334 0.0779677 0.08291745 0.07771116 0.08186346 0.07873958 0.08291745 0.07771116 0.08318191 0.0774551 0.08344686 0.07719939 0.08344686 0.07719939 0.0837121 0.07694411 0.08397775 0.07668924 0.08397775 0.07668924 0.08424383 0.07643473 0.08504432 0.07567381 0.08424383 0.07643473 0.08451026 0.07618069 0.08504432 0.07567381 0.08451026 0.07618069 0.08477705 0.07592701 0.08504432 0.07567381 0.08504432 0.07567381 0.08531188 0.07542097 0.08557987 0.07516855 0.08557987 0.07516855 0.08584827 0.07491654 0.08611702 0.07466495 0.08611702 0.07466495 0.0863862 0.07441371 0.08665573 0.07416296 0.08665573 0.07416296 0.08692568 0.07391262 0.08611702 0.07466495 0.08692568 0.07391262 0.08719593 0.07366263 0.08611702 0.07466495 0.08719593 0.07366263 0.08746665 0.07341313 0.08828103 0.072667 0.08746665 0.07341313 0.08773773 0.07316398 0.08828103 0.072667 0.08773773 0.07316398 0.08800917 0.07291531 0.08828103 0.072667 0.08828103 0.072667 0.08855324 0.07241916 0.08882582 0.07217168 0.08882582 0.07217168 0.08909881 0.07192468 0.08828103 0.072667 0.08909881 0.07192468 0.08937215 0.07167804 0.08828103 0.072667 0.08937215 0.07167804 0.08964586 0.07143187 0.08991998 0.07118612 0.08991998 0.07118612 0.09019446 0.07094079 0.09046936 0.07069581 0.09046936 0.07069581 0.09074455 0.07045131 0.09157252 0.06972038 0.09074455 0.07045131 0.09102016 0.07020723 0.09157252 0.06972038 0.09102016 0.07020723 0.09129619 0.06996357 0.09157252 0.06972038 0.09157252 0.06972038 0.09184926 0.06947755 0.09212636 0.06923514 0.09212636 0.06923514 0.09240382 0.06899321 0.09157252 0.06972038 0.09240382 0.06899321 0.0926817 0.06875163 0.09157252 0.06972038 0.0926817 0.06875163 0.09295994 0.06851053 0.09379678 0.06778979 0.09295994 0.06851053 0.09323847 0.06826984 0.09379678 0.06778979 0.09323847 0.06826984 0.09351742 0.06802958 0.09379678 0.06778979 0.09379678 0.06778979 0.09407645 0.06755036 0.09491771 0.06683474 0.09407645 0.06755036 0.09435653 0.0673114 0.09491771 0.06683474 0.09435653 0.0673114 0.09463691 0.06707286 0.09491771 0.06683474 0.09491771 0.06683474 0.09519886 0.0665971 0.09548038 0.06635981 0.09548038 0.06635981 0.09576231 0.066123 0.09604454 0.06588661 0.09604454 0.06588661 0.09632712 0.0656507 0.09717714 0.06494545 0.09632712 0.0656507 0.09661012 0.0654152 0.09717714 0.06494545 0.09661012 0.0654152 0.09689342 0.06518012 0.09717714 0.06494545 0.09717714 0.06494545 0.09746116 0.06471127 0.09774559 0.0644775 0.09774559 0.0644775 0.09803032 0.06424415 0.09717714 0.06494545 0.09803032 0.06424415 0.09831547 0.06401121 0.09717714 0.06494545 0.09831547 0.06401121 0.09860098 0.06377875 0.09888678 0.06354677 0.09888678 0.06354677 0.099173 0.06331515 0.09945952 0.063084 0.09945952 0.063084 0.09974646 0.06285333 0.1006093 0.06216382 0.09974646 0.06285333 0.1000337 0.06262302 0.1006093 0.06216382 0.1000337 0.06262302 0.1003213 0.06239324 0.1006093 0.06216382 0.1006093 0.06216382 0.1008976 0.06193488 0.1011862 0.06170636 0.1011862 0.06170636 0.1014752 0.06147837 0.1006093 0.06216382 0.1014752 0.06147837 0.1017646 0.06125074 0.1006093 0.06216382 0.1017646 0.06125074 0.1020543 0.06102359 0.1029255 0.06034475 0.1020543 0.06102359 0.1023444 0.06079685 0.1029255 0.06034475 0.1023444 0.06079685 0.1026348 0.06057053 0.1029255 0.06034475 0.1029255 0.06034475 0.1032167 0.06011933 0.1035081 0.05989438 0.1035081 0.05989438 0.1037999 0.05966991 0.104092 0.05944585 0.104092 0.05944585 0.1043845 0.05922228 0.1046773 0.05899912 0.1046773 0.05899912 0.1049705 0.05877643 0.104092 0.05944585 0.1049705 0.05877643 0.105264 0.05855417 0.104092 0.05944585 0.105264 0.05855417 0.1055578 0.05833238 0.105852 0.05811107 0.105852 0.05811107 0.1061465 0.05789011 0.105264 0.05855417 0.1061465 0.05789011 0.1064414 0.05766969 0.105264 0.05855417 0.1064414 0.05766969 0.1067366 0.05744969 0.1070321 0.05723017 0.1070321 0.05723017 0.107328 0.05701106 0.1076242 0.05679249 0.1076242 0.05679249 0.1079208 0.05657428 0.1082177 0.05635654 0.1082177 0.05635654 0.1085149 0.05613929 0.1088124 0.0559225 0.1088124 0.0559225 0.1091103 0.05570614 0.1094085 0.05549025 0.1094085 0.05549025 0.109707 0.05527484 0.1088124 0.0559225 0.109707 0.05527484 0.1100059 0.05505985 0.1088124 0.0559225 0.1100059 0.05505985 0.1103051 0.05484533 0.1112046 0.05420452 0.1103051 0.05484533 0.1106046 0.05463129 0.1112046 0.05420452 0.1106046 0.05463129 0.1109045 0.05441766 0.1112046 0.05420452 0.1112046 0.05420452 0.1115052 0.05399185 0.111806 0.0537796 0.111806 0.0537796 0.1121072 0.05356788 0.1124086 0.05335658 0.1124086 0.05335658 0.1127105 0.05314576 0.1136178 0.05251604 0.1127105 0.05314576 0.1130126 0.05293536 0.1136178 0.05251604 0.1130126 0.05293536 0.1133151 0.05272549 0.1136178 0.05251604 0.1136178 0.05251604 0.1139209 0.05230706 0.1142243 0.05209857 0.1142243 0.05209857 0.1145281 0.05189049 0.1136178 0.05251604 0.1145281 0.05189049 0.1148321 0.05168294 0.1136178 0.05251604 0.1148321 0.05168294 0.1151365 0.05147582 0.1154412 0.05126917 0.1154412 0.05126917 0.1157462 0.051063 0.1160515 0.0508573 0.1160515 0.0508573 0.1163572 0.05065202 0.1166631 0.05044728 0.1166631 0.05044728 0.1169694 0.05024296 0.1160515 0.0508573 0.1169694 0.05024296 0.117276 0.05003911 0.1160515 0.0508573 0.117276 0.05003911 0.1175829 0.0498358 0.1178901 0.0496329 0.1178901 0.0496329 0.1181976 0.04943048 0.1185054 0.04922854 0.1185054 0.04922854 0.1188135 0.04902702 0.119122 0.04882603 0.119122 0.04882603 0.1194307 0.04862552 0.1197398 0.04842549 0.1197398 0.04842549 0.1200491 0.04822587 0.1209791 0.04763001 0.1200491 0.04822587 0.1203588 0.0480268 0.1209791 0.04763001 0.1203588 0.0480268 0.1206688 0.04782813 0.1209791 0.04763001 0.1209791 0.04763001 0.1212897 0.04743236 0.1222232 0.04684215 0.1212897 0.04743236 0.1216006 0.04723513 0.1222232 0.04684215 0.1216006 0.04723513 0.1219117 0.04703837 0.1222232 0.04684215 0.1222232 0.04684215 0.122535 0.04664641 0.1228471 0.04645109 0.1228471 0.04645109 0.1231595 0.0462563 0.1234722 0.04606193 0.1234722 0.04606193 0.1237851 0.04586809 0.1247259 0.04528945 0.1237851 0.04586809 0.1240984 0.04567474 0.1247259 0.04528945 0.1240984 0.04567474 0.124412 0.04548186 0.1247259 0.04528945 0.1247259 0.04528945 0.1250401 0.04509752 0.1253545 0.04490607 0.1253545 0.04490607 0.1256693 0.0447151 0.1247259 0.04528945 0.1256693 0.0447151 0.1259843 0.04452461 0.1247259 0.04528945 0.1259843 0.04452461 0.1262997 0.04433465 0.1272475 0.04376757 0.1262997 0.04433465 0.1266153 0.0441451 0.1272475 0.04376757 0.1266153 0.0441451 0.1269312 0.0439561 0.1272475 0.04376757 0.1272475 0.04376757 0.127564 0.04357951 0.1278807 0.04339194 0.1278807 0.04339194 0.1281978 0.04320484 0.1285152 0.04301822 0.1285152 0.04301822 0.1288328 0.04283213 0.1291508 0.04264652 0.1291508 0.04264652 0.129469 0.04246133 0.1297875 0.04227674 0.1297875 0.04227674 0.1301063 0.04209256 0.1304253 0.04190886 0.1304253 0.04190886 0.1307446 0.04172569 0.1310643 0.041543 0.1310643 0.041543 0.1313842 0.04136079 0.1317044 0.04117912 0.1317044 0.04117912 0.1320249 0.04099792 0.1310643 0.041543 0.1320249 0.04099792 0.1323456 0.04081714 0.1310643 0.041543 0.1323456 0.04081714 0.1326667 0.04063695 0.1336314 0.0400992 0.1326667 0.04063695 0.1329879 0.04045718 0.1336314 0.0400992 0.1329879 0.04045718 0.1333095 0.04027795 0.1336314 0.0400992 0.1336314 0.0400992 0.1339535 0.03992092 0.1342759 0.03974318 0.1342759 0.03974318 0.1345986 0.03956592 0.1349215 0.03938913 0.1349215 0.03938913 0.1352447 0.03921282 0.1355682 0.03903704 0.1355682 0.03903704 0.1358919 0.03886175 0.1349215 0.03938913 0.1358919 0.03886175 0.1362159 0.03868699 0.1349215 0.03938913 0.1362159 0.03868699 0.1365402 0.0385127 0.1368647 0.03833889 0.1368647 0.03833889 0.1371896 0.03816556 0.1375147 0.03799277 0.1375147 0.03799277 0.13784 0.03782045 0.1381656 0.03764867 0.1381656 0.03764867 0.1384915 0.03747737 0.1375147 0.03799277 0.1384915 0.03747737 0.1388176 0.03730654 0.1375147 0.03799277 0.1388176 0.03730654 0.139144 0.03713625 0.1394707 0.03696644 0.1394707 0.03696644 0.1397976 0.03679716 0.1388176 0.03730654 0.1397976 0.03679716 0.1401247 0.03662836 0.1388176 0.03730654 0.1401247 0.03662836 0.1404522 0.0364601 0.1414361 0.03595823 0.1404522 0.0364601 0.1407799 0.03629225 0.1414361 0.03595823 0.1407799 0.03629225 0.1411079 0.036125 0.1414361 0.03595823 0.1414361 0.03595823 0.1417645 0.03579193 0.1427515 0.03529608 0.1417645 0.03579193 0.1420933 0.03562617 0.1427515 0.03529608 0.1420933 0.03562617 0.1424222 0.03546088 0.1427515 0.03529608 0.1427515 0.03529608 0.1430809 0.03513181 0.1434106 0.03496807 0.1434106 0.03496807 0.1437407 0.03480482 0.1427515 0.03529608 0.1437407 0.03480482 0.1440709 0.0346421 0.1427515 0.03529608 0.1440709 0.0346421 0.1444013 0.03447985 0.1447321 0.03431808 0.1447321 0.03431808 0.1450631 0.03415685 0.1440709 0.0346421 0.1450631 0.03415685 0.1453943 0.03399616 0.1440709 0.0346421 0.1453943 0.03399616 0.1457257 0.03383594 0.1460574 0.03367626 0.1460574 0.03367626 0.1463894 0.03351706 0.1453943 0.03399616 0.1463894 0.03351706 0.1467216 0.03335839 0.1453943 0.03399616 0.1467216 0.03335839 0.1470541 0.0332002 0.1473867 0.03304255 0.1473867 0.03304255 0.1477197 0.03288543 0.1467216 0.03335839 0.1477197 0.03288543 0.1480528 0.03272879 0.1467216 0.03335839 0.1480528 0.03272879 0.1483862 0.03257262 0.1493879 0.03210729 0.1483862 0.03257262 0.1487199 0.03241699 0.1493879 0.03210729 0.1487199 0.03241699 0.1490538 0.0322619 0.1493879 0.03210729 0.1493879 0.03210729 0.1497223 0.03195321 0.1500568 0.03179967 0.1500568 0.03179967 0.1503917 0.0316466 0.1507267 0.03149408 0.1507267 0.03149408 0.1510621 0.03134202 0.1513976 0.03119051 0.1513976 0.03119051 0.1517333 0.03103953 0.1507267 0.03149408 0.1517333 0.03103953 0.1520694 0.03088903 0.1507267 0.03149408 0.1520694 0.03088903 0.1524056 0.03073906 0.152742 0.03058964 0.152742 0.03058964 0.1530787 0.03044068 0.1534156 0.03029227 0.1534156 0.03029227 0.1537528 0.03014439 0.1540902 0.02999699 0.1540902 0.02999699 0.1544278 0.02985012 0.1534156 0.03029227 0.1544278 0.02985012 0.1547656 0.02970379 0.1534156 0.03029227 0.1547656 0.02970379 0.1551036 0.02955794 0.1554419 0.02941262 0.1554419 0.02941262 0.1557804 0.02926784 0.1547656 0.02970379 0.1557804 0.02926784 0.1561191 0.0291236 0.1547656 0.02970379 0.1561191 0.0291236 0.156458 0.02897983 0.1574761 0.02855169 0.156458 0.02897983 0.1567972 0.0288366 0.1574761 0.02855169 0.1567972 0.0288366 0.1571365 0.02869391 0.1574761 0.02855169 0.1574761 0.02855169 0.1578159 0.02841007 0.1581559 0.02826887 0.1581559 0.02826887 0.1584962 0.02812826 0.1588367 0.02798813 0.1588367 0.02798813 0.1591773 0.0278486 0.1602006 0.02743297 0.1591773 0.0278486 0.1595182 0.02770954 0.1602006 0.02743297 0.1595182 0.02770954 0.1598593 0.02757096 0.1602006 0.02743297 0.1602006 0.02743297 0.1605421 0.02729547 0.1615679 0.02688616 0.1605421 0.02729547 0.1608839 0.02715849 0.1615679 0.02688616 0.1608839 0.02715849 0.1612258 0.02702206 0.1615679 0.02688616 0.1615679 0.02688616 0.1619103 0.0267508 0.1622529 0.02661591 0.1622529 0.02661591 0.1625956 0.02648156 0.1629386 0.02634775 0.1629386 0.02634775 0.1632818 0.02621448 0.1643126 0.02581775 0.1632818 0.02621448 0.1636251 0.02608168 0.1643126 0.02581775 0.1636251 0.02608168 0.1639688 0.02594947 0.1643126 0.02581775 0.1643126 0.02581775 0.1646565 0.02568662 0.1656897 0.02529621 0.1646565 0.02568662 0.1650007 0.0255559 0.1656897 0.02529621 0.1650007 0.0255559 0.1653451 0.02542579 0.1656897 0.02529621 0.1656897 0.02529621 0.1660345 0.02516716 0.1663795 0.02503859 0.1663795 0.02503859 0.1667247 0.02491062 0.1656897 0.02529621 0.1667247 0.02491062 0.16707 0.02478313 0.1656897 0.02529621 0.16707 0.02478313 0.1674156 0.02465617 0.1677614 0.02452975 0.1677614 0.02452975 0.1681073 0.02440387 0.1684535 0.02427852 0.1684535 0.02427852 0.1687999 0.0241537 0.16984 0.02378243 0.1687999 0.0241537 0.1691464 0.02402943 0.16984 0.02378243 0.1691464 0.02402943 0.1694931 0.02390563 0.16984 0.02378243 0.16984 0.02378243 0.1701872 0.0236597 0.1705344 0.02353757 0.1705344 0.02353757 0.1708819 0.02341592 0.1712296 0.0232948 0.1712296 0.0232948 0.1715775 0.02317428 0.1726222 0.02281576 0.1715775 0.02317428 0.1719255 0.02305424 0.1726222 0.02281576 0.1719255 0.02305424 0.1722737 0.02293473 0.1726222 0.02281576 0.1726222 0.02281576 0.1729707 0.02269732 0.1733195 0.02257943 0.1733195 0.02257943 0.1736685 0.02246206 0.1740176 0.02234524 0.1740176 0.02234524 0.1743668 0.02222895 0.1747164 0.0221132 0.1747164 0.0221132 0.175066 0.02199798 0.1754159 0.0218833 0.1754159 0.0218833 0.1757659 0.02176916 0.1768169 0.02142995 0.1757659 0.02176916 0.1761161 0.02165555 0.1768169 0.02142995 0.1761161 0.02165555 0.1764664 0.02154248 0.1768169 0.02142995 0.1768169 0.02142995 0.1771677 0.02131801 0.1775186 0.02120655 0.1775186 0.02120655 0.1778696 0.02109563 0.1782208 0.02098524 0.1782208 0.02098524 0.1785722 0.02087539 0.1789237 0.02076607 0.1789237 0.02076607 0.1792755 0.02065736 0.1782208 0.02098524 0.1792755 0.02065736 0.1796274 0.02054911 0.1782208 0.02098524 0.1796274 0.02054911 0.1799794 0.02044147 0.1810365 0.02012163 0.1799794 0.02044147 0.1803317 0.0203343 0.1810365 0.02012163 0.1803317 0.0203343 0.180684 0.02022767 0.1810365 0.02012163 0.1810365 0.02012163 0.1813893 0.02001613 0.1817421 0.01991117 0.1817421 0.01991117 0.1820952 0.01980668 0.1824484 0.01970279 0.1824484 0.01970279 0.1828017 0.01959949 0.1838628 0.01929265 0.1828017 0.01959949 0.1831552 0.01949667 0.1838628 0.01929265 0.1831552 0.01949667 0.1835089 0.01939439 0.1838628 0.01929265 0.1838628 0.01929265 0.1842167 0.0191915 0.1852796 0.01889121 0.1842167 0.0191915 0.1845709 0.01909083 0.1852796 0.01889121 0.1845709 0.01909083 0.1849251 0.01899075 0.1852796 0.01889121 0.1852796 0.01889121 0.1856341 0.01879221 0.1866989 0.01849842 0.1856341 0.01879221 0.1859889 0.01869374 0.1866989 0.01849842 0.1859889 0.01869374 0.1863438 0.01859581 0.1866989 0.01849842 0.1866989 0.01849842 0.187054 0.01840162 0.1881205 0.01811438 0.187054 0.01840162 0.1874094 0.0183053 0.1881205 0.01811438 0.1874094 0.0183053 0.1877649 0.01820957 0.1881205 0.01811438 0.1881205 0.01811438 0.1884763 0.01801973 0.1888322 0.01792562 0.1888322 0.01792562 0.1891883 0.0178321 0.1881205 0.01811438 0.1891883 0.0178321 0.1895445 0.01773905 0.1881205 0.01811438 0.1895445 0.01773905 0.1899008 0.01764661 0.1902573 0.0175547 0.1902573 0.0175547 0.190614 0.01746332 0.1909708 0.01737248 0.1909708 0.01737248 0.1913277 0.01728218 0.1923993 0.01701468 0.1913277 0.01728218 0.1916847 0.01719248 0.1923993 0.01701468 0.1916847 0.01719248 0.1920419 0.01710331 0.1923993 0.01701468 0.1923993 0.01701468 0.1927567 0.01692658 0.1931143 0.01683902 0.1931143 0.01683902 0.193472 0.01675206 0.1923993 0.01701468 0.193472 0.01675206 0.1938299 0.01666563 0.1923993 0.01701468 0.1938299 0.01666563 0.1941879 0.01657974 0.194546 0.01649439 0.194546 0.01649439 0.1949043 0.01640957 0.1938299 0.01666563 0.1949043 0.01640957 0.1952627 0.01632535 0.1938299 0.01666563 0.1952627 0.01632535 0.1956212 0.01624166 0.1959798 0.01615852 0.1959798 0.01615852 0.1963386 0.0160759 0.1966975 0.01599389 0.1966975 0.01599389 0.1970565 0.01591241 0.1974157 0.01583147 0.1974157 0.01583147 0.197775 0.01575106 0.1981343 0.01567125 0.1981343 0.01567125 0.1984938 0.01559197 0.1988535 0.01551324 0.1988535 0.01551324 0.1992133 0.01543503 0.1981343 0.01567125 0.1992133 0.01543503 0.1995731 0.01535743 0.1981343 0.01567125 0.1995731 0.01535743 0.1999331 0.01528036 0.2010138 0.01505243 0.1999331 0.01528036 0.2002933 0.01520383 0.2010138 0.01505243 0.2002933 0.01520383 0.2006534 0.01512783 0.2010138 0.01505243 0.2010138 0.01505243 0.2013743 0.01497757 0.2017349 0.01490324 0.2017349 0.01490324 0.2020956 0.01482945 0.2010138 0.01505243 0.2020956 0.01482945 0.2024564 0.01475626 0.2010138 0.01505243 0.2024564 0.01475626 0.2028173 0.0146836 0.2031783 0.01461154 0.2031783 0.01461154 0.2035394 0.01453995 0.2039006 0.01446896 0.2039006 0.01446896 0.204262 0.01439851 0.2046235 0.01432865 0.2046235 0.01432865 0.2049851 0.01425933 0.2039006 0.01446896 0.2049851 0.01425933 0.2053467 0.01419055 0.2039006 0.01446896 0.2053467 0.01419055 0.2057085 0.0141223 0.2060704 0.01405465 0.2060704 0.01405465 0.2064324 0.01398754 0.2053467 0.01419055 0.2064324 0.01398754 0.2067945 0.01392102 0.2053467 0.01419055 0.2067945 0.01392102 0.2071567 0.01385498 0.2075189 0.01378959 0.2075189 0.01378959 0.2078813 0.01372468 0.2082439 0.01366037 0.2082439 0.01366037 0.2086064 0.01359653 0.2089691 0.01353335 0.2089691 0.01353335 0.2093319 0.0134707 0.2082439 0.01366037 0.2093319 0.0134707 0.2096948 0.0134086 0.2082439 0.01366037 0.2096948 0.0134086 0.2100577 0.01334702 0.2111473 0.01316571 0.2100577 0.01334702 0.2104208 0.01328605 0.2111473 0.01316571 0.2104208 0.01328605 0.210784 0.01322561 0.2111473 0.01316571 0.2111473 0.01316571 0.2115106 0.0131064 0.211874 0.01304763 0.211874 0.01304763 0.2122375 0.01298946 0.2126011 0.01293176 0.2126011 0.01293176 0.2129648 0.01287472 0.2140565 0.01270675 0.2129648 0.01287472 0.2133287 0.01281815 0.2140565 0.01270675 0.2133287 0.01281815 0.2136925 0.01276218 0.2140565 0.01270675 0.2140565 0.01270675 0.2144205 0.01265192 0.2155132 0.01249068 0.2144205 0.01265192 0.2147846 0.01259762 0.2155132 0.01249068 0.2147846 0.01259762 0.2151489 0.01254385 0.2155132 0.01249068 0.2155132 0.01249068 0.2158775 0.01243805 0.216242 0.01238602 0.216242 0.01238602 0.2166065 0.01233452 0.2169712 0.01228356 0.2169712 0.01228356 0.2173358 0.01223319 0.2184303 0.01208537 0.2173358 0.01223319 0.2177006 0.01218336 0.2184303 0.01208537 0.2177006 0.01218336 0.2180655 0.01213407 0.2184303 0.01208537 0.2184303 0.01208537 0.2187954 0.01203721 0.2198908 0.01189613 0.2187954 0.01203721 0.2191604 0.01198965 0.2198908 0.01189613 0.2191604 0.01198965 0.2195256 0.01194262 0.2198908 0.01189613 0.2198908 0.01189613 0.220256 0.01185023 0.2206214 0.01180487 0.2206214 0.01180487 0.2209869 0.01176011 0.2198908 0.01189613 0.2209869 0.01176011 0.2213523 0.01171588 0.2198908 0.01189613 0.2213523 0.01171588 0.2217179 0.01167219 0.2220835 0.0116291 0.2220835 0.0116291 0.2224492 0.0115866 0.2228149 0.01154458 0.2228149 0.01154458 0.2231808 0.01150315 0.2235466 0.01146233 0.2235466 0.01146233 0.2239126 0.01142203 0.2228149 0.01154458 0.2239126 0.01142203 0.2242786 0.01138228 0.2228149 0.01154458 0.2242786 0.01138228 0.2246447 0.01134312 0.2257432 0.01122897 0.2246447 0.01134312 0.2250108 0.01130449 0.2257432 0.01122897 0.2250108 0.01130449 0.225377 0.01126641 0.2257432 0.01122897 0.2257432 0.01122897 0.2261095 0.01119202 0.2264758 0.01115566 0.2264758 0.01115566 0.2268423 0.01111984 0.2257432 0.01122897 0.2268423 0.01111984 0.2272087 0.01108461 0.2257432 0.01122897 0.2272087 0.01108461 0.2275753 0.01104992 0.2279418 0.01101583 0.2279418 0.01101583 0.2283084 0.01098221 0.2286751 0.01094925 0.2286751 0.01094925 0.2290418 0.01091682 0.2294086 0.01088494 0.2294086 0.01088494 0.2297754 0.01085364 0.2286751 0.01094925 0.2297754 0.01085364 0.2301423 0.01082289 0.2286751 0.01094925 0.2301423 0.01082289 0.2305092 0.01079273 0.2308762 0.0107631 0.2308762 0.0107631 0.2312432 0.01073408 0.2301423 0.01082289 0.2312432 0.01073408 0.2316102 0.01070559 0.2301423 0.01082289 0.2316102 0.01070559 0.2319774 0.01067763 0.2330788 0.01059722 0.2319774 0.01067763 0.2323445 0.01065027 0.2330788 0.01059722 0.2323445 0.01065027 0.2327117 0.01062345 0.2330788 0.01059722 0.2330788 0.01059722 0.2334461 0.01057153 0.2338134 0.01054644 0.2338134 0.01054644 0.2341808 0.01052188 0.2345482 0.01049792 0.2345482 0.01049792 0.2349156 0.0104745 0.236018 0.01040762 0.2349156 0.0104745 0.235283 0.01045161 0.236018 0.01040762 0.235283 0.01045161 0.2356505 0.01042932 0.236018 0.01040762 0.236018 0.01040762 0.2363855 0.01038646 0.2367531 0.01036584 0.2367531 0.01036584 0.2371207 0.01034581 0.2374883 0.01032632 0.2374883 0.01032632 0.237856 0.01030743 0.2382237 0.01028907 0.2382237 0.01028907 0.2385914 0.01027131 0.2389592 0.01025408 0.2389592 0.01025408 0.239327 0.01023739 0.2396948 0.0102213 0.2396948 0.0102213 0.2400626 0.0102058 0.2389592 0.01025408 0.2400626 0.0102058 0.2404305 0.01019084 0.2389592 0.01025408 0.2404305 0.01019084 0.2407984 0.01017642 0.2411662 0.01016259 0.2411662 0.01016259 0.2415342 0.01014935 0.2419021 0.01013666 0.2419021 0.01013666 0.2422701 0.0101245 0.242638 0.01011294 0.242638 0.01011294 0.243006 0.01010191 0.243374 0.01009148 0.243374 0.01009148 0.2437421 0.01008158 0.2441101 0.01007229 0.2441101 0.01007229 0.2444781 0.01006352 0.2448462 0.0100553 0.2448462 0.0100553 0.2452143 0.01004773 0.2463186 0.01002824 0.2452143 0.01004773 0.2455824 0.01004064 0.2463186 0.01002824 0.2455824 0.01004064 0.2459505 0.01003414 0.2463186 0.01002824 0.2463186 0.01002824 0.2466867 0.01002287 0.2477911 0.01001018 0.2466867 0.01002287 0.2470548 0.01001805 0.2477911 0.01001018 0.2470548 0.01001805 0.2474229 0.01001381 0.2477911 0.01001018 0.2477911 0.01001018 0.2481592 0.01000702 0.2485274 0.01000452 0.2485274 0.01000452 0.2488955 0.01000255 0.2477911 0.01001018 0.2488955 0.01000255 0.2492637 0.01000112 0.2477911 0.01001018 0.2492637 0.01000112 0.2496318 0.01000028 0.2507363 0.01000112 0.2496318 0.01000028 0.25 0.00999999 0.2507363 0.01000112 0.25 0.00999999 0.2503681 0.01000028 0.2507363 0.01000112 0.2507363 0.01000112 0.2511045 0.01000255 0.2522089 0.01001018 0.2511045 0.01000255 0.2514726 0.01000452 0.2522089 0.01001018 0.2514726 0.01000452 0.2518408 0.01000702 0.2522089 0.01001018 0.2522089 0.01001018 0.252577 0.01001381 0.2529451 0.01001805 0.2529451 0.01001805 0.2533133 0.01002287 0.2522089 0.01001018 0.2533133 0.01002287 0.2536814 0.01002824 0.2522089 0.01001018 0.2536814 0.01002824 0.2540495 0.01003414 0.2544176 0.01004064 0.2544176 0.01004064 0.2547857 0.01004773 0.2536814 0.01002824 0.2547857 0.01004773 0.2551538 0.0100553 0.2536814 0.01002824 0.2551538 0.0100553 0.2555218 0.01006352 0.2558899 0.01007229 0.2558899 0.01007229 0.2562579 0.01008158 0.256626 0.01009148 0.256626 0.01009148 0.256994 0.01010191 0.257362 0.01011294 0.257362 0.01011294 0.2577299 0.0101245 0.2580979 0.01013666 0.2580979 0.01013666 0.2584658 0.01014935 0.2588337 0.01016259 0.2588337 0.01016259 0.2592016 0.01017642 0.2595695 0.01019084 0.2595695 0.01019084 0.2599374 0.0102058 0.2610408 0.01025408 0.2599374 0.0102058 0.2603052 0.0102213 0.2610408 0.01025408 0.2603052 0.0102213 0.260673 0.01023739 0.2610408 0.01025408 0.2610408 0.01025408 0.2614085 0.01027131 0.2625116 0.01032632 0.2614085 0.01027131 0.2617762 0.01028907 0.2625116 0.01032632 0.2617762 0.01028907 0.2621439 0.01030743 0.2625116 0.01032632 0.2625116 0.01032632 0.2628793 0.01034581 0.2632468 0.01036584 0.2632468 0.01036584 0.2636144 0.01038646 0.263982 0.01040762 0.263982 0.01040762 0.2643495 0.01042932 0.264717 0.01045161 0.264717 0.01045161 0.2650844 0.0104745 0.2654518 0.01049792 0.2654518 0.01049792 0.2658192 0.01052188 0.2669211 0.01059722 0.2658192 0.01052188 0.2661865 0.01054644 0.2669211 0.01059722 0.2661865 0.01054644 0.2665538 0.01057153 0.2669211 0.01059722 0.2669211 0.01059722 0.2672883 0.01062345 0.2676555 0.01065027 0.2676555 0.01065027 0.2680226 0.01067763 0.2683897 0.01070559 0.2683897 0.01070559 0.2687568 0.01073408 0.2698577 0.01082289 0.2687568 0.01073408 0.2691238 0.0107631 0.2698577 0.01082289 0.2691238 0.0107631 0.2694907 0.01079273 0.2698577 0.01082289 0.2698577 0.01082289 0.2702245 0.01085364 0.2713248 0.01094925 0.2702245 0.01085364 0.2705913 0.01088494 0.2713248 0.01094925 0.2705913 0.01088494 0.2709581 0.01091682 0.2713248 0.01094925 0.2713248 0.01094925 0.2716915 0.01098221 0.2720581 0.01101583 0.2720581 0.01101583 0.2724247 0.01104992 0.2713248 0.01094925 0.2724247 0.01104992 0.2727912 0.01108461 0.2713248 0.01094925 0.2727912 0.01108461 0.2731577 0.01111984 0.2742568 0.01122897 0.2731577 0.01111984 0.2735241 0.01115566 0.2742568 0.01122897 0.2735241 0.01115566 0.2738904 0.01119202 0.2742568 0.01122897 0.2742568 0.01122897 0.274623 0.01126641 0.2749892 0.01130449 0.2749892 0.01130449 0.2753553 0.01134312 0.2742568 0.01122897 0.2753553 0.01134312 0.2757214 0.01138228 0.2742568 0.01122897 0.2757214 0.01138228 0.2760874 0.01142203 0.277185 0.01154458 0.2760874 0.01142203 0.2764533 0.01146233 0.277185 0.01154458 0.2764533 0.01146233 0.2768192 0.01150315 0.277185 0.01154458 0.277185 0.01154458 0.2775508 0.0115866 0.2779164 0.0116291 0.2779164 0.0116291 0.2782821 0.01167219 0.2786477 0.01171588 0.2786477 0.01171588 0.2790132 0.01176011 0.2801092 0.01189613 0.2790132 0.01176011 0.2793785 0.01180487 0.2801092 0.01189613 0.2793785 0.01180487 0.2797439 0.01185023 0.2801092 0.01189613 0.2801092 0.01189613 0.2804744 0.01194262 0.2808396 0.01198965 0.2808396 0.01198965 0.2812046 0.01203721 0.2801092 0.01189613 0.2812046 0.01203721 0.2815696 0.01208537 0.2801092 0.01189613 0.2815696 0.01208537 0.2819345 0.01213407 0.2822993 0.01218336 0.2822993 0.01218336 0.2826641 0.01223319 0.2815696 0.01208537 0.2826641 0.01223319 0.2830289 0.01228356 0.2815696 0.01208537 0.2830289 0.01228356 0.2833935 0.01233452 0.283758 0.01238602 0.283758 0.01238602 0.2841224 0.01243805 0.2844868 0.01249068 0.2844868 0.01249068 0.2848511 0.01254385 0.2852153 0.01259762 0.2852153 0.01259762 0.2855795 0.01265192 0.2844868 0.01249068 0.2855795 0.01265192 0.2859435 0.01270675 0.2844868 0.01249068 0.2859435 0.01270675 0.2863075 0.01276218 0.2866714 0.01281815 0.2866714 0.01281815 0.2870351 0.01287472 0.2859435 0.01270675 0.2870351 0.01287472 0.2873988 0.01293176 0.2859435 0.01270675 0.2873988 0.01293176 0.2877624 0.01298946 0.2888527 0.01316571 0.2877624 0.01298946 0.2881259 0.01304763 0.2888527 0.01316571 0.2881259 0.01304763 0.2884894 0.0131064 0.2888527 0.01316571 0.2888527 0.01316571 0.289216 0.01322561 0.2895792 0.01328605 0.2895792 0.01328605 0.2899422 0.01334702 0.2888527 0.01316571 0.2899422 0.01334702 0.2903052 0.0134086 0.2888527 0.01316571 0.2903052 0.0134086 0.2906681 0.0134707 0.2917561 0.01366037 0.2906681 0.0134707 0.2910308 0.01353335 0.2917561 0.01366037 0.2910308 0.01353335 0.2913935 0.01359653 0.2917561 0.01366037 0.2917561 0.01366037 0.2921186 0.01372468 0.292481 0.01378959 0.292481 0.01378959 0.2928433 0.01385498 0.2932055 0.01392102 0.2932055 0.01392102 0.2935676 0.01398754 0.2946532 0.01419055 0.2935676 0.01398754 0.2939296 0.01405465 0.2946532 0.01419055 0.2939296 0.01405465 0.2942914 0.0141223 0.2946532 0.01419055 0.2946532 0.01419055 0.2950149 0.01425933 0.2960993 0.01446896 0.2950149 0.01425933 0.2953765 0.01432865 0.2960993 0.01446896 0.2953765 0.01432865 0.2957379 0.01439851 0.2960993 0.01446896 0.2960993 0.01446896 0.2964605 0.01453995 0.2968217 0.01461154 0.2968217 0.01461154 0.2971827 0.0146836 0.2975436 0.01475626 0.2975436 0.01475626 0.2979044 0.01482945 0.2989861 0.01505243 0.2979044 0.01482945 0.2982651 0.01490324 0.2989861 0.01505243 0.2982651 0.01490324 0.2986257 0.01497757 0.2989861 0.01505243 0.2989861 0.01505243 0.2993465 0.01512783 0.2997067 0.01520383 0.2997067 0.01520383 0.3000668 0.01528036 0.2989861 0.01505243 0.3000668 0.01528036 0.3004269 0.01535743 0.2989861 0.01505243 0.3004269 0.01535743 0.3007867 0.01543503 0.3018656 0.01567125 0.3007867 0.01543503 0.3011465 0.01551324 0.3018656 0.01567125 0.3011465 0.01551324 0.3015061 0.01559197 0.3018656 0.01567125 0.3018656 0.01567125 0.302225 0.01575106 0.3025843 0.01583147 0.3025843 0.01583147 0.3029434 0.01591241 0.3033025 0.01599389 0.3033025 0.01599389 0.3036614 0.0160759 0.3040201 0.01615852 0.3040201 0.01615852 0.3043788 0.01624166 0.3033025 0.01599389 0.3043788 0.01624166 0.3047373 0.01632535 0.3033025 0.01599389 0.3047373 0.01632535 0.3050957 0.01640957 0.3061701 0.01666563 0.3050957 0.01640957 0.305454 0.01649439 0.3061701 0.01666563 0.305454 0.01649439 0.3058121 0.01657974 0.3061701 0.01666563 0.3061701 0.01666563 0.3065279 0.01675206 0.3076007 0.01701468 0.3065279 0.01675206 0.3068857 0.01683902 0.3076007 0.01701468 0.3068857 0.01683902 0.3072432 0.01692658 0.3076007 0.01701468 0.3076007 0.01701468 0.3079581 0.01710331 0.3083152 0.01719248 0.3083152 0.01719248 0.3086723 0.01728218 0.3076007 0.01701468 0.3086723 0.01728218 0.3090292 0.01737248 0.3076007 0.01701468 0.3090292 0.01737248 0.309386 0.01746332 0.3097426 0.0175547 0.3097426 0.0175547 0.3100991 0.01764661 0.3104555 0.01773905 0.3104555 0.01773905 0.3108117 0.0178321 0.3118795 0.01811438 0.3108117 0.0178321 0.3111678 0.01792562 0.3118795 0.01811438 0.3111678 0.01792562 0.3115237 0.01801973 0.3118795 0.01811438 0.3118795 0.01811438 0.3122351 0.01820957 0.3125906 0.0183053 0.3125906 0.0183053 0.3129459 0.01840162 0.3118795 0.01811438 0.3129459 0.01840162 0.3133011 0.01849842 0.3118795 0.01811438 0.3133011 0.01849842 0.3136562 0.01859581 0.314011 0.01869374 0.314011 0.01869374 0.3143658 0.01879221 0.3147204 0.01889121 0.3147204 0.01889121 0.3150748 0.01899075 0.3154291 0.01909083 0.3154291 0.01909083 0.3157833 0.0191915 0.3147204 0.01889121 0.3157833 0.0191915 0.3161373 0.01929265 0.3147204 0.01889121 0.3161373 0.01929265 0.3164911 0.01939439 0.3168447 0.01949667 0.3168447 0.01949667 0.3171982 0.01959949 0.3161373 0.01929265 0.3171982 0.01959949 0.3175516 0.01970279 0.3161373 0.01929265 0.3175516 0.01970279 0.3179048 0.01980668 0.3182578 0.01991117 0.3182578 0.01991117 0.3186107 0.02001613 0.3189634 0.02012163 0.3189634 0.02012163 0.3193159 0.02022767 0.3196683 0.0203343 0.3196683 0.0203343 0.3200206 0.02044147 0.3189634 0.02012163 0.3200206 0.02044147 0.3203726 0.02054911 0.3189634 0.02012163 0.3203726 0.02054911 0.3207245 0.02065736 0.3217791 0.02098524 0.3207245 0.02065736 0.3210762 0.02076607 0.3217791 0.02098524 0.3210762 0.02076607 0.3214278 0.02087539 0.3217791 0.02098524 0.3217791 0.02098524 0.3221304 0.02109563 0.3224814 0.02120655 0.3224814 0.02120655 0.3228323 0.02131801 0.323183 0.02142995 0.323183 0.02142995 0.3235335 0.02154248 0.3238839 0.02165555 0.3238839 0.02165555 0.3242341 0.02176916 0.323183 0.02142995 0.3242341 0.02176916 0.3245841 0.0218833 0.323183 0.02142995 0.3245841 0.0218833 0.324934 0.02199798 0.3252836 0.0221132 0.3252836 0.0221132 0.3256331 0.02222895 0.3259824 0.02234524 0.3259824 0.02234524 0.3263316 0.02246206 0.3273779 0.02281576 0.3263316 0.02246206 0.3266805 0.02257943 0.3273779 0.02281576 0.3266805 0.02257943 0.3270292 0.02269732 0.3273779 0.02281576 0.3273779 0.02281576 0.3277263 0.02293473 0.3280745 0.02305424 0.3280745 0.02305424 0.3284225 0.02317428 0.3273779 0.02281576 0.3284225 0.02317428 0.3287703 0.0232948 0.3273779 0.02281576 0.3287703 0.0232948 0.329118 0.02341592 0.3294655 0.02353757 0.3294655 0.02353757 0.3298128 0.0236597 0.3287703 0.0232948 0.3298128 0.0236597 0.3301599 0.02378243 0.3287703 0.0232948 0.3301599 0.02378243 0.3305068 0.02390563 0.3308536 0.02402943 0.3308536 0.02402943 0.3312001 0.0241537 0.3301599 0.02378243 0.3312001 0.0241537 0.3315464 0.02427852 0.3301599 0.02378243 0.3315464 0.02427852 0.3318926 0.02440387 0.3322386 0.02452975 0.3322386 0.02452975 0.3325843 0.02465617 0.3315464 0.02427852 0.3325843 0.02465617 0.3329299 0.02478313 0.3315464 0.02427852 0.3329299 0.02478313 0.3332753 0.02491062 0.3343102 0.02529621 0.3332753 0.02491062 0.3336205 0.02503859 0.3343102 0.02529621 0.3336205 0.02503859 0.3339655 0.02516716 0.3343102 0.02529621 0.3343102 0.02529621 0.3346549 0.02542579 0.3349993 0.0255559 0.3349993 0.0255559 0.3353434 0.02568662 0.3343102 0.02529621 0.3353434 0.02568662 0.3356874 0.02581775 0.3343102 0.02529621 0.3356874 0.02581775 0.3360312 0.02594947 0.3363748 0.02608168 0.3363748 0.02608168 0.3367182 0.02621448 0.3356874 0.02581775 0.3367182 0.02621448 0.3370614 0.02634775 0.3356874 0.02581775 0.3370614 0.02634775 0.3374043 0.02648156 0.3377471 0.02661591 0.3377471 0.02661591 0.3380897 0.0267508 0.338432 0.02688616 0.338432 0.02688616 0.3387742 0.02702206 0.3391161 0.02715849 0.3391161 0.02715849 0.3394579 0.02729547 0.338432 0.02688616 0.3394579 0.02729547 0.3397994 0.02743297 0.338432 0.02688616 0.3397994 0.02743297 0.3401407 0.02757096 0.3404818 0.02770954 0.3404818 0.02770954 0.3408226 0.0278486 0.3397994 0.02743297 0.3408226 0.0278486 0.3411633 0.02798813 0.3397994 0.02743297 0.3411633 0.02798813 0.3415038 0.02812826 0.341844 0.02826887 0.341844 0.02826887 0.342184 0.02841007 0.3425239 0.02855169 0.3425239 0.02855169 0.3428635 0.02869391 0.3432028 0.0288366 0.3432028 0.0288366 0.3435419 0.02897983 0.3425239 0.02855169 0.3435419 0.02897983 0.3438809 0.0291236 0.3425239 0.02855169 0.3438809 0.0291236 0.3442196 0.02926784 0.3452344 0.02970379 0.3442196 0.02926784 0.3445581 0.02941262 0.3452344 0.02970379 0.3445581 0.02941262 0.3448964 0.02955794 0.3452344 0.02970379 0.3452344 0.02970379 0.3455722 0.02985012 0.3465843 0.03029227 0.3455722 0.02985012 0.3459098 0.02999699 0.3465843 0.03029227 0.3459098 0.02999699 0.3462471 0.03014439 0.3465843 0.03029227 0.3465843 0.03029227 0.3469212 0.03044068 0.3472579 0.03058964 0.3472579 0.03058964 0.3475944 0.03073906 0.3479306 0.03088903 0.3479306 0.03088903 0.3482666 0.03103953 0.3492732 0.03149408 0.3482666 0.03103953 0.3486024 0.03119051 0.3492732 0.03149408 0.3486024 0.03119051 0.3489379 0.03134202 0.3492732 0.03149408 0.3492732 0.03149408 0.3496083 0.0316466 0.3499431 0.03179967 0.3499431 0.03179967 0.3502777 0.03195321 0.3492732 0.03149408 0.3502777 0.03195321 0.3506121 0.03210729 0.3492732 0.03149408 0.3506121 0.03210729 0.3509462 0.0322619 0.35128 0.03241699 0.35128 0.03241699 0.3516137 0.03257262 0.3506121 0.03210729 0.3516137 0.03257262 0.3519471 0.03272879 0.3506121 0.03210729 0.3519471 0.03272879 0.3522803 0.03288543 0.3532783 0.03335839 0.3522803 0.03288543 0.3526132 0.03304255 0.3532783 0.03335839 0.3526132 0.03304255 0.3529459 0.0332002 0.3532783 0.03335839 0.3532783 0.03335839 0.3536105 0.03351706 0.3546057 0.03399616 0.3536105 0.03351706 0.3539425 0.03367626 0.3546057 0.03399616 0.3539425 0.03367626 0.3542742 0.03383594 0.3546057 0.03399616 0.3546057 0.03399616 0.3549369 0.03415685 0.3559291 0.0346421 0.3549369 0.03415685 0.3552679 0.03431808 0.3559291 0.0346421 0.3552679 0.03431808 0.3555986 0.03447985 0.3559291 0.0346421 0.3559291 0.0346421 0.3562594 0.03480482 0.3572485 0.03529608 0.3562594 0.03480482 0.3565893 0.03496807 0.3572485 0.03529608 0.3565893 0.03496807 0.3569191 0.03513181 0.3572485 0.03529608 0.3572485 0.03529608 0.3575778 0.03546088 0.3579067 0.03562617 0.3579067 0.03562617 0.3582354 0.03579193 0.3572485 0.03529608 0.3582354 0.03579193 0.3585639 0.03595823 0.3572485 0.03529608 0.3585639 0.03595823 0.3588921 0.036125 0.35922 0.03629225 0.35922 0.03629225 0.3595477 0.0364601 0.3585639 0.03595823 0.3595477 0.0364601 0.3598752 0.03662836 0.3585639 0.03595823 0.3598752 0.03662836 0.3602024 0.03679716 0.3611823 0.03730654 0.3602024 0.03679716 0.3605293 0.03696644 0.3611823 0.03730654 0.3605293 0.03696644 0.3608559 0.03713625 0.3611823 0.03730654 0.3611823 0.03730654 0.3615085 0.03747737 0.3624853 0.03799277 0.3615085 0.03747737 0.3618344 0.03764867 0.3624853 0.03799277 0.3618344 0.03764867 0.36216 0.03782045 0.3624853 0.03799277 0.3624853 0.03799277 0.3628104 0.03816556 0.3631352 0.03833889 0.3631352 0.03833889 0.3634598 0.0385127 0.363784 0.03868699 0.363784 0.03868699 0.364108 0.03886175 0.3650785 0.03938913 0.364108 0.03886175 0.3644318 0.03903704 0.3650785 0.03938913 0.3644318 0.03903704 0.3647553 0.03921282 0.3650785 0.03938913 0.3650785 0.03938913 0.3654015 0.03956592 0.3657241 0.03974318 0.3657241 0.03974318 0.3660465 0.03992092 0.3650785 0.03938913 0.3660465 0.03992092 0.3663686 0.0400992 0.3650785 0.03938913 0.3663686 0.0400992 0.3666905 0.04027795 0.367012 0.04045718 0.367012 0.04045718 0.3673334 0.04063695 0.3663686 0.0400992 0.3673334 0.04063695 0.3676543 0.04081714 0.3663686 0.0400992 0.3676543 0.04081714 0.3679751 0.04099792 0.3689357 0.041543 0.3679751 0.04099792 0.3682956 0.04117912 0.3689357 0.041543 0.3682956 0.04117912 0.3686158 0.04136079 0.3689357 0.041543 0.3689357 0.041543 0.3692553 0.04172569 0.3695746 0.04190886 0.3695746 0.04190886 0.3698937 0.04209256 0.3702125 0.04227674 0.3702125 0.04227674 0.370531 0.04246133 0.3708492 0.04264652 0.3708492 0.04264652 0.3711671 0.04283213 0.3714848 0.04301822 0.3714848 0.04301822 0.3718022 0.04320484 0.3721193 0.04339194 0.3721193 0.04339194 0.3724361 0.04357951 0.3727526 0.04376757 0.3727526 0.04376757 0.3730688 0.0439561 0.3733847 0.0441451 0.3733847 0.0441451 0.3737003 0.04433465 0.3727526 0.04376757 0.3737003 0.04433465 0.3740156 0.04452461 0.3727526 0.04376757 0.3740156 0.04452461 0.3743306 0.0447151 0.3752741 0.04528945 0.3743306 0.0447151 0.3746454 0.04490607 0.3752741 0.04528945 0.3746454 0.04490607 0.3749599 0.04509752 0.3752741 0.04528945 0.3752741 0.04528945 0.3755879 0.04548186 0.3759015 0.04567474 0.3759015 0.04567474 0.3762148 0.04586809 0.3752741 0.04528945 0.3762148 0.04586809 0.3765278 0.04606193 0.3752741 0.04528945 0.3765278 0.04606193 0.3768405 0.0462563 0.3771529 0.04645109 0.3771529 0.04645109 0.377465 0.04664641 0.3777768 0.04684215 0.3777768 0.04684215 0.3780882 0.04703837 0.3783994 0.04723513 0.3783994 0.04723513 0.3787103 0.04743236 0.3777768 0.04684215 0.3787103 0.04743236 0.3790209 0.04763001 0.3777768 0.04684215 0.3790209 0.04763001 0.3793312 0.04782813 0.3796412 0.0480268 0.3796412 0.0480268 0.3799508 0.04822587 0.3790209 0.04763001 0.3799508 0.04822587 0.3802602 0.04842549 0.3790209 0.04763001 0.3802602 0.04842549 0.3805692 0.04862552 0.380878 0.04882603 0.380878 0.04882603 0.3811864 0.04902702 0.3814946 0.04922854 0.3814946 0.04922854 0.3818024 0.04943048 0.3821099 0.0496329 0.3821099 0.0496329 0.3824171 0.0498358 0.382724 0.05003911 0.382724 0.05003911 0.3830306 0.05024296 0.3839485 0.0508573 0.3830306 0.05024296 0.3833369 0.05044728 0.3839485 0.0508573 0.3833369 0.05044728 0.3836428 0.05065202 0.3839485 0.0508573 0.3839485 0.0508573 0.3842537 0.051063 0.3845588 0.05126917 0.3845588 0.05126917 0.3848634 0.05147582 0.3851678 0.05168294 0.3851678 0.05168294 0.3854719 0.05189049 0.3863822 0.05251604 0.3854719 0.05189049 0.3857756 0.05209857 0.3863822 0.05251604 0.3857756 0.05209857 0.3860791 0.05230706 0.3863822 0.05251604 0.3863822 0.05251604 0.3866849 0.05272549 0.3869874 0.05293536 0.3869874 0.05293536 0.3872895 0.05314576 0.3863822 0.05251604 0.3872895 0.05314576 0.3875913 0.05335658 0.3863822 0.05251604 0.3875913 0.05335658 0.3878928 0.05356788 0.388194 0.0537796 0.388194 0.0537796 0.3884948 0.05399185 0.3887953 0.05420452 0.3887953 0.05420452 0.3890955 0.05441766 0.3893954 0.05463129 0.3893954 0.05463129 0.3896949 0.05484533 0.3887953 0.05420452 0.3896949 0.05484533 0.3899941 0.05505985 0.3887953 0.05420452 0.3899941 0.05505985 0.390293 0.05527484 0.3911876 0.0559225 0.390293 0.05527484 0.3905915 0.05549025 0.3911876 0.0559225 0.3905915 0.05549025 0.3908897 0.05570614 0.3911876 0.0559225 0.3911876 0.0559225 0.3914851 0.05613929 0.3917824 0.05635654 0.3917824 0.05635654 0.3920792 0.05657428 0.3923758 0.05679249 0.3923758 0.05679249 0.392672 0.05701106 0.3929678 0.05723017 0.3929678 0.05723017 0.3932633 0.05744969 0.3935586 0.05766969 0.3935586 0.05766969 0.3938534 0.05789011 0.394736 0.05855417 0.3938534 0.05789011 0.3941479 0.05811107 0.394736 0.05855417 0.3941479 0.05811107 0.3944422 0.05833238 0.394736 0.05855417 0.394736 0.05855417 0.3950295 0.05877643 0.3959079 0.05944585 0.3950295 0.05877643 0.3953226 0.05899912 0.3959079 0.05944585 0.3953226 0.05899912 0.3956155 0.05922228 0.3959079 0.05944585 0.3959079 0.05944585 0.3962001 0.05966991 0.3964919 0.05989438 0.3964919 0.05989438 0.3967833 0.06011933 0.3970744 0.06034475 0.3970744 0.06034475 0.3973652 0.06057053 0.3976556 0.06079685 0.3976556 0.06079685 0.3979457 0.06102359 0.3970744 0.06034475 0.3979457 0.06102359 0.3982354 0.06125074 0.3970744 0.06034475 0.3982354 0.06125074 0.3985247 0.06147837 0.3993907 0.06216382 0.3985247 0.06147837 0.3988137 0.06170636 0.3993907 0.06216382 0.3988137 0.06170636 0.3991024 0.06193488 0.3993907 0.06216382 0.3993907 0.06216382 0.3996787 0.06239324 0.3999663 0.06262302 0.3999663 0.06262302 0.4002535 0.06285333 0.3993907 0.06216382 0.4002535 0.06285333 0.4005404 0.063084 0.3993907 0.06216382 0.4005404 0.063084 0.400827 0.06331515 0.4011132 0.06354677 0.4011132 0.06354677 0.401399 0.06377875 0.4016845 0.06401121 0.4016845 0.06401121 0.4019696 0.06424415 0.4028229 0.06494545 0.4019696 0.06424415 0.4022544 0.0644775 0.4028229 0.06494545 0.4022544 0.0644775 0.4025388 0.06471127 0.4028229 0.06494545 0.4028229 0.06494545 0.4031065 0.06518012 0.4033899 0.0654152 0.4033899 0.0654152 0.4036728 0.0656507 0.4028229 0.06494545 0.4036728 0.0656507 0.4039555 0.06588661 0.4028229 0.06494545 0.4039555 0.06588661 0.4042377 0.066123 0.4045196 0.06635981 0.4045196 0.06635981 0.4048011 0.0665971 0.4050822 0.06683474 0.4050822 0.06683474 0.405363 0.06707286 0.4056435 0.0673114 0.4056435 0.0673114 0.4059235 0.06755036 0.4050822 0.06683474 0.4059235 0.06755036 0.4062032 0.06778979 0.4050822 0.06683474 0.4062032 0.06778979 0.4064825 0.06802958 0.4067615 0.06826984 0.4067615 0.06826984 0.4070401 0.06851053 0.4062032 0.06778979 0.4070401 0.06851053 0.4073183 0.06875163 0.4062032 0.06778979 0.4073183 0.06875163 0.4075961 0.06899321 0.4078736 0.06923514 0.4078736 0.06923514 0.4081507 0.06947755 0.4073183 0.06875163 0.4081507 0.06947755 0.4084274 0.06972038 0.4073183 0.06875163 0.4084274 0.06972038 0.4087038 0.06996357 0.4089798 0.07020723 0.4089798 0.07020723 0.4092554 0.07045131 0.4084274 0.06972038 0.4092554 0.07045131 0.4095306 0.07069581 0.4084274 0.06972038 0.4095306 0.07069581 0.4098055 0.07094079 0.41008 0.07118612 0.41008 0.07118612 0.4103541 0.07143187 0.4106279 0.07167804 0.4106279 0.07167804 0.4109011 0.07192468 0.411719 0.072667 0.4109011 0.07192468 0.4111741 0.07217168 0.411719 0.072667 0.4111741 0.07217168 0.4114468 0.07241916 0.411719 0.072667 0.411719 0.072667 0.4119908 0.07291531 0.4122623 0.07316398 0.4122623 0.07316398 0.4125334 0.07341313 0.411719 0.072667 0.4125334 0.07341313 0.412804 0.07366263 0.411719 0.072667 0.412804 0.07366263 0.4130743 0.07391262 0.4138829 0.07466495 0.4130743 0.07391262 0.4133442 0.07416296 0.4138829 0.07466495 0.4133442 0.07416296 0.4136138 0.07441371 0.4138829 0.07466495 0.4138829 0.07466495 0.4141517 0.07491654 0.4144201 0.07516855 0.4144201 0.07516855 0.4146881 0.07542097 0.4149557 0.07567381 0.4149557 0.07567381 0.4152229 0.07592701 0.4154897 0.07618069 0.4154897 0.07618069 0.4157562 0.07643473 0.4149557 0.07567381 0.4157562 0.07643473 0.4160223 0.07668924 0.4149557 0.07567381 0.4160223 0.07668924 0.4162879 0.07694411 0.4165531 0.07719939 0.4165531 0.07719939 0.416818 0.0774551 0.4170825 0.07771116 0.4170825 0.07771116 0.4173466 0.0779677 0.4176103 0.07822459 0.4176103 0.07822459 0.4178736 0.07848191 0.4181365 0.07873958 0.4181365 0.07873958 0.418399 0.07899773 0.4186611 0.07925623 0.4186611 0.07925623 0.4189229 0.07951515 0.4181365 0.07873958 0.4189229 0.07951515 0.4191842 0.07977449 0.4181365 0.07873958 0.4191842 0.07977449 0.4194451 0.08003425 0.4197056 0.08029437 0.4197056 0.08029437 0.4199658 0.0805549 0.4191842 0.07977449 0.4199658 0.0805549 0.4202255 0.08081579 0.4191842 0.07977449 0.4202255 0.08081579 0.4204848 0.08107709 0.4207437 0.08133882 0.4207437 0.08133882 0.4210023 0.08160096 0.4202255 0.08081579 0.4210023 0.08160096 0.4212604 0.08186346 0.4202255 0.08081579 0.4212604 0.08186346 0.4215181 0.08212637 0.4217754 0.08238965 0.4217754 0.08238965 0.4220323 0.08265334 0.4212604 0.08186346 0.4220323 0.08265334 0.4222888 0.08291745 0.4212604 0.08186346 0.4222888 0.08291745 0.4225449 0.08318191 0.4228006 0.08344686 0.4228006 0.08344686 0.4230559 0.0837121 0.4233108 0.08397775 0.4233108 0.08397775 0.4235652 0.08424383 0.4243262 0.08504432 0.4235652 0.08424383 0.4238193 0.08451026 0.4243262 0.08504432 0.4238193 0.08451026 0.4240729 0.08477705 0.4243262 0.08504432 0.4243262 0.08504432 0.424579 0.08531188 0.4248315 0.08557987 0.4248315 0.08557987 0.4250835 0.08584827 0.4253351 0.08611702 0.4253351 0.08611702 0.4255862 0.0863862 0.425837 0.08665573 0.425837 0.08665573 0.4260874 0.08692568 0.4253351 0.08611702 0.4260874 0.08692568 0.4263373 0.08719593 0.4253351 0.08611702 0.4263373 0.08719593 0.4265869 0.08746665 0.4273329 0.08828103 0.4265869 0.08746665 0.426836 0.08773773 0.4273329 0.08828103 0.426836 0.08773773 0.4270847 0.08800917 0.4273329 0.08828103 0.4273329 0.08828103 0.4275808 0.08855324 0.4278283 0.08882582 0.4278283 0.08882582 0.4280753 0.08909881 0.4273329 0.08828103 0.4280753 0.08909881 0.4283219 0.08937215 0.4273329 0.08828103 0.4283219 0.08937215 0.4285681 0.08964586 0.4288139 0.08991998 0.4288139 0.08991998 0.4290592 0.09019446 0.4293041 0.09046936 0.4293041 0.09046936 0.4295486 0.09074455 0.4302796 0.09157252 0.4295486 0.09074455 0.4297927 0.09102016 0.4302796 0.09157252 0.4297927 0.09102016 0.4300364 0.09129619 0.4302796 0.09157252 0.4302796 0.09157252 0.4305225 0.09184926 0.4307649 0.09212636 0.4307649 0.09212636 0.4310068 0.09240382 0.4302796 0.09157252 0.4310068 0.09240382 0.4312483 0.0926817 0.4302796 0.09157252 0.4312483 0.0926817 0.4314894 0.09295994 0.4322102 0.09379678 0.4314894 0.09295994 0.4317301 0.09323847 0.4322102 0.09379678 0.4317301 0.09323847 0.4319704 0.09351742 0.4322102 0.09379678 0.4322102 0.09379678 0.4324496 0.09407645 0.4331652 0.09491771 0.4324496 0.09407645 0.4326885 0.09435653 0.4331652 0.09491771 0.4326885 0.09435653 0.4329271 0.09463691 0.4331652 0.09491771 0.4331652 0.09491771 0.4334029 0.09519886 0.4336401 0.09548038 0.4336401 0.09548038 0.4338769 0.09576231 0.4341133 0.09604454 0.4341133 0.09604454 0.4343493 0.09632712 0.4350546 0.09717714 0.4343493 0.09632712 0.4345848 0.09661012 0.4350546 0.09717714 0.4345848 0.09661012 0.4348199 0.09689342 0.4350546 0.09717714 0.4350546 0.09717714 0.4352887 0.09746116 0.4355225 0.09774559 0.4355225 0.09774559 0.4357559 0.09803032 0.4350546 0.09717714 0.4357559 0.09803032 0.4359887 0.09831547 0.4350546 0.09717714 0.4359887 0.09831547 0.4362212 0.09860098 0.4364532 0.09888678 0.4364532 0.09888678 0.4366848 0.099173 0.4369159 0.09945952 0.4369159 0.09945952 0.4371467 0.09974646 0.4378361 0.1006093 0.4371467 0.09974646 0.4373769 0.1000337 0.4378361 0.1006093 0.4373769 0.1000337 0.4376068 0.1003213 0.4378361 0.1006093 0.4378361 0.1006093 0.4380651 0.1008976 0.4382936 0.1011862 0.4382936 0.1011862 0.4385216 0.1014752 0.4378361 0.1006093 0.4385216 0.1014752 0.4387493 0.1017646 0.4378361 0.1006093 0.4387493 0.1017646 0.4389764 0.1020543 0.4396553 0.1029255 0.4389764 0.1020543 0.4392032 0.1023444 0.4396553 0.1029255 0.4392032 0.1023444 0.4394294 0.1026348 0.4396553 0.1029255 0.4396553 0.1029255 0.4398806 0.1032167 0.4401056 0.1035081 0.4401056 0.1035081 0.44033 0.1037999 0.4405541 0.104092 0.4405541 0.104092 0.4407777 0.1043845 0.4410009 0.1046773 0.4410009 0.1046773 0.4412236 0.1049705 0.4405541 0.104092 0.4412236 0.1049705 0.4414458 0.105264 0.4405541 0.104092 0.4414458 0.105264 0.4416676 0.1055578 0.4418889 0.105852 0.4418889 0.105852 0.4421098 0.1061465 0.4414458 0.105264 0.4421098 0.1061465 0.4423303 0.1064414 0.4414458 0.105264 0.4423303 0.1064414 0.4425503 0.1067366 0.4427698 0.1070321 0.4427698 0.1070321 0.4429889 0.107328 0.4432075 0.1076242 0.4432075 0.1076242 0.4434257 0.1079208 0.4436434 0.1082177 0.4436434 0.1082177 0.4438607 0.1085149 0.4440775 0.1088124 0.4440775 0.1088124 0.4442939 0.1091103 0.4445097 0.1094085 0.4445097 0.1094085 0.4447252 0.109707 0.4440775 0.1088124 0.4447252 0.109707 0.4449402 0.1100059 0.4440775 0.1088124 0.4449402 0.1100059 0.4451547 0.1103051 0.4457954 0.1112046 0.4451547 0.1103051 0.4453687 0.1106046 0.4457954 0.1112046 0.4453687 0.1106046 0.4455823 0.1109045 0.4457954 0.1112046 0.4457954 0.1112046 0.4460082 0.1115052 0.4462203 0.111806 0.4462203 0.111806 0.4464321 0.1121072 0.4466434 0.1124086 0.4466434 0.1124086 0.4468542 0.1127105 0.447484 0.1136178 0.4468542 0.1127105 0.4470646 0.1130126 0.447484 0.1136178 0.4470646 0.1130126 0.4472745 0.1133151 0.447484 0.1136178 0.447484 0.1136178 0.4476929 0.1139209 0.4479014 0.1142243 0.4479014 0.1142243 0.4481095 0.1145281 0.447484 0.1136178 0.4481095 0.1145281 0.4483171 0.1148321 0.447484 0.1136178 0.4483171 0.1148321 0.4485242 0.1151365 0.4487308 0.1154412 0.4487308 0.1154412 0.448937 0.1157462 0.4491427 0.1160515 0.4491427 0.1160515 0.4493479 0.1163572 0.4495527 0.1166631 0.4495527 0.1166631 0.449757 0.1169694 0.4491427 0.1160515 0.449757 0.1169694 0.4499608 0.117276 0.4491427 0.1160515 0.4499608 0.117276 0.4501642 0.1175829 0.4503671 0.1178901 0.4503671 0.1178901 0.4505695 0.1181976 0.4507715 0.1185054 0.4507715 0.1185054 0.4509729 0.1188135 0.4511739 0.119122 0.4511739 0.119122 0.4513745 0.1194307 0.4515745 0.1197398 0.4515745 0.1197398 0.4517741 0.1200491 0.45237 0.1209791 0.4517741 0.1200491 0.4519732 0.1203588 0.45237 0.1209791 0.4519732 0.1203588 0.4521718 0.1206688 0.45237 0.1209791 0.45237 0.1209791 0.4525676 0.1212897 0.4531578 0.1222232 0.4525676 0.1212897 0.4527649 0.1216006 0.4531578 0.1222232 0.4527649 0.1216006 0.4529616 0.1219117 0.4531578 0.1222232 0.4531578 0.1222232 0.4533536 0.122535 0.4535489 0.1228471 0.4535489 0.1228471 0.4537437 0.1231595 0.453938 0.1234722 0.453938 0.1234722 0.4541319 0.1237851 0.4547106 0.1247259 0.4541319 0.1237851 0.4543253 0.1240984 0.4547106 0.1247259 0.4543253 0.1240984 0.4545181 0.124412 0.4547106 0.1247259 0.4547106 0.1247259 0.4549025 0.1250401 0.4550939 0.1253545 0.4550939 0.1253545 0.4552849 0.1256693 0.4547106 0.1247259 0.4552849 0.1256693 0.4554753 0.1259843 0.4547106 0.1247259 0.4554753 0.1259843 0.4556654 0.1262997 0.4562324 0.1272475 0.4556654 0.1262997 0.4558548 0.1266153 0.4562324 0.1272475 0.4558548 0.1266153 0.4560439 0.1269312 0.4562324 0.1272475 0.4562324 0.1272475 0.4564205 0.127564 0.4566081 0.1278807 0.4566081 0.1278807 0.4567952 0.1281978 0.4569817 0.1285152 0.4569817 0.1285152 0.4571679 0.1288328 0.4573535 0.1291508 0.4573535 0.1291508 0.4575386 0.129469 0.4577233 0.1297875 0.4577233 0.1297875 0.4579074 0.1301063 0.4580911 0.1304253 0.4580911 0.1304253 0.4582743 0.1307446 0.4584569 0.1310643 0.4584569 0.1310643 0.4586392 0.1313842 0.4588209 0.1317044 0.4588209 0.1317044 0.4590021 0.1320249 0.4584569 0.1310643 0.4590021 0.1320249 0.4591828 0.1323456 0.4584569 0.1310643 0.4591828 0.1323456 0.4593631 0.1326667 0.4599008 0.1336314 0.4593631 0.1326667 0.4595428 0.1329879 0.4599008 0.1336314 0.4595428 0.1329879 0.4597221 0.1333095 0.4599008 0.1336314 0.4599008 0.1336314 0.460079 0.1339535 0.4602568 0.1342759 0.4602568 0.1342759 0.4604341 0.1345986 0.4606109 0.1349215 0.4606109 0.1349215 0.4607871 0.1352447 0.460963 0.1355682 0.460963 0.1355682 0.4611382 0.1358919 0.4606109 0.1349215 0.4611382 0.1358919 0.461313 0.1362159 0.4606109 0.1349215 0.461313 0.1362159 0.4614873 0.1365402 0.4616611 0.1368647 0.4616611 0.1368647 0.4618344 0.1371896 0.4620072 0.1375147 0.4620072 0.1375147 0.4621795 0.13784 0.4623513 0.1381656 0.4623513 0.1381656 0.4625226 0.1384915 0.4620072 0.1375147 0.4625226 0.1384915 0.4626934 0.1388176 0.4620072 0.1375147 0.4626934 0.1388176 0.4628637 0.139144 0.4630335 0.1394707 0.4630335 0.1394707 0.4632028 0.1397976 0.4626934 0.1388176 0.4632028 0.1397976 0.4633716 0.1401247 0.4626934 0.1388176 0.4633716 0.1401247 0.4635399 0.1404522 0.4640418 0.1414361 0.4635399 0.1404522 0.4637077 0.1407799 0.4640418 0.1414361 0.4637077 0.1407799 0.463875 0.1411079 0.4640418 0.1414361 0.4640418 0.1414361 0.4642081 0.1417645 0.4647039 0.1427515 0.4642081 0.1417645 0.4643738 0.1420933 0.4647039 0.1427515 0.4643738 0.1420933 0.4645391 0.1424222 0.4647039 0.1427515 0.4647039 0.1427515 0.4648681 0.1430809 0.4650319 0.1434106 0.4650319 0.1434106 0.4651951 0.1437407 0.4647039 0.1427515 0.4651951 0.1437407 0.4653579 0.1440709 0.4647039 0.1427515 0.4653579 0.1440709 0.4655202 0.1444013 0.4656819 0.1447321 0.4656819 0.1447321 0.4658431 0.1450631 0.4653579 0.1440709 0.4658431 0.1450631 0.4660038 0.1453943 0.4653579 0.1440709 0.4660038 0.1453943 0.466164 0.1457257 0.4663237 0.1460574 0.4663237 0.1460574 0.4664829 0.1463894 0.4660038 0.1453943 0.4664829 0.1463894 0.4666416 0.1467216 0.4660038 0.1453943 0.4666416 0.1467216 0.4667997 0.1470541 0.4669575 0.1473867 0.4669575 0.1473867 0.4671146 0.1477197 0.4666416 0.1467216 0.4671146 0.1477197 0.4672712 0.1480528 0.4666416 0.1467216 0.4672712 0.1480528 0.4674273 0.1483862 0.4678927 0.1493879 0.4674273 0.1483862 0.467583 0.1487199 0.4678927 0.1493879 0.467583 0.1487199 0.4677381 0.1490538 0.4678927 0.1493879 0.4678927 0.1493879 0.4680467 0.1497223 0.4682003 0.1500568 0.4682003 0.1500568 0.4683533 0.1503917 0.4685059 0.1507267 0.4685059 0.1507267 0.4686579 0.1510621 0.4688094 0.1513976 0.4688094 0.1513976 0.4689604 0.1517333 0.4685059 0.1507267 0.4689604 0.1517333 0.4691109 0.1520694 0.4685059 0.1507267 0.4691109 0.1520694 0.4692609 0.1524056 0.4694103 0.152742 0.4694103 0.152742 0.4695593 0.1530787 0.4697077 0.1534156 0.4697077 0.1534156 0.4698556 0.1537528 0.470003 0.1540902 0.470003 0.1540902 0.4701498 0.1544278 0.4697077 0.1534156 0.4701498 0.1544278 0.4702962 0.1547656 0.4697077 0.1534156 0.4702962 0.1547656 0.470442 0.1551036 0.4705873 0.1554419 0.4705873 0.1554419 0.4707321 0.1557804 0.4702962 0.1547656 0.4707321 0.1557804 0.4708764 0.1561191 0.4702962 0.1547656 0.4708764 0.1561191 0.4710201 0.156458 0.4714483 0.1574761 0.4710201 0.156458 0.4711633 0.1567972 0.4714483 0.1574761 0.4711633 0.1567972 0.4713061 0.1571365 0.4714483 0.1574761 0.4714483 0.1574761 0.4715899 0.1578159 0.4717311 0.1581559 0.4717311 0.1581559 0.4718717 0.1584962 0.4720118 0.1588367 0.4720118 0.1588367 0.4721514 0.1591773 0.472567 0.1602006 0.4721514 0.1591773 0.4722905 0.1595182 0.472567 0.1602006 0.4722905 0.1595182 0.472429 0.1598593 0.472567 0.1602006 0.472567 0.1602006 0.4727045 0.1605421 0.4731138 0.1615679 0.4727045 0.1605421 0.4728415 0.1608839 0.4731138 0.1615679 0.4728415 0.1608839 0.4729779 0.1612258 0.4731138 0.1615679 0.4731138 0.1615679 0.4732492 0.1619103 0.4733841 0.1622529 0.4733841 0.1622529 0.4735184 0.1625956 0.4736523 0.1629386 0.4736523 0.1629386 0.4737855 0.1632818 0.4741822 0.1643126 0.4737855 0.1632818 0.4739183 0.1636251 0.4741822 0.1643126 0.4739183 0.1636251 0.4740505 0.1639688 0.4741822 0.1643126 0.4741822 0.1643126 0.4743134 0.1646565 0.4747037 0.1656897 0.4743134 0.1646565 0.474444 0.1650007 0.4747037 0.1656897 0.474444 0.1650007 0.4745742 0.1653451 0.4747037 0.1656897 0.4747037 0.1656897 0.4748328 0.1660345 0.4749614 0.1663795 0.4749614 0.1663795 0.4750894 0.1667247 0.4747037 0.1656897 0.4750894 0.1667247 0.4752169 0.16707 0.4747037 0.1656897 0.4752169 0.16707 0.4753438 0.1674156 0.4754702 0.1677614 0.4754702 0.1677614 0.4755961 0.1681073 0.4757214 0.1684535 0.4757214 0.1684535 0.4758463 0.1687999 0.4762176 0.16984 0.4758463 0.1687999 0.4759706 0.1691464 0.4762176 0.16984 0.4759706 0.1691464 0.4760943 0.1694931 0.4762176 0.16984 0.4762176 0.16984 0.4763402 0.1701872 0.4764624 0.1705344 0.4764624 0.1705344 0.4765841 0.1708819 0.4767051 0.1712296 0.4767051 0.1712296 0.4768257 0.1715775 0.4771842 0.1726222 0.4768257 0.1715775 0.4769458 0.1719255 0.4771842 0.1726222 0.4769458 0.1719255 0.4770653 0.1722737 0.4771842 0.1726222 0.4771842 0.1726222 0.4773026 0.1729707 0.4774205 0.1733195 0.4774205 0.1733195 0.4775379 0.1736685 0.4776547 0.1740176 0.4776547 0.1740176 0.477771 0.1743668 0.4778867 0.1747164 0.4778867 0.1747164 0.478002 0.175066 0.4781166 0.1754159 0.4781166 0.1754159 0.4782308 0.1757659 0.47857 0.1768169 0.4782308 0.1757659 0.4783444 0.1761161 0.47857 0.1768169 0.4783444 0.1761161 0.4784575 0.1764664 0.47857 0.1768169 0.47857 0.1768169 0.478682 0.1771677 0.4787935 0.1775186 0.4787935 0.1775186 0.4789044 0.1778696 0.4790148 0.1782208 0.4790148 0.1782208 0.4791246 0.1785722 0.4792339 0.1789237 0.4792339 0.1789237 0.4793426 0.1792755 0.4790148 0.1782208 0.4793426 0.1792755 0.4794509 0.1796274 0.4790148 0.1782208 0.4794509 0.1796274 0.4795585 0.1799794 0.4798783 0.1810365 0.4795585 0.1799794 0.4796657 0.1803317 0.4798783 0.1810365 0.4796657 0.1803317 0.4797723 0.180684 0.4798783 0.1810365 0.4798783 0.1810365 0.4799839 0.1813893 0.4800888 0.1817421 0.4800888 0.1817421 0.4801933 0.1820952 0.4802972 0.1824484 0.4802972 0.1824484 0.4804005 0.1828017 0.4807073 0.1838628 0.4804005 0.1828017 0.4805033 0.1831552 0.4807073 0.1838628 0.4805033 0.1831552 0.4806056 0.1835089 0.4807073 0.1838628 0.4807073 0.1838628 0.4808085 0.1842167 0.4811088 0.1852796 0.4808085 0.1842167 0.4809091 0.1845709 0.4811088 0.1852796 0.4809091 0.1845709 0.4810093 0.1849251 0.4811088 0.1852796 0.4811088 0.1852796 0.4812078 0.1856341 0.4815015 0.1866989 0.4812078 0.1856341 0.4813063 0.1859889 0.4815015 0.1866989 0.4813063 0.1859889 0.4814042 0.1863438 0.4815015 0.1866989 0.4815015 0.1866989 0.4815984 0.187054 0.4818856 0.1881205 0.4815984 0.187054 0.4816946 0.1874094 0.4818856 0.1881205 0.4816946 0.1874094 0.4817904 0.1877649 0.4818856 0.1881205 0.4818856 0.1881205 0.4819803 0.1884763 0.4820743 0.1888322 0.4820743 0.1888322 0.4821679 0.1891883 0.4818856 0.1881205 0.4821679 0.1891883 0.4822609 0.1895445 0.4818856 0.1881205 0.4822609 0.1895445 0.4823534 0.1899008 0.4824453 0.1902573 0.4824453 0.1902573 0.4825367 0.190614 0.4826275 0.1909708 0.4826275 0.1909708 0.4827178 0.1913277 0.4829853 0.1923993 0.4827178 0.1913277 0.4828075 0.1916847 0.4829853 0.1923993 0.4828075 0.1916847 0.4828967 0.1920419 0.4829853 0.1923993 0.4829853 0.1923993 0.4830734 0.1927567 0.4831609 0.1931143 0.4831609 0.1931143 0.4832479 0.193472 0.4829853 0.1923993 0.4832479 0.193472 0.4833344 0.1938299 0.4829853 0.1923993 0.4833344 0.1938299 0.4834203 0.1941879 0.4835056 0.194546 0.4835056 0.194546 0.4835904 0.1949043 0.4833344 0.1938299 0.4835904 0.1949043 0.4836746 0.1952627 0.4833344 0.1938299 0.4836746 0.1952627 0.4837583 0.1956212 0.4838414 0.1959798 0.4838414 0.1959798 0.483924 0.1963386 0.4840061 0.1966975 0.4840061 0.1966975 0.4840875 0.1970565 0.4841685 0.1974157 0.4841685 0.1974157 0.4842489 0.197775 0.4843288 0.1981343 0.4843288 0.1981343 0.484408 0.1984938 0.4844868 0.1988535 0.4844868 0.1988535 0.4845649 0.1992133 0.4843288 0.1981343 0.4845649 0.1992133 0.4846426 0.1995731 0.4843288 0.1981343 0.4846426 0.1995731 0.4847196 0.1999331 0.4849476 0.2010138 0.4847196 0.1999331 0.4847962 0.2002933 0.4849476 0.2010138 0.4847962 0.2002933 0.4848722 0.2006534 0.4849476 0.2010138 0.4849476 0.2010138 0.4850224 0.2013743 0.4850968 0.2017349 0.4850968 0.2017349 0.4851705 0.2020956 0.4849476 0.2010138 0.4851705 0.2020956 0.4852437 0.2024564 0.4849476 0.2010138 0.4852437 0.2024564 0.4853163 0.2028173 0.4853885 0.2031783 0.4853885 0.2031783 0.48546 0.2035394 0.485531 0.2039006 0.485531 0.2039006 0.4856014 0.204262 0.4856714 0.2046235 0.4856714 0.2046235 0.4857407 0.2049851 0.485531 0.2039006 0.4857407 0.2049851 0.4858095 0.2053467 0.485531 0.2039006 0.4858095 0.2053467 0.4858776 0.2057085 0.4859453 0.2060704 0.4859453 0.2060704 0.4860124 0.2064324 0.4858095 0.2053467 0.4860124 0.2064324 0.486079 0.2067945 0.4858095 0.2053467 0.486079 0.2067945 0.486145 0.2071567 0.4862104 0.2075189 0.4862104 0.2075189 0.4862753 0.2078813 0.4863396 0.2082439 0.4863396 0.2082439 0.4864034 0.2086064 0.4864667 0.2089691 0.4864667 0.2089691 0.4865293 0.2093319 0.4863396 0.2082439 0.4865293 0.2093319 0.4865914 0.2096948 0.4863396 0.2082439 0.4865914 0.2096948 0.4866529 0.2100577 0.4868342 0.2111473 0.4866529 0.2100577 0.486714 0.2104208 0.4868342 0.2111473 0.486714 0.2104208 0.4867744 0.210784 0.4868342 0.2111473 0.4868342 0.2111473 0.4868935 0.2115106 0.4869523 0.211874 0.4869523 0.211874 0.4870105 0.2122375 0.4870682 0.2126011 0.4870682 0.2126011 0.4871253 0.2129648 0.4872932 0.2140565 0.4871253 0.2129648 0.4871818 0.2133287 0.4872932 0.2140565 0.4871818 0.2133287 0.4872378 0.2136925 0.4872932 0.2140565 0.4872932 0.2140565 0.487348 0.2144205 0.4875093 0.2155132 0.487348 0.2144205 0.4874024 0.2147846 0.4875093 0.2155132 0.4874024 0.2147846 0.4874561 0.2151489 0.4875093 0.2155132 0.4875093 0.2155132 0.4875619 0.2158775 0.487614 0.216242 0.487614 0.216242 0.4876655 0.2166065 0.4877164 0.2169712 0.4877164 0.2169712 0.4877668 0.2173358 0.4879146 0.2184303 0.4877668 0.2173358 0.4878166 0.2177006 0.4879146 0.2184303 0.4878166 0.2177006 0.4878659 0.2180655 0.4879146 0.2184303 0.4879146 0.2184303 0.4879627 0.2187954 0.4881038 0.2198908 0.4879627 0.2187954 0.4880104 0.2191604 0.4881038 0.2198908 0.4880104 0.2191604 0.4880574 0.2195256 0.4881038 0.2198908 0.4881038 0.2198908 0.4881498 0.220256 0.4881951 0.2206214 0.4881951 0.2206214 0.4882399 0.2209869 0.4881038 0.2198908 0.4882399 0.2209869 0.4882841 0.2213523 0.4881038 0.2198908 0.4882841 0.2213523 0.4883278 0.2217179 0.4883708 0.2220835 0.4883708 0.2220835 0.4884134 0.2224492 0.4884554 0.2228149 0.4884554 0.2228149 0.4884968 0.2231808 0.4885377 0.2235466 0.4885377 0.2235466 0.488578 0.2239126 0.4884554 0.2228149 0.488578 0.2239126 0.4886177 0.2242786 0.4884554 0.2228149 0.4886177 0.2242786 0.4886569 0.2246447 0.488771 0.2257432 0.4886569 0.2246447 0.4886955 0.2250108 0.488771 0.2257432 0.4886955 0.2250108 0.4887335 0.225377 0.488771 0.2257432 0.488771 0.2257432 0.488808 0.2261095 0.4888443 0.2264758 0.4888443 0.2264758 0.4888801 0.2268423 0.488771 0.2257432 0.4888801 0.2268423 0.4889154 0.2272087 0.488771 0.2257432 0.4889154 0.2272087 0.4889501 0.2275753 0.4889842 0.2279418 0.4889842 0.2279418 0.4890177 0.2283084 0.4890507 0.2286751 0.4890507 0.2286751 0.4890832 0.2290418 0.489115 0.2294086 0.489115 0.2294086 0.4891463 0.2297754 0.4890507 0.2286751 0.4891463 0.2297754 0.4891771 0.2301423 0.4890507 0.2286751 0.4891771 0.2301423 0.4892073 0.2305092 0.4892368 0.2308762 0.4892368 0.2308762 0.4892659 0.2312432 0.4891771 0.2301423 0.4892659 0.2312432 0.4892944 0.2316102 0.4891771 0.2301423 0.4892944 0.2316102 0.4893223 0.2319774 0.4894027 0.2330788 0.4893223 0.2319774 0.4893497 0.2323445 0.4894027 0.2330788 0.4893497 0.2323445 0.4893765 0.2327117 0.4894027 0.2330788 0.4894027 0.2330788 0.4894284 0.2334461 0.4894535 0.2338134 0.4894535 0.2338134 0.4894781 0.2341808 0.4895021 0.2345482 0.4895021 0.2345482 0.4895255 0.2349156 0.4895924 0.236018 0.4895255 0.2349156 0.4895483 0.235283 0.4895924 0.236018 0.4895483 0.235283 0.4895706 0.2356505 0.4895924 0.236018 0.4895924 0.236018 0.4896135 0.2363855 0.4896341 0.2367531 0.4896341 0.2367531 0.4896542 0.2371207 0.4896737 0.2374883 0.4896737 0.2374883 0.4896926 0.237856 0.4897109 0.2382237 0.4897109 0.2382237 0.4897287 0.2385914 0.4897459 0.2389592 0.4897459 0.2389592 0.4897626 0.239327 0.4897786 0.2396948 0.4897786 0.2396948 0.4897942 0.2400626 0.4897459 0.2389592 0.4897942 0.2400626 0.4898092 0.2404305 0.4897459 0.2389592 0.4898092 0.2404305 0.4898235 0.2407984 0.4898374 0.2411662 0.4898374 0.2411662 0.4898506 0.2415342 0.4898633 0.2419021 0.4898633 0.2419021 0.4898755 0.2422701 0.4898871 0.242638 0.4898871 0.242638 0.4898981 0.243006 0.4899085 0.243374 0.4899085 0.243374 0.4899184 0.2437421 0.4899277 0.2441101 0.4899277 0.2441101 0.4899365 0.2444781 0.4899446 0.2448462 0.4899446 0.2448462 0.4899523 0.2452143 0.4899718 0.2463186 0.4899523 0.2452143 0.4899594 0.2455824 0.4899718 0.2463186 0.4899594 0.2455824 0.4899659 0.2459505 0.4899718 0.2463186 0.4899718 0.2463186 0.4899771 0.2466867 0.4899898 0.2477911 0.4899771 0.2466867 0.489982 0.2470548 0.4899898 0.2477911 0.489982 0.2470548 0.4899862 0.2474229 0.4899898 0.2477911 0.4899898 0.2477911 0.4899929 0.2481592 0.4899955 0.2485274 0.4899955 0.2485274 0.4899975 0.2488955 0.4899898 0.2477911 0.4899975 0.2488955 0.4899989 0.2492637 0.4899898 0.2477911 0.4899989 0.2492637 0.4899997 0.2496318 0.4899989 0.2507363 0.4899997 0.2496318 0.49 0.25 0.4899989 0.2507363 0.49 0.25 0.4899997 0.2503681 0.4899989 0.2507363 0.4899989 0.2507363 0.4899975 0.2511045 0.4899898 0.2522089 0.4899975 0.2511045 0.4899955 0.2514726 0.4899898 0.2522089 0.4899955 0.2514726 0.4899929 0.2518408 0.4899898 0.2522089 0.4899898 0.2522089 0.4899862 0.252577 0.489982 0.2529451 0.489982 0.2529451 0.4899771 0.2533133 0.4899898 0.2522089 0.4899771 0.2533133 0.4899718 0.2536814 0.4899898 0.2522089 0.4899718 0.2536814 0.4899659 0.2540495 0.4899594 0.2544176 0.4899594 0.2544176 0.4899523 0.2547857 0.4899718 0.2536814 0.4899523 0.2547857 0.4899446 0.2551538 0.4899718 0.2536814 0.4899446 0.2551538 0.4899365 0.2555218 0.4899277 0.2558899 0.4899277 0.2558899 0.4899184 0.2562579 0.4899085 0.256626 0.4899085 0.256626 0.4898981 0.256994 0.4898871 0.257362 0.4898871 0.257362 0.4898755 0.2577299 0.4898633 0.2580979 0.4898633 0.2580979 0.4898506 0.2584658 0.4898374 0.2588337 0.4898374 0.2588337 0.4898235 0.2592016 0.4898092 0.2595695 0.4898092 0.2595695 0.4897942 0.2599374 0.4897459 0.2610408 0.4897942 0.2599374 0.4897786 0.2603052 0.4897459 0.2610408 0.4897786 0.2603052 0.4897626 0.260673 0.4897459 0.2610408 0.4897459 0.2610408 0.4897287 0.2614085 0.4896737 0.2625116 0.4897287 0.2614085 0.4897109 0.2617762 0.4896737 0.2625116 0.4897109 0.2617762 0.4896926 0.2621439 0.4896737 0.2625116 0.4896737 0.2625116 0.4896542 0.2628793 0.4896341 0.2632468 0.4896341 0.2632468 0.4896135 0.2636144 0.4895924 0.263982 0.4895924 0.263982 0.4895706 0.2643495 0.4895483 0.264717 0.4895483 0.264717 0.4895255 0.2650844 0.4895021 0.2654518 0.4895021 0.2654518 0.4894781 0.2658192 0.4894027 0.2669211 0.4894781 0.2658192 0.4894535 0.2661865 0.4894027 0.2669211 0.4894535 0.2661865 0.4894284 0.2665538 0.4894027 0.2669211 0.4894027 0.2669211 0.4893765 0.2672883 0.4893497 0.2676555 0.4893497 0.2676555 0.4893223 0.2680226 0.4892944 0.2683897 0.4892944 0.2683897 0.4892659 0.2687568 0.4891771 0.2698577 0.4892659 0.2687568 0.4892368 0.2691238 0.4891771 0.2698577 0.4892368 0.2691238 0.4892073 0.2694907 0.4891771 0.2698577 0.4891771 0.2698577 0.4891463 0.2702245 0.4890507 0.2713248 0.4891463 0.2702245 0.489115 0.2705913 0.4890507 0.2713248 0.489115 0.2705913 0.4890832 0.2709581 0.4890507 0.2713248 0.4890507 0.2713248 0.4890177 0.2716915 0.4889842 0.2720581 0.4889842 0.2720581 0.4889501 0.2724247 0.4890507 0.2713248 0.4889501 0.2724247 0.4889154 0.2727912 0.4890507 0.2713248 0.4889154 0.2727912 0.4888801 0.2731577 0.488771 0.2742568 0.4888801 0.2731577 0.4888443 0.2735241 0.488771 0.2742568 0.4888443 0.2735241 0.488808 0.2738904 0.488771 0.2742568 0.488771 0.2742568 0.4887335 0.274623 0.4886955 0.2749892 0.4886955 0.2749892 0.4886569 0.2753553 0.488771 0.2742568 0.4886569 0.2753553 0.4886177 0.2757214 0.488771 0.2742568 0.4886177 0.2757214 0.488578 0.2760874 0.4884554 0.277185 0.488578 0.2760874 0.4885377 0.2764533 0.4884554 0.277185 0.4885377 0.2764533 0.4884968 0.2768192 0.4884554 0.277185 0.4884554 0.277185 0.4884134 0.2775508 0.4883708 0.2779164 0.4883708 0.2779164 0.4883278 0.2782821 0.4882841 0.2786477 0.4882841 0.2786477 0.4882399 0.2790132 0.4881038 0.2801092 0.4882399 0.2790132 0.4881951 0.2793785 0.4881038 0.2801092 0.4881951 0.2793785 0.4881498 0.2797439 0.4881038 0.2801092 0.4881038 0.2801092 0.4880574 0.2804744 0.4880104 0.2808396 0.4880104 0.2808396 0.4879627 0.2812046 0.4881038 0.2801092 0.4879627 0.2812046 0.4879146 0.2815696 0.4881038 0.2801092 0.4879146 0.2815696 0.4878659 0.2819345 0.4878166 0.2822993 0.4878166 0.2822993 0.4877668 0.2826641 0.4879146 0.2815696 0.4877668 0.2826641 0.4877164 0.2830289 0.4879146 0.2815696 0.4877164 0.2830289 0.4876655 0.2833935 0.487614 0.283758 0.487614 0.283758 0.4875619 0.2841224 0.4875093 0.2844868 0.4875093 0.2844868 0.4874561 0.2848511 0.4874024 0.2852153 0.4874024 0.2852153 0.487348 0.2855795 0.4875093 0.2844868 0.487348 0.2855795 0.4872932 0.2859435 0.4875093 0.2844868 0.4872932 0.2859435 0.4872378 0.2863075 0.4871818 0.2866714 0.4871818 0.2866714 0.4871253 0.2870351 0.4872932 0.2859435 0.4871253 0.2870351 0.4870682 0.2873988 0.4872932 0.2859435 0.4870682 0.2873988 0.4870105 0.2877624 0.4868342 0.2888527 0.4870105 0.2877624 0.4869523 0.2881259 0.4868342 0.2888527 0.4869523 0.2881259 0.4868935 0.2884894 0.4868342 0.2888527 0.4868342 0.2888527 0.4867744 0.289216 0.486714 0.2895792 0.486714 0.2895792 0.4866529 0.2899422 0.4868342 0.2888527 0.4866529 0.2899422 0.4865914 0.2903052 0.4868342 0.2888527 0.4865914 0.2903052 0.4865293 0.2906681 0.4863396 0.2917561 0.4865293 0.2906681 0.4864667 0.2910308 0.4863396 0.2917561 0.4864667 0.2910308 0.4864034 0.2913935 0.4863396 0.2917561 0.4863396 0.2917561 0.4862753 0.2921186 0.4862104 0.292481 0.4862104 0.292481 0.486145 0.2928433 0.486079 0.2932055 0.486079 0.2932055 0.4860124 0.2935676 0.4858095 0.2946532 0.4860124 0.2935676 0.4859453 0.2939296 0.4858095 0.2946532 0.4859453 0.2939296 0.4858776 0.2942914 0.4858095 0.2946532 0.4858095 0.2946532 0.4857407 0.2950149 0.485531 0.2960993 0.4857407 0.2950149 0.4856714 0.2953765 0.485531 0.2960993 0.4856714 0.2953765 0.4856014 0.2957379 0.485531 0.2960993 0.485531 0.2960993 0.48546 0.2964605 0.4853885 0.2968217 0.4853885 0.2968217 0.4853163 0.2971827 0.4852437 0.2975436 0.4852437 0.2975436 0.4851705 0.2979044 0.4849476 0.2989861 0.4851705 0.2979044 0.4850968 0.2982651 0.4849476 0.2989861 0.4850968 0.2982651 0.4850224 0.2986257 0.4849476 0.2989861 0.4849476 0.2989861 0.4848722 0.2993465 0.4847962 0.2997067 0.4847962 0.2997067 0.4847196 0.3000668 0.4849476 0.2989861 0.4847196 0.3000668 0.4846426 0.3004269 0.4849476 0.2989861 0.4846426 0.3004269 0.4845649 0.3007867 0.4843288 0.3018656 0.4845649 0.3007867 0.4844868 0.3011465 0.4843288 0.3018656 0.4844868 0.3011465 0.484408 0.3015061 0.4843288 0.3018656 0.4843288 0.3018656 0.4842489 0.302225 0.4841685 0.3025843 0.4841685 0.3025843 0.4840875 0.3029434 0.4840061 0.3033025 0.4840061 0.3033025 0.483924 0.3036614 0.4838414 0.3040201 0.4838414 0.3040201 0.4837583 0.3043788 0.4840061 0.3033025 0.4837583 0.3043788 0.4836746 0.3047373 0.4840061 0.3033025 0.4836746 0.3047373 0.4835904 0.3050957 0.4833344 0.3061701 0.4835904 0.3050957 0.4835056 0.305454 0.4833344 0.3061701 0.4835056 0.305454 0.4834203 0.3058121 0.4833344 0.3061701 0.4833344 0.3061701 0.4832479 0.3065279 0.4829853 0.3076007 0.4832479 0.3065279 0.4831609 0.3068857 0.4829853 0.3076007 0.4831609 0.3068857 0.4830734 0.3072432 0.4829853 0.3076007 0.4829853 0.3076007 0.4828967 0.3079581 0.4828075 0.3083152 0.4828075 0.3083152 0.4827178 0.3086723 0.4829853 0.3076007 0.4827178 0.3086723 0.4826275 0.3090292 0.4829853 0.3076007 0.4826275 0.3090292 0.4825367 0.309386 0.4824453 0.3097426 0.4824453 0.3097426 0.4823534 0.3100991 0.4822609 0.3104555 0.4822609 0.3104555 0.4821679 0.3108117 0.4818856 0.3118795 0.4821679 0.3108117 0.4820743 0.3111678 0.4818856 0.3118795 0.4820743 0.3111678 0.4819803 0.3115237 0.4818856 0.3118795 0.4818856 0.3118795 0.4817904 0.3122351 0.4816946 0.3125906 0.4816946 0.3125906 0.4815984 0.3129459 0.4818856 0.3118795 0.4815984 0.3129459 0.4815015 0.3133011 0.4818856 0.3118795 0.4815015 0.3133011 0.4814042 0.3136562 0.4813063 0.314011 0.4813063 0.314011 0.4812078 0.3143658 0.4811088 0.3147204 0.4811088 0.3147204 0.4810093 0.3150748 0.4809091 0.3154291 0.4809091 0.3154291 0.4808085 0.3157833 0.4811088 0.3147204 0.4808085 0.3157833 0.4807073 0.3161373 0.4811088 0.3147204 0.4807073 0.3161373 0.4806056 0.3164911 0.4805033 0.3168447 0.4805033 0.3168447 0.4804005 0.3171982 0.4807073 0.3161373 0.4804005 0.3171982 0.4802972 0.3175516 0.4807073 0.3161373 0.4802972 0.3175516 0.4801933 0.3179048 0.4800888 0.3182578 0.4800888 0.3182578 0.4799839 0.3186107 0.4798783 0.3189634 0.4798783 0.3189634 0.4797723 0.3193159 0.4796657 0.3196683 0.4796657 0.3196683 0.4795585 0.3200206 0.4798783 0.3189634 0.4795585 0.3200206 0.4794509 0.3203726 0.4798783 0.3189634 0.4794509 0.3203726 0.4793426 0.3207245 0.4790148 0.3217791 0.4793426 0.3207245 0.4792339 0.3210762 0.4790148 0.3217791 0.4792339 0.3210762 0.4791246 0.3214278 0.4790148 0.3217791 0.4790148 0.3217791 0.4789044 0.3221304 0.4787935 0.3224814 0.4787935 0.3224814 0.478682 0.3228323 0.47857 0.323183 0.47857 0.323183 0.4784575 0.3235335 0.4783444 0.3238839 0.4783444 0.3238839 0.4782308 0.3242341 0.47857 0.323183 0.4782308 0.3242341 0.4781166 0.3245841 0.47857 0.323183 0.4781166 0.3245841 0.478002 0.324934 0.4778867 0.3252836 0.4778867 0.3252836 0.477771 0.3256331 0.4776547 0.3259824 0.4776547 0.3259824 0.4775379 0.3263316 0.4771842 0.3273779 0.4775379 0.3263316 0.4774205 0.3266805 0.4771842 0.3273779 0.4774205 0.3266805 0.4773026 0.3270292 0.4771842 0.3273779 0.4771842 0.3273779 0.4770653 0.3277263 0.4769458 0.3280745 0.4769458 0.3280745 0.4768257 0.3284225 0.4771842 0.3273779 0.4768257 0.3284225 0.4767051 0.3287703 0.4771842 0.3273779 0.4767051 0.3287703 0.4765841 0.329118 0.4764624 0.3294655 0.4764624 0.3294655 0.4763402 0.3298128 0.4767051 0.3287703 0.4763402 0.3298128 0.4762176 0.3301599 0.4767051 0.3287703 0.4762176 0.3301599 0.4760943 0.3305068 0.4759706 0.3308536 0.4759706 0.3308536 0.4758463 0.3312001 0.4762176 0.3301599 0.4758463 0.3312001 0.4757214 0.3315464 0.4762176 0.3301599 0.4757214 0.3315464 0.4755961 0.3318926 0.4754702 0.3322386 0.4754702 0.3322386 0.4753438 0.3325843 0.4757214 0.3315464 0.4753438 0.3325843 0.4752169 0.3329299 0.4757214 0.3315464 0.4752169 0.3329299 0.4750894 0.3332753 0.4747037 0.3343102 0.4750894 0.3332753 0.4749614 0.3336205 0.4747037 0.3343102 0.4749614 0.3336205 0.4748328 0.3339655 0.4747037 0.3343102 0.4747037 0.3343102 0.4745742 0.3346549 0.474444 0.3349993 0.474444 0.3349993 0.4743134 0.3353434 0.4747037 0.3343102 0.4743134 0.3353434 0.4741822 0.3356874 0.4747037 0.3343102 0.4741822 0.3356874 0.4740505 0.3360312 0.4739183 0.3363748 0.4739183 0.3363748 0.4737855 0.3367182 0.4741822 0.3356874 0.4737855 0.3367182 0.4736523 0.3370614 0.4741822 0.3356874 0.4736523 0.3370614 0.4735184 0.3374043 0.4733841 0.3377471 0.4733841 0.3377471 0.4732492 0.3380897 0.4731138 0.338432 0.4731138 0.338432 0.4729779 0.3387742 0.4728415 0.3391161 0.4728415 0.3391161 0.4727045 0.3394579 0.4731138 0.338432 0.4727045 0.3394579 0.472567 0.3397994 0.4731138 0.338432 0.472567 0.3397994 0.472429 0.3401407 0.4722905 0.3404818 0.4722905 0.3404818 0.4721514 0.3408226 0.472567 0.3397994 0.4721514 0.3408226 0.4720118 0.3411633 0.472567 0.3397994 0.4720118 0.3411633 0.4718717 0.3415038 0.4717311 0.341844 0.4717311 0.341844 0.4715899 0.342184 0.4714483 0.3425239 0.4714483 0.3425239 0.4713061 0.3428635 0.4711633 0.3432028 0.4711633 0.3432028 0.4710201 0.3435419 0.4714483 0.3425239 0.4710201 0.3435419 0.4708764 0.3438809 0.4714483 0.3425239 0.4708764 0.3438809 0.4707321 0.3442196 0.4702962 0.3452344 0.4707321 0.3442196 0.4705873 0.3445581 0.4702962 0.3452344 0.4705873 0.3445581 0.470442 0.3448964 0.4702962 0.3452344 0.4702962 0.3452344 0.4701498 0.3455722 0.4697077 0.3465843 0.4701498 0.3455722 0.470003 0.3459098 0.4697077 0.3465843 0.470003 0.3459098 0.4698556 0.3462471 0.4697077 0.3465843 0.4697077 0.3465843 0.4695593 0.3469212 0.4694103 0.3472579 0.4694103 0.3472579 0.4692609 0.3475944 0.4691109 0.3479306 0.4691109 0.3479306 0.4689604 0.3482666 0.4685059 0.3492732 0.4689604 0.3482666 0.4688094 0.3486024 0.4685059 0.3492732 0.4688094 0.3486024 0.4686579 0.3489379 0.4685059 0.3492732 0.4685059 0.3492732 0.4683533 0.3496083 0.4682003 0.3499431 0.4682003 0.3499431 0.4680467 0.3502777 0.4685059 0.3492732 0.4680467 0.3502777 0.4678927 0.3506121 0.4685059 0.3492732 0.4678927 0.3506121 0.4677381 0.3509462 0.467583 0.35128 0.467583 0.35128 0.4674273 0.3516137 0.4678927 0.3506121 0.4674273 0.3516137 0.4672712 0.3519471 0.4678927 0.3506121 0.4672712 0.3519471 0.4671146 0.3522803 0.4666416 0.3532783 0.4671146 0.3522803 0.4669575 0.3526132 0.4666416 0.3532783 0.4669575 0.3526132 0.4667997 0.3529459 0.4666416 0.3532783 0.4666416 0.3532783 0.4664829 0.3536105 0.4660038 0.3546057 0.4664829 0.3536105 0.4663237 0.3539425 0.4660038 0.3546057 0.4663237 0.3539425 0.466164 0.3542742 0.4660038 0.3546057 0.4660038 0.3546057 0.4658431 0.3549369 0.4653579 0.3559291 0.4658431 0.3549369 0.4656819 0.3552679 0.4653579 0.3559291 0.4656819 0.3552679 0.4655202 0.3555986 0.4653579 0.3559291 0.4653579 0.3559291 0.4651951 0.3562594 0.4647039 0.3572485 0.4651951 0.3562594 0.4650319 0.3565893 0.4647039 0.3572485 0.4650319 0.3565893 0.4648681 0.3569191 0.4647039 0.3572485 0.4647039 0.3572485 0.4645391 0.3575778 0.4643738 0.3579067 0.4643738 0.3579067 0.4642081 0.3582354 0.4647039 0.3572485 0.4642081 0.3582354 0.4640418 0.3585639 0.4647039 0.3572485 0.4640418 0.3585639 0.463875 0.3588921 0.4637077 0.35922 0.4637077 0.35922 0.4635399 0.3595477 0.4640418 0.3585639 0.4635399 0.3595477 0.4633716 0.3598752 0.4640418 0.3585639 0.4633716 0.3598752 0.4632028 0.3602024 0.4626934 0.3611823 0.4632028 0.3602024 0.4630335 0.3605293 0.4626934 0.3611823 0.4630335 0.3605293 0.4628637 0.3608559 0.4626934 0.3611823 0.4626934 0.3611823 0.4625226 0.3615085 0.4620072 0.3624853 0.4625226 0.3615085 0.4623513 0.3618344 0.4620072 0.3624853 0.4623513 0.3618344 0.4621795 0.36216 0.4620072 0.3624853 0.4620072 0.3624853 0.4618344 0.3628104 0.4616611 0.3631352 0.4616611 0.3631352 0.4614873 0.3634598 0.461313 0.363784 0.461313 0.363784 0.4611382 0.364108 0.4606109 0.3650785 0.4611382 0.364108 0.460963 0.3644318 0.4606109 0.3650785 0.460963 0.3644318 0.4607871 0.3647553 0.4606109 0.3650785 0.4606109 0.3650785 0.4604341 0.3654015 0.4602568 0.3657241 0.4602568 0.3657241 0.460079 0.3660465 0.4606109 0.3650785 0.460079 0.3660465 0.4599008 0.3663686 0.4606109 0.3650785 0.4599008 0.3663686 0.4597221 0.3666905 0.4595428 0.367012 0.4595428 0.367012 0.4593631 0.3673334 0.4599008 0.3663686 0.4593631 0.3673334 0.4591828 0.3676543 0.4599008 0.3663686 0.4591828 0.3676543 0.4590021 0.3679751 0.4584569 0.3689357 0.4590021 0.3679751 0.4588209 0.3682956 0.4584569 0.3689357 0.4588209 0.3682956 0.4586392 0.3686158 0.4584569 0.3689357 0.4584569 0.3689357 0.4582743 0.3692553 0.4580911 0.3695746 0.4580911 0.3695746 0.4579074 0.3698937 0.4577233 0.3702125 0.4577233 0.3702125 0.4575386 0.370531 0.4573535 0.3708492 0.4573535 0.3708492 0.4571679 0.3711671 0.4569817 0.3714848 0.4569817 0.3714848 0.4567952 0.3718022 0.4566081 0.3721193 0.4566081 0.3721193 0.4564205 0.3724361 0.4562324 0.3727526 0.4562324 0.3727526 0.4560439 0.3730688 0.4558548 0.3733847 0.4558548 0.3733847 0.4556654 0.3737003 0.4562324 0.3727526 0.4556654 0.3737003 0.4554753 0.3740156 0.4562324 0.3727526 0.4554753 0.3740156 0.4552849 0.3743306 0.4547106 0.3752741 0.4552849 0.3743306 0.4550939 0.3746454 0.4547106 0.3752741 0.4550939 0.3746454 0.4549025 0.3749599 0.4547106 0.3752741 0.4547106 0.3752741 0.4545181 0.3755879 0.4543253 0.3759015 0.4543253 0.3759015 0.4541319 0.3762148 0.4547106 0.3752741 0.4541319 0.3762148 0.453938 0.3765278 0.4547106 0.3752741 0.453938 0.3765278 0.4537437 0.3768405 0.4535489 0.3771529 0.4535489 0.3771529 0.4533536 0.377465 0.4531578 0.3777768 0.4531578 0.3777768 0.4529616 0.3780882 0.4527649 0.3783994 0.4527649 0.3783994 0.4525676 0.3787103 0.4531578 0.3777768 0.4525676 0.3787103 0.45237 0.3790209 0.4531578 0.3777768 0.45237 0.3790209 0.4521718 0.3793312 0.4519732 0.3796412 0.4519732 0.3796412 0.4517741 0.3799508 0.45237 0.3790209 0.4517741 0.3799508 0.4515745 0.3802602 0.45237 0.3790209 0.4515745 0.3802602 0.4513745 0.3805692 0.4511739 0.380878 0.4511739 0.380878 0.4509729 0.3811864 0.4507715 0.3814946 0.4507715 0.3814946 0.4505695 0.3818024 0.4503671 0.3821099 0.4503671 0.3821099 0.4501642 0.3824171 0.4499608 0.382724 0.4499608 0.382724 0.449757 0.3830306 0.4491427 0.3839485 0.449757 0.3830306 0.4495527 0.3833369 0.4491427 0.3839485 0.4495527 0.3833369 0.4493479 0.3836428 0.4491427 0.3839485 0.4491427 0.3839485 0.448937 0.3842537 0.4487308 0.3845588 0.4487308 0.3845588 0.4485242 0.3848634 0.4483171 0.3851678 0.4483171 0.3851678 0.4481095 0.3854719 0.447484 0.3863822 0.4481095 0.3854719 0.4479014 0.3857756 0.447484 0.3863822 0.4479014 0.3857756 0.4476929 0.3860791 0.447484 0.3863822 0.447484 0.3863822 0.4472745 0.3866849 0.4470646 0.3869874 0.4470646 0.3869874 0.4468542 0.3872895 0.447484 0.3863822 0.4468542 0.3872895 0.4466434 0.3875913 0.447484 0.3863822 0.4466434 0.3875913 0.4464321 0.3878928 0.4462203 0.388194 0.4462203 0.388194 0.4460082 0.3884948 0.4457954 0.3887953 0.4457954 0.3887953 0.4455823 0.3890955 0.4453687 0.3893954 0.4453687 0.3893954 0.4451547 0.3896949 0.4457954 0.3887953 0.4451547 0.3896949 0.4449402 0.3899941 0.4457954 0.3887953 0.4449402 0.3899941 0.4447252 0.390293 0.4440775 0.3911876 0.4447252 0.390293 0.4445097 0.3905915 0.4440775 0.3911876 0.4445097 0.3905915 0.4442939 0.3908897 0.4440775 0.3911876 0.4440775 0.3911876 0.4438607 0.3914851 0.4436434 0.3917824 0.4436434 0.3917824 0.4434257 0.3920792 0.4432075 0.3923758 0.4432075 0.3923758 0.4429889 0.392672 0.4427698 0.3929678 0.4427698 0.3929678 0.4425503 0.3932633 0.4423303 0.3935586 0.4423303 0.3935586 0.4421098 0.3938534 0.4414458 0.394736 0.4421098 0.3938534 0.4418889 0.3941479 0.4414458 0.394736 0.4418889 0.3941479 0.4416676 0.3944422 0.4414458 0.394736 0.4414458 0.394736 0.4412236 0.3950295 0.4405541 0.3959079 0.4412236 0.3950295 0.4410009 0.3953226 0.4405541 0.3959079 0.4410009 0.3953226 0.4407777 0.3956155 0.4405541 0.3959079 0.4405541 0.3959079 0.44033 0.3962001 0.4401056 0.3964919 0.4401056 0.3964919 0.4398806 0.3967833 0.4396553 0.3970744 0.4396553 0.3970744 0.4394294 0.3973652 0.4392032 0.3976556 0.4392032 0.3976556 0.4389764 0.3979457 0.4396553 0.3970744 0.4389764 0.3979457 0.4387493 0.3982354 0.4396553 0.3970744 0.4387493 0.3982354 0.4385216 0.3985247 0.4378361 0.3993907 0.4385216 0.3985247 0.4382936 0.3988137 0.4378361 0.3993907 0.4382936 0.3988137 0.4380651 0.3991024 0.4378361 0.3993907 0.4378361 0.3993907 0.4376068 0.3996787 0.4373769 0.3999663 0.4373769 0.3999663 0.4371467 0.4002535 0.4378361 0.3993907 0.4371467 0.4002535 0.4369159 0.4005404 0.4378361 0.3993907 0.4369159 0.4005404 0.4366848 0.400827 0.4364532 0.4011132 0.4364532 0.4011132 0.4362212 0.401399 0.4359887 0.4016845 0.4359887 0.4016845 0.4357559 0.4019696 0.4350546 0.4028229 0.4357559 0.4019696 0.4355225 0.4022544 0.4350546 0.4028229 0.4355225 0.4022544 0.4352887 0.4025388 0.4350546 0.4028229 0.4350546 0.4028229 0.4348199 0.4031065 0.4345848 0.4033899 0.4345848 0.4033899 0.4343493 0.4036728 0.4350546 0.4028229 0.4343493 0.4036728 0.4341133 0.4039555 0.4350546 0.4028229 0.4341133 0.4039555 0.4338769 0.4042377 0.4336401 0.4045196 0.4336401 0.4045196 0.4334029 0.4048011 0.4331652 0.4050822 0.4331652 0.4050822 0.4329271 0.405363 0.4326885 0.4056435 0.4326885 0.4056435 0.4324496 0.4059235 0.4331652 0.4050822 0.4324496 0.4059235 0.4322102 0.4062032 0.4331652 0.4050822 0.4322102 0.4062032 0.4319704 0.4064825 0.4317301 0.4067615 0.4317301 0.4067615 0.4314894 0.4070401 0.4322102 0.4062032 0.4314894 0.4070401 0.4312483 0.4073183 0.4322102 0.4062032 0.4312483 0.4073183 0.4310068 0.4075961 0.4307649 0.4078736 0.4307649 0.4078736 0.4305225 0.4081507 0.4312483 0.4073183 0.4305225 0.4081507 0.4302796 0.4084274 0.4312483 0.4073183 0.4302796 0.4084274 0.4300364 0.4087038 0.4297927 0.4089798 0.4297927 0.4089798 0.4295486 0.4092554 0.4302796 0.4084274 0.4295486 0.4092554 0.4293041 0.4095306 0.4302796 0.4084274 0.4293041 0.4095306 0.4290592 0.4098055 0.4288139 0.41008 0.4288139 0.41008 0.4285681 0.4103541 0.4283219 0.4106279 0.4283219 0.4106279 0.4280753 0.4109011 0.4273329 0.411719 0.4280753 0.4109011 0.4278283 0.4111741 0.4273329 0.411719 0.4278283 0.4111741 0.4275808 0.4114468 0.4273329 0.411719 0.4273329 0.411719 0.4270847 0.4119908 0.426836 0.4122623 0.426836 0.4122623 0.4265869 0.4125334 0.4273329 0.411719 0.4265869 0.4125334 0.4263373 0.412804 0.4273329 0.411719 0.4263373 0.412804 0.4260874 0.4130743 0.4253351 0.4138829 0.4260874 0.4130743 0.425837 0.4133442 0.4253351 0.4138829 0.425837 0.4133442 0.4255862 0.4136138 0.4253351 0.4138829 0.4253351 0.4138829 0.4250835 0.4141517 0.4248315 0.4144201 0.4248315 0.4144201 0.424579 0.4146881 0.4243262 0.4149557 0.4243262 0.4149557 0.4240729 0.4152229 0.4238193 0.4154897 0.4238193 0.4154897 0.4235652 0.4157562 0.4243262 0.4149557 0.4235652 0.4157562 0.4233108 0.4160223 0.4243262 0.4149557 0.4233108 0.4160223 0.4230559 0.4162879 0.4228006 0.4165531 0.4228006 0.4165531 0.4225449 0.416818 0.4222888 0.4170825 0.4222888 0.4170825 0.4220323 0.4173466 0.4217754 0.4176103 0.4217754 0.4176103 0.4215181 0.4178736 0.4212604 0.4181365 0.4212604 0.4181365 0.4210023 0.418399 0.4207437 0.4186611 0.4207437 0.4186611 0.4204848 0.4189229 0.4212604 0.4181365 0.4204848 0.4189229 0.4202255 0.4191842 0.4212604 0.4181365 0.4202255 0.4191842 0.4199658 0.4194451 0.4197056 0.4197056 0.4197056 0.4197056 0.4194451 0.4199658 0.4202255 0.4191842 0.4194451 0.4199658 0.4191842 0.4202255 0.4202255 0.4191842 0.4191842 0.4202255 0.4189229 0.4204848 0.4186611 0.4207437 0.4186611 0.4207437 0.418399 0.4210023 0.4191842 0.4202255 0.418399 0.4210023 0.4181365 0.4212604 0.4191842 0.4202255 0.4181365 0.4212604 0.4178736 0.4215181 0.4176103 0.4217754 0.4176103 0.4217754 0.4173466 0.4220323 0.4181365 0.4212604 0.4173466 0.4220323 0.4170825 0.4222888 0.4181365 0.4212604 0.4170825 0.4222888 0.416818 0.4225449 0.4165531 0.4228006 0.4165531 0.4228006 0.4162879 0.4230559 0.4160223 0.4233108 0.4160223 0.4233108 0.4157562 0.4235652 0.4149557 0.4243262 0.4157562 0.4235652 0.4154897 0.4238193 0.4149557 0.4243262 0.4154897 0.4238193 0.4152229 0.4240729 0.4149557 0.4243262 0.4149557 0.4243262 0.4146881 0.424579 0.4144201 0.4248315 0.4144201 0.4248315 0.4141517 0.4250835 0.4138829 0.4253351 0.4138829 0.4253351 0.4136138 0.4255862 0.4133442 0.425837 0.4133442 0.425837 0.4130743 0.4260874 0.4138829 0.4253351 0.4130743 0.4260874 0.412804 0.4263373 0.4138829 0.4253351 0.412804 0.4263373 0.4125334 0.4265869 0.411719 0.4273329 0.4125334 0.4265869 0.4122623 0.426836 0.411719 0.4273329 0.4122623 0.426836 0.4119908 0.4270847 0.411719 0.4273329 0.411719 0.4273329 0.4114468 0.4275808 0.4111741 0.4278283 0.4111741 0.4278283 0.4109011 0.4280753 0.411719 0.4273329 0.4109011 0.4280753 0.4106279 0.4283219 0.411719 0.4273329 0.4106279 0.4283219 0.4103541 0.4285681 0.41008 0.4288139 0.41008 0.4288139 0.4098055 0.4290592 0.4095306 0.4293041 0.4095306 0.4293041 0.4092554 0.4295486 0.4084274 0.4302796 0.4092554 0.4295486 0.4089798 0.4297927 0.4084274 0.4302796 0.4089798 0.4297927 0.4087038 0.4300364 0.4084274 0.4302796 0.4084274 0.4302796 0.4081507 0.4305225 0.4078736 0.4307649 0.4078736 0.4307649 0.4075961 0.4310068 0.4084274 0.4302796 0.4075961 0.4310068 0.4073183 0.4312483 0.4084274 0.4302796 0.4073183 0.4312483 0.4070401 0.4314894 0.4062032 0.4322102 0.4070401 0.4314894 0.4067615 0.4317301 0.4062032 0.4322102 0.4067615 0.4317301 0.4064825 0.4319704 0.4062032 0.4322102 0.4062032 0.4322102 0.4059235 0.4324496 0.4050822 0.4331652 0.4059235 0.4324496 0.4056435 0.4326885 0.4050822 0.4331652 0.4056435 0.4326885 0.405363 0.4329271 0.4050822 0.4331652 0.4050822 0.4331652 0.4048011 0.4334029 0.4045196 0.4336401 0.4045196 0.4336401 0.4042377 0.4338769 0.4039555 0.4341133 0.4039555 0.4341133 0.4036728 0.4343493 0.4028229 0.4350546 0.4036728 0.4343493 0.4033899 0.4345848 0.4028229 0.4350546 0.4033899 0.4345848 0.4031065 0.4348199 0.4028229 0.4350546 0.4028229 0.4350546 0.4025388 0.4352887 0.4022544 0.4355225 0.4022544 0.4355225 0.4019696 0.4357559 0.4028229 0.4350546 0.4019696 0.4357559 0.4016845 0.4359887 0.4028229 0.4350546 0.4016845 0.4359887 0.401399 0.4362212 0.4011132 0.4364532 0.4011132 0.4364532 0.400827 0.4366848 0.4005404 0.4369159 0.4005404 0.4369159 0.4002535 0.4371467 0.3993907 0.4378361 0.4002535 0.4371467 0.3999663 0.4373769 0.3993907 0.4378361 0.3999663 0.4373769 0.3996787 0.4376068 0.3993907 0.4378361 0.3993907 0.4378361 0.3991024 0.4380651 0.3988137 0.4382936 0.3988137 0.4382936 0.3985247 0.4385216 0.3993907 0.4378361 0.3985247 0.4385216 0.3982354 0.4387493 0.3993907 0.4378361 0.3982354 0.4387493 0.3979457 0.4389764 0.3970744 0.4396553 0.3979457 0.4389764 0.3976556 0.4392032 0.3970744 0.4396553 0.3976556 0.4392032 0.3973652 0.4394294 0.3970744 0.4396553 0.3970744 0.4396553 0.3967833 0.4398806 0.3964919 0.4401056 0.3964919 0.4401056 0.3962001 0.44033 0.3959079 0.4405541 0.3959079 0.4405541 0.3956155 0.4407777 0.3953226 0.4410009 0.3953226 0.4410009 0.3950295 0.4412236 0.3959079 0.4405541 0.3950295 0.4412236 0.394736 0.4414458 0.3959079 0.4405541 0.394736 0.4414458 0.3944422 0.4416676 0.3941479 0.4418889 0.3941479 0.4418889 0.3938534 0.4421098 0.394736 0.4414458 0.3938534 0.4421098 0.3935586 0.4423303 0.394736 0.4414458 0.3935586 0.4423303 0.3932633 0.4425503 0.3929678 0.4427698 0.3929678 0.4427698 0.392672 0.4429889 0.3923758 0.4432075 0.3923758 0.4432075 0.3920792 0.4434257 0.3917824 0.4436434 0.3917824 0.4436434 0.3914851 0.4438607 0.3911876 0.4440775 0.3911876 0.4440775 0.3908897 0.4442939 0.3905915 0.4445097 0.3905915 0.4445097 0.390293 0.4447252 0.3911876 0.4440775 0.390293 0.4447252 0.3899941 0.4449402 0.3911876 0.4440775 0.3899941 0.4449402 0.3896949 0.4451547 0.3887953 0.4457954 0.3896949 0.4451547 0.3893954 0.4453687 0.3887953 0.4457954 0.3893954 0.4453687 0.3890955 0.4455823 0.3887953 0.4457954 0.3887953 0.4457954 0.3884948 0.4460082 0.388194 0.4462203 0.388194 0.4462203 0.3878928 0.4464321 0.3875913 0.4466434 0.3875913 0.4466434 0.3872895 0.4468542 0.3863822 0.447484 0.3872895 0.4468542 0.3869874 0.4470646 0.3863822 0.447484 0.3869874 0.4470646 0.3866849 0.4472745 0.3863822 0.447484 0.3863822 0.447484 0.3860791 0.4476929 0.3857756 0.4479014 0.3857756 0.4479014 0.3854719 0.4481095 0.3863822 0.447484 0.3854719 0.4481095 0.3851678 0.4483171 0.3863822 0.447484 0.3851678 0.4483171 0.3848634 0.4485242 0.3845588 0.4487308 0.3845588 0.4487308 0.3842537 0.448937 0.3839485 0.4491427 0.3839485 0.4491427 0.3836428 0.4493479 0.3833369 0.4495527 0.3833369 0.4495527 0.3830306 0.449757 0.3839485 0.4491427 0.3830306 0.449757 0.382724 0.4499608 0.3839485 0.4491427 0.382724 0.4499608 0.3824171 0.4501642 0.3821099 0.4503671 0.3821099 0.4503671 0.3818024 0.4505695 0.3814946 0.4507715 0.3814946 0.4507715 0.3811864 0.4509729 0.380878 0.4511739 0.380878 0.4511739 0.3805692 0.4513745 0.3802602 0.4515745 0.3802602 0.4515745 0.3799508 0.4517741 0.3790209 0.45237 0.3799508 0.4517741 0.3796412 0.4519732 0.3790209 0.45237 0.3796412 0.4519732 0.3793312 0.4521718 0.3790209 0.45237 0.3790209 0.45237 0.3787103 0.4525676 0.3777768 0.4531578 0.3787103 0.4525676 0.3783994 0.4527649 0.3777768 0.4531578 0.3783994 0.4527649 0.3780882 0.4529616 0.3777768 0.4531578 0.3777768 0.4531578 0.377465 0.4533536 0.3771529 0.4535489 0.3771529 0.4535489 0.3768405 0.4537437 0.3765278 0.453938 0.3765278 0.453938 0.3762148 0.4541319 0.3752741 0.4547106 0.3762148 0.4541319 0.3759015 0.4543253 0.3752741 0.4547106 0.3759015 0.4543253 0.3755879 0.4545181 0.3752741 0.4547106 0.3752741 0.4547106 0.3749599 0.4549025 0.3746454 0.4550939 0.3746454 0.4550939 0.3743306 0.4552849 0.3752741 0.4547106 0.3743306 0.4552849 0.3740156 0.4554753 0.3752741 0.4547106 0.3740156 0.4554753 0.3737003 0.4556654 0.3727526 0.4562324 0.3737003 0.4556654 0.3733847 0.4558548 0.3727526 0.4562324 0.3733847 0.4558548 0.3730688 0.4560439 0.3727526 0.4562324 0.3727526 0.4562324 0.3724361 0.4564205 0.3721193 0.4566081 0.3721193 0.4566081 0.3718022 0.4567952 0.3714848 0.4569817 0.3714848 0.4569817 0.3711671 0.4571679 0.3708492 0.4573535 0.3708492 0.4573535 0.370531 0.4575386 0.3702125 0.4577233 0.3702125 0.4577233 0.3698937 0.4579074 0.3695746 0.4580911 0.3695746 0.4580911 0.3692553 0.4582743 0.3689357 0.4584569 0.3689357 0.4584569 0.3686158 0.4586392 0.3682956 0.4588209 0.3682956 0.4588209 0.3679751 0.4590021 0.3689357 0.4584569 0.3679751 0.4590021 0.3676543 0.4591828 0.3689357 0.4584569 0.3676543 0.4591828 0.3673334 0.4593631 0.3663686 0.4599008 0.3673334 0.4593631 0.367012 0.4595428 0.3663686 0.4599008 0.367012 0.4595428 0.3666905 0.4597221 0.3663686 0.4599008 0.3663686 0.4599008 0.3660465 0.460079 0.3657241 0.4602568 0.3657241 0.4602568 0.3654015 0.4604341 0.3650785 0.4606109 0.3650785 0.4606109 0.3647553 0.4607871 0.3644318 0.460963 0.3644318 0.460963 0.364108 0.4611382 0.3650785 0.4606109 0.364108 0.4611382 0.363784 0.461313 0.3650785 0.4606109 0.363784 0.461313 0.3634598 0.4614873 0.3631352 0.4616611 0.3631352 0.4616611 0.3628104 0.4618344 0.3624853 0.4620072 0.3624853 0.4620072 0.36216 0.4621795 0.3618344 0.4623513 0.3618344 0.4623513 0.3615085 0.4625226 0.3624853 0.4620072 0.3615085 0.4625226 0.3611823 0.4626934 0.3624853 0.4620072 0.3611823 0.4626934 0.3608559 0.4628637 0.3605293 0.4630335 0.3605293 0.4630335 0.3602024 0.4632028 0.3611823 0.4626934 0.3602024 0.4632028 0.3598752 0.4633716 0.3611823 0.4626934 0.3598752 0.4633716 0.3595477 0.4635399 0.3585639 0.4640418 0.3595477 0.4635399 0.35922 0.4637077 0.3585639 0.4640418 0.35922 0.4637077 0.3588921 0.463875 0.3585639 0.4640418 0.3585639 0.4640418 0.3582354 0.4642081 0.3572485 0.4647039 0.3582354 0.4642081 0.3579067 0.4643738 0.3572485 0.4647039 0.3579067 0.4643738 0.3575778 0.4645391 0.3572485 0.4647039 0.3572485 0.4647039 0.3569191 0.4648681 0.3565893 0.4650319 0.3565893 0.4650319 0.3562594 0.4651951 0.3572485 0.4647039 0.3562594 0.4651951 0.3559291 0.4653579 0.3572485 0.4647039 0.3559291 0.4653579 0.3555986 0.4655202 0.3552679 0.4656819 0.3552679 0.4656819 0.3549369 0.4658431 0.3559291 0.4653579 0.3549369 0.4658431 0.3546057 0.4660038 0.3559291 0.4653579 0.3546057 0.4660038 0.3542742 0.466164 0.3539425 0.4663237 0.3539425 0.4663237 0.3536105 0.4664829 0.3546057 0.4660038 0.3536105 0.4664829 0.3532783 0.4666416 0.3546057 0.4660038 0.3532783 0.4666416 0.3529459 0.4667997 0.3526132 0.4669575 0.3526132 0.4669575 0.3522803 0.4671146 0.3532783 0.4666416 0.3522803 0.4671146 0.3519471 0.4672712 0.3532783 0.4666416 0.3519471 0.4672712 0.3516137 0.4674273 0.3506121 0.4678927 0.3516137 0.4674273 0.35128 0.467583 0.3506121 0.4678927 0.35128 0.467583 0.3509462 0.4677381 0.3506121 0.4678927 0.3506121 0.4678927 0.3502777 0.4680467 0.3499431 0.4682003 0.3499431 0.4682003 0.3496083 0.4683533 0.3492732 0.4685059 0.3492732 0.4685059 0.3489379 0.4686579 0.3486024 0.4688094 0.3486024 0.4688094 0.3482666 0.4689604 0.3492732 0.4685059 0.3482666 0.4689604 0.3479306 0.4691109 0.3492732 0.4685059 0.3479306 0.4691109 0.3475944 0.4692609 0.3472579 0.4694103 0.3472579 0.4694103 0.3469212 0.4695593 0.3465843 0.4697077 0.3465843 0.4697077 0.3462471 0.4698556 0.3459098 0.470003 0.3459098 0.470003 0.3455722 0.4701498 0.3465843 0.4697077 0.3455722 0.4701498 0.3452344 0.4702962 0.3465843 0.4697077 0.3452344 0.4702962 0.3448964 0.470442 0.3445581 0.4705873 0.3445581 0.4705873 0.3442196 0.4707321 0.3452344 0.4702962 0.3442196 0.4707321 0.3438809 0.4708764 0.3452344 0.4702962 0.3438809 0.4708764 0.3435419 0.4710201 0.3425239 0.4714483 0.3435419 0.4710201 0.3432028 0.4711633 0.3425239 0.4714483 0.3432028 0.4711633 0.3428635 0.4713061 0.3425239 0.4714483 0.3425239 0.4714483 0.342184 0.4715899 0.341844 0.4717311 0.341844 0.4717311 0.3415038 0.4718717 0.3411633 0.4720118 0.3411633 0.4720118 0.3408226 0.4721514 0.3397994 0.472567 0.3408226 0.4721514 0.3404818 0.4722905 0.3397994 0.472567 0.3404818 0.4722905 0.3401407 0.472429 0.3397994 0.472567 0.3397994 0.472567 0.3394579 0.4727045 0.338432 0.4731138 0.3394579 0.4727045 0.3391161 0.4728415 0.338432 0.4731138 0.3391161 0.4728415 0.3387742 0.4729779 0.338432 0.4731138 0.338432 0.4731138 0.3380897 0.4732492 0.3377471 0.4733841 0.3377471 0.4733841 0.3374043 0.4735184 0.3370614 0.4736523 0.3370614 0.4736523 0.3367182 0.4737855 0.3356874 0.4741822 0.3367182 0.4737855 0.3363748 0.4739183 0.3356874 0.4741822 0.3363748 0.4739183 0.3360312 0.4740505 0.3356874 0.4741822 0.3356874 0.4741822 0.3353434 0.4743134 0.3343102 0.4747037 0.3353434 0.4743134 0.3349993 0.474444 0.3343102 0.4747037 0.3349993 0.474444 0.3346549 0.4745742 0.3343102 0.4747037 0.3343102 0.4747037 0.3339655 0.4748328 0.3336205 0.4749614 0.3336205 0.4749614 0.3332753 0.4750894 0.3343102 0.4747037 0.3332753 0.4750894 0.3329299 0.4752169 0.3343102 0.4747037 0.3329299 0.4752169 0.3325843 0.4753438 0.3322386 0.4754702 0.3322386 0.4754702 0.3318926 0.4755961 0.3315464 0.4757214 0.3315464 0.4757214 0.3312001 0.4758463 0.3301599 0.4762176 0.3312001 0.4758463 0.3308536 0.4759706 0.3301599 0.4762176 0.3308536 0.4759706 0.3305068 0.4760943 0.3301599 0.4762176 0.3301599 0.4762176 0.3298128 0.4763402 0.3294655 0.4764624 0.3294655 0.4764624 0.329118 0.4765841 0.3287703 0.4767051 0.3287703 0.4767051 0.3284225 0.4768257 0.3273779 0.4771842 0.3284225 0.4768257 0.3280745 0.4769458 0.3273779 0.4771842 0.3280745 0.4769458 0.3277263 0.4770653 0.3273779 0.4771842 0.3273779 0.4771842 0.3270292 0.4773026 0.3266805 0.4774205 0.3266805 0.4774205 0.3263316 0.4775379 0.3259824 0.4776547 0.3259824 0.4776547 0.3256331 0.477771 0.3252836 0.4778867 0.3252836 0.4778867 0.324934 0.478002 0.3245841 0.4781166 0.3245841 0.4781166 0.3242341 0.4782308 0.323183 0.47857 0.3242341 0.4782308 0.3238839 0.4783444 0.323183 0.47857 0.3238839 0.4783444 0.3235335 0.4784575 0.323183 0.47857 0.323183 0.47857 0.3228323 0.478682 0.3224814 0.4787935 0.3224814 0.4787935 0.3221304 0.4789044 0.3217791 0.4790148 0.3217791 0.4790148 0.3214278 0.4791246 0.3210762 0.4792339 0.3210762 0.4792339 0.3207245 0.4793426 0.3217791 0.4790148 0.3207245 0.4793426 0.3203726 0.4794509 0.3217791 0.4790148 0.3203726 0.4794509 0.3200206 0.4795585 0.3189634 0.4798783 0.3200206 0.4795585 0.3196683 0.4796657 0.3189634 0.4798783 0.3196683 0.4796657 0.3193159 0.4797723 0.3189634 0.4798783 0.3189634 0.4798783 0.3186107 0.4799839 0.3182578 0.4800888 0.3182578 0.4800888 0.3179048 0.4801933 0.3175516 0.4802972 0.3175516 0.4802972 0.3171982 0.4804005 0.3161373 0.4807073 0.3171982 0.4804005 0.3168447 0.4805033 0.3161373 0.4807073 0.3168447 0.4805033 0.3164911 0.4806056 0.3161373 0.4807073 0.3161373 0.4807073 0.3157833 0.4808085 0.3147204 0.4811088 0.3157833 0.4808085 0.3154291 0.4809091 0.3147204 0.4811088 0.3154291 0.4809091 0.3150748 0.4810093 0.3147204 0.4811088 0.3147204 0.4811088 0.3143658 0.4812078 0.3133011 0.4815015 0.3143658 0.4812078 0.314011 0.4813063 0.3133011 0.4815015 0.314011 0.4813063 0.3136562 0.4814042 0.3133011 0.4815015 0.3133011 0.4815015 0.3129459 0.4815984 0.3118795 0.4818856 0.3129459 0.4815984 0.3125906 0.4816946 0.3118795 0.4818856 0.3125906 0.4816946 0.3122351 0.4817904 0.3118795 0.4818856 0.3118795 0.4818856 0.3115237 0.4819803 0.3111678 0.4820743 0.3111678 0.4820743 0.3108117 0.4821679 0.3118795 0.4818856 0.3108117 0.4821679 0.3104555 0.4822609 0.3118795 0.4818856 0.3104555 0.4822609 0.3100991 0.4823534 0.3097426 0.4824453 0.3097426 0.4824453 0.309386 0.4825367 0.3090292 0.4826275 0.3090292 0.4826275 0.3086723 0.4827178 0.3076007 0.4829853 0.3086723 0.4827178 0.3083152 0.4828075 0.3076007 0.4829853 0.3083152 0.4828075 0.3079581 0.4828967 0.3076007 0.4829853 0.3076007 0.4829853 0.3072432 0.4830734 0.3068857 0.4831609 0.3068857 0.4831609 0.3065279 0.4832479 0.3076007 0.4829853 0.3065279 0.4832479 0.3061701 0.4833344 0.3076007 0.4829853 0.3061701 0.4833344 0.3058121 0.4834203 0.305454 0.4835056 0.305454 0.4835056 0.3050957 0.4835904 0.3061701 0.4833344 0.3050957 0.4835904 0.3047373 0.4836746 0.3061701 0.4833344 0.3047373 0.4836746 0.3043788 0.4837583 0.3040201 0.4838414 0.3040201 0.4838414 0.3036614 0.483924 0.3033025 0.4840061 0.3033025 0.4840061 0.3029434 0.4840875 0.3025843 0.4841685 0.3025843 0.4841685 0.302225 0.4842489 0.3018656 0.4843288 0.3018656 0.4843288 0.3015061 0.484408 0.3011465 0.4844868 0.3011465 0.4844868 0.3007867 0.4845649 0.3018656 0.4843288 0.3007867 0.4845649 0.3004269 0.4846426 0.3018656 0.4843288 0.3004269 0.4846426 0.3000668 0.4847196 0.2989861 0.4849476 0.3000668 0.4847196 0.2997067 0.4847962 0.2989861 0.4849476 0.2997067 0.4847962 0.2993465 0.4848722 0.2989861 0.4849476 0.2989861 0.4849476 0.2986257 0.4850224 0.2982651 0.4850968 0.2982651 0.4850968 0.2979044 0.4851705 0.2989861 0.4849476 0.2979044 0.4851705 0.2975436 0.4852437 0.2989861 0.4849476 0.2975436 0.4852437 0.2971827 0.4853163 0.2968217 0.4853885 0.2968217 0.4853885 0.2964605 0.48546 0.2960993 0.485531 0.2960993 0.485531 0.2957379 0.4856014 0.2953765 0.4856714 0.2953765 0.4856714 0.2950149 0.4857407 0.2960993 0.485531 0.2950149 0.4857407 0.2946532 0.4858095 0.2960993 0.485531 0.2946532 0.4858095 0.2942914 0.4858776 0.2939296 0.4859453 0.2939296 0.4859453 0.2935676 0.4860124 0.2946532 0.4858095 0.2935676 0.4860124 0.2932055 0.486079 0.2946532 0.4858095 0.2932055 0.486079 0.2928433 0.486145 0.292481 0.4862104 0.292481 0.4862104 0.2921186 0.4862753 0.2917561 0.4863396 0.2917561 0.4863396 0.2913935 0.4864034 0.2910308 0.4864667 0.2910308 0.4864667 0.2906681 0.4865293 0.2917561 0.4863396 0.2906681 0.4865293 0.2903052 0.4865914 0.2917561 0.4863396 0.2903052 0.4865914 0.2899422 0.4866529 0.2888527 0.4868342 0.2899422 0.4866529 0.2895792 0.486714 0.2888527 0.4868342 0.2895792 0.486714 0.289216 0.4867744 0.2888527 0.4868342 0.2888527 0.4868342 0.2884894 0.4868935 0.2881259 0.4869523 0.2881259 0.4869523 0.2877624 0.4870105 0.2873988 0.4870682 0.2873988 0.4870682 0.2870351 0.4871253 0.2859435 0.4872932 0.2870351 0.4871253 0.2866714 0.4871818 0.2859435 0.4872932 0.2866714 0.4871818 0.2863075 0.4872378 0.2859435 0.4872932 0.2859435 0.4872932 0.2855795 0.487348 0.2844868 0.4875093 0.2855795 0.487348 0.2852153 0.4874024 0.2844868 0.4875093 0.2852153 0.4874024 0.2848511 0.4874561 0.2844868 0.4875093 0.2844868 0.4875093 0.2841224 0.4875619 0.283758 0.487614 0.283758 0.487614 0.2833935 0.4876655 0.2830289 0.4877164 0.2830289 0.4877164 0.2826641 0.4877668 0.2815696 0.4879146 0.2826641 0.4877668 0.2822993 0.4878166 0.2815696 0.4879146 0.2822993 0.4878166 0.2819345 0.4878659 0.2815696 0.4879146 0.2815696 0.4879146 0.2812046 0.4879627 0.2801092 0.4881038 0.2812046 0.4879627 0.2808396 0.4880104 0.2801092 0.4881038 0.2808396 0.4880104 0.2804744 0.4880574 0.2801092 0.4881038 0.2801092 0.4881038 0.2797439 0.4881498 0.2793785 0.4881951 0.2793785 0.4881951 0.2790132 0.4882399 0.2801092 0.4881038 0.2790132 0.4882399 0.2786477 0.4882841 0.2801092 0.4881038 0.2786477 0.4882841 0.2782821 0.4883278 0.2779164 0.4883708 0.2779164 0.4883708 0.2775508 0.4884134 0.277185 0.4884554 0.277185 0.4884554 0.2768192 0.4884968 0.2764533 0.4885377 0.2764533 0.4885377 0.2760874 0.488578 0.277185 0.4884554 0.2760874 0.488578 0.2757214 0.4886177 0.277185 0.4884554 0.2757214 0.4886177 0.2753553 0.4886569 0.2742568 0.488771 0.2753553 0.4886569 0.2749892 0.4886955 0.2742568 0.488771 0.2749892 0.4886955 0.274623 0.4887335 0.2742568 0.488771 0.2742568 0.488771 0.2738904 0.488808 0.2735241 0.4888443 0.2735241 0.4888443 0.2731577 0.4888801 0.2742568 0.488771 0.2731577 0.4888801 0.2727912 0.4889154 0.2742568 0.488771 0.2727912 0.4889154 0.2724247 0.4889501 0.2720581 0.4889842 0.2720581 0.4889842 0.2716915 0.4890177 0.2713248 0.4890507 0.2713248 0.4890507 0.2709581 0.4890832 0.2705913 0.489115 0.2705913 0.489115 0.2702245 0.4891463 0.2713248 0.4890507 0.2702245 0.4891463 0.2698577 0.4891771 0.2713248 0.4890507 0.2698577 0.4891771 0.2694907 0.4892073 0.2691238 0.4892368 0.2691238 0.4892368 0.2687568 0.4892659 0.2698577 0.4891771 0.2687568 0.4892659 0.2683897 0.4892944 0.2698577 0.4891771 0.2683897 0.4892944 0.2680226 0.4893223 0.2669211 0.4894027 0.2680226 0.4893223 0.2676555 0.4893497 0.2669211 0.4894027 0.2676555 0.4893497 0.2672883 0.4893765 0.2669211 0.4894027 0.2669211 0.4894027 0.2665538 0.4894284 0.2661865 0.4894535 0.2661865 0.4894535 0.2658192 0.4894781 0.2654518 0.4895021 0.2654518 0.4895021 0.2650844 0.4895255 0.263982 0.4895924 0.2650844 0.4895255 0.264717 0.4895483 0.263982 0.4895924 0.264717 0.4895483 0.2643495 0.4895706 0.263982 0.4895924 0.263982 0.4895924 0.2636144 0.4896135 0.2632468 0.4896341 0.2632468 0.4896341 0.2628793 0.4896542 0.2625116 0.4896737 0.2625116 0.4896737 0.2621439 0.4896926 0.2617762 0.4897109 0.2617762 0.4897109 0.2614085 0.4897287 0.2610408 0.4897459 0.2610408 0.4897459 0.260673 0.4897626 0.2603052 0.4897786 0.2603052 0.4897786 0.2599374 0.4897942 0.2610408 0.4897459 0.2599374 0.4897942 0.2595695 0.4898092 0.2610408 0.4897459 0.2595695 0.4898092 0.2592016 0.4898235 0.2588337 0.4898374 0.2588337 0.4898374 0.2584658 0.4898506 0.2580979 0.4898633 0.2580979 0.4898633 0.2577299 0.4898755 0.257362 0.4898871 0.257362 0.4898871 0.256994 0.4898981 0.256626 0.4899085 0.256626 0.4899085 0.2562579 0.4899184 0.2558899 0.4899277 0.2558899 0.4899277 0.2555218 0.4899365 0.2551538 0.4899446 0.2551538 0.4899446 0.2547857 0.4899523 0.2536814 0.4899718 0.2547857 0.4899523 0.2544176 0.4899594 0.2536814 0.4899718 0.2544176 0.4899594 0.2540495 0.4899659 0.2536814 0.4899718 0.2536814 0.4899718 0.2533133 0.4899771 0.2522089 0.4899898 0.2533133 0.4899771 0.2529451 0.489982 0.2522089 0.4899898 0.2529451 0.489982 0.252577 0.4899862 0.2522089 0.4899898 0.2522089 0.4899898 0.2518408 0.4899929 0.2514726 0.4899955 0.2514726 0.4899955 0.2511045 0.4899975 0.2522089 0.4899898 0.2511045 0.4899975 0.2507363 0.4899989 0.2522089 0.4899898 0.2448462 0.4899446 0.2441101 0.4899277 0.2419021 0.4898633 0.2441101 0.4899277 0.243374 0.4899085 0.2419021 0.4898633 0.243374 0.4899085 0.242638 0.4898871 0.2419021 0.4898633 0.2419021 0.4898633 0.2411662 0.4898374 0.2389592 0.4897459 0.2411662 0.4898374 0.2404305 0.4898092 0.2389592 0.4897459 0.2374883 0.4896737 0.2367531 0.4896341 0.2389592 0.4897459 0.2367531 0.4896341 0.236018 0.4895924 0.2389592 0.4897459 0.236018 0.4895924 0.235283 0.4895483 0.2330788 0.4894027 0.235283 0.4895483 0.2345482 0.4895021 0.2330788 0.4894027 0.2330788 0.4894027 0.2323445 0.4893497 0.2301423 0.4891771 0.2323445 0.4893497 0.2316102 0.4892944 0.2301423 0.4891771 0.2228149 0.4884554 0.2220835 0.4883708 0.2242786 0.4886177 0.2220835 0.4883708 0.2213523 0.4882841 0.2242786 0.4886177 0.2169712 0.4877164 0.216242 0.487614 0.2184303 0.4879146 0.216242 0.487614 0.2155132 0.4875093 0.2184303 0.4879146 0.2082439 0.4863396 0.2075189 0.4862104 0.2067945 0.486079 0.2039006 0.485531 0.2031783 0.4853885 0.2024564 0.4852437 0.1981343 0.4843288 0.1974157 0.4841685 0.1952627 0.4836746 0.1974157 0.4841685 0.1966975 0.4840061 0.1952627 0.4836746 0.1909708 0.4826275 0.1902573 0.4824453 0.1923993 0.4829853 0.1902573 0.4824453 0.1895445 0.4822609 0.1923993 0.4829853 0.1866989 0.4815015 0.1859889 0.4813063 0.1838628 0.4807073 0.1859889 0.4813063 0.1852796 0.4811088 0.1838628 0.4807073 0.1824484 0.4802972 0.1817421 0.4800888 0.1838628 0.4807073 0.1817421 0.4800888 0.1810365 0.4798783 0.1838628 0.4807073 0.1782208 0.4790148 0.1775186 0.4787935 0.1754159 0.4781166 0.1775186 0.4787935 0.1768169 0.47857 0.1754159 0.4781166 0.1754159 0.4781166 0.1747164 0.4778867 0.1726222 0.4771842 0.1747164 0.4778867 0.1740176 0.4776547 0.1726222 0.4771842 0.1629386 0.4736523 0.1622529 0.4733841 0.1643126 0.4741822 0.1622529 0.4733841 0.1615679 0.4731138 0.1643126 0.4741822 0.1588367 0.4720118 0.1581559 0.4717311 0.1561191 0.4708764 0.1581559 0.4717311 0.1574761 0.4714483 0.1561191 0.4708764 0.1534156 0.4697077 0.152742 0.4694103 0.1507267 0.4685059 0.152742 0.4694103 0.1520694 0.4691109 0.1507267 0.4685059 0.1375147 0.4620072 0.1368647 0.4616611 0.1349215 0.4606109 0.1368647 0.4616611 0.1362159 0.461313 0.1349215 0.4606109 0.1310643 0.4584569 0.1304253 0.4580911 0.1323456 0.4591828 0.1304253 0.4580911 0.1297875 0.4577233 0.1323456 0.4591828 0.1297875 0.4577233 0.1291508 0.4573535 0.1272475 0.4562324 0.1291508 0.4573535 0.1285152 0.4569817 0.1272475 0.4562324 0.1285152 0.4569817 0.1278807 0.4566081 0.1272475 0.4562324 0.1234722 0.453938 0.1228471 0.4535489 0.1247259 0.4547106 0.1228471 0.4535489 0.1222232 0.4531578 0.1247259 0.4547106 0.1197398 0.4515745 0.119122 0.4511739 0.1185054 0.4507715 0.1185054 0.4507715 0.1178901 0.4503671 0.1197398 0.4515745 0.1178901 0.4503671 0.117276 0.4499608 0.1197398 0.4515745 0.1160515 0.4491427 0.1154412 0.4487308 0.1148321 0.4483171 0.1124086 0.4466434 0.111806 0.4462203 0.1112046 0.4457954 0.1088124 0.4440775 0.1082177 0.4436434 0.1076242 0.4432075 0.1076242 0.4432075 0.1070321 0.4427698 0.105264 0.4414458 0.1070321 0.4427698 0.1064414 0.4423303 0.105264 0.4414458 0.104092 0.4405541 0.1035081 0.4401056 0.105264 0.4414458 0.1035081 0.4401056 0.1029255 0.4396553 0.105264 0.4414458 0.09945952 0.4369159 0.09888678 0.4364532 0.1006093 0.4378361 0.09888678 0.4364532 0.09831547 0.4359887 0.1006093 0.4378361 0.09604454 0.4341133 0.09548038 0.4336401 0.09379678 0.4322102 0.09548038 0.4336401 0.09491771 0.4331652 0.09379678 0.4322102 0.09046936 0.4293041 0.08991998 0.4288139 0.09157252 0.4302796 0.08991998 0.4288139 0.08937215 0.4283219 0.09157252 0.4302796 0.08611702 0.4253351 0.08557987 0.4248315 0.08719593 0.4263373 0.08557987 0.4248315 0.08504432 0.4243262 0.08719593 0.4263373 0.08397775 0.4233108 0.08344686 0.4228006 0.08504432 0.4243262 0.08344686 0.4228006 0.08291745 0.4222888 0.08504432 0.4243262 0.08291745 0.4222888 0.08238965 0.4217754 0.08081579 0.4202255 0.08238965 0.4217754 0.08186346 0.4212604 0.08081579 0.4202255 0.07771116 0.4170825 0.07719939 0.4165531 0.07873958 0.4181365 0.07719939 0.4165531 0.07668924 0.4160223 0.07873958 0.4181365 0.07567381 0.4149557 0.07516855 0.4144201 0.07466495 0.4138829 0.07167804 0.4106279 0.07118612 0.41008 0.072667 0.411719 0.07118612 0.41008 0.07069581 0.4095306 0.072667 0.411719 0.06683474 0.4050822 0.06635981 0.4045196 0.06494545 0.4028229 0.06635981 0.4045196 0.06588661 0.4039555 0.06494545 0.4028229 0.06401121 0.4016845 0.06354677 0.4011132 0.06494545 0.4028229 0.06354677 0.4011132 0.063084 0.4005404 0.06494545 0.4028229 0.06034475 0.3970744 0.05989438 0.3964919 0.06125074 0.3982354 0.05989438 0.3964919 0.05944585 0.3959079 0.06125074 0.3982354 0.05766969 0.3935586 0.05723017 0.3929678 0.0559225 0.3911876 0.05723017 0.3929678 0.05679249 0.3923758 0.0559225 0.3911876 0.05679249 0.3923758 0.05635654 0.3917824 0.0559225 0.3911876 0.05420452 0.3887953 0.0537796 0.388194 0.05335658 0.3875913 0.05168294 0.3851678 0.05126917 0.3845588 0.0508573 0.3839485 0.05003911 0.382724 0.0496329 0.3821099 0.0508573 0.3839485 0.0496329 0.3821099 0.04922854 0.3814946 0.0508573 0.3839485 0.04922854 0.3814946 0.04882603 0.380878 0.04842549 0.3802602 0.04684215 0.3777768 0.04645109 0.3771529 0.04763001 0.3790209 0.04645109 0.3771529 0.04606193 0.3765278 0.04763001 0.3790209 0.04376757 0.3727526 0.04339194 0.3721193 0.04452461 0.3740156 0.04339194 0.3721193 0.04301822 0.3714848 0.04452461 0.3740156 0.04301822 0.3714848 0.04264652 0.3708492 0.041543 0.3689357 0.04264652 0.3708492 0.04227674 0.3702125 0.041543 0.3689357 0.04227674 0.3702125 0.04190886 0.3695746 0.041543 0.3689357 0.0400992 0.3663686 0.03974318 0.3657241 0.03868699 0.363784 0.03974318 0.3657241 0.03938913 0.3650785 0.03868699 0.363784 0.03868699 0.363784 0.03833889 0.3631352 0.03799277 0.3624853 0.03210729 0.3506121 0.03179967 0.3499431 0.03088903 0.3479306 0.03179967 0.3499431 0.03149408 0.3492732 0.03088903 0.3479306 0.03088903 0.3479306 0.03058964 0.3472579 0.02970379 0.3452344 0.03058964 0.3472579 0.03029227 0.3465843 0.02970379 0.3452344 0.02855169 0.3425239 0.02826887 0.341844 0.02743297 0.3397994 0.02826887 0.341844 0.02798813 0.3411633 0.02743297 0.3397994 0.02688616 0.338432 0.02661591 0.3377471 0.02743297 0.3397994 0.02661591 0.3377471 0.02634775 0.3370614 0.02743297 0.3397994 0.02478313 0.3329299 0.02452975 0.3322386 0.02529621 0.3343102 0.02452975 0.3322386 0.02427852 0.3315464 0.02529621 0.3343102 0.02378243 0.3301599 0.02353757 0.3294655 0.02427852 0.3315464 0.02353757 0.3294655 0.0232948 0.3287703 0.02427852 0.3315464 0.02281576 0.3273779 0.02257943 0.3266805 0.0232948 0.3287703 0.02257943 0.3266805 0.02234524 0.3259824 0.0232948 0.3287703 0.02234524 0.3259824 0.0221132 0.3252836 0.02142995 0.323183 0.0221132 0.3252836 0.0218833 0.3245841 0.02142995 0.323183 0.02142995 0.323183 0.02120655 0.3224814 0.02054911 0.3203726 0.02120655 0.3224814 0.02098524 0.3217791 0.02054911 0.3203726 0.02012163 0.3189634 0.01991117 0.3182578 0.02054911 0.3203726 0.01991117 0.3182578 0.01970279 0.3175516 0.02054911 0.3203726 0.01773905 0.3104555 0.0175547 0.3097426 0.01811438 0.3118795 0.0175547 0.3097426 0.01737248 0.3090292 0.01811438 0.3118795 0.01632535 0.3047373 0.01615852 0.3040201 0.01666563 0.3061701 0.01615852 0.3040201 0.01599389 0.3033025 0.01666563 0.3061701 0.01599389 0.3033025 0.01583147 0.3025843 0.01535743 0.3004269 0.01583147 0.3025843 0.01567125 0.3018656 0.01535743 0.3004269 0.01475626 0.2975436 0.01461154 0.2968217 0.01419055 0.2946532 0.01461154 0.2968217 0.01446896 0.2960993 0.01419055 0.2946532 0.01392102 0.2932055 0.01378959 0.292481 0.01419055 0.2946532 0.01378959 0.292481 0.01366037 0.2917561 0.01419055 0.2946532 0.01316571 0.2888527 0.01304763 0.2881259 0.01270675 0.2859435 0.01304763 0.2881259 0.01293176 0.2873988 0.01270675 0.2859435 0.01249068 0.2844868 0.01238602 0.283758 0.01270675 0.2859435 0.01238602 0.283758 0.01228356 0.2830289 0.01270675 0.2859435 0.01171588 0.2786477 0.0116291 0.2779164 0.01189613 0.2801092 0.0116291 0.2779164 0.01154458 0.277185 0.01189613 0.2801092 0.01108461 0.2727912 0.01101583 0.2720581 0.01122897 0.2742568 0.01101583 0.2720581 0.01094925 0.2713248 0.01122897 0.2742568 0.01059722 0.2669211 0.01054644 0.2661865 0.01070559 0.2683897 0.01054644 0.2661865 0.01049792 0.2654518 0.01070559 0.2683897 0.01040762 0.263982 0.01036584 0.2632468 0.01049792 0.2654518 0.01036584 0.2632468 0.01032632 0.2625116 0.01049792 0.2654518 0.01032632 0.2625116 0.01028907 0.2617762 0.01019084 0.2595695 0.01028907 0.2617762 0.01025408 0.2610408 0.01019084 0.2595695 0.01019084 0.2595695 0.01016259 0.2588337 0.01009148 0.256626 0.01016259 0.2588337 0.01013666 0.2580979 0.01009148 0.256626 0.01013666 0.2580979 0.01011294 0.257362 0.01009148 0.256626 0.01009148 0.256626 0.01007229 0.2558899 0.0100553 0.2551538 0.0100553 0.2448462 0.01007229 0.2441101 0.01013666 0.2419021 0.01007229 0.2441101 0.01009148 0.243374 0.01013666 0.2419021 0.01009148 0.243374 0.01011294 0.242638 0.01013666 0.2419021 0.01013666 0.2419021 0.01016259 0.2411662 0.01025408 0.2389592 0.01016259 0.2411662 0.01019084 0.2404305 0.01025408 0.2389592 0.01032632 0.2374883 0.01036584 0.2367531 0.01025408 0.2389592 0.01036584 0.2367531 0.01040762 0.236018 0.01025408 0.2389592 0.01040762 0.236018 0.01045161 0.235283 0.01059722 0.2330788 0.01045161 0.235283 0.01049792 0.2345482 0.01059722 0.2330788 0.01059722 0.2330788 0.01065027 0.2323445 0.01082289 0.2301423 0.01065027 0.2323445 0.01070559 0.2316102 0.01082289 0.2301423 0.01154458 0.2228149 0.0116291 0.2220835 0.01138228 0.2242786 0.0116291 0.2220835 0.01171588 0.2213523 0.01138228 0.2242786 0.01228356 0.2169712 0.01238602 0.216242 0.01208537 0.2184303 0.01238602 0.216242 0.01249068 0.2155132 0.01208537 0.2184303 0.01366037 0.2082439 0.01378959 0.2075189 0.01392102 0.2067945 0.01446896 0.2039006 0.01461154 0.2031783 0.01475626 0.2024564 0.01567125 0.1981343 0.01583147 0.1974157 0.01632535 0.1952627 0.01583147 0.1974157 0.01599389 0.1966975 0.01632535 0.1952627 0.01737248 0.1909708 0.0175547 0.1902573 0.01701468 0.1923993 0.0175547 0.1902573 0.01773905 0.1895445 0.01701468 0.1923993 0.01849842 0.1866989 0.01869374 0.1859889 0.01929265 0.1838628 0.01869374 0.1859889 0.01889121 0.1852796 0.01929265 0.1838628 0.01970279 0.1824484 0.01991117 0.1817421 0.01929265 0.1838628 0.01991117 0.1817421 0.02012163 0.1810365 0.01929265 0.1838628 0.02098524 0.1782208 0.02120655 0.1775186 0.0218833 0.1754159 0.02120655 0.1775186 0.02142995 0.1768169 0.0218833 0.1754159 0.0218833 0.1754159 0.0221132 0.1747164 0.02281576 0.1726222 0.0221132 0.1747164 0.02234524 0.1740176 0.02281576 0.1726222 0.02634775 0.1629386 0.02661591 0.1622529 0.02581775 0.1643126 0.02661591 0.1622529 0.02688616 0.1615679 0.02581775 0.1643126 0.02798813 0.1588367 0.02826887 0.1581559 0.0291236 0.1561191 0.02826887 0.1581559 0.02855169 0.1574761 0.0291236 0.1561191 0.03029227 0.1534156 0.03058964 0.152742 0.03149408 0.1507267 0.03058964 0.152742 0.03088903 0.1520694 0.03149408 0.1507267 0.03799277 0.1375147 0.03833889 0.1368647 0.03938913 0.1349215 0.03833889 0.1368647 0.03868699 0.1362159 0.03938913 0.1349215 0.041543 0.1310643 0.04190886 0.1304253 0.04081714 0.1323456 0.04190886 0.1304253 0.04227674 0.1297875 0.04081714 0.1323456 0.04227674 0.1297875 0.04264652 0.1291508 0.04376757 0.1272475 0.04264652 0.1291508 0.04301822 0.1285152 0.04376757 0.1272475 0.04301822 0.1285152 0.04339194 0.1278807 0.04376757 0.1272475 0.04606193 0.1234722 0.04645109 0.1228471 0.04528945 0.1247259 0.04645109 0.1228471 0.04684215 0.1222232 0.04528945 0.1247259 0.04842549 0.1197398 0.04882603 0.119122 0.04922854 0.1185054 0.04922854 0.1185054 0.0496329 0.1178901 0.04842549 0.1197398 0.0496329 0.1178901 0.05003911 0.117276 0.04842549 0.1197398 0.0508573 0.1160515 0.05126917 0.1154412 0.05168294 0.1148321 0.05335658 0.1124086 0.0537796 0.111806 0.05420452 0.1112046 0.0559225 0.1088124 0.05635654 0.1082177 0.05679249 0.1076242 0.05679249 0.1076242 0.05723017 0.1070321 0.05855417 0.105264 0.05723017 0.1070321 0.05766969 0.1064414 0.05855417 0.105264 0.05944585 0.104092 0.05989438 0.1035081 0.05855417 0.105264 0.05989438 0.1035081 0.06034475 0.1029255 0.05855417 0.105264 0.063084 0.09945952 0.06354677 0.09888678 0.06216382 0.1006093 0.06354677 0.09888678 0.06401121 0.09831547 0.06216382 0.1006093 0.06588661 0.09604454 0.06635981 0.09548038 0.06778979 0.09379678 0.06635981 0.09548038 0.06683474 0.09491771 0.06778979 0.09379678 0.07069581 0.09046936 0.07118612 0.08991998 0.06972038 0.09157252 0.07118612 0.08991998 0.07167804 0.08937215 0.06972038 0.09157252 0.07466495 0.08611702 0.07516855 0.08557987 0.07366263 0.08719593 0.07516855 0.08557987 0.07567381 0.08504432 0.07366263 0.08719593 0.07668924 0.08397775 0.07719939 0.08344686 0.07567381 0.08504432 0.07719939 0.08344686 0.07771116 0.08291745 0.07567381 0.08504432 0.07771116 0.08291745 0.07822459 0.08238965 0.07977449 0.08081579 0.07822459 0.08238965 0.07873958 0.08186346 0.07977449 0.08081579 0.08291745 0.07771116 0.08344686 0.07719939 0.08186346 0.07873958 0.08344686 0.07719939 0.08397775 0.07668924 0.08186346 0.07873958 0.08504432 0.07567381 0.08557987 0.07516855 0.08611702 0.07466495 0.08937215 0.07167804 0.08991998 0.07118612 0.08828103 0.072667 0.08991998 0.07118612 0.09046936 0.07069581 0.08828103 0.072667 0.09491771 0.06683474 0.09548038 0.06635981 0.09717714 0.06494545 0.09548038 0.06635981 0.09604454 0.06588661 0.09717714 0.06494545 0.09831547 0.06401121 0.09888678 0.06354677 0.09717714 0.06494545 0.09888678 0.06354677 0.09945952 0.063084 0.09717714 0.06494545 0.1029255 0.06034475 0.1035081 0.05989438 0.1017646 0.06125074 0.1035081 0.05989438 0.104092 0.05944585 0.1017646 0.06125074 0.1064414 0.05766969 0.1070321 0.05723017 0.1088124 0.0559225 0.1070321 0.05723017 0.1076242 0.05679249 0.1088124 0.0559225 0.1076242 0.05679249 0.1082177 0.05635654 0.1088124 0.0559225 0.1112046 0.05420452 0.111806 0.0537796 0.1124086 0.05335658 0.1148321 0.05168294 0.1154412 0.05126917 0.1160515 0.0508573 0.117276 0.05003911 0.1178901 0.0496329 0.1160515 0.0508573 0.1178901 0.0496329 0.1185054 0.04922854 0.1160515 0.0508573 0.1185054 0.04922854 0.119122 0.04882603 0.1197398 0.04842549 0.1222232 0.04684215 0.1228471 0.04645109 0.1209791 0.04763001 0.1228471 0.04645109 0.1234722 0.04606193 0.1209791 0.04763001 0.1272475 0.04376757 0.1278807 0.04339194 0.1259843 0.04452461 0.1278807 0.04339194 0.1285152 0.04301822 0.1259843 0.04452461 0.1285152 0.04301822 0.1291508 0.04264652 0.1310643 0.041543 0.1291508 0.04264652 0.1297875 0.04227674 0.1310643 0.041543 0.1297875 0.04227674 0.1304253 0.04190886 0.1310643 0.041543 0.1336314 0.0400992 0.1342759 0.03974318 0.1362159 0.03868699 0.1342759 0.03974318 0.1349215 0.03938913 0.1362159 0.03868699 0.1362159 0.03868699 0.1368647 0.03833889 0.1375147 0.03799277 0.1493879 0.03210729 0.1500568 0.03179967 0.1520694 0.03088903 0.1500568 0.03179967 0.1507267 0.03149408 0.1520694 0.03088903 0.1520694 0.03088903 0.152742 0.03058964 0.1547656 0.02970379 0.152742 0.03058964 0.1534156 0.03029227 0.1547656 0.02970379 0.1574761 0.02855169 0.1581559 0.02826887 0.1602006 0.02743297 0.1581559 0.02826887 0.1588367 0.02798813 0.1602006 0.02743297 0.1615679 0.02688616 0.1622529 0.02661591 0.1602006 0.02743297 0.1622529 0.02661591 0.1629386 0.02634775 0.1602006 0.02743297 0.16707 0.02478313 0.1677614 0.02452975 0.1656897 0.02529621 0.1677614 0.02452975 0.1684535 0.02427852 0.1656897 0.02529621 0.16984 0.02378243 0.1705344 0.02353757 0.1684535 0.02427852 0.1705344 0.02353757 0.1712296 0.0232948 0.1684535 0.02427852 0.1726222 0.02281576 0.1733195 0.02257943 0.1712296 0.0232948 0.1733195 0.02257943 0.1740176 0.02234524 0.1712296 0.0232948 0.1740176 0.02234524 0.1747164 0.0221132 0.1768169 0.02142995 0.1747164 0.0221132 0.1754159 0.0218833 0.1768169 0.02142995 0.1768169 0.02142995 0.1775186 0.02120655 0.1796274 0.02054911 0.1775186 0.02120655 0.1782208 0.02098524 0.1796274 0.02054911 0.1810365 0.02012163 0.1817421 0.01991117 0.1796274 0.02054911 0.1817421 0.01991117 0.1824484 0.01970279 0.1796274 0.02054911 0.1895445 0.01773905 0.1902573 0.0175547 0.1881205 0.01811438 0.1902573 0.0175547 0.1909708 0.01737248 0.1881205 0.01811438 0.1952627 0.01632535 0.1959798 0.01615852 0.1938299 0.01666563 0.1959798 0.01615852 0.1966975 0.01599389 0.1938299 0.01666563 0.1966975 0.01599389 0.1974157 0.01583147 0.1995731 0.01535743 0.1974157 0.01583147 0.1981343 0.01567125 0.1995731 0.01535743 0.2024564 0.01475626 0.2031783 0.01461154 0.2053467 0.01419055 0.2031783 0.01461154 0.2039006 0.01446896 0.2053467 0.01419055 0.2067945 0.01392102 0.2075189 0.01378959 0.2053467 0.01419055 0.2075189 0.01378959 0.2082439 0.01366037 0.2053467 0.01419055 0.2111473 0.01316571 0.211874 0.01304763 0.2140565 0.01270675 0.211874 0.01304763 0.2126011 0.01293176 0.2140565 0.01270675 0.2155132 0.01249068 0.216242 0.01238602 0.2140565 0.01270675 0.216242 0.01238602 0.2169712 0.01228356 0.2140565 0.01270675 0.2213523 0.01171588 0.2220835 0.0116291 0.2198908 0.01189613 0.2220835 0.0116291 0.2228149 0.01154458 0.2198908 0.01189613 0.2272087 0.01108461 0.2279418 0.01101583 0.2257432 0.01122897 0.2279418 0.01101583 0.2286751 0.01094925 0.2257432 0.01122897 0.2330788 0.01059722 0.2338134 0.01054644 0.2316102 0.01070559 0.2338134 0.01054644 0.2345482 0.01049792 0.2316102 0.01070559 0.236018 0.01040762 0.2367531 0.01036584 0.2345482 0.01049792 0.2367531 0.01036584 0.2374883 0.01032632 0.2345482 0.01049792 0.2374883 0.01032632 0.2382237 0.01028907 0.2404305 0.01019084 0.2382237 0.01028907 0.2389592 0.01025408 0.2404305 0.01019084 0.2404305 0.01019084 0.2411662 0.01016259 0.243374 0.01009148 0.2411662 0.01016259 0.2419021 0.01013666 0.243374 0.01009148 0.2419021 0.01013666 0.242638 0.01011294 0.243374 0.01009148 0.243374 0.01009148 0.2441101 0.01007229 0.2448462 0.0100553 0.2551538 0.0100553 0.2558899 0.01007229 0.2580979 0.01013666 0.2558899 0.01007229 0.256626 0.01009148 0.2580979 0.01013666 0.256626 0.01009148 0.257362 0.01011294 0.2580979 0.01013666 0.2580979 0.01013666 0.2588337 0.01016259 0.2610408 0.01025408 0.2588337 0.01016259 0.2595695 0.01019084 0.2610408 0.01025408 0.2625116 0.01032632 0.2632468 0.01036584 0.2610408 0.01025408 0.2632468 0.01036584 0.263982 0.01040762 0.2610408 0.01025408 0.263982 0.01040762 0.264717 0.01045161 0.2669211 0.01059722 0.264717 0.01045161 0.2654518 0.01049792 0.2669211 0.01059722 0.2669211 0.01059722 0.2676555 0.01065027 0.2698577 0.01082289 0.2676555 0.01065027 0.2683897 0.01070559 0.2698577 0.01082289 0.277185 0.01154458 0.2779164 0.0116291 0.2757214 0.01138228 0.2779164 0.0116291 0.2786477 0.01171588 0.2757214 0.01138228 0.2830289 0.01228356 0.283758 0.01238602 0.2815696 0.01208537 0.283758 0.01238602 0.2844868 0.01249068 0.2815696 0.01208537 0.2917561 0.01366037 0.292481 0.01378959 0.2932055 0.01392102 0.2960993 0.01446896 0.2968217 0.01461154 0.2975436 0.01475626 0.3018656 0.01567125 0.3025843 0.01583147 0.3047373 0.01632535 0.3025843 0.01583147 0.3033025 0.01599389 0.3047373 0.01632535 0.3090292 0.01737248 0.3097426 0.0175547 0.3076007 0.01701468 0.3097426 0.0175547 0.3104555 0.01773905 0.3076007 0.01701468 0.3133011 0.01849842 0.314011 0.01869374 0.3161373 0.01929265 0.314011 0.01869374 0.3147204 0.01889121 0.3161373 0.01929265 0.3175516 0.01970279 0.3182578 0.01991117 0.3161373 0.01929265 0.3182578 0.01991117 0.3189634 0.02012163 0.3161373 0.01929265 0.3217791 0.02098524 0.3224814 0.02120655 0.3245841 0.0218833 0.3224814 0.02120655 0.323183 0.02142995 0.3245841 0.0218833 0.3245841 0.0218833 0.3252836 0.0221132 0.3273779 0.02281576 0.3252836 0.0221132 0.3259824 0.02234524 0.3273779 0.02281576 0.3370614 0.02634775 0.3377471 0.02661591 0.3356874 0.02581775 0.3377471 0.02661591 0.338432 0.02688616 0.3356874 0.02581775 0.3411633 0.02798813 0.341844 0.02826887 0.3438809 0.0291236 0.341844 0.02826887 0.3425239 0.02855169 0.3438809 0.0291236 0.3465843 0.03029227 0.3472579 0.03058964 0.3492732 0.03149408 0.3472579 0.03058964 0.3479306 0.03088903 0.3492732 0.03149408 0.3624853 0.03799277 0.3631352 0.03833889 0.3650785 0.03938913 0.3631352 0.03833889 0.363784 0.03868699 0.3650785 0.03938913 0.3689357 0.041543 0.3695746 0.04190886 0.3676543 0.04081714 0.3695746 0.04190886 0.3702125 0.04227674 0.3676543 0.04081714 0.3702125 0.04227674 0.3708492 0.04264652 0.3727526 0.04376757 0.3708492 0.04264652 0.3714848 0.04301822 0.3727526 0.04376757 0.3714848 0.04301822 0.3721193 0.04339194 0.3727526 0.04376757 0.3765278 0.04606193 0.3771529 0.04645109 0.3752741 0.04528945 0.3771529 0.04645109 0.3777768 0.04684215 0.3752741 0.04528945 0.3802602 0.04842549 0.380878 0.04882603 0.3814946 0.04922854 0.3814946 0.04922854 0.3821099 0.0496329 0.3802602 0.04842549 0.3821099 0.0496329 0.382724 0.05003911 0.3802602 0.04842549 0.3839485 0.0508573 0.3845588 0.05126917 0.3851678 0.05168294 0.3875913 0.05335658 0.388194 0.0537796 0.3887953 0.05420452 0.3911876 0.0559225 0.3917824 0.05635654 0.3923758 0.05679249 0.3923758 0.05679249 0.3929678 0.05723017 0.394736 0.05855417 0.3929678 0.05723017 0.3935586 0.05766969 0.394736 0.05855417 0.3959079 0.05944585 0.3964919 0.05989438 0.394736 0.05855417 0.3964919 0.05989438 0.3970744 0.06034475 0.394736 0.05855417 0.4005404 0.063084 0.4011132 0.06354677 0.3993907 0.06216382 0.4011132 0.06354677 0.4016845 0.06401121 0.3993907 0.06216382 0.4039555 0.06588661 0.4045196 0.06635981 0.4062032 0.06778979 0.4045196 0.06635981 0.4050822 0.06683474 0.4062032 0.06778979 0.4095306 0.07069581 0.41008 0.07118612 0.4084274 0.06972038 0.41008 0.07118612 0.4106279 0.07167804 0.4084274 0.06972038 0.4138829 0.07466495 0.4144201 0.07516855 0.412804 0.07366263 0.4144201 0.07516855 0.4149557 0.07567381 0.412804 0.07366263 0.4160223 0.07668924 0.4165531 0.07719939 0.4149557 0.07567381 0.4165531 0.07719939 0.4170825 0.07771116 0.4149557 0.07567381 0.4170825 0.07771116 0.4176103 0.07822459 0.4191842 0.07977449 0.4176103 0.07822459 0.4181365 0.07873958 0.4191842 0.07977449 0.4222888 0.08291745 0.4228006 0.08344686 0.4212604 0.08186346 0.4228006 0.08344686 0.4233108 0.08397775 0.4212604 0.08186346 0.4243262 0.08504432 0.4248315 0.08557987 0.4253351 0.08611702 0.4283219 0.08937215 0.4288139 0.08991998 0.4273329 0.08828103 0.4288139 0.08991998 0.4293041 0.09046936 0.4273329 0.08828103 0.4331652 0.09491771 0.4336401 0.09548038 0.4350546 0.09717714 0.4336401 0.09548038 0.4341133 0.09604454 0.4350546 0.09717714 0.4359887 0.09831547 0.4364532 0.09888678 0.4350546 0.09717714 0.4364532 0.09888678 0.4369159 0.09945952 0.4350546 0.09717714 0.4396553 0.1029255 0.4401056 0.1035081 0.4387493 0.1017646 0.4401056 0.1035081 0.4405541 0.104092 0.4387493 0.1017646 0.4423303 0.1064414 0.4427698 0.1070321 0.4440775 0.1088124 0.4427698 0.1070321 0.4432075 0.1076242 0.4440775 0.1088124 0.4432075 0.1076242 0.4436434 0.1082177 0.4440775 0.1088124 0.4457954 0.1112046 0.4462203 0.111806 0.4466434 0.1124086 0.4483171 0.1148321 0.4487308 0.1154412 0.4491427 0.1160515 0.4499608 0.117276 0.4503671 0.1178901 0.4491427 0.1160515 0.4503671 0.1178901 0.4507715 0.1185054 0.4491427 0.1160515 0.4507715 0.1185054 0.4511739 0.119122 0.4515745 0.1197398 0.4531578 0.1222232 0.4535489 0.1228471 0.45237 0.1209791 0.4535489 0.1228471 0.453938 0.1234722 0.45237 0.1209791 0.4562324 0.1272475 0.4566081 0.1278807 0.4554753 0.1259843 0.4566081 0.1278807 0.4569817 0.1285152 0.4554753 0.1259843 0.4569817 0.1285152 0.4573535 0.1291508 0.4584569 0.1310643 0.4573535 0.1291508 0.4577233 0.1297875 0.4584569 0.1310643 0.4577233 0.1297875 0.4580911 0.1304253 0.4584569 0.1310643 0.4599008 0.1336314 0.4602568 0.1342759 0.461313 0.1362159 0.4602568 0.1342759 0.4606109 0.1349215 0.461313 0.1362159 0.461313 0.1362159 0.4616611 0.1368647 0.4620072 0.1375147 0.4678927 0.1493879 0.4682003 0.1500568 0.4691109 0.1520694 0.4682003 0.1500568 0.4685059 0.1507267 0.4691109 0.1520694 0.4691109 0.1520694 0.4694103 0.152742 0.4702962 0.1547656 0.4694103 0.152742 0.4697077 0.1534156 0.4702962 0.1547656 0.4714483 0.1574761 0.4717311 0.1581559 0.472567 0.1602006 0.4717311 0.1581559 0.4720118 0.1588367 0.472567 0.1602006 0.4731138 0.1615679 0.4733841 0.1622529 0.472567 0.1602006 0.4733841 0.1622529 0.4736523 0.1629386 0.472567 0.1602006 0.4752169 0.16707 0.4754702 0.1677614 0.4747037 0.1656897 0.4754702 0.1677614 0.4757214 0.1684535 0.4747037 0.1656897 0.4762176 0.16984 0.4764624 0.1705344 0.4757214 0.1684535 0.4764624 0.1705344 0.4767051 0.1712296 0.4757214 0.1684535 0.4771842 0.1726222 0.4774205 0.1733195 0.4767051 0.1712296 0.4774205 0.1733195 0.4776547 0.1740176 0.4767051 0.1712296 0.4776547 0.1740176 0.4778867 0.1747164 0.47857 0.1768169 0.4778867 0.1747164 0.4781166 0.1754159 0.47857 0.1768169 0.47857 0.1768169 0.4787935 0.1775186 0.4794509 0.1796274 0.4787935 0.1775186 0.4790148 0.1782208 0.4794509 0.1796274 0.4798783 0.1810365 0.4800888 0.1817421 0.4794509 0.1796274 0.4800888 0.1817421 0.4802972 0.1824484 0.4794509 0.1796274 0.4822609 0.1895445 0.4824453 0.1902573 0.4818856 0.1881205 0.4824453 0.1902573 0.4826275 0.1909708 0.4818856 0.1881205 0.4836746 0.1952627 0.4838414 0.1959798 0.4833344 0.1938299 0.4838414 0.1959798 0.4840061 0.1966975 0.4833344 0.1938299 0.4840061 0.1966975 0.4841685 0.1974157 0.4846426 0.1995731 0.4841685 0.1974157 0.4843288 0.1981343 0.4846426 0.1995731 0.4852437 0.2024564 0.4853885 0.2031783 0.4858095 0.2053467 0.4853885 0.2031783 0.485531 0.2039006 0.4858095 0.2053467 0.486079 0.2067945 0.4862104 0.2075189 0.4858095 0.2053467 0.4862104 0.2075189 0.4863396 0.2082439 0.4858095 0.2053467 0.4868342 0.2111473 0.4869523 0.211874 0.4872932 0.2140565 0.4869523 0.211874 0.4870682 0.2126011 0.4872932 0.2140565 0.4875093 0.2155132 0.487614 0.216242 0.4872932 0.2140565 0.487614 0.216242 0.4877164 0.2169712 0.4872932 0.2140565 0.4882841 0.2213523 0.4883708 0.2220835 0.4881038 0.2198908 0.4883708 0.2220835 0.4884554 0.2228149 0.4881038 0.2198908 0.4889154 0.2272087 0.4889842 0.2279418 0.488771 0.2257432 0.4889842 0.2279418 0.4890507 0.2286751 0.488771 0.2257432 0.4894027 0.2330788 0.4894535 0.2338134 0.4892944 0.2316102 0.4894535 0.2338134 0.4895021 0.2345482 0.4892944 0.2316102 0.4895924 0.236018 0.4896341 0.2367531 0.4895021 0.2345482 0.4896341 0.2367531 0.4896737 0.2374883 0.4895021 0.2345482 0.4896737 0.2374883 0.4897109 0.2382237 0.4898092 0.2404305 0.4897109 0.2382237 0.4897459 0.2389592 0.4898092 0.2404305 0.4898092 0.2404305 0.4898374 0.2411662 0.4899085 0.243374 0.4898374 0.2411662 0.4898633 0.2419021 0.4899085 0.243374 0.4898633 0.2419021 0.4898871 0.242638 0.4899085 0.243374 0.4899085 0.243374 0.4899277 0.2441101 0.4899446 0.2448462 0.4899446 0.2551538 0.4899277 0.2558899 0.4898633 0.2580979 0.4899277 0.2558899 0.4899085 0.256626 0.4898633 0.2580979 0.4899085 0.256626 0.4898871 0.257362 0.4898633 0.2580979 0.4898633 0.2580979 0.4898374 0.2588337 0.4897459 0.2610408 0.4898374 0.2588337 0.4898092 0.2595695 0.4897459 0.2610408 0.4896737 0.2625116 0.4896341 0.2632468 0.4897459 0.2610408 0.4896341 0.2632468 0.4895924 0.263982 0.4897459 0.2610408 0.4895924 0.263982 0.4895483 0.264717 0.4894027 0.2669211 0.4895483 0.264717 0.4895021 0.2654518 0.4894027 0.2669211 0.4894027 0.2669211 0.4893497 0.2676555 0.4891771 0.2698577 0.4893497 0.2676555 0.4892944 0.2683897 0.4891771 0.2698577 0.4884554 0.277185 0.4883708 0.2779164 0.4886177 0.2757214 0.4883708 0.2779164 0.4882841 0.2786477 0.4886177 0.2757214 0.4877164 0.2830289 0.487614 0.283758 0.4879146 0.2815696 0.487614 0.283758 0.4875093 0.2844868 0.4879146 0.2815696 0.4863396 0.2917561 0.4862104 0.292481 0.486079 0.2932055 0.485531 0.2960993 0.4853885 0.2968217 0.4852437 0.2975436 0.4843288 0.3018656 0.4841685 0.3025843 0.4836746 0.3047373 0.4841685 0.3025843 0.4840061 0.3033025 0.4836746 0.3047373 0.4826275 0.3090292 0.4824453 0.3097426 0.4829853 0.3076007 0.4824453 0.3097426 0.4822609 0.3104555 0.4829853 0.3076007 0.4815015 0.3133011 0.4813063 0.314011 0.4807073 0.3161373 0.4813063 0.314011 0.4811088 0.3147204 0.4807073 0.3161373 0.4802972 0.3175516 0.4800888 0.3182578 0.4807073 0.3161373 0.4800888 0.3182578 0.4798783 0.3189634 0.4807073 0.3161373 0.4790148 0.3217791 0.4787935 0.3224814 0.4781166 0.3245841 0.4787935 0.3224814 0.47857 0.323183 0.4781166 0.3245841 0.4781166 0.3245841 0.4778867 0.3252836 0.4771842 0.3273779 0.4778867 0.3252836 0.4776547 0.3259824 0.4771842 0.3273779 0.4736523 0.3370614 0.4733841 0.3377471 0.4741822 0.3356874 0.4733841 0.3377471 0.4731138 0.338432 0.4741822 0.3356874 0.4720118 0.3411633 0.4717311 0.341844 0.4708764 0.3438809 0.4717311 0.341844 0.4714483 0.3425239 0.4708764 0.3438809 0.4697077 0.3465843 0.4694103 0.3472579 0.4685059 0.3492732 0.4694103 0.3472579 0.4691109 0.3479306 0.4685059 0.3492732 0.4620072 0.3624853 0.4616611 0.3631352 0.4606109 0.3650785 0.4616611 0.3631352 0.461313 0.363784 0.4606109 0.3650785 0.4584569 0.3689357 0.4580911 0.3695746 0.4591828 0.3676543 0.4580911 0.3695746 0.4577233 0.3702125 0.4591828 0.3676543 0.4577233 0.3702125 0.4573535 0.3708492 0.4562324 0.3727526 0.4573535 0.3708492 0.4569817 0.3714848 0.4562324 0.3727526 0.4569817 0.3714848 0.4566081 0.3721193 0.4562324 0.3727526 0.453938 0.3765278 0.4535489 0.3771529 0.4547106 0.3752741 0.4535489 0.3771529 0.4531578 0.3777768 0.4547106 0.3752741 0.4515745 0.3802602 0.4511739 0.380878 0.4507715 0.3814946 0.4507715 0.3814946 0.4503671 0.3821099 0.4515745 0.3802602 0.4503671 0.3821099 0.4499608 0.382724 0.4515745 0.3802602 0.4491427 0.3839485 0.4487308 0.3845588 0.4483171 0.3851678 0.4466434 0.3875913 0.4462203 0.388194 0.4457954 0.3887953 0.4440775 0.3911876 0.4436434 0.3917824 0.4432075 0.3923758 0.4432075 0.3923758 0.4427698 0.3929678 0.4414458 0.394736 0.4427698 0.3929678 0.4423303 0.3935586 0.4414458 0.394736 0.4405541 0.3959079 0.4401056 0.3964919 0.4414458 0.394736 0.4401056 0.3964919 0.4396553 0.3970744 0.4414458 0.394736 0.4369159 0.4005404 0.4364532 0.4011132 0.4378361 0.3993907 0.4364532 0.4011132 0.4359887 0.4016845 0.4378361 0.3993907 0.4341133 0.4039555 0.4336401 0.4045196 0.4322102 0.4062032 0.4336401 0.4045196 0.4331652 0.4050822 0.4322102 0.4062032 0.4293041 0.4095306 0.4288139 0.41008 0.4302796 0.4084274 0.4288139 0.41008 0.4283219 0.4106279 0.4302796 0.4084274 0.4253351 0.4138829 0.4248315 0.4144201 0.4263373 0.412804 0.4248315 0.4144201 0.4243262 0.4149557 0.4263373 0.412804 0.4233108 0.4160223 0.4228006 0.4165531 0.4243262 0.4149557 0.4228006 0.4165531 0.4222888 0.4170825 0.4243262 0.4149557 0.4222888 0.4170825 0.4217754 0.4176103 0.4202255 0.4191842 0.4217754 0.4176103 0.4212604 0.4181365 0.4202255 0.4191842 0.4170825 0.4222888 0.4165531 0.4228006 0.4181365 0.4212604 0.4165531 0.4228006 0.4160223 0.4233108 0.4181365 0.4212604 0.4149557 0.4243262 0.4144201 0.4248315 0.4138829 0.4253351 0.4106279 0.4283219 0.41008 0.4288139 0.411719 0.4273329 0.41008 0.4288139 0.4095306 0.4293041 0.411719 0.4273329 0.4050822 0.4331652 0.4045196 0.4336401 0.4028229 0.4350546 0.4045196 0.4336401 0.4039555 0.4341133 0.4028229 0.4350546 0.4016845 0.4359887 0.4011132 0.4364532 0.4028229 0.4350546 0.4011132 0.4364532 0.4005404 0.4369159 0.4028229 0.4350546 0.3970744 0.4396553 0.3964919 0.4401056 0.3982354 0.4387493 0.3964919 0.4401056 0.3959079 0.4405541 0.3982354 0.4387493 0.3935586 0.4423303 0.3929678 0.4427698 0.3911876 0.4440775 0.3929678 0.4427698 0.3923758 0.4432075 0.3911876 0.4440775 0.3923758 0.4432075 0.3917824 0.4436434 0.3911876 0.4440775 0.3887953 0.4457954 0.388194 0.4462203 0.3875913 0.4466434 0.3851678 0.4483171 0.3845588 0.4487308 0.3839485 0.4491427 0.382724 0.4499608 0.3821099 0.4503671 0.3839485 0.4491427 0.3821099 0.4503671 0.3814946 0.4507715 0.3839485 0.4491427 0.3814946 0.4507715 0.380878 0.4511739 0.3802602 0.4515745 0.3777768 0.4531578 0.3771529 0.4535489 0.3790209 0.45237 0.3771529 0.4535489 0.3765278 0.453938 0.3790209 0.45237 0.3727526 0.4562324 0.3721193 0.4566081 0.3740156 0.4554753 0.3721193 0.4566081 0.3714848 0.4569817 0.3740156 0.4554753 0.3714848 0.4569817 0.3708492 0.4573535 0.3689357 0.4584569 0.3708492 0.4573535 0.3702125 0.4577233 0.3689357 0.4584569 0.3702125 0.4577233 0.3695746 0.4580911 0.3689357 0.4584569 0.3663686 0.4599008 0.3657241 0.4602568 0.363784 0.461313 0.3657241 0.4602568 0.3650785 0.4606109 0.363784 0.461313 0.363784 0.461313 0.3631352 0.4616611 0.3624853 0.4620072 0.3506121 0.4678927 0.3499431 0.4682003 0.3479306 0.4691109 0.3499431 0.4682003 0.3492732 0.4685059 0.3479306 0.4691109 0.3479306 0.4691109 0.3472579 0.4694103 0.3452344 0.4702962 0.3472579 0.4694103 0.3465843 0.4697077 0.3452344 0.4702962 0.3425239 0.4714483 0.341844 0.4717311 0.3397994 0.472567 0.341844 0.4717311 0.3411633 0.4720118 0.3397994 0.472567 0.338432 0.4731138 0.3377471 0.4733841 0.3397994 0.472567 0.3377471 0.4733841 0.3370614 0.4736523 0.3397994 0.472567 0.3329299 0.4752169 0.3322386 0.4754702 0.3343102 0.4747037 0.3322386 0.4754702 0.3315464 0.4757214 0.3343102 0.4747037 0.3301599 0.4762176 0.3294655 0.4764624 0.3315464 0.4757214 0.3294655 0.4764624 0.3287703 0.4767051 0.3315464 0.4757214 0.3273779 0.4771842 0.3266805 0.4774205 0.3287703 0.4767051 0.3266805 0.4774205 0.3259824 0.4776547 0.3287703 0.4767051 0.3259824 0.4776547 0.3252836 0.4778867 0.323183 0.47857 0.3252836 0.4778867 0.3245841 0.4781166 0.323183 0.47857 0.323183 0.47857 0.3224814 0.4787935 0.3203726 0.4794509 0.3224814 0.4787935 0.3217791 0.4790148 0.3203726 0.4794509 0.3189634 0.4798783 0.3182578 0.4800888 0.3203726 0.4794509 0.3182578 0.4800888 0.3175516 0.4802972 0.3203726 0.4794509 0.3104555 0.4822609 0.3097426 0.4824453 0.3118795 0.4818856 0.3097426 0.4824453 0.3090292 0.4826275 0.3118795 0.4818856 0.3047373 0.4836746 0.3040201 0.4838414 0.3061701 0.4833344 0.3040201 0.4838414 0.3033025 0.4840061 0.3061701 0.4833344 0.3033025 0.4840061 0.3025843 0.4841685 0.3004269 0.4846426 0.3025843 0.4841685 0.3018656 0.4843288 0.3004269 0.4846426 0.2975436 0.4852437 0.2968217 0.4853885 0.2946532 0.4858095 0.2968217 0.4853885 0.2960993 0.485531 0.2946532 0.4858095 0.2932055 0.486079 0.292481 0.4862104 0.2946532 0.4858095 0.292481 0.4862104 0.2917561 0.4863396 0.2946532 0.4858095 0.2888527 0.4868342 0.2881259 0.4869523 0.2859435 0.4872932 0.2881259 0.4869523 0.2873988 0.4870682 0.2859435 0.4872932 0.2844868 0.4875093 0.283758 0.487614 0.2859435 0.4872932 0.283758 0.487614 0.2830289 0.4877164 0.2859435 0.4872932 0.2786477 0.4882841 0.2779164 0.4883708 0.2801092 0.4881038 0.2779164 0.4883708 0.277185 0.4884554 0.2801092 0.4881038 0.2727912 0.4889154 0.2720581 0.4889842 0.2742568 0.488771 0.2720581 0.4889842 0.2713248 0.4890507 0.2742568 0.488771 0.2669211 0.4894027 0.2661865 0.4894535 0.2683897 0.4892944 0.2661865 0.4894535 0.2654518 0.4895021 0.2683897 0.4892944 0.263982 0.4895924 0.2632468 0.4896341 0.2654518 0.4895021 0.2632468 0.4896341 0.2625116 0.4896737 0.2654518 0.4895021 0.2625116 0.4896737 0.2617762 0.4897109 0.2595695 0.4898092 0.2617762 0.4897109 0.2610408 0.4897459 0.2595695 0.4898092 0.2595695 0.4898092 0.2588337 0.4898374 0.256626 0.4899085 0.2588337 0.4898374 0.2580979 0.4898633 0.256626 0.4899085 0.2580979 0.4898633 0.257362 0.4898871 0.256626 0.4899085 0.256626 0.4899085 0.2558899 0.4899277 0.2551538 0.4899446 0.2507363 0.4899989 0.2492637 0.4899989 0.2477911 0.4899898 0.2477911 0.4899898 0.2463186 0.4899718 0.2448462 0.4899446 0.2301423 0.4891771 0.2286751 0.4890507 0.2272087 0.4889154 0.2272087 0.4889154 0.2257432 0.488771 0.2213523 0.4882841 0.2257432 0.488771 0.2242786 0.4886177 0.2213523 0.4882841 0.2213523 0.4882841 0.2198908 0.4881038 0.2184303 0.4879146 0.2155132 0.4875093 0.2140565 0.4872932 0.2126011 0.4870682 0.2126011 0.4870682 0.2111473 0.4868342 0.2155132 0.4875093 0.2111473 0.4868342 0.2096948 0.4865914 0.2155132 0.4875093 0.2096948 0.4865914 0.2082439 0.4863396 0.2039006 0.485531 0.2082439 0.4863396 0.2067945 0.486079 0.2039006 0.485531 0.2067945 0.486079 0.2053467 0.4858095 0.2039006 0.485531 0.2039006 0.485531 0.2024564 0.4852437 0.1981343 0.4843288 0.2024564 0.4852437 0.2010138 0.4849476 0.1981343 0.4843288 0.2010138 0.4849476 0.1995731 0.4846426 0.1981343 0.4843288 0.1952627 0.4836746 0.1938299 0.4833344 0.1981343 0.4843288 0.1938299 0.4833344 0.1923993 0.4829853 0.1981343 0.4843288 0.1895445 0.4822609 0.1881205 0.4818856 0.1923993 0.4829853 0.1881205 0.4818856 0.1866989 0.4815015 0.1923993 0.4829853 0.1810365 0.4798783 0.1796274 0.4794509 0.1782208 0.4790148 0.1726222 0.4771842 0.1712296 0.4767051 0.1754159 0.4781166 0.1712296 0.4767051 0.16984 0.4762176 0.1754159 0.4781166 0.16984 0.4762176 0.1684535 0.4757214 0.1643126 0.4741822 0.1684535 0.4757214 0.16707 0.4752169 0.1643126 0.4741822 0.16707 0.4752169 0.1656897 0.4747037 0.1643126 0.4741822 0.1615679 0.4731138 0.1602006 0.472567 0.1643126 0.4741822 0.1602006 0.472567 0.1588367 0.4720118 0.1643126 0.4741822 0.1561191 0.4708764 0.1547656 0.4702962 0.1534156 0.4697077 0.1507267 0.4685059 0.1493879 0.4678927 0.1534156 0.4697077 0.1493879 0.4678927 0.1480528 0.4672712 0.1534156 0.4697077 0.1480528 0.4672712 0.1467216 0.4666416 0.1453943 0.4660038 0.1453943 0.4660038 0.1440709 0.4653579 0.1480528 0.4672712 0.1440709 0.4653579 0.1427515 0.4647039 0.1480528 0.4672712 0.1427515 0.4647039 0.1414361 0.4640418 0.1401247 0.4633716 0.1401247 0.4633716 0.1388176 0.4626934 0.1375147 0.4620072 0.1349215 0.4606109 0.1336314 0.4599008 0.1375147 0.4620072 0.1336314 0.4599008 0.1323456 0.4591828 0.1375147 0.4620072 0.1272475 0.4562324 0.1259843 0.4554753 0.1247259 0.4547106 0.1222232 0.4531578 0.1209791 0.45237 0.1197398 0.4515745 0.117276 0.4499608 0.1160515 0.4491427 0.1124086 0.4466434 0.1160515 0.4491427 0.1148321 0.4483171 0.1124086 0.4466434 0.1148321 0.4483171 0.1136178 0.447484 0.1124086 0.4466434 0.1124086 0.4466434 0.1112046 0.4457954 0.1100059 0.4449402 0.1100059 0.4449402 0.1088124 0.4440775 0.1124086 0.4466434 0.1088124 0.4440775 0.1076242 0.4432075 0.1124086 0.4466434 0.1029255 0.4396553 0.1017646 0.4387493 0.1006093 0.4378361 0.09831547 0.4359887 0.09717714 0.4350546 0.09379678 0.4322102 0.09717714 0.4350546 0.09604454 0.4341133 0.09379678 0.4322102 0.09379678 0.4322102 0.0926817 0.4312483 0.09157252 0.4302796 0.08937215 0.4283219 0.08828103 0.4273329 0.08504432 0.4243262 0.08828103 0.4273329 0.08719593 0.4263373 0.08504432 0.4243262 0.08081579 0.4202255 0.07977449 0.4191842 0.07668924 0.4160223 0.07977449 0.4191842 0.07873958 0.4181365 0.07668924 0.4160223 0.07668924 0.4160223 0.07567381 0.4149557 0.072667 0.411719 0.07567381 0.4149557 0.07466495 0.4138829 0.072667 0.411719 0.07466495 0.4138829 0.07366263 0.412804 0.072667 0.411719 0.07069581 0.4095306 0.06972038 0.4084274 0.072667 0.411719 0.06972038 0.4084274 0.06875163 0.4073183 0.072667 0.411719 0.06875163 0.4073183 0.06778979 0.4062032 0.06494545 0.4028229 0.06778979 0.4062032 0.06683474 0.4050822 0.06494545 0.4028229 0.063084 0.4005404 0.06216382 0.3993907 0.06494545 0.4028229 0.06216382 0.3993907 0.06125074 0.3982354 0.06494545 0.4028229 0.05944585 0.3959079 0.05855417 0.394736 0.05766969 0.3935586 0.0559225 0.3911876 0.05505985 0.3899941 0.05420452 0.3887953 0.05420452 0.3887953 0.05335658 0.3875913 0.0508573 0.3839485 0.05335658 0.3875913 0.05251604 0.3863822 0.0508573 0.3839485 0.05251604 0.3863822 0.05168294 0.3851678 0.0508573 0.3839485 0.04922854 0.3814946 0.04842549 0.3802602 0.0508573 0.3839485 0.04842549 0.3802602 0.04763001 0.3790209 0.0508573 0.3839485 0.04606193 0.3765278 0.04528945 0.3752741 0.04763001 0.3790209 0.04528945 0.3752741 0.04452461 0.3740156 0.04763001 0.3790209 0.041543 0.3689357 0.04081714 0.3676543 0.0400992 0.3663686 0.03868699 0.363784 0.03799277 0.3624853 0.03595823 0.3585639 0.03799277 0.3624853 0.03730654 0.3611823 0.03595823 0.3585639 0.03730654 0.3611823 0.03662836 0.3598752 0.03595823 0.3585639 0.03595823 0.3585639 0.03529608 0.3572485 0.0346421 0.3559291 0.0346421 0.3559291 0.03399616 0.3546057 0.03335839 0.3532783 0.03335839 0.3532783 0.03272879 0.3519471 0.03210729 0.3506121 0.02970379 0.3452344 0.0291236 0.3438809 0.02855169 0.3425239 0.02634775 0.3370614 0.02581775 0.3356874 0.02427852 0.3315464 0.02581775 0.3356874 0.02529621 0.3343102 0.02427852 0.3315464 0.01970279 0.3175516 0.01929265 0.3161373 0.02054911 0.3203726 0.01929265 0.3161373 0.01889121 0.3147204 0.02054911 0.3203726 0.01889121 0.3147204 0.01849842 0.3133011 0.01811438 0.3118795 0.01737248 0.3090292 0.01701468 0.3076007 0.01666563 0.3061701 0.01535743 0.3004269 0.01505243 0.2989861 0.01475626 0.2975436 0.01366037 0.2917561 0.0134086 0.2903052 0.01316571 0.2888527 0.01228356 0.2830289 0.01208537 0.2815696 0.01270675 0.2859435 0.01208537 0.2815696 0.01189613 0.2801092 0.01270675 0.2859435 0.01154458 0.277185 0.01138228 0.2757214 0.01122897 0.2742568 0.01094925 0.2713248 0.01082289 0.2698577 0.01122897 0.2742568 0.01082289 0.2698577 0.01070559 0.2683897 0.01122897 0.2742568 0.01009148 0.256626 0.0100553 0.2551538 0.01002824 0.2536814 0.01002824 0.2536814 0.01001018 0.2522089 0.01009148 0.256626 0.01001018 0.2522089 0.01000112 0.2507363 0.01009148 0.256626 0.01000112 0.2507363 0.01000112 0.2492637 0.01001018 0.2477911 0.01001018 0.2477911 0.01002824 0.2463186 0.0100553 0.2448462 0.01082289 0.2301423 0.01094925 0.2286751 0.01108461 0.2272087 0.01108461 0.2272087 0.01122897 0.2257432 0.01171588 0.2213523 0.01122897 0.2257432 0.01138228 0.2242786 0.01171588 0.2213523 0.01171588 0.2213523 0.01189613 0.2198908 0.01208537 0.2184303 0.01249068 0.2155132 0.01270675 0.2140565 0.01293176 0.2126011 0.01293176 0.2126011 0.01316571 0.2111473 0.01249068 0.2155132 0.01316571 0.2111473 0.0134086 0.2096948 0.01249068 0.2155132 0.0134086 0.2096948 0.01366037 0.2082439 0.01446896 0.2039006 0.01366037 0.2082439 0.01392102 0.2067945 0.01446896 0.2039006 0.01392102 0.2067945 0.01419055 0.2053467 0.01446896 0.2039006 0.01446896 0.2039006 0.01475626 0.2024564 0.01567125 0.1981343 0.01475626 0.2024564 0.01505243 0.2010138 0.01567125 0.1981343 0.01505243 0.2010138 0.01535743 0.1995731 0.01567125 0.1981343 0.01632535 0.1952627 0.01666563 0.1938299 0.01567125 0.1981343 0.01666563 0.1938299 0.01701468 0.1923993 0.01567125 0.1981343 0.01773905 0.1895445 0.01811438 0.1881205 0.01701468 0.1923993 0.01811438 0.1881205 0.01849842 0.1866989 0.01701468 0.1923993 0.02012163 0.1810365 0.02054911 0.1796274 0.02098524 0.1782208 0.02281576 0.1726222 0.0232948 0.1712296 0.0218833 0.1754159 0.0232948 0.1712296 0.02378243 0.16984 0.0218833 0.1754159 0.02378243 0.16984 0.02427852 0.1684535 0.02581775 0.1643126 0.02427852 0.1684535 0.02478313 0.16707 0.02581775 0.1643126 0.02478313 0.16707 0.02529621 0.1656897 0.02581775 0.1643126 0.02688616 0.1615679 0.02743297 0.1602006 0.02581775 0.1643126 0.02743297 0.1602006 0.02798813 0.1588367 0.02581775 0.1643126 0.0291236 0.1561191 0.02970379 0.1547656 0.03029227 0.1534156 0.03149408 0.1507267 0.03210729 0.1493879 0.03029227 0.1534156 0.03210729 0.1493879 0.03272879 0.1480528 0.03029227 0.1534156 0.03272879 0.1480528 0.03335839 0.1467216 0.03399616 0.1453943 0.03399616 0.1453943 0.0346421 0.1440709 0.03272879 0.1480528 0.0346421 0.1440709 0.03529608 0.1427515 0.03272879 0.1480528 0.03529608 0.1427515 0.03595823 0.1414361 0.03662836 0.1401247 0.03662836 0.1401247 0.03730654 0.1388176 0.03799277 0.1375147 0.03938913 0.1349215 0.0400992 0.1336314 0.03799277 0.1375147 0.0400992 0.1336314 0.04081714 0.1323456 0.03799277 0.1375147 0.04376757 0.1272475 0.04452461 0.1259843 0.04528945 0.1247259 0.04684215 0.1222232 0.04763001 0.1209791 0.04842549 0.1197398 0.05003911 0.117276 0.0508573 0.1160515 0.05335658 0.1124086 0.0508573 0.1160515 0.05168294 0.1148321 0.05335658 0.1124086 0.05168294 0.1148321 0.05251604 0.1136178 0.05335658 0.1124086 0.05335658 0.1124086 0.05420452 0.1112046 0.05505985 0.1100059 0.05505985 0.1100059 0.0559225 0.1088124 0.05335658 0.1124086 0.0559225 0.1088124 0.05679249 0.1076242 0.05335658 0.1124086 0.06034475 0.1029255 0.06125074 0.1017646 0.06216382 0.1006093 0.06401121 0.09831547 0.06494545 0.09717714 0.06778979 0.09379678 0.06494545 0.09717714 0.06588661 0.09604454 0.06778979 0.09379678 0.06778979 0.09379678 0.06875163 0.0926817 0.06972038 0.09157252 0.07167804 0.08937215 0.072667 0.08828103 0.07567381 0.08504432 0.072667 0.08828103 0.07366263 0.08719593 0.07567381 0.08504432 0.07977449 0.08081579 0.08081579 0.07977449 0.08397775 0.07668924 0.08081579 0.07977449 0.08186346 0.07873958 0.08397775 0.07668924 0.08397775 0.07668924 0.08504432 0.07567381 0.08828103 0.072667 0.08504432 0.07567381 0.08611702 0.07466495 0.08828103 0.072667 0.08611702 0.07466495 0.08719593 0.07366263 0.08828103 0.072667 0.09046936 0.07069581 0.09157252 0.06972038 0.08828103 0.072667 0.09157252 0.06972038 0.0926817 0.06875163 0.08828103 0.072667 0.0926817 0.06875163 0.09379678 0.06778979 0.09717714 0.06494545 0.09379678 0.06778979 0.09491771 0.06683474 0.09717714 0.06494545 0.09945952 0.063084 0.1006093 0.06216382 0.09717714 0.06494545 0.1006093 0.06216382 0.1017646 0.06125074 0.09717714 0.06494545 0.104092 0.05944585 0.105264 0.05855417 0.1064414 0.05766969 0.1088124 0.0559225 0.1100059 0.05505985 0.1112046 0.05420452 0.1112046 0.05420452 0.1124086 0.05335658 0.1160515 0.0508573 0.1124086 0.05335658 0.1136178 0.05251604 0.1160515 0.0508573 0.1136178 0.05251604 0.1148321 0.05168294 0.1160515 0.0508573 0.1185054 0.04922854 0.1197398 0.04842549 0.1160515 0.0508573 0.1197398 0.04842549 0.1209791 0.04763001 0.1160515 0.0508573 0.1234722 0.04606193 0.1247259 0.04528945 0.1209791 0.04763001 0.1247259 0.04528945 0.1259843 0.04452461 0.1209791 0.04763001 0.1310643 0.041543 0.1323456 0.04081714 0.1336314 0.0400992 0.1362159 0.03868699 0.1375147 0.03799277 0.1414361 0.03595823 0.1375147 0.03799277 0.1388176 0.03730654 0.1414361 0.03595823 0.1388176 0.03730654 0.1401247 0.03662836 0.1414361 0.03595823 0.1414361 0.03595823 0.1427515 0.03529608 0.1440709 0.0346421 0.1440709 0.0346421 0.1453943 0.03399616 0.1467216 0.03335839 0.1467216 0.03335839 0.1480528 0.03272879 0.1493879 0.03210729 0.1547656 0.02970379 0.1561191 0.0291236 0.1574761 0.02855169 0.1629386 0.02634775 0.1643126 0.02581775 0.1684535 0.02427852 0.1643126 0.02581775 0.1656897 0.02529621 0.1684535 0.02427852 0.1824484 0.01970279 0.1838628 0.01929265 0.1796274 0.02054911 0.1838628 0.01929265 0.1852796 0.01889121 0.1796274 0.02054911 0.1852796 0.01889121 0.1866989 0.01849842 0.1881205 0.01811438 0.1909708 0.01737248 0.1923993 0.01701468 0.1938299 0.01666563 0.1995731 0.01535743 0.2010138 0.01505243 0.2024564 0.01475626 0.2082439 0.01366037 0.2096948 0.0134086 0.2111473 0.01316571 0.2169712 0.01228356 0.2184303 0.01208537 0.2140565 0.01270675 0.2184303 0.01208537 0.2198908 0.01189613 0.2140565 0.01270675 0.2228149 0.01154458 0.2242786 0.01138228 0.2257432 0.01122897 0.2286751 0.01094925 0.2301423 0.01082289 0.2257432 0.01122897 0.2301423 0.01082289 0.2316102 0.01070559 0.2257432 0.01122897 0.243374 0.01009148 0.2448462 0.0100553 0.2463186 0.01002824 0.2463186 0.01002824 0.2477911 0.01001018 0.243374 0.01009148 0.2477911 0.01001018 0.2492637 0.01000112 0.243374 0.01009148 0.2492637 0.01000112 0.2507363 0.01000112 0.2522089 0.01001018 0.2522089 0.01001018 0.2536814 0.01002824 0.2551538 0.0100553 0.2698577 0.01082289 0.2713248 0.01094925 0.2727912 0.01108461 0.2727912 0.01108461 0.2742568 0.01122897 0.2786477 0.01171588 0.2742568 0.01122897 0.2757214 0.01138228 0.2786477 0.01171588 0.2786477 0.01171588 0.2801092 0.01189613 0.2815696 0.01208537 0.2844868 0.01249068 0.2859435 0.01270675 0.2873988 0.01293176 0.2873988 0.01293176 0.2888527 0.01316571 0.2844868 0.01249068 0.2888527 0.01316571 0.2903052 0.0134086 0.2844868 0.01249068 0.2903052 0.0134086 0.2917561 0.01366037 0.2960993 0.01446896 0.2917561 0.01366037 0.2932055 0.01392102 0.2960993 0.01446896 0.2932055 0.01392102 0.2946532 0.01419055 0.2960993 0.01446896 0.2960993 0.01446896 0.2975436 0.01475626 0.3018656 0.01567125 0.2975436 0.01475626 0.2989861 0.01505243 0.3018656 0.01567125 0.2989861 0.01505243 0.3004269 0.01535743 0.3018656 0.01567125 0.3047373 0.01632535 0.3061701 0.01666563 0.3018656 0.01567125 0.3061701 0.01666563 0.3076007 0.01701468 0.3018656 0.01567125 0.3104555 0.01773905 0.3118795 0.01811438 0.3076007 0.01701468 0.3118795 0.01811438 0.3133011 0.01849842 0.3076007 0.01701468 0.3189634 0.02012163 0.3203726 0.02054911 0.3217791 0.02098524 0.3273779 0.02281576 0.3287703 0.0232948 0.3245841 0.0218833 0.3287703 0.0232948 0.3301599 0.02378243 0.3245841 0.0218833 0.3301599 0.02378243 0.3315464 0.02427852 0.3356874 0.02581775 0.3315464 0.02427852 0.3329299 0.02478313 0.3356874 0.02581775 0.3329299 0.02478313 0.3343102 0.02529621 0.3356874 0.02581775 0.338432 0.02688616 0.3397994 0.02743297 0.3356874 0.02581775 0.3397994 0.02743297 0.3411633 0.02798813 0.3356874 0.02581775 0.3438809 0.0291236 0.3452344 0.02970379 0.3465843 0.03029227 0.3492732 0.03149408 0.3506121 0.03210729 0.3465843 0.03029227 0.3506121 0.03210729 0.3519471 0.03272879 0.3465843 0.03029227 0.3519471 0.03272879 0.3532783 0.03335839 0.3546057 0.03399616 0.3546057 0.03399616 0.3559291 0.0346421 0.3519471 0.03272879 0.3559291 0.0346421 0.3572485 0.03529608 0.3519471 0.03272879 0.3572485 0.03529608 0.3585639 0.03595823 0.3598752 0.03662836 0.3598752 0.03662836 0.3611823 0.03730654 0.3624853 0.03799277 0.3650785 0.03938913 0.3663686 0.0400992 0.3624853 0.03799277 0.3663686 0.0400992 0.3676543 0.04081714 0.3624853 0.03799277 0.3727526 0.04376757 0.3740156 0.04452461 0.3752741 0.04528945 0.3777768 0.04684215 0.3790209 0.04763001 0.3802602 0.04842549 0.382724 0.05003911 0.3839485 0.0508573 0.3875913 0.05335658 0.3839485 0.0508573 0.3851678 0.05168294 0.3875913 0.05335658 0.3851678 0.05168294 0.3863822 0.05251604 0.3875913 0.05335658 0.3875913 0.05335658 0.3887953 0.05420452 0.3899941 0.05505985 0.3899941 0.05505985 0.3911876 0.0559225 0.3875913 0.05335658 0.3911876 0.0559225 0.3923758 0.05679249 0.3875913 0.05335658 0.3970744 0.06034475 0.3982354 0.06125074 0.3993907 0.06216382 0.4016845 0.06401121 0.4028229 0.06494545 0.4062032 0.06778979 0.4028229 0.06494545 0.4039555 0.06588661 0.4062032 0.06778979 0.4062032 0.06778979 0.4073183 0.06875163 0.4084274 0.06972038 0.4106279 0.07167804 0.411719 0.072667 0.4149557 0.07567381 0.411719 0.072667 0.412804 0.07366263 0.4149557 0.07567381 0.4191842 0.07977449 0.4202255 0.08081579 0.4233108 0.08397775 0.4202255 0.08081579 0.4212604 0.08186346 0.4233108 0.08397775 0.4233108 0.08397775 0.4243262 0.08504432 0.4273329 0.08828103 0.4243262 0.08504432 0.4253351 0.08611702 0.4273329 0.08828103 0.4253351 0.08611702 0.4263373 0.08719593 0.4273329 0.08828103 0.4293041 0.09046936 0.4302796 0.09157252 0.4273329 0.08828103 0.4302796 0.09157252 0.4312483 0.0926817 0.4273329 0.08828103 0.4312483 0.0926817 0.4322102 0.09379678 0.4350546 0.09717714 0.4322102 0.09379678 0.4331652 0.09491771 0.4350546 0.09717714 0.4369159 0.09945952 0.4378361 0.1006093 0.4350546 0.09717714 0.4378361 0.1006093 0.4387493 0.1017646 0.4350546 0.09717714 0.4405541 0.104092 0.4414458 0.105264 0.4423303 0.1064414 0.4440775 0.1088124 0.4449402 0.1100059 0.4457954 0.1112046 0.4457954 0.1112046 0.4466434 0.1124086 0.4491427 0.1160515 0.4466434 0.1124086 0.447484 0.1136178 0.4491427 0.1160515 0.447484 0.1136178 0.4483171 0.1148321 0.4491427 0.1160515 0.4507715 0.1185054 0.4515745 0.1197398 0.4491427 0.1160515 0.4515745 0.1197398 0.45237 0.1209791 0.4491427 0.1160515 0.453938 0.1234722 0.4547106 0.1247259 0.45237 0.1209791 0.4547106 0.1247259 0.4554753 0.1259843 0.45237 0.1209791 0.4584569 0.1310643 0.4591828 0.1323456 0.4599008 0.1336314 0.461313 0.1362159 0.4620072 0.1375147 0.4640418 0.1414361 0.4620072 0.1375147 0.4626934 0.1388176 0.4640418 0.1414361 0.4626934 0.1388176 0.4633716 0.1401247 0.4640418 0.1414361 0.4640418 0.1414361 0.4647039 0.1427515 0.4653579 0.1440709 0.4653579 0.1440709 0.4660038 0.1453943 0.4666416 0.1467216 0.4666416 0.1467216 0.4672712 0.1480528 0.4678927 0.1493879 0.4702962 0.1547656 0.4708764 0.1561191 0.4714483 0.1574761 0.4736523 0.1629386 0.4741822 0.1643126 0.4757214 0.1684535 0.4741822 0.1643126 0.4747037 0.1656897 0.4757214 0.1684535 0.4802972 0.1824484 0.4807073 0.1838628 0.4794509 0.1796274 0.4807073 0.1838628 0.4811088 0.1852796 0.4794509 0.1796274 0.4811088 0.1852796 0.4815015 0.1866989 0.4818856 0.1881205 0.4826275 0.1909708 0.4829853 0.1923993 0.4833344 0.1938299 0.4846426 0.1995731 0.4849476 0.2010138 0.4852437 0.2024564 0.4863396 0.2082439 0.4865914 0.2096948 0.4868342 0.2111473 0.4877164 0.2169712 0.4879146 0.2184303 0.4872932 0.2140565 0.4879146 0.2184303 0.4881038 0.2198908 0.4872932 0.2140565 0.4884554 0.2228149 0.4886177 0.2242786 0.488771 0.2257432 0.4890507 0.2286751 0.4891771 0.2301423 0.488771 0.2257432 0.4891771 0.2301423 0.4892944 0.2316102 0.488771 0.2257432 0.4899085 0.243374 0.4899446 0.2448462 0.4899718 0.2463186 0.4899718 0.2463186 0.4899898 0.2477911 0.4899085 0.243374 0.4899898 0.2477911 0.4899989 0.2492637 0.4899085 0.243374 0.4899989 0.2492637 0.4899989 0.2507363 0.4899898 0.2522089 0.4899898 0.2522089 0.4899718 0.2536814 0.4899446 0.2551538 0.4891771 0.2698577 0.4890507 0.2713248 0.4889154 0.2727912 0.4889154 0.2727912 0.488771 0.2742568 0.4882841 0.2786477 0.488771 0.2742568 0.4886177 0.2757214 0.4882841 0.2786477 0.4882841 0.2786477 0.4881038 0.2801092 0.4879146 0.2815696 0.4875093 0.2844868 0.4872932 0.2859435 0.4870682 0.2873988 0.4870682 0.2873988 0.4868342 0.2888527 0.4875093 0.2844868 0.4868342 0.2888527 0.4865914 0.2903052 0.4875093 0.2844868 0.4865914 0.2903052 0.4863396 0.2917561 0.485531 0.2960993 0.4863396 0.2917561 0.486079 0.2932055 0.485531 0.2960993 0.486079 0.2932055 0.4858095 0.2946532 0.485531 0.2960993 0.485531 0.2960993 0.4852437 0.2975436 0.4843288 0.3018656 0.4852437 0.2975436 0.4849476 0.2989861 0.4843288 0.3018656 0.4849476 0.2989861 0.4846426 0.3004269 0.4843288 0.3018656 0.4836746 0.3047373 0.4833344 0.3061701 0.4843288 0.3018656 0.4833344 0.3061701 0.4829853 0.3076007 0.4843288 0.3018656 0.4822609 0.3104555 0.4818856 0.3118795 0.4829853 0.3076007 0.4818856 0.3118795 0.4815015 0.3133011 0.4829853 0.3076007 0.4798783 0.3189634 0.4794509 0.3203726 0.4790148 0.3217791 0.4771842 0.3273779 0.4767051 0.3287703 0.4781166 0.3245841 0.4767051 0.3287703 0.4762176 0.3301599 0.4781166 0.3245841 0.4762176 0.3301599 0.4757214 0.3315464 0.4741822 0.3356874 0.4757214 0.3315464 0.4752169 0.3329299 0.4741822 0.3356874 0.4752169 0.3329299 0.4747037 0.3343102 0.4741822 0.3356874 0.4731138 0.338432 0.472567 0.3397994 0.4741822 0.3356874 0.472567 0.3397994 0.4720118 0.3411633 0.4741822 0.3356874 0.4708764 0.3438809 0.4702962 0.3452344 0.4697077 0.3465843 0.4685059 0.3492732 0.4678927 0.3506121 0.4697077 0.3465843 0.4678927 0.3506121 0.4672712 0.3519471 0.4697077 0.3465843 0.4672712 0.3519471 0.4666416 0.3532783 0.4660038 0.3546057 0.4660038 0.3546057 0.4653579 0.3559291 0.4672712 0.3519471 0.4653579 0.3559291 0.4647039 0.3572485 0.4672712 0.3519471 0.4647039 0.3572485 0.4640418 0.3585639 0.4633716 0.3598752 0.4633716 0.3598752 0.4626934 0.3611823 0.4620072 0.3624853 0.4606109 0.3650785 0.4599008 0.3663686 0.4620072 0.3624853 0.4599008 0.3663686 0.4591828 0.3676543 0.4620072 0.3624853 0.4562324 0.3727526 0.4554753 0.3740156 0.4547106 0.3752741 0.4531578 0.3777768 0.45237 0.3790209 0.4515745 0.3802602 0.4499608 0.382724 0.4491427 0.3839485 0.4466434 0.3875913 0.4491427 0.3839485 0.4483171 0.3851678 0.4466434 0.3875913 0.4483171 0.3851678 0.447484 0.3863822 0.4466434 0.3875913 0.4466434 0.3875913 0.4457954 0.3887953 0.4449402 0.3899941 0.4449402 0.3899941 0.4440775 0.3911876 0.4466434 0.3875913 0.4440775 0.3911876 0.4432075 0.3923758 0.4466434 0.3875913 0.4396553 0.3970744 0.4387493 0.3982354 0.4378361 0.3993907 0.4359887 0.4016845 0.4350546 0.4028229 0.4322102 0.4062032 0.4350546 0.4028229 0.4341133 0.4039555 0.4322102 0.4062032 0.4322102 0.4062032 0.4312483 0.4073183 0.4302796 0.4084274 0.4283219 0.4106279 0.4273329 0.411719 0.4243262 0.4149557 0.4273329 0.411719 0.4263373 0.412804 0.4243262 0.4149557 0.4202255 0.4191842 0.4191842 0.4202255 0.4160223 0.4233108 0.4191842 0.4202255 0.4181365 0.4212604 0.4160223 0.4233108 0.4160223 0.4233108 0.4149557 0.4243262 0.411719 0.4273329 0.4149557 0.4243262 0.4138829 0.4253351 0.411719 0.4273329 0.4138829 0.4253351 0.412804 0.4263373 0.411719 0.4273329 0.4095306 0.4293041 0.4084274 0.4302796 0.411719 0.4273329 0.4084274 0.4302796 0.4073183 0.4312483 0.411719 0.4273329 0.4073183 0.4312483 0.4062032 0.4322102 0.4028229 0.4350546 0.4062032 0.4322102 0.4050822 0.4331652 0.4028229 0.4350546 0.4005404 0.4369159 0.3993907 0.4378361 0.4028229 0.4350546 0.3993907 0.4378361 0.3982354 0.4387493 0.4028229 0.4350546 0.3959079 0.4405541 0.394736 0.4414458 0.3935586 0.4423303 0.3911876 0.4440775 0.3899941 0.4449402 0.3887953 0.4457954 0.3887953 0.4457954 0.3875913 0.4466434 0.3839485 0.4491427 0.3875913 0.4466434 0.3863822 0.447484 0.3839485 0.4491427 0.3863822 0.447484 0.3851678 0.4483171 0.3839485 0.4491427 0.3814946 0.4507715 0.3802602 0.4515745 0.3839485 0.4491427 0.3802602 0.4515745 0.3790209 0.45237 0.3839485 0.4491427 0.3765278 0.453938 0.3752741 0.4547106 0.3790209 0.45237 0.3752741 0.4547106 0.3740156 0.4554753 0.3790209 0.45237 0.3689357 0.4584569 0.3676543 0.4591828 0.3663686 0.4599008 0.363784 0.461313 0.3624853 0.4620072 0.3585639 0.4640418 0.3624853 0.4620072 0.3611823 0.4626934 0.3585639 0.4640418 0.3611823 0.4626934 0.3598752 0.4633716 0.3585639 0.4640418 0.3585639 0.4640418 0.3572485 0.4647039 0.3559291 0.4653579 0.3559291 0.4653579 0.3546057 0.4660038 0.3532783 0.4666416 0.3532783 0.4666416 0.3519471 0.4672712 0.3506121 0.4678927 0.3452344 0.4702962 0.3438809 0.4708764 0.3425239 0.4714483 0.3370614 0.4736523 0.3356874 0.4741822 0.3315464 0.4757214 0.3356874 0.4741822 0.3343102 0.4747037 0.3315464 0.4757214 0.3175516 0.4802972 0.3161373 0.4807073 0.3203726 0.4794509 0.3161373 0.4807073 0.3147204 0.4811088 0.3203726 0.4794509 0.3147204 0.4811088 0.3133011 0.4815015 0.3118795 0.4818856 0.3090292 0.4826275 0.3076007 0.4829853 0.3061701 0.4833344 0.3004269 0.4846426 0.2989861 0.4849476 0.2975436 0.4852437 0.2917561 0.4863396 0.2903052 0.4865914 0.2888527 0.4868342 0.2830289 0.4877164 0.2815696 0.4879146 0.2859435 0.4872932 0.2815696 0.4879146 0.2801092 0.4881038 0.2859435 0.4872932 0.277185 0.4884554 0.2757214 0.4886177 0.2742568 0.488771 0.2713248 0.4890507 0.2698577 0.4891771 0.2742568 0.488771 0.2698577 0.4891771 0.2683897 0.4892944 0.2742568 0.488771 0.256626 0.4899085 0.2551538 0.4899446 0.2536814 0.4899718 0.2536814 0.4899718 0.2522089 0.4899898 0.256626 0.4899085 0.2522089 0.4899898 0.2507363 0.4899989 0.256626 0.4899085 0.2507363 0.4899989 0.2477911 0.4899898 0.2389592 0.4897459 0.2477911 0.4899898 0.2448462 0.4899446 0.2389592 0.4897459 0.2448462 0.4899446 0.2419021 0.4898633 0.2389592 0.4897459 0.2389592 0.4897459 0.236018 0.4895924 0.2330788 0.4894027 0.2330788 0.4894027 0.2301423 0.4891771 0.2272087 0.4889154 0.2213523 0.4882841 0.2184303 0.4879146 0.2272087 0.4889154 0.2184303 0.4879146 0.2155132 0.4875093 0.2272087 0.4889154 0.1866989 0.4815015 0.1838628 0.4807073 0.1810365 0.4798783 0.1810365 0.4798783 0.1782208 0.4790148 0.1754159 0.4781166 0.1588367 0.4720118 0.1561191 0.4708764 0.1480528 0.4672712 0.1561191 0.4708764 0.1534156 0.4697077 0.1480528 0.4672712 0.1427515 0.4647039 0.1401247 0.4633716 0.1480528 0.4672712 0.1401247 0.4633716 0.1375147 0.4620072 0.1480528 0.4672712 0.1323456 0.4591828 0.1297875 0.4577233 0.1375147 0.4620072 0.1297875 0.4577233 0.1272475 0.4562324 0.1375147 0.4620072 0.1272475 0.4562324 0.1247259 0.4547106 0.1222232 0.4531578 0.1222232 0.4531578 0.1197398 0.4515745 0.1272475 0.4562324 0.1197398 0.4515745 0.117276 0.4499608 0.1272475 0.4562324 0.1076242 0.4432075 0.105264 0.4414458 0.09831547 0.4359887 0.105264 0.4414458 0.1029255 0.4396553 0.09831547 0.4359887 0.1029255 0.4396553 0.1006093 0.4378361 0.09831547 0.4359887 0.09379678 0.4322102 0.09157252 0.4302796 0.09831547 0.4359887 0.09157252 0.4302796 0.08937215 0.4283219 0.09831547 0.4359887 0.08504432 0.4243262 0.08291745 0.4222888 0.08081579 0.4202255 0.06125074 0.3982354 0.05944585 0.3959079 0.06494545 0.4028229 0.05944585 0.3959079 0.05766969 0.3935586 0.06494545 0.4028229 0.05766969 0.3935586 0.0559225 0.3911876 0.05420452 0.3887953 0.04452461 0.3740156 0.04301822 0.3714848 0.041543 0.3689357 0.041543 0.3689357 0.0400992 0.3663686 0.03868699 0.363784 0.03595823 0.3585639 0.0346421 0.3559291 0.03868699 0.363784 0.0346421 0.3559291 0.03335839 0.3532783 0.03868699 0.363784 0.03335839 0.3532783 0.03210729 0.3506121 0.03088903 0.3479306 0.03088903 0.3479306 0.02970379 0.3452344 0.03335839 0.3532783 0.02970379 0.3452344 0.02855169 0.3425239 0.03335839 0.3532783 0.02855169 0.3425239 0.02743297 0.3397994 0.02427852 0.3315464 0.02743297 0.3397994 0.02634775 0.3370614 0.02427852 0.3315464 0.02427852 0.3315464 0.0232948 0.3287703 0.02234524 0.3259824 0.02234524 0.3259824 0.02142995 0.323183 0.02427852 0.3315464 0.02142995 0.323183 0.02054911 0.3203726 0.02427852 0.3315464 0.01889121 0.3147204 0.01811438 0.3118795 0.02054911 0.3203726 0.01811438 0.3118795 0.01737248 0.3090292 0.02054911 0.3203726 0.01737248 0.3090292 0.01666563 0.3061701 0.01475626 0.2975436 0.01666563 0.3061701 0.01599389 0.3033025 0.01475626 0.2975436 0.01599389 0.3033025 0.01535743 0.3004269 0.01475626 0.2975436 0.01475626 0.2975436 0.01419055 0.2946532 0.01366037 0.2917561 0.01366037 0.2917561 0.01316571 0.2888527 0.01475626 0.2975436 0.01316571 0.2888527 0.01270675 0.2859435 0.01475626 0.2975436 0.01189613 0.2801092 0.01154458 0.277185 0.01122897 0.2742568 0.01070559 0.2683897 0.01049792 0.2654518 0.01032632 0.2625116 0.01032632 0.2625116 0.01019084 0.2595695 0.01000112 0.2507363 0.01019084 0.2595695 0.01009148 0.256626 0.01000112 0.2507363 0.01000112 0.2507363 0.01001018 0.2477911 0.01025408 0.2389592 0.01001018 0.2477911 0.0100553 0.2448462 0.01025408 0.2389592 0.0100553 0.2448462 0.01013666 0.2419021 0.01025408 0.2389592 0.01025408 0.2389592 0.01040762 0.236018 0.01059722 0.2330788 0.01059722 0.2330788 0.01082289 0.2301423 0.01108461 0.2272087 0.01171588 0.2213523 0.01208537 0.2184303 0.01108461 0.2272087 0.01208537 0.2184303 0.01249068 0.2155132 0.01108461 0.2272087 0.01849842 0.1866989 0.01929265 0.1838628 0.02012163 0.1810365 0.02012163 0.1810365 0.02098524 0.1782208 0.0218833 0.1754159 0.02798813 0.1588367 0.0291236 0.1561191 0.03272879 0.1480528 0.0291236 0.1561191 0.03029227 0.1534156 0.03272879 0.1480528 0.03529608 0.1427515 0.03662836 0.1401247 0.03272879 0.1480528 0.03662836 0.1401247 0.03799277 0.1375147 0.03272879 0.1480528 0.04081714 0.1323456 0.04227674 0.1297875 0.03799277 0.1375147 0.04227674 0.1297875 0.04376757 0.1272475 0.03799277 0.1375147 0.04376757 0.1272475 0.04528945 0.1247259 0.04684215 0.1222232 0.04684215 0.1222232 0.04842549 0.1197398 0.04376757 0.1272475 0.04842549 0.1197398 0.05003911 0.117276 0.04376757 0.1272475 0.05679249 0.1076242 0.05855417 0.105264 0.06401121 0.09831547 0.05855417 0.105264 0.06034475 0.1029255 0.06401121 0.09831547 0.06034475 0.1029255 0.06216382 0.1006093 0.06401121 0.09831547 0.06778979 0.09379678 0.06972038 0.09157252 0.06401121 0.09831547 0.06972038 0.09157252 0.07167804 0.08937215 0.06401121 0.09831547 0.07567381 0.08504432 0.07771116 0.08291745 0.07977449 0.08081579 0.1017646 0.06125074 0.104092 0.05944585 0.09717714 0.06494545 0.104092 0.05944585 0.1064414 0.05766969 0.09717714 0.06494545 0.1064414 0.05766969 0.1088124 0.0559225 0.1112046 0.05420452 0.1259843 0.04452461 0.1285152 0.04301822 0.1310643 0.041543 0.1310643 0.041543 0.1336314 0.0400992 0.1362159 0.03868699 0.1414361 0.03595823 0.1440709 0.0346421 0.1362159 0.03868699 0.1440709 0.0346421 0.1467216 0.03335839 0.1362159 0.03868699 0.1467216 0.03335839 0.1493879 0.03210729 0.1520694 0.03088903 0.1520694 0.03088903 0.1547656 0.02970379 0.1467216 0.03335839 0.1547656 0.02970379 0.1574761 0.02855169 0.1467216 0.03335839 0.1574761 0.02855169 0.1602006 0.02743297 0.1684535 0.02427852 0.1602006 0.02743297 0.1629386 0.02634775 0.1684535 0.02427852 0.1684535 0.02427852 0.1712296 0.0232948 0.1740176 0.02234524 0.1740176 0.02234524 0.1768169 0.02142995 0.1684535 0.02427852 0.1768169 0.02142995 0.1796274 0.02054911 0.1684535 0.02427852 0.1852796 0.01889121 0.1881205 0.01811438 0.1796274 0.02054911 0.1881205 0.01811438 0.1909708 0.01737248 0.1796274 0.02054911 0.1909708 0.01737248 0.1938299 0.01666563 0.2024564 0.01475626 0.1938299 0.01666563 0.1966975 0.01599389 0.2024564 0.01475626 0.1966975 0.01599389 0.1995731 0.01535743 0.2024564 0.01475626 0.2024564 0.01475626 0.2053467 0.01419055 0.2082439 0.01366037 0.2082439 0.01366037 0.2111473 0.01316571 0.2024564 0.01475626 0.2111473 0.01316571 0.2140565 0.01270675 0.2024564 0.01475626 0.2198908 0.01189613 0.2228149 0.01154458 0.2257432 0.01122897 0.2316102 0.01070559 0.2345482 0.01049792 0.2374883 0.01032632 0.2374883 0.01032632 0.2404305 0.01019084 0.2492637 0.01000112 0.2404305 0.01019084 0.243374 0.01009148 0.2492637 0.01000112 0.2492637 0.01000112 0.2522089 0.01001018 0.2610408 0.01025408 0.2522089 0.01001018 0.2551538 0.0100553 0.2610408 0.01025408 0.2551538 0.0100553 0.2580979 0.01013666 0.2610408 0.01025408 0.2610408 0.01025408 0.263982 0.01040762 0.2669211 0.01059722 0.2669211 0.01059722 0.2698577 0.01082289 0.2727912 0.01108461 0.2786477 0.01171588 0.2815696 0.01208537 0.2727912 0.01108461 0.2815696 0.01208537 0.2844868 0.01249068 0.2727912 0.01108461 0.3133011 0.01849842 0.3161373 0.01929265 0.3189634 0.02012163 0.3189634 0.02012163 0.3217791 0.02098524 0.3245841 0.0218833 0.3411633 0.02798813 0.3438809 0.0291236 0.3519471 0.03272879 0.3438809 0.0291236 0.3465843 0.03029227 0.3519471 0.03272879 0.3572485 0.03529608 0.3598752 0.03662836 0.3519471 0.03272879 0.3598752 0.03662836 0.3624853 0.03799277 0.3519471 0.03272879 0.3676543 0.04081714 0.3702125 0.04227674 0.3624853 0.03799277 0.3702125 0.04227674 0.3727526 0.04376757 0.3624853 0.03799277 0.3727526 0.04376757 0.3752741 0.04528945 0.3777768 0.04684215 0.3777768 0.04684215 0.3802602 0.04842549 0.3727526 0.04376757 0.3802602 0.04842549 0.382724 0.05003911 0.3727526 0.04376757 0.3923758 0.05679249 0.394736 0.05855417 0.4016845 0.06401121 0.394736 0.05855417 0.3970744 0.06034475 0.4016845 0.06401121 0.3970744 0.06034475 0.3993907 0.06216382 0.4016845 0.06401121 0.4062032 0.06778979 0.4084274 0.06972038 0.4016845 0.06401121 0.4084274 0.06972038 0.4106279 0.07167804 0.4016845 0.06401121 0.4149557 0.07567381 0.4170825 0.07771116 0.4191842 0.07977449 0.4387493 0.1017646 0.4405541 0.104092 0.4350546 0.09717714 0.4405541 0.104092 0.4423303 0.1064414 0.4350546 0.09717714 0.4423303 0.1064414 0.4440775 0.1088124 0.4457954 0.1112046 0.4554753 0.1259843 0.4569817 0.1285152 0.4584569 0.1310643 0.4584569 0.1310643 0.4599008 0.1336314 0.461313 0.1362159 0.4640418 0.1414361 0.4653579 0.1440709 0.461313 0.1362159 0.4653579 0.1440709 0.4666416 0.1467216 0.461313 0.1362159 0.4666416 0.1467216 0.4678927 0.1493879 0.4691109 0.1520694 0.4691109 0.1520694 0.4702962 0.1547656 0.4666416 0.1467216 0.4702962 0.1547656 0.4714483 0.1574761 0.4666416 0.1467216 0.4714483 0.1574761 0.472567 0.1602006 0.4757214 0.1684535 0.472567 0.1602006 0.4736523 0.1629386 0.4757214 0.1684535 0.4757214 0.1684535 0.4767051 0.1712296 0.4776547 0.1740176 0.4776547 0.1740176 0.47857 0.1768169 0.4757214 0.1684535 0.47857 0.1768169 0.4794509 0.1796274 0.4757214 0.1684535 0.4811088 0.1852796 0.4818856 0.1881205 0.4794509 0.1796274 0.4818856 0.1881205 0.4826275 0.1909708 0.4794509 0.1796274 0.4826275 0.1909708 0.4833344 0.1938299 0.4852437 0.2024564 0.4833344 0.1938299 0.4840061 0.1966975 0.4852437 0.2024564 0.4840061 0.1966975 0.4846426 0.1995731 0.4852437 0.2024564 0.4852437 0.2024564 0.4858095 0.2053467 0.4863396 0.2082439 0.4863396 0.2082439 0.4868342 0.2111473 0.4852437 0.2024564 0.4868342 0.2111473 0.4872932 0.2140565 0.4852437 0.2024564 0.4881038 0.2198908 0.4884554 0.2228149 0.488771 0.2257432 0.4892944 0.2316102 0.4895021 0.2345482 0.4896737 0.2374883 0.4896737 0.2374883 0.4898092 0.2404305 0.4899989 0.2492637 0.4898092 0.2404305 0.4899085 0.243374 0.4899989 0.2492637 0.4899989 0.2492637 0.4899898 0.2522089 0.4897459 0.2610408 0.4899898 0.2522089 0.4899446 0.2551538 0.4897459 0.2610408 0.4899446 0.2551538 0.4898633 0.2580979 0.4897459 0.2610408 0.4897459 0.2610408 0.4895924 0.263982 0.4894027 0.2669211 0.4894027 0.2669211 0.4891771 0.2698577 0.4889154 0.2727912 0.4882841 0.2786477 0.4879146 0.2815696 0.4889154 0.2727912 0.4879146 0.2815696 0.4875093 0.2844868 0.4889154 0.2727912 0.4815015 0.3133011 0.4807073 0.3161373 0.4798783 0.3189634 0.4798783 0.3189634 0.4790148 0.3217791 0.4781166 0.3245841 0.4720118 0.3411633 0.4708764 0.3438809 0.4672712 0.3519471 0.4708764 0.3438809 0.4697077 0.3465843 0.4672712 0.3519471 0.4647039 0.3572485 0.4633716 0.3598752 0.4672712 0.3519471 0.4633716 0.3598752 0.4620072 0.3624853 0.4672712 0.3519471 0.4591828 0.3676543 0.4577233 0.3702125 0.4620072 0.3624853 0.4577233 0.3702125 0.4562324 0.3727526 0.4620072 0.3624853 0.4562324 0.3727526 0.4547106 0.3752741 0.4531578 0.3777768 0.4531578 0.3777768 0.4515745 0.3802602 0.4562324 0.3727526 0.4515745 0.3802602 0.4499608 0.382724 0.4562324 0.3727526 0.4432075 0.3923758 0.4414458 0.394736 0.4359887 0.4016845 0.4414458 0.394736 0.4396553 0.3970744 0.4359887 0.4016845 0.4396553 0.3970744 0.4378361 0.3993907 0.4359887 0.4016845 0.4322102 0.4062032 0.4302796 0.4084274 0.4359887 0.4016845 0.4302796 0.4084274 0.4283219 0.4106279 0.4359887 0.4016845 0.4243262 0.4149557 0.4222888 0.4170825 0.4202255 0.4191842 0.3982354 0.4387493 0.3959079 0.4405541 0.4028229 0.4350546 0.3959079 0.4405541 0.3935586 0.4423303 0.4028229 0.4350546 0.3935586 0.4423303 0.3911876 0.4440775 0.3887953 0.4457954 0.3740156 0.4554753 0.3714848 0.4569817 0.3689357 0.4584569 0.3689357 0.4584569 0.3663686 0.4599008 0.363784 0.461313 0.3585639 0.4640418 0.3559291 0.4653579 0.363784 0.461313 0.3559291 0.4653579 0.3532783 0.4666416 0.363784 0.461313 0.3532783 0.4666416 0.3506121 0.4678927 0.3479306 0.4691109 0.3479306 0.4691109 0.3452344 0.4702962 0.3532783 0.4666416 0.3452344 0.4702962 0.3425239 0.4714483 0.3532783 0.4666416 0.3425239 0.4714483 0.3397994 0.472567 0.3315464 0.4757214 0.3397994 0.472567 0.3370614 0.4736523 0.3315464 0.4757214 0.3315464 0.4757214 0.3287703 0.4767051 0.3259824 0.4776547 0.3259824 0.4776547 0.323183 0.47857 0.3315464 0.4757214 0.323183 0.47857 0.3203726 0.4794509 0.3315464 0.4757214 0.3147204 0.4811088 0.3118795 0.4818856 0.3203726 0.4794509 0.3118795 0.4818856 0.3090292 0.4826275 0.3203726 0.4794509 0.3090292 0.4826275 0.3061701 0.4833344 0.2975436 0.4852437 0.3061701 0.4833344 0.3033025 0.4840061 0.2975436 0.4852437 0.3033025 0.4840061 0.3004269 0.4846426 0.2975436 0.4852437 0.2975436 0.4852437 0.2946532 0.4858095 0.2917561 0.4863396 0.2917561 0.4863396 0.2888527 0.4868342 0.2975436 0.4852437 0.2888527 0.4868342 0.2859435 0.4872932 0.2975436 0.4852437 0.2801092 0.4881038 0.277185 0.4884554 0.2742568 0.488771 0.2683897 0.4892944 0.2654518 0.4895021 0.2625116 0.4896737 0.2625116 0.4896737 0.2595695 0.4898092 0.2507363 0.4899989 0.2595695 0.4898092 0.256626 0.4899085 0.2507363 0.4899989 0.2389592 0.4897459 0.2330788 0.4894027 0.2507363 0.4899989 0.2330788 0.4894027 0.2272087 0.4889154 0.2507363 0.4899989 0.2155132 0.4875093 0.2096948 0.4865914 0.2039006 0.485531 0.2039006 0.485531 0.1981343 0.4843288 0.1923993 0.4829853 0.1923993 0.4829853 0.1866989 0.4815015 0.2039006 0.485531 0.1866989 0.4815015 0.1810365 0.4798783 0.2039006 0.485531 0.1810365 0.4798783 0.1754159 0.4781166 0.16984 0.4762176 0.16984 0.4762176 0.1643126 0.4741822 0.1588367 0.4720118 0.117276 0.4499608 0.1124086 0.4466434 0.09831547 0.4359887 0.1124086 0.4466434 0.1076242 0.4432075 0.09831547 0.4359887 0.08937215 0.4283219 0.08504432 0.4243262 0.09831547 0.4359887 0.08504432 0.4243262 0.08081579 0.4202255 0.09831547 0.4359887 0.08081579 0.4202255 0.07668924 0.4160223 0.072667 0.411719 0.072667 0.411719 0.06875163 0.4073183 0.06494545 0.4028229 0.05766969 0.3935586 0.05420452 0.3887953 0.06494545 0.4028229 0.05420452 0.3887953 0.0508573 0.3839485 0.06494545 0.4028229 0.0508573 0.3839485 0.04763001 0.3790209 0.04452461 0.3740156 0.04452461 0.3740156 0.041543 0.3689357 0.0508573 0.3839485 0.041543 0.3689357 0.03868699 0.363784 0.0508573 0.3839485 0.01270675 0.2859435 0.01189613 0.2801092 0.01475626 0.2975436 0.01189613 0.2801092 0.01122897 0.2742568 0.01475626 0.2975436 0.01122897 0.2742568 0.01070559 0.2683897 0.01000112 0.2507363 0.01070559 0.2683897 0.01032632 0.2625116 0.01000112 0.2507363 0.01025408 0.2389592 0.01059722 0.2330788 0.01000112 0.2507363 0.01059722 0.2330788 0.01108461 0.2272087 0.01000112 0.2507363 0.01249068 0.2155132 0.0134086 0.2096948 0.01446896 0.2039006 0.01446896 0.2039006 0.01567125 0.1981343 0.01701468 0.1923993 0.01701468 0.1923993 0.01849842 0.1866989 0.01446896 0.2039006 0.01849842 0.1866989 0.02012163 0.1810365 0.01446896 0.2039006 0.02012163 0.1810365 0.0218833 0.1754159 0.02378243 0.16984 0.02378243 0.16984 0.02581775 0.1643126 0.02798813 0.1588367 0.05003911 0.117276 0.05335658 0.1124086 0.06401121 0.09831547 0.05335658 0.1124086 0.05679249 0.1076242 0.06401121 0.09831547 0.07167804 0.08937215 0.07567381 0.08504432 0.06401121 0.09831547 0.07567381 0.08504432 0.07977449 0.08081579 0.06401121 0.09831547 0.07977449 0.08081579 0.08397775 0.07668924 0.08828103 0.072667 0.08828103 0.072667 0.0926817 0.06875163 0.09717714 0.06494545 0.1064414 0.05766969 0.1112046 0.05420452 0.09717714 0.06494545 0.1112046 0.05420452 0.1160515 0.0508573 0.09717714 0.06494545 0.1160515 0.0508573 0.1209791 0.04763001 0.1259843 0.04452461 0.1259843 0.04452461 0.1310643 0.041543 0.1160515 0.0508573 0.1310643 0.041543 0.1362159 0.03868699 0.1160515 0.0508573 0.2140565 0.01270675 0.2198908 0.01189613 0.2024564 0.01475626 0.2198908 0.01189613 0.2257432 0.01122897 0.2024564 0.01475626 0.2257432 0.01122897 0.2316102 0.01070559 0.2492637 0.01000112 0.2316102 0.01070559 0.2374883 0.01032632 0.2492637 0.01000112 0.2610408 0.01025408 0.2669211 0.01059722 0.2492637 0.01000112 0.2669211 0.01059722 0.2727912 0.01108461 0.2492637 0.01000112 0.2844868 0.01249068 0.2903052 0.0134086 0.2960993 0.01446896 0.2960993 0.01446896 0.3018656 0.01567125 0.3076007 0.01701468 0.3076007 0.01701468 0.3133011 0.01849842 0.2960993 0.01446896 0.3133011 0.01849842 0.3189634 0.02012163 0.2960993 0.01446896 0.3189634 0.02012163 0.3245841 0.0218833 0.3301599 0.02378243 0.3301599 0.02378243 0.3356874 0.02581775 0.3411633 0.02798813 0.382724 0.05003911 0.3875913 0.05335658 0.4016845 0.06401121 0.3875913 0.05335658 0.3923758 0.05679249 0.4016845 0.06401121 0.4106279 0.07167804 0.4149557 0.07567381 0.4016845 0.06401121 0.4149557 0.07567381 0.4191842 0.07977449 0.4016845 0.06401121 0.4191842 0.07977449 0.4233108 0.08397775 0.4273329 0.08828103 0.4273329 0.08828103 0.4312483 0.0926817 0.4350546 0.09717714 0.4423303 0.1064414 0.4457954 0.1112046 0.4350546 0.09717714 0.4457954 0.1112046 0.4491427 0.1160515 0.4350546 0.09717714 0.4491427 0.1160515 0.45237 0.1209791 0.4554753 0.1259843 0.4554753 0.1259843 0.4584569 0.1310643 0.4491427 0.1160515 0.4584569 0.1310643 0.461313 0.1362159 0.4491427 0.1160515 0.4872932 0.2140565 0.4881038 0.2198908 0.4852437 0.2024564 0.4881038 0.2198908 0.488771 0.2257432 0.4852437 0.2024564 0.488771 0.2257432 0.4892944 0.2316102 0.4899989 0.2492637 0.4892944 0.2316102 0.4896737 0.2374883 0.4899989 0.2492637 0.4897459 0.2610408 0.4894027 0.2669211 0.4899989 0.2492637 0.4894027 0.2669211 0.4889154 0.2727912 0.4899989 0.2492637 0.4875093 0.2844868 0.4865914 0.2903052 0.485531 0.2960993 0.485531 0.2960993 0.4843288 0.3018656 0.4829853 0.3076007 0.4829853 0.3076007 0.4815015 0.3133011 0.485531 0.2960993 0.4815015 0.3133011 0.4798783 0.3189634 0.485531 0.2960993 0.4798783 0.3189634 0.4781166 0.3245841 0.4762176 0.3301599 0.4762176 0.3301599 0.4741822 0.3356874 0.4720118 0.3411633 0.4499608 0.382724 0.4466434 0.3875913 0.4359887 0.4016845 0.4466434 0.3875913 0.4432075 0.3923758 0.4359887 0.4016845 0.4283219 0.4106279 0.4243262 0.4149557 0.4359887 0.4016845 0.4243262 0.4149557 0.4202255 0.4191842 0.4359887 0.4016845 0.4202255 0.4191842 0.4160223 0.4233108 0.411719 0.4273329 0.411719 0.4273329 0.4073183 0.4312483 0.4028229 0.4350546 0.3935586 0.4423303 0.3887953 0.4457954 0.4028229 0.4350546 0.3887953 0.4457954 0.3839485 0.4491427 0.4028229 0.4350546 0.3839485 0.4491427 0.3790209 0.45237 0.3740156 0.4554753 0.3740156 0.4554753 0.3689357 0.4584569 0.3839485 0.4491427 0.3689357 0.4584569 0.363784 0.461313 0.3839485 0.4491427 0.2859435 0.4872932 0.2801092 0.4881038 0.2975436 0.4852437 0.2801092 0.4881038 0.2742568 0.488771 0.2975436 0.4852437 0.2742568 0.488771 0.2683897 0.4892944 0.2507363 0.4899989 0.2683897 0.4892944 0.2625116 0.4896737 0.2507363 0.4899989 0.2272087 0.4889154 0.2155132 0.4875093 0.2507363 0.4899989 0.2155132 0.4875093 0.2039006 0.485531 0.2507363 0.4899989 0.1810365 0.4798783 0.16984 0.4762176 0.2039006 0.485531 0.16984 0.4762176 0.1588367 0.4720118 0.2039006 0.485531 0.1588367 0.4720118 0.1480528 0.4672712 0.1375147 0.4620072 0.1375147 0.4620072 0.1272475 0.4562324 0.117276 0.4499608 0.08081579 0.4202255 0.072667 0.411719 0.06494545 0.4028229 0.03868699 0.363784 0.03335839 0.3532783 0.02855169 0.3425239 0.02855169 0.3425239 0.02427852 0.3315464 0.01475626 0.2975436 0.02427852 0.3315464 0.02054911 0.3203726 0.01475626 0.2975436 0.02054911 0.3203726 0.01737248 0.3090292 0.01475626 0.2975436 0.01108461 0.2272087 0.01249068 0.2155132 0.01000112 0.2507363 0.01249068 0.2155132 0.01446896 0.2039006 0.01000112 0.2507363 0.02012163 0.1810365 0.02378243 0.16984 0.01446896 0.2039006 0.02378243 0.16984 0.02798813 0.1588367 0.01446896 0.2039006 0.02798813 0.1588367 0.03272879 0.1480528 0.03799277 0.1375147 0.03799277 0.1375147 0.04376757 0.1272475 0.05003911 0.117276 0.07977449 0.08081579 0.08828103 0.072667 0.09717714 0.06494545 0.1362159 0.03868699 0.1467216 0.03335839 0.1574761 0.02855169 0.1574761 0.02855169 0.1684535 0.02427852 0.2024564 0.01475626 0.1684535 0.02427852 0.1796274 0.02054911 0.2024564 0.01475626 0.1796274 0.02054911 0.1909708 0.01737248 0.2024564 0.01475626 0.2727912 0.01108461 0.2844868 0.01249068 0.2492637 0.01000112 0.2844868 0.01249068 0.2960993 0.01446896 0.2492637 0.01000112 0.3189634 0.02012163 0.3301599 0.02378243 0.2960993 0.01446896 0.3301599 0.02378243 0.3411633 0.02798813 0.2960993 0.01446896 0.3411633 0.02798813 0.3519471 0.03272879 0.3624853 0.03799277 0.3624853 0.03799277 0.3727526 0.04376757 0.382724 0.05003911 0.4191842 0.07977449 0.4273329 0.08828103 0.4350546 0.09717714 0.461313 0.1362159 0.4666416 0.1467216 0.4714483 0.1574761 0.4714483 0.1574761 0.4757214 0.1684535 0.4852437 0.2024564 0.4757214 0.1684535 0.4794509 0.1796274 0.4852437 0.2024564 0.4794509 0.1796274 0.4826275 0.1909708 0.4852437 0.2024564 0.4889154 0.2727912 0.4875093 0.2844868 0.4899989 0.2492637 0.4875093 0.2844868 0.485531 0.2960993 0.4899989 0.2492637 0.4798783 0.3189634 0.4762176 0.3301599 0.485531 0.2960993 0.4762176 0.3301599 0.4720118 0.3411633 0.485531 0.2960993 0.4720118 0.3411633 0.4672712 0.3519471 0.4620072 0.3624853 0.4620072 0.3624853 0.4562324 0.3727526 0.4499608 0.382724 0.4202255 0.4191842 0.411719 0.4273329 0.4028229 0.4350546 0.363784 0.461313 0.3532783 0.4666416 0.3425239 0.4714483 0.3425239 0.4714483 0.3315464 0.4757214 0.2975436 0.4852437 0.3315464 0.4757214 0.3203726 0.4794509 0.2975436 0.4852437 0.3203726 0.4794509 0.3090292 0.4826275 0.2975436 0.4852437 0.1588367 0.4720118 0.1375147 0.4620072 0.08081579 0.4202255 0.1375147 0.4620072 0.117276 0.4499608 0.08081579 0.4202255 0.117276 0.4499608 0.09831547 0.4359887 0.08081579 0.4202255 0.08081579 0.4202255 0.06494545 0.4028229 0.0508573 0.3839485 0.0508573 0.3839485 0.03868699 0.363784 0.08081579 0.4202255 0.03868699 0.363784 0.02855169 0.3425239 0.08081579 0.4202255 0.01475626 0.2975436 0.01122897 0.2742568 0.01000112 0.2507363 0.02798813 0.1588367 0.03799277 0.1375147 0.07977449 0.08081579 0.03799277 0.1375147 0.05003911 0.117276 0.07977449 0.08081579 0.05003911 0.117276 0.06401121 0.09831547 0.07977449 0.08081579 0.07977449 0.08081579 0.09717714 0.06494545 0.1160515 0.0508573 0.1160515 0.0508573 0.1362159 0.03868699 0.07977449 0.08081579 0.1362159 0.03868699 0.1574761 0.02855169 0.07977449 0.08081579 0.2024564 0.01475626 0.2257432 0.01122897 0.2492637 0.01000112 0.3411633 0.02798813 0.3624853 0.03799277 0.4191842 0.07977449 0.3624853 0.03799277 0.382724 0.05003911 0.4191842 0.07977449 0.382724 0.05003911 0.4016845 0.06401121 0.4191842 0.07977449 0.4191842 0.07977449 0.4350546 0.09717714 0.4491427 0.1160515 0.4491427 0.1160515 0.461313 0.1362159 0.4191842 0.07977449 0.461313 0.1362159 0.4714483 0.1574761 0.4191842 0.07977449 0.4852437 0.2024564 0.488771 0.2257432 0.4899989 0.2492637 0.4720118 0.3411633 0.4620072 0.3624853 0.4202255 0.4191842 0.4620072 0.3624853 0.4499608 0.382724 0.4202255 0.4191842 0.4499608 0.382724 0.4359887 0.4016845 0.4202255 0.4191842 0.4202255 0.4191842 0.4028229 0.4350546 0.3839485 0.4491427 0.3839485 0.4491427 0.363784 0.461313 0.4202255 0.4191842 0.363784 0.461313 0.3425239 0.4714483 0.4202255 0.4191842 0.2975436 0.4852437 0.2742568 0.488771 0.2507363 0.4899989 0.2507363 0.4899989 0.2039006 0.485531 0.1588367 0.4720118 0.02855169 0.3425239 0.01475626 0.2975436 0.08081579 0.4202255 0.01475626 0.2975436 0.01000112 0.2507363 0.08081579 0.4202255 0.01000112 0.2507363 0.01446896 0.2039006 0.02798813 0.1588367 0.1574761 0.02855169 0.2024564 0.01475626 0.07977449 0.08081579 0.2024564 0.01475626 0.2492637 0.01000112 0.07977449 0.08081579 0.2492637 0.01000112 0.2960993 0.01446896 0.3411633 0.02798813 0.4714483 0.1574761 0.4852437 0.2024564 0.4191842 0.07977449 0.4852437 0.2024564 0.4899989 0.2492637 0.4191842 0.07977449 0.4899989 0.2492637 0.485531 0.2960993 0.4720118 0.3411633 0.3425239 0.4714483 0.2975436 0.4852437 0.4202255 0.4191842 0.2975436 0.4852437 0.2507363 0.4899989 0.4202255 0.4191842 0.2507363 0.4899989 0.1588367 0.4720118 0.08081579 0.4202255 0.01000112 0.2507363 0.02798813 0.1588367 0.07977449 0.08081579 0.2492637 0.01000112 0.3411633 0.02798813 0.4191842 0.07977449 0.4899989 0.2492637 0.4720118 0.3411633 0.4202255 0.4191842 0.2507363 0.4899989 0.08081579 0.4202255 0.01000112 0.2507363 0.01000112 0.2507363 0.07977449 0.08081579 0.2507363 0.4899989 0.07977449 0.08081579 0.2492637 0.01000112 0.2507363 0.4899989 0.2492637 0.01000112 0.4191842 0.07977449 0.4899989 0.2492637 0.4899989 0.2492637 0.4202255 0.4191842 0.2492637 0.01000112 4.88281e-4 1 2.44141e-4 1 2.44141e-4 0.5 2.44141e-4 1 0 1 0 0.5 0.7496318 0.4899997 0.75 0.49 0.7503682 0.4899997 0.7503682 0.4899997 0.7507363 0.4899989 0.7511045 0.4899975 0.7511045 0.4899975 0.7514726 0.4899955 0.7518408 0.4899929 0.7518408 0.4899929 0.7522089 0.4899898 0.7511045 0.4899975 0.7522089 0.4899898 0.7525771 0.4899862 0.7511045 0.4899975 0.7525771 0.4899862 0.7529452 0.489982 0.7533133 0.4899771 0.7533133 0.4899771 0.7536814 0.4899718 0.7540495 0.4899659 0.7540495 0.4899659 0.7544176 0.4899594 0.7547857 0.4899523 0.7547857 0.4899523 0.7551538 0.4899446 0.7540495 0.4899659 0.7551538 0.4899446 0.7555218 0.4899365 0.7540495 0.4899659 0.7555218 0.4899365 0.7558899 0.4899277 0.756994 0.4898981 0.7558899 0.4899277 0.756258 0.4899184 0.756994 0.4898981 0.756258 0.4899184 0.756626 0.4899085 0.756994 0.4898981 0.756994 0.4898981 0.757362 0.4898871 0.7584658 0.4898506 0.757362 0.4898871 0.75773 0.4898755 0.7584658 0.4898506 0.75773 0.4898755 0.7580979 0.4898633 0.7584658 0.4898506 0.7584658 0.4898506 0.7588337 0.4898374 0.7599374 0.4897942 0.7588337 0.4898374 0.7592017 0.4898235 0.7599374 0.4897942 0.7592017 0.4898235 0.7595695 0.4898092 0.7599374 0.4897942 0.7599374 0.4897942 0.7603052 0.4897786 0.760673 0.4897626 0.760673 0.4897626 0.7610408 0.4897459 0.7614085 0.4897287 0.7614085 0.4897287 0.7617763 0.4897109 0.7628793 0.4896542 0.7617763 0.4897109 0.762144 0.4896926 0.7628793 0.4896542 0.762144 0.4896926 0.7625116 0.4896737 0.7628793 0.4896542 0.7628793 0.4896542 0.7632468 0.4896341 0.7636144 0.4896135 0.7636144 0.4896135 0.763982 0.4895924 0.7643495 0.4895706 0.7643495 0.4895706 0.764717 0.4895483 0.7658192 0.4894781 0.764717 0.4895483 0.7650845 0.4895255 0.7658192 0.4894781 0.7650845 0.4895255 0.7654519 0.4895021 0.7658192 0.4894781 0.7658192 0.4894781 0.7661865 0.4894535 0.7672883 0.4893765 0.7661865 0.4894535 0.7665538 0.4894284 0.7672883 0.4893765 0.7665538 0.4894284 0.7669211 0.4894027 0.7672883 0.4893765 0.7672883 0.4893765 0.7676555 0.4893497 0.7680227 0.4893223 0.7680227 0.4893223 0.7683897 0.4892944 0.7687568 0.4892659 0.7687568 0.4892659 0.7691238 0.4892368 0.7702245 0.4891463 0.7691238 0.4892368 0.7694907 0.4892073 0.7702245 0.4891463 0.7694907 0.4892073 0.7698577 0.4891771 0.7702245 0.4891463 0.7702245 0.4891463 0.7705914 0.489115 0.7709581 0.4890832 0.7709581 0.4890832 0.7713249 0.4890507 0.7716915 0.4890177 0.7716915 0.4890177 0.7720581 0.4889842 0.7731577 0.4888801 0.7720581 0.4889842 0.7724247 0.4889501 0.7731577 0.4888801 0.7724247 0.4889501 0.7727913 0.4889154 0.7731577 0.4888801 0.7731577 0.4888801 0.7735241 0.4888443 0.7738905 0.488808 0.7738905 0.488808 0.7742568 0.488771 0.7731577 0.4888801 0.7742568 0.488771 0.774623 0.4887335 0.7731577 0.4888801 0.774623 0.4887335 0.7749892 0.4886955 0.7753553 0.4886569 0.7753553 0.4886569 0.7757214 0.4886177 0.7760874 0.488578 0.7760874 0.488578 0.7764533 0.4885377 0.7775508 0.4884134 0.7764533 0.4885377 0.7768192 0.4884968 0.7775508 0.4884134 0.7768192 0.4884968 0.777185 0.4884554 0.7775508 0.4884134 0.7775508 0.4884134 0.7779165 0.4883708 0.7790132 0.4882399 0.7779165 0.4883708 0.7782821 0.4883278 0.7790132 0.4882399 0.7782821 0.4883278 0.7786477 0.4882841 0.7790132 0.4882399 0.7790132 0.4882399 0.7793785 0.4881951 0.7797439 0.4881498 0.7797439 0.4881498 0.7801092 0.4881038 0.7790132 0.4882399 0.7801092 0.4881038 0.7804744 0.4880574 0.7790132 0.4882399 0.7804744 0.4880574 0.7808396 0.4880104 0.7812046 0.4879627 0.7812046 0.4879627 0.7815696 0.4879146 0.7804744 0.4880574 0.7815696 0.4879146 0.7819345 0.4878659 0.7804744 0.4880574 0.7819345 0.4878659 0.7822994 0.4878166 0.7826641 0.4877668 0.7826641 0.4877668 0.7830289 0.4877164 0.7833935 0.4876655 0.7833935 0.4876655 0.783758 0.487614 0.7848511 0.4874561 0.783758 0.487614 0.7841224 0.4875619 0.7848511 0.4874561 0.7841224 0.4875619 0.7844868 0.4875093 0.7848511 0.4874561 0.7848511 0.4874561 0.7852153 0.4874024 0.7855795 0.487348 0.7855795 0.487348 0.7859435 0.4872932 0.7863075 0.4872378 0.7863075 0.4872378 0.7866714 0.4871818 0.7877624 0.4870105 0.7866714 0.4871818 0.7870351 0.4871253 0.7877624 0.4870105 0.7870351 0.4871253 0.7873988 0.4870682 0.7877624 0.4870105 0.7877624 0.4870105 0.7881259 0.4869523 0.7884894 0.4868935 0.7884894 0.4868935 0.7888528 0.4868342 0.789216 0.4867744 0.789216 0.4867744 0.7895792 0.486714 0.7899422 0.4866529 0.7899422 0.4866529 0.7903052 0.4865914 0.7906681 0.4865293 0.7906681 0.4865293 0.7910309 0.4864667 0.7913935 0.4864034 0.7913935 0.4864034 0.7917562 0.4863396 0.7906681 0.4865293 0.7917562 0.4863396 0.7921186 0.4862753 0.7906681 0.4865293 0.7921186 0.4862753 0.792481 0.4862104 0.7935676 0.4860124 0.792481 0.4862104 0.7928433 0.486145 0.7935676 0.4860124 0.7928433 0.486145 0.7932055 0.486079 0.7935676 0.4860124 0.7935676 0.4860124 0.7939296 0.4859453 0.7950149 0.4857407 0.7939296 0.4859453 0.7942914 0.4858776 0.7950149 0.4857407 0.7942914 0.4858776 0.7946532 0.4858095 0.7950149 0.4857407 0.7950149 0.4857407 0.7953765 0.4856714 0.7957379 0.4856014 0.7957379 0.4856014 0.7960993 0.485531 0.7964605 0.48546 0.7964605 0.48546 0.7968217 0.4853885 0.7971827 0.4853163 0.7971827 0.4853163 0.7975437 0.4852437 0.7979044 0.4851705 0.7979044 0.4851705 0.7982651 0.4850968 0.7986257 0.4850224 0.7986257 0.4850224 0.7989861 0.4849476 0.7979044 0.4851705 0.7989861 0.4849476 0.7993465 0.4848722 0.7979044 0.4851705 0.7993465 0.4848722 0.7997068 0.4847962 0.8000668 0.4847196 0.8000668 0.4847196 0.8004269 0.4846426 0.8007867 0.4845649 0.8007867 0.4845649 0.8011465 0.4844868 0.8015061 0.484408 0.8015061 0.484408 0.8018656 0.4843288 0.8022251 0.4842489 0.8022251 0.4842489 0.8025843 0.4841685 0.8029435 0.4840875 0.8029435 0.4840875 0.8033025 0.4840061 0.8036614 0.483924 0.8036614 0.483924 0.8040202 0.4838414 0.8050957 0.4835904 0.8040202 0.4838414 0.8043788 0.4837583 0.8050957 0.4835904 0.8043788 0.4837583 0.8047373 0.4836746 0.8050957 0.4835904 0.8050957 0.4835904 0.805454 0.4835056 0.8058121 0.4834203 0.8058121 0.4834203 0.8061701 0.4833344 0.8065279 0.4832479 0.8065279 0.4832479 0.8068857 0.4831609 0.8072433 0.4830734 0.8072433 0.4830734 0.8076007 0.4829853 0.8079581 0.4828967 0.8079581 0.4828967 0.8083153 0.4828075 0.8086723 0.4827178 0.8086723 0.4827178 0.8090292 0.4826275 0.809386 0.4825367 0.809386 0.4825367 0.8097426 0.4824453 0.8108117 0.4821679 0.8097426 0.4824453 0.8100991 0.4823534 0.8108117 0.4821679 0.8100991 0.4823534 0.8104555 0.4822609 0.8108117 0.4821679 0.8108117 0.4821679 0.8111678 0.4820743 0.8115237 0.4819803 0.8115237 0.4819803 0.8118795 0.4818856 0.8108117 0.4821679 0.8118795 0.4818856 0.8122351 0.4817904 0.8108117 0.4821679 0.8122351 0.4817904 0.8125906 0.4816946 0.812946 0.4815984 0.812946 0.4815984 0.8133012 0.4815015 0.8136562 0.4814042 0.8136562 0.4814042 0.8140111 0.4813063 0.8143658 0.4812078 0.8143658 0.4812078 0.8147204 0.4811088 0.8150749 0.4810093 0.8150749 0.4810093 0.8154292 0.4809091 0.8157833 0.4808085 0.8157833 0.4808085 0.8161373 0.4807073 0.8164911 0.4806056 0.8164911 0.4806056 0.8168447 0.4805033 0.8171982 0.4804005 0.8171982 0.4804005 0.8175516 0.4802972 0.8179048 0.4801933 0.8179048 0.4801933 0.8182578 0.4800888 0.8193159 0.4797723 0.8182578 0.4800888 0.8186107 0.4799839 0.8193159 0.4797723 0.8186107 0.4799839 0.8189634 0.4798783 0.8193159 0.4797723 0.8193159 0.4797723 0.8196683 0.4796657 0.8200206 0.4795585 0.8200206 0.4795585 0.8203726 0.4794509 0.8207245 0.4793426 0.8207245 0.4793426 0.8210762 0.4792339 0.8214278 0.4791246 0.8214278 0.4791246 0.8217791 0.4790148 0.8221304 0.4789044 0.8221304 0.4789044 0.8224814 0.4787935 0.8235335 0.4784575 0.8224814 0.4787935 0.8228323 0.478682 0.8235335 0.4784575 0.8228323 0.478682 0.823183 0.47857 0.8235335 0.4784575 0.8235335 0.4784575 0.8238839 0.4783444 0.8242341 0.4782308 0.8242341 0.4782308 0.8245841 0.4781166 0.824934 0.478002 0.824934 0.478002 0.8252837 0.4778867 0.8263316 0.4775379 0.8252837 0.4778867 0.8256331 0.477771 0.8263316 0.4775379 0.8256331 0.477771 0.8259824 0.4776547 0.8263316 0.4775379 0.8263316 0.4775379 0.8266805 0.4774205 0.8277263 0.4770653 0.8266805 0.4774205 0.8270292 0.4773026 0.8277263 0.4770653 0.8270292 0.4773026 0.8273779 0.4771842 0.8277263 0.4770653 0.8277263 0.4770653 0.8280745 0.4769458 0.8284225 0.4768257 0.8284225 0.4768257 0.8287703 0.4767051 0.829118 0.4765841 0.829118 0.4765841 0.8294655 0.4764624 0.8305069 0.4760943 0.8294655 0.4764624 0.8298128 0.4763402 0.8305069 0.4760943 0.8298128 0.4763402 0.8301599 0.4762176 0.8305069 0.4760943 0.8305069 0.4760943 0.8308536 0.4759706 0.8312001 0.4758463 0.8312001 0.4758463 0.8315464 0.4757214 0.8318926 0.4755961 0.8318926 0.4755961 0.8322386 0.4754702 0.8332753 0.4750894 0.8322386 0.4754702 0.8325843 0.4753438 0.8332753 0.4750894 0.8325843 0.4753438 0.8329299 0.4752169 0.8332753 0.4750894 0.8332753 0.4750894 0.8336205 0.4749614 0.8339655 0.4748328 0.8339655 0.4748328 0.8343103 0.4747037 0.8332753 0.4750894 0.8343103 0.4747037 0.8346549 0.4745742 0.8332753 0.4750894 0.8346549 0.4745742 0.8349993 0.474444 0.8353434 0.4743134 0.8353434 0.4743134 0.8356875 0.4741822 0.8360312 0.4740505 0.8360312 0.4740505 0.8363748 0.4739183 0.8367182 0.4737855 0.8367182 0.4737855 0.8370614 0.4736523 0.8374044 0.4735184 0.8374044 0.4735184 0.8377471 0.4733841 0.8380897 0.4732492 0.8380897 0.4732492 0.838432 0.4731138 0.8387742 0.4729779 0.8387742 0.4729779 0.8391161 0.4728415 0.8394579 0.4727045 0.8394579 0.4727045 0.8397994 0.472567 0.8387742 0.4729779 0.8397994 0.472567 0.8401407 0.472429 0.8387742 0.4729779 0.8401407 0.472429 0.8404818 0.4722905 0.8408226 0.4721514 0.8408226 0.4721514 0.8411633 0.4720118 0.8415038 0.4718717 0.8415038 0.4718717 0.841844 0.4717311 0.8421841 0.4715899 0.8421841 0.4715899 0.8425239 0.4714483 0.8428635 0.4713061 0.8428635 0.4713061 0.8432028 0.4711633 0.843542 0.4710201 0.843542 0.4710201 0.8438809 0.4708764 0.8428635 0.4713061 0.8438809 0.4708764 0.8442196 0.4707321 0.8428635 0.4713061 0.8442196 0.4707321 0.8445581 0.4705873 0.8448964 0.470442 0.8448964 0.470442 0.8452344 0.4702962 0.8442196 0.4707321 0.8452344 0.4702962 0.8455722 0.4701498 0.8442196 0.4707321 0.8455722 0.4701498 0.8459098 0.470003 0.8462472 0.4698556 0.8462472 0.4698556 0.8465843 0.4697077 0.8455722 0.4701498 0.8465843 0.4697077 0.8469212 0.4695593 0.8455722 0.4701498 0.8469212 0.4695593 0.8472579 0.4694103 0.8482666 0.4689604 0.8472579 0.4694103 0.8475944 0.4692609 0.8482666 0.4689604 0.8475944 0.4692609 0.8479306 0.4691109 0.8482666 0.4689604 0.8482666 0.4689604 0.8486024 0.4688094 0.8489379 0.4686579 0.8489379 0.4686579 0.8492732 0.4685059 0.8482666 0.4689604 0.8492732 0.4685059 0.8496083 0.4683533 0.8482666 0.4689604 0.8496083 0.4683533 0.8499431 0.4682003 0.8502777 0.4680467 0.8502777 0.4680467 0.8506121 0.4678927 0.8509462 0.4677381 0.8509462 0.4677381 0.8512801 0.467583 0.8516137 0.4674273 0.8516137 0.4674273 0.8519471 0.4672712 0.8522803 0.4671146 0.8522803 0.4671146 0.8526132 0.4669575 0.8529459 0.4667997 0.8529459 0.4667997 0.8532783 0.4666416 0.8536106 0.4664829 0.8536106 0.4664829 0.8539425 0.4663237 0.8542742 0.466164 0.8542742 0.466164 0.8546057 0.4660038 0.8549369 0.4658431 0.8549369 0.4658431 0.8552679 0.4656819 0.8555986 0.4655202 0.8555986 0.4655202 0.8559291 0.4653579 0.8549369 0.4658431 0.8559291 0.4653579 0.8562594 0.4651951 0.8549369 0.4658431 0.8562594 0.4651951 0.8565893 0.4650319 0.8569191 0.4648681 0.8569191 0.4648681 0.8572486 0.4647039 0.8562594 0.4651951 0.8572486 0.4647039 0.8575778 0.4645391 0.8562594 0.4651951 0.8575778 0.4645391 0.8579067 0.4643738 0.8582354 0.4642081 0.8582354 0.4642081 0.8585639 0.4640418 0.8588921 0.463875 0.8588921 0.463875 0.85922 0.4637077 0.8595477 0.4635399 0.8595477 0.4635399 0.8598752 0.4633716 0.8602024 0.4632028 0.8602024 0.4632028 0.8605293 0.4630335 0.8608559 0.4628637 0.8608559 0.4628637 0.8611823 0.4626934 0.8615085 0.4625226 0.8615085 0.4625226 0.8618344 0.4623513 0.86216 0.4621795 0.86216 0.4621795 0.8624853 0.4620072 0.8615085 0.4625226 0.8624853 0.4620072 0.8628104 0.4618344 0.8615085 0.4625226 0.8628104 0.4618344 0.8631352 0.4616611 0.8641081 0.4611382 0.8631352 0.4616611 0.8634598 0.4614873 0.8641081 0.4611382 0.8634598 0.4614873 0.8637841 0.461313 0.8641081 0.4611382 0.8641081 0.4611382 0.8644318 0.460963 0.8647553 0.4607871 0.8647553 0.4607871 0.8650785 0.4606109 0.8641081 0.4611382 0.8650785 0.4606109 0.8654015 0.4604341 0.8641081 0.4611382 0.8654015 0.4604341 0.8657241 0.4602568 0.8660465 0.460079 0.8660465 0.460079 0.8663686 0.4599008 0.8666905 0.4597221 0.8666905 0.4597221 0.867012 0.4595428 0.8673334 0.4593631 0.8673334 0.4593631 0.8676544 0.4591828 0.8679751 0.4590021 0.8679751 0.4590021 0.8682956 0.4588209 0.8692553 0.4582743 0.8682956 0.4588209 0.8686158 0.4586392 0.8692553 0.4582743 0.8686158 0.4586392 0.8689357 0.4584569 0.8692553 0.4582743 0.8692553 0.4582743 0.8695747 0.4580911 0.870531 0.4575386 0.8695747 0.4580911 0.8698937 0.4579074 0.870531 0.4575386 0.8698937 0.4579074 0.8702125 0.4577233 0.870531 0.4575386 0.870531 0.4575386 0.8708492 0.4573535 0.8718022 0.4567952 0.8708492 0.4573535 0.8711672 0.4571679 0.8718022 0.4567952 0.8711672 0.4571679 0.8714848 0.4569817 0.8718022 0.4567952 0.8718022 0.4567952 0.8721193 0.4566081 0.8724361 0.4564205 0.8724361 0.4564205 0.8727526 0.4562324 0.8730688 0.4560439 0.8730688 0.4560439 0.8733847 0.4558548 0.8737003 0.4556654 0.8737003 0.4556654 0.8740156 0.4554753 0.8743306 0.4552849 0.8743306 0.4552849 0.8746455 0.4550939 0.8749599 0.4549025 0.8749599 0.4549025 0.8752741 0.4547106 0.8743306 0.4552849 0.8752741 0.4547106 0.8755879 0.4545181 0.8743306 0.4552849 0.8755879 0.4545181 0.8759015 0.4543253 0.8762148 0.4541319 0.8762148 0.4541319 0.8765278 0.453938 0.8768405 0.4537437 0.8768405 0.4537437 0.8771529 0.4535489 0.877465 0.4533536 0.877465 0.4533536 0.8777768 0.4531578 0.8780882 0.4529616 0.8780882 0.4529616 0.8783994 0.4527649 0.8787103 0.4525676 0.8787103 0.4525676 0.8790209 0.45237 0.8793312 0.4521718 0.8793312 0.4521718 0.8796412 0.4519732 0.8799508 0.4517741 0.8799508 0.4517741 0.8802602 0.4515745 0.8793312 0.4521718 0.8802602 0.4515745 0.8805692 0.4513745 0.8793312 0.4521718 0.8805692 0.4513745 0.880878 0.4511739 0.8818024 0.4505695 0.880878 0.4511739 0.8811864 0.4509729 0.8818024 0.4505695 0.8811864 0.4509729 0.8814946 0.4507715 0.8818024 0.4505695 0.8818024 0.4505695 0.8821099 0.4503671 0.8830306 0.449757 0.8821099 0.4503671 0.8824171 0.4501642 0.8830306 0.449757 0.8824171 0.4501642 0.8827241 0.4499608 0.8830306 0.449757 0.8830306 0.449757 0.8833369 0.4495527 0.8836428 0.4493479 0.8836428 0.4493479 0.8839485 0.4491427 0.8830306 0.449757 0.8839485 0.4491427 0.8842537 0.448937 0.8830306 0.449757 0.8842537 0.448937 0.8845588 0.4487308 0.8854719 0.4481095 0.8845588 0.4487308 0.8848635 0.4485242 0.8854719 0.4481095 0.8848635 0.4485242 0.8851678 0.4483171 0.8854719 0.4481095 0.8854719 0.4481095 0.8857756 0.4479014 0.8860791 0.4476929 0.8860791 0.4476929 0.8863822 0.447484 0.8854719 0.4481095 0.8863822 0.447484 0.8866849 0.4472745 0.8854719 0.4481095 0.8866849 0.4472745 0.8869874 0.4470646 0.8872895 0.4468542 0.8872895 0.4468542 0.8875913 0.4466434 0.8878929 0.4464321 0.8878929 0.4464321 0.888194 0.4462203 0.8884948 0.4460082 0.8884948 0.4460082 0.8887953 0.4457954 0.8878929 0.4464321 0.8887953 0.4457954 0.8890955 0.4455823 0.8878929 0.4464321 0.8890955 0.4455823 0.8893954 0.4453687 0.8896949 0.4451547 0.8896949 0.4451547 0.8899941 0.4449402 0.890293 0.4447252 0.890293 0.4447252 0.8905915 0.4445097 0.8908897 0.4442939 0.8908897 0.4442939 0.8911876 0.4440775 0.890293 0.4447252 0.8911876 0.4440775 0.8914851 0.4438607 0.890293 0.4447252 0.8914851 0.4438607 0.8917824 0.4436434 0.8920792 0.4434257 0.8920792 0.4434257 0.8923758 0.4432075 0.8914851 0.4438607 0.8923758 0.4432075 0.892672 0.4429889 0.8914851 0.4438607 0.892672 0.4429889 0.8929678 0.4427698 0.8932633 0.4425503 0.8932633 0.4425503 0.8935586 0.4423303 0.8938534 0.4421098 0.8938534 0.4421098 0.894148 0.4418889 0.8944422 0.4416676 0.8944422 0.4416676 0.894736 0.4414458 0.8938534 0.4421098 0.894736 0.4414458 0.8950295 0.4412236 0.8938534 0.4421098 0.8950295 0.4412236 0.8953226 0.4410009 0.8956155 0.4407777 0.8956155 0.4407777 0.8959079 0.4405541 0.8950295 0.4412236 0.8959079 0.4405541 0.8962001 0.44033 0.8950295 0.4412236 0.8962001 0.44033 0.8964919 0.4401056 0.8967834 0.4398806 0.8967834 0.4398806 0.8970744 0.4396553 0.8962001 0.44033 0.8970744 0.4396553 0.8973652 0.4394294 0.8962001 0.44033 0.8973652 0.4394294 0.8976556 0.4392032 0.8979457 0.4389764 0.8979457 0.4389764 0.8982354 0.4387493 0.8985248 0.4385216 0.8985248 0.4385216 0.8988137 0.4382936 0.8991024 0.4380651 0.8991024 0.4380651 0.8993907 0.4378361 0.8985248 0.4385216 0.8993907 0.4378361 0.8996787 0.4376068 0.8985248 0.4385216 0.8996787 0.4376068 0.8999663 0.4373769 0.9002535 0.4371467 0.9002535 0.4371467 0.9005404 0.4369159 0.900827 0.4366848 0.900827 0.4366848 0.9011132 0.4364532 0.901399 0.4362212 0.901399 0.4362212 0.9016845 0.4359887 0.900827 0.4366848 0.9016845 0.4359887 0.9019696 0.4357559 0.900827 0.4366848 0.9019696 0.4357559 0.9022544 0.4355225 0.9025388 0.4352887 0.9025388 0.4352887 0.9028229 0.4350546 0.9019696 0.4357559 0.9028229 0.4350546 0.9031066 0.4348199 0.9019696 0.4357559 0.9031066 0.4348199 0.9033899 0.4345848 0.9036728 0.4343493 0.9036728 0.4343493 0.9039555 0.4341133 0.9042377 0.4338769 0.9042377 0.4338769 0.9045196 0.4336401 0.905363 0.4329271 0.9045196 0.4336401 0.9048011 0.4334029 0.905363 0.4329271 0.9048011 0.4334029 0.9050822 0.4331652 0.905363 0.4329271 0.905363 0.4329271 0.9056435 0.4326885 0.9059235 0.4324496 0.9059235 0.4324496 0.9062032 0.4322102 0.9064825 0.4319704 0.9064825 0.4319704 0.9067615 0.4317301 0.9070401 0.4314894 0.9070401 0.4314894 0.9073183 0.4312483 0.9075961 0.4310068 0.9075961 0.4310068 0.9078736 0.4307649 0.9081507 0.4305225 0.9081507 0.4305225 0.9084275 0.4302796 0.9075961 0.4310068 0.9084275 0.4302796 0.9087038 0.4300364 0.9075961 0.4310068 0.9087038 0.4300364 0.9089798 0.4297927 0.9092554 0.4295486 0.9092554 0.4295486 0.9095306 0.4293041 0.9098055 0.4290592 0.9098055 0.4290592 0.91008 0.4288139 0.9103541 0.4285681 0.9103541 0.4285681 0.9106279 0.4283219 0.9109012 0.4280753 0.9109012 0.4280753 0.9111742 0.4278283 0.9114468 0.4275808 0.9114468 0.4275808 0.911719 0.4273329 0.9109012 0.4280753 0.911719 0.4273329 0.9119908 0.4270847 0.9109012 0.4280753 0.9119908 0.4270847 0.9122623 0.426836 0.9125334 0.4265869 0.9125334 0.4265869 0.912804 0.4263373 0.9130743 0.4260874 0.9130743 0.4260874 0.9133443 0.425837 0.9136138 0.4255862 0.9136138 0.4255862 0.913883 0.4253351 0.9141517 0.4250835 0.9141517 0.4250835 0.9144201 0.4248315 0.9146881 0.424579 0.9146881 0.424579 0.9149557 0.4243262 0.9141517 0.4250835 0.9149557 0.4243262 0.9152229 0.4240729 0.9141517 0.4250835 0.9152229 0.4240729 0.9154897 0.4238193 0.9157562 0.4235652 0.9157562 0.4235652 0.9160223 0.4233108 0.9162879 0.4230559 0.9162879 0.4230559 0.9165531 0.4228006 0.9173466 0.4220323 0.9165531 0.4228006 0.916818 0.4225449 0.9173466 0.4220323 0.916818 0.4225449 0.9170826 0.4222888 0.9173466 0.4220323 0.9173466 0.4220323 0.9176103 0.4217754 0.918399 0.4210023 0.9176103 0.4217754 0.9178736 0.4215181 0.918399 0.4210023 0.9178736 0.4215181 0.9181365 0.4212604 0.918399 0.4210023 0.918399 0.4210023 0.9186611 0.4207437 0.9189229 0.4204848 0.9189229 0.4204848 0.9191842 0.4202255 0.9194451 0.4199658 0.9194451 0.4199658 0.9197056 0.4197056 0.9199658 0.4194451 0.9199658 0.4194451 0.9202255 0.4191842 0.9194451 0.4199658 0.9202255 0.4191842 0.9204848 0.4189229 0.9194451 0.4199658 0.9204848 0.4189229 0.9207437 0.4186611 0.9210023 0.418399 0.9210023 0.418399 0.9212604 0.4181365 0.9215181 0.4178736 0.9215181 0.4178736 0.9217754 0.4176103 0.9220323 0.4173466 0.9220323 0.4173466 0.9222888 0.4170825 0.9225449 0.416818 0.9225449 0.416818 0.9228006 0.4165531 0.9235652 0.4157562 0.9228006 0.4165531 0.9230559 0.4162879 0.9235652 0.4157562 0.9230559 0.4162879 0.9233108 0.4160223 0.9235652 0.4157562 0.9235652 0.4157562 0.9238193 0.4154897 0.9240729 0.4152229 0.9240729 0.4152229 0.9243262 0.4149557 0.9235652 0.4157562 0.9243262 0.4149557 0.924579 0.4146881 0.9235652 0.4157562 0.924579 0.4146881 0.9248315 0.4144201 0.9255862 0.4136138 0.9248315 0.4144201 0.9250835 0.4141517 0.9255862 0.4136138 0.9250835 0.4141517 0.9253351 0.4138829 0.9255862 0.4136138 0.9255862 0.4136138 0.925837 0.4133442 0.9260874 0.4130743 0.9260874 0.4130743 0.9263374 0.412804 0.9265869 0.4125334 0.9265869 0.4125334 0.926836 0.4122623 0.9270847 0.4119908 0.9270847 0.4119908 0.9273329 0.411719 0.9265869 0.4125334 0.9273329 0.411719 0.9275808 0.4114468 0.9265869 0.4125334 0.9275808 0.4114468 0.9278283 0.4111741 0.9280753 0.4109011 0.9280753 0.4109011 0.9283219 0.4106279 0.9285681 0.4103541 0.9285681 0.4103541 0.9288139 0.41008 0.9290592 0.4098055 0.9290592 0.4098055 0.9293041 0.4095306 0.9295486 0.4092554 0.9295486 0.4092554 0.9297928 0.4089798 0.9300364 0.4087038 0.9300364 0.4087038 0.9302796 0.4084274 0.9295486 0.4092554 0.9302796 0.4084274 0.9305225 0.4081507 0.9295486 0.4092554 0.9305225 0.4081507 0.9307649 0.4078736 0.9310068 0.4075961 0.9310068 0.4075961 0.9312483 0.4073183 0.9314894 0.4070401 0.9314894 0.4070401 0.9317301 0.4067615 0.9319704 0.4064825 0.9319704 0.4064825 0.9322102 0.4062032 0.9314894 0.4070401 0.9322102 0.4062032 0.9324496 0.4059235 0.9314894 0.4070401 0.9324496 0.4059235 0.9326885 0.4056435 0.9334029 0.4048011 0.9326885 0.4056435 0.9329271 0.405363 0.9334029 0.4048011 0.9329271 0.405363 0.9331652 0.4050822 0.9334029 0.4048011 0.9334029 0.4048011 0.9336401 0.4045196 0.9343493 0.4036728 0.9336401 0.4045196 0.9338769 0.4042377 0.9343493 0.4036728 0.9338769 0.4042377 0.9341133 0.4039555 0.9343493 0.4036728 0.9343493 0.4036728 0.9345848 0.4033899 0.9348199 0.4031065 0.9348199 0.4031065 0.9350546 0.4028229 0.9343493 0.4036728 0.9350546 0.4028229 0.9352887 0.4025388 0.9343493 0.4036728 0.9352887 0.4025388 0.9355225 0.4022544 0.9357559 0.4019696 0.9357559 0.4019696 0.9359887 0.4016845 0.9362212 0.401399 0.9362212 0.401399 0.9364532 0.4011132 0.9371467 0.4002535 0.9364532 0.4011132 0.9366848 0.400827 0.9371467 0.4002535 0.9366848 0.400827 0.936916 0.4005404 0.9371467 0.4002535 0.9371467 0.4002535 0.9373769 0.3999663 0.9376068 0.3996787 0.9376068 0.3996787 0.9378362 0.3993907 0.9371467 0.4002535 0.9378362 0.3993907 0.9380651 0.3991024 0.9371467 0.4002535 0.9380651 0.3991024 0.9382936 0.3988137 0.9385216 0.3985247 0.9385216 0.3985247 0.9387493 0.3982354 0.9389764 0.3979457 0.9389764 0.3979457 0.9392032 0.3976556 0.9394294 0.3973652 0.9394294 0.3973652 0.9396553 0.3970744 0.9389764 0.3979457 0.9396553 0.3970744 0.9398806 0.3967833 0.9389764 0.3979457 0.9398806 0.3967833 0.9401056 0.3964919 0.9407777 0.3956155 0.9401056 0.3964919 0.94033 0.3962001 0.9407777 0.3956155 0.94033 0.3962001 0.9405542 0.3959079 0.9407777 0.3956155 0.9407777 0.3956155 0.9410009 0.3953226 0.9412236 0.3950295 0.9412236 0.3950295 0.9414458 0.394736 0.9416676 0.3944422 0.9416676 0.3944422 0.9418889 0.3941479 0.9425503 0.3932633 0.9418889 0.3941479 0.9421098 0.3938534 0.9425503 0.3932633 0.9421098 0.3938534 0.9423303 0.3935586 0.9425503 0.3932633 0.9425503 0.3932633 0.9427698 0.3929678 0.9429889 0.392672 0.9429889 0.392672 0.9432075 0.3923758 0.9434257 0.3920792 0.9434257 0.3920792 0.9436434 0.3917824 0.9438607 0.3914851 0.9438607 0.3914851 0.9440775 0.3911876 0.9434257 0.3920792 0.9440775 0.3911876 0.9442939 0.3908897 0.9434257 0.3920792 0.9442939 0.3908897 0.9445098 0.3905915 0.9447252 0.390293 0.9447252 0.390293 0.9449402 0.3899941 0.9451547 0.3896949 0.9451547 0.3896949 0.9453687 0.3893954 0.9455823 0.3890955 0.9455823 0.3890955 0.9457954 0.3887953 0.9451547 0.3896949 0.9457954 0.3887953 0.9460082 0.3884948 0.9451547 0.3896949 0.9460082 0.3884948 0.9462203 0.388194 0.9464321 0.3878928 0.9464321 0.3878928 0.9466434 0.3875913 0.9460082 0.3884948 0.9466434 0.3875913 0.9468542 0.3872895 0.9460082 0.3884948 0.9468542 0.3872895 0.9470646 0.3869874 0.9472745 0.3866849 0.9472745 0.3866849 0.947484 0.3863822 0.9468542 0.3872895 0.947484 0.3863822 0.9476929 0.3860791 0.9468542 0.3872895 0.9476929 0.3860791 0.9479014 0.3857756 0.9481095 0.3854719 0.9481095 0.3854719 0.9483171 0.3851678 0.9485242 0.3848634 0.9485242 0.3848634 0.9487308 0.3845588 0.948937 0.3842537 0.948937 0.3842537 0.9491427 0.3839485 0.9485242 0.3848634 0.9491427 0.3839485 0.9493479 0.3836428 0.9485242 0.3848634 0.9493479 0.3836428 0.9495527 0.3833369 0.9501642 0.3824171 0.9495527 0.3833369 0.949757 0.3830306 0.9501642 0.3824171 0.949757 0.3830306 0.9499608 0.382724 0.9501642 0.3824171 0.9501642 0.3824171 0.9503671 0.3821099 0.9505695 0.3818024 0.9505695 0.3818024 0.9507715 0.3814946 0.9509729 0.3811864 0.9509729 0.3811864 0.9511739 0.380878 0.9513745 0.3805692 0.9513745 0.3805692 0.9515745 0.3802602 0.9509729 0.3811864 0.9515745 0.3802602 0.9517741 0.3799508 0.9509729 0.3811864 0.9517741 0.3799508 0.9519732 0.3796412 0.9521718 0.3793312 0.9521718 0.3793312 0.95237 0.3790209 0.9517741 0.3799508 0.95237 0.3790209 0.9525676 0.3787103 0.9517741 0.3799508 0.9525676 0.3787103 0.9527649 0.3783994 0.9533536 0.377465 0.9527649 0.3783994 0.9529616 0.3780882 0.9533536 0.377465 0.9529616 0.3780882 0.9531578 0.3777768 0.9533536 0.377465 0.9533536 0.377465 0.9535489 0.3771529 0.9541319 0.3762148 0.9535489 0.3771529 0.9537437 0.3768405 0.9541319 0.3762148 0.9537437 0.3768405 0.953938 0.3765278 0.9541319 0.3762148 0.9541319 0.3762148 0.9543253 0.3759015 0.9545181 0.3755879 0.9545181 0.3755879 0.9547106 0.3752741 0.9541319 0.3762148 0.9547106 0.3752741 0.9549025 0.3749599 0.9541319 0.3762148 0.9549025 0.3749599 0.9550939 0.3746454 0.9552849 0.3743306 0.9552849 0.3743306 0.9554753 0.3740156 0.9556654 0.3737003 0.9556654 0.3737003 0.9558549 0.3733847 0.9564205 0.3724361 0.9558549 0.3733847 0.9560439 0.3730688 0.9564205 0.3724361 0.9560439 0.3730688 0.9562324 0.3727526 0.9564205 0.3724361 0.9564205 0.3724361 0.9566081 0.3721193 0.9571679 0.3711671 0.9566081 0.3721193 0.9567952 0.3718022 0.9571679 0.3711671 0.9567952 0.3718022 0.9569818 0.3714848 0.9571679 0.3711671 0.9571679 0.3711671 0.9573535 0.3708492 0.9575386 0.370531 0.9575386 0.370531 0.9577233 0.3702125 0.9579074 0.3698937 0.9579074 0.3698937 0.9580911 0.3695746 0.9586392 0.3686158 0.9580911 0.3695746 0.9582743 0.3692553 0.9586392 0.3686158 0.9582743 0.3692553 0.958457 0.3689357 0.9586392 0.3686158 0.9586392 0.3686158 0.9588209 0.3682956 0.9590021 0.3679751 0.9590021 0.3679751 0.9591828 0.3676543 0.9593631 0.3673334 0.9593631 0.3673334 0.9595428 0.367012 0.9597221 0.3666905 0.9597221 0.3666905 0.9599008 0.3663686 0.9600791 0.3660465 0.9600791 0.3660465 0.9602568 0.3657241 0.9604341 0.3654015 0.9604341 0.3654015 0.9606109 0.3650785 0.9607872 0.3647553 0.9607872 0.3647553 0.960963 0.3644318 0.9611382 0.364108 0.9611382 0.364108 0.961313 0.363784 0.9614873 0.3634598 0.9614873 0.3634598 0.9616611 0.3631352 0.9621795 0.36216 0.9616611 0.3631352 0.9618344 0.3628104 0.9621795 0.36216 0.9618344 0.3628104 0.9620072 0.3624853 0.9621795 0.36216 0.9621795 0.36216 0.9623513 0.3618344 0.9625226 0.3615085 0.9625226 0.3615085 0.9626934 0.3611823 0.9628637 0.3608559 0.9628637 0.3608559 0.9630335 0.3605293 0.9632028 0.3602024 0.9632028 0.3602024 0.9633716 0.3598752 0.9635399 0.3595477 0.9635399 0.3595477 0.9637077 0.35922 0.963875 0.3588921 0.963875 0.3588921 0.9640418 0.3585639 0.9635399 0.3595477 0.9640418 0.3585639 0.9642081 0.3582354 0.9635399 0.3595477 0.9642081 0.3582354 0.9643738 0.3579067 0.9645391 0.3575778 0.9645391 0.3575778 0.9647039 0.3572485 0.9642081 0.3582354 0.9647039 0.3572485 0.9648681 0.3569191 0.9642081 0.3582354 0.9648681 0.3569191 0.9650319 0.3565893 0.9651951 0.3562594 0.9651951 0.3562594 0.9653579 0.3559291 0.9655202 0.3555986 0.9655202 0.3555986 0.9656819 0.3552679 0.9658431 0.3549369 0.9658431 0.3549369 0.9660038 0.3546057 0.966164 0.3542742 0.966164 0.3542742 0.9663237 0.3539425 0.9664829 0.3536105 0.9664829 0.3536105 0.9666416 0.3532783 0.9667997 0.3529459 0.9667997 0.3529459 0.9669575 0.3526132 0.9671146 0.3522803 0.9671146 0.3522803 0.9672712 0.3519471 0.9674274 0.3516137 0.9674274 0.3516137 0.967583 0.35128 0.9677381 0.3509462 0.9677381 0.3509462 0.9678927 0.3506121 0.9674274 0.3516137 0.9678927 0.3506121 0.9680467 0.3502777 0.9674274 0.3516137 0.9680467 0.3502777 0.9682003 0.3499431 0.9683534 0.3496083 0.9683534 0.3496083 0.9685059 0.3492732 0.9680467 0.3502777 0.9685059 0.3492732 0.968658 0.3489379 0.9680467 0.3502777 0.968658 0.3489379 0.9688094 0.3486024 0.9689604 0.3482666 0.9689604 0.3482666 0.9691109 0.3479306 0.9692609 0.3475944 0.9692609 0.3475944 0.9694103 0.3472579 0.9698556 0.3462471 0.9694103 0.3472579 0.9695593 0.3469212 0.9698556 0.3462471 0.9695593 0.3469212 0.9697077 0.3465843 0.9698556 0.3462471 0.9698556 0.3462471 0.970003 0.3459098 0.9701498 0.3455722 0.9701498 0.3455722 0.9702962 0.3452344 0.970442 0.3448964 0.970442 0.3448964 0.9705873 0.3445581 0.9707321 0.3442196 0.9707321 0.3442196 0.9708764 0.3438809 0.970442 0.3448964 0.9708764 0.3438809 0.9710201 0.3435419 0.970442 0.3448964 0.9710201 0.3435419 0.9711634 0.3432028 0.9713061 0.3428635 0.9713061 0.3428635 0.9714483 0.3425239 0.9715899 0.342184 0.9715899 0.342184 0.9717311 0.341844 0.9721514 0.3408226 0.9717311 0.341844 0.9718717 0.3415038 0.9721514 0.3408226 0.9718717 0.3415038 0.9720118 0.3411633 0.9721514 0.3408226 0.9721514 0.3408226 0.9722905 0.3404818 0.972429 0.3401407 0.972429 0.3401407 0.972567 0.3397994 0.9721514 0.3408226 0.972567 0.3397994 0.9727045 0.3394579 0.9721514 0.3408226 0.9727045 0.3394579 0.9728415 0.3391161 0.9729779 0.3387742 0.9729779 0.3387742 0.9731138 0.338432 0.9727045 0.3394579 0.9731138 0.338432 0.9732492 0.3380897 0.9727045 0.3394579 0.9732492 0.3380897 0.9733841 0.3377471 0.9735184 0.3374043 0.9735184 0.3374043 0.9736523 0.3370614 0.9737855 0.3367182 0.9737855 0.3367182 0.9739183 0.3363748 0.9740505 0.3360312 0.9740505 0.3360312 0.9741822 0.3356874 0.9737855 0.3367182 0.9741822 0.3356874 0.9743134 0.3353434 0.9737855 0.3367182 0.9743134 0.3353434 0.974444 0.3349993 0.9745742 0.3346549 0.9745742 0.3346549 0.9747037 0.3343102 0.9743134 0.3353434 0.9747037 0.3343102 0.9748328 0.3339655 0.9743134 0.3353434 0.9748328 0.3339655 0.9749614 0.3336205 0.9750894 0.3332753 0.9750894 0.3332753 0.9752169 0.3329299 0.9753438 0.3325843 0.9753438 0.3325843 0.9754702 0.3322386 0.9755961 0.3318926 0.9755961 0.3318926 0.9757215 0.3315464 0.9753438 0.3325843 0.9757215 0.3315464 0.9758463 0.3312001 0.9753438 0.3325843 0.9758463 0.3312001 0.9759706 0.3308536 0.9760944 0.3305068 0.9760944 0.3305068 0.9762176 0.3301599 0.9758463 0.3312001 0.9762176 0.3301599 0.9763402 0.3298128 0.9758463 0.3312001 0.9763402 0.3298128 0.9764624 0.3294655 0.9768257 0.3284225 0.9764624 0.3294655 0.9765841 0.329118 0.9768257 0.3284225 0.9765841 0.329118 0.9767051 0.3287703 0.9768257 0.3284225 0.9768257 0.3284225 0.9769458 0.3280745 0.9770653 0.3277263 0.9770653 0.3277263 0.9771842 0.3273779 0.9768257 0.3284225 0.9771842 0.3273779 0.9773027 0.3270292 0.9768257 0.3284225 0.9773027 0.3270292 0.9774206 0.3266805 0.9775379 0.3263316 0.9775379 0.3263316 0.9776547 0.3259824 0.9777711 0.3256331 0.9777711 0.3256331 0.9778867 0.3252836 0.978002 0.324934 0.978002 0.324934 0.9781166 0.3245841 0.9782308 0.3242341 0.9782308 0.3242341 0.9783444 0.3238839 0.9784575 0.3235335 0.9784575 0.3235335 0.97857 0.323183 0.9782308 0.3242341 0.97857 0.323183 0.978682 0.3228323 0.9782308 0.3242341 0.978682 0.3228323 0.9787935 0.3224814 0.9791246 0.3214278 0.9787935 0.3224814 0.9789044 0.3221304 0.9791246 0.3214278 0.9789044 0.3221304 0.9790148 0.3217791 0.9791246 0.3214278 0.9791246 0.3214278 0.9792339 0.3210762 0.9793426 0.3207245 0.9793426 0.3207245 0.9794509 0.3203726 0.9795585 0.3200206 0.9795585 0.3200206 0.9796657 0.3196683 0.9797723 0.3193159 0.9797723 0.3193159 0.9798783 0.3189634 0.9799839 0.3186107 0.9799839 0.3186107 0.9800888 0.3182578 0.9804005 0.3171982 0.9800888 0.3182578 0.9801933 0.3179048 0.9804005 0.3171982 0.9801933 0.3179048 0.9802972 0.3175516 0.9804005 0.3171982 0.9804005 0.3171982 0.9805033 0.3168447 0.9806056 0.3164911 0.9806056 0.3164911 0.9807073 0.3161373 0.9804005 0.3171982 0.9807073 0.3161373 0.9808085 0.3157833 0.9804005 0.3171982 0.9808085 0.3157833 0.9809091 0.3154291 0.9810093 0.3150748 0.9810093 0.3150748 0.9811088 0.3147204 0.9808085 0.3157833 0.9811088 0.3147204 0.9812078 0.3143658 0.9808085 0.3157833 0.9812078 0.3143658 0.9813063 0.314011 0.9814042 0.3136562 0.9814042 0.3136562 0.9815015 0.3133011 0.9812078 0.3143658 0.9815015 0.3133011 0.9815984 0.3129459 0.9812078 0.3143658 0.9815984 0.3129459 0.9816946 0.3125906 0.9817904 0.3122351 0.9817904 0.3122351 0.9818856 0.3118795 0.9815984 0.3129459 0.9818856 0.3118795 0.9819803 0.3115237 0.9815984 0.3129459 0.9819803 0.3115237 0.9820744 0.3111678 0.9821679 0.3108117 0.9821679 0.3108117 0.982261 0.3104555 0.9823534 0.3100991 0.9823534 0.3100991 0.9824453 0.3097426 0.9827178 0.3086723 0.9824453 0.3097426 0.9825367 0.309386 0.9827178 0.3086723 0.9825367 0.309386 0.9826275 0.3090292 0.9827178 0.3086723 0.9827178 0.3086723 0.9828075 0.3083152 0.9828967 0.3079581 0.9828967 0.3079581 0.9829853 0.3076007 0.9830734 0.3072432 0.9830734 0.3072432 0.9831609 0.3068857 0.9832479 0.3065279 0.9832479 0.3065279 0.9833344 0.3061701 0.9834203 0.3058121 0.9834203 0.3058121 0.9835056 0.305454 0.9835904 0.3050957 0.9835904 0.3050957 0.9836747 0.3047373 0.9837583 0.3043788 0.9837583 0.3043788 0.9838414 0.3040201 0.9840876 0.3029434 0.9838414 0.3040201 0.983924 0.3036614 0.9840876 0.3029434 0.983924 0.3036614 0.9840061 0.3033025 0.9840876 0.3029434 0.9840876 0.3029434 0.9841685 0.3025843 0.984408 0.3015061 0.9841685 0.3025843 0.9842489 0.302225 0.984408 0.3015061 0.9842489 0.302225 0.9843288 0.3018656 0.984408 0.3015061 0.984408 0.3015061 0.9844868 0.3011465 0.9845649 0.3007867 0.9845649 0.3007867 0.9846426 0.3004269 0.9847196 0.3000668 0.9847196 0.3000668 0.9847962 0.2997067 0.9848722 0.2993465 0.9848722 0.2993465 0.9849476 0.2989861 0.9847196 0.3000668 0.9849476 0.2989861 0.9850224 0.2986257 0.9847196 0.3000668 0.9850224 0.2986257 0.9850968 0.2982651 0.9851705 0.2979044 0.9851705 0.2979044 0.9852437 0.2975436 0.9850224 0.2986257 0.9852437 0.2975436 0.9853163 0.2971827 0.9850224 0.2986257 0.9853163 0.2971827 0.9853885 0.2968217 0.9856014 0.2957379 0.9853885 0.2968217 0.9854601 0.2964605 0.9856014 0.2957379 0.9854601 0.2964605 0.985531 0.2960993 0.9856014 0.2957379 0.9856014 0.2957379 0.9856714 0.2953765 0.9857407 0.2950149 0.9857407 0.2950149 0.9858095 0.2946532 0.9858776 0.2942914 0.9858776 0.2942914 0.9859454 0.2939296 0.9860124 0.2935676 0.9860124 0.2935676 0.986079 0.2932055 0.986145 0.2928433 0.986145 0.2928433 0.9862104 0.292481 0.9862753 0.2921186 0.9862753 0.2921186 0.9863396 0.2917561 0.9864034 0.2913935 0.9864034 0.2913935 0.9864667 0.2910308 0.9865293 0.2906681 0.9865293 0.2906681 0.9865914 0.2903052 0.986653 0.2899422 0.986653 0.2899422 0.986714 0.2895792 0.9867744 0.289216 0.9867744 0.289216 0.9868342 0.2888527 0.986653 0.2899422 0.9868342 0.2888527 0.9868935 0.2884894 0.986653 0.2899422 0.9868935 0.2884894 0.9869523 0.2881259 0.9870105 0.2877624 0.9870105 0.2877624 0.9870682 0.2873988 0.9871253 0.2870351 0.9871253 0.2870351 0.9871818 0.2866714 0.9872378 0.2863075 0.9872378 0.2863075 0.9872932 0.2859435 0.9871253 0.2870351 0.9872932 0.2859435 0.9873481 0.2855795 0.9871253 0.2870351 0.9873481 0.2855795 0.9874024 0.2852153 0.9874561 0.2848511 0.9874561 0.2848511 0.9875093 0.2844868 0.9873481 0.2855795 0.9875093 0.2844868 0.9875619 0.2841224 0.9873481 0.2855795 0.9875619 0.2841224 0.987614 0.283758 0.9877668 0.2826641 0.987614 0.283758 0.9876655 0.2833935 0.9877668 0.2826641 0.9876655 0.2833935 0.9877164 0.2830289 0.9877668 0.2826641 0.9877668 0.2826641 0.9878166 0.2822993 0.9878659 0.2819345 0.9878659 0.2819345 0.9879146 0.2815696 0.9877668 0.2826641 0.9879146 0.2815696 0.9879627 0.2812046 0.9877668 0.2826641 0.9879627 0.2812046 0.9880104 0.2808396 0.9880574 0.2804744 0.9880574 0.2804744 0.9881038 0.2801092 0.9879627 0.2812046 0.9881038 0.2801092 0.9881498 0.2797439 0.9879627 0.2812046 0.9881498 0.2797439 0.9881951 0.2793785 0.9882399 0.2790132 0.9882399 0.2790132 0.9882841 0.2786477 0.9883278 0.2782821 0.9883278 0.2782821 0.9883708 0.2779164 0.9884134 0.2775508 0.9884134 0.2775508 0.9884554 0.277185 0.9883278 0.2782821 0.9884554 0.277185 0.9884968 0.2768192 0.9883278 0.2782821 0.9884968 0.2768192 0.9885377 0.2764533 0.9886569 0.2753553 0.9885377 0.2764533 0.988578 0.2760874 0.9886569 0.2753553 0.988578 0.2760874 0.9886177 0.2757214 0.9886569 0.2753553 0.9886569 0.2753553 0.9886955 0.2749892 0.9887335 0.274623 0.9887335 0.274623 0.988771 0.2742568 0.9886569 0.2753553 0.988771 0.2742568 0.988808 0.2738904 0.9886569 0.2753553 0.988808 0.2738904 0.9888443 0.2735241 0.9889501 0.2724247 0.9888443 0.2735241 0.9888802 0.2731577 0.9889501 0.2724247 0.9888802 0.2731577 0.9889154 0.2727912 0.9889501 0.2724247 0.9889501 0.2724247 0.9889842 0.2720581 0.9890832 0.2709581 0.9889842 0.2720581 0.9890177 0.2716915 0.9890832 0.2709581 0.9890177 0.2716915 0.9890508 0.2713248 0.9890832 0.2709581 0.9890832 0.2709581 0.989115 0.2705913 0.9891464 0.2702245 0.9891464 0.2702245 0.9891771 0.2698577 0.9890832 0.2709581 0.9891771 0.2698577 0.9892073 0.2694907 0.9890832 0.2709581 0.9892073 0.2694907 0.9892368 0.2691238 0.9892659 0.2687568 0.9892659 0.2687568 0.9892944 0.2683897 0.9893223 0.2680226 0.9893223 0.2680226 0.9893497 0.2676555 0.9893765 0.2672883 0.9893765 0.2672883 0.9894028 0.2669211 0.9893223 0.2680226 0.9894028 0.2669211 0.9894284 0.2665538 0.9893223 0.2680226 0.9894284 0.2665538 0.9894536 0.2661865 0.9894781 0.2658192 0.9894781 0.2658192 0.9895021 0.2654518 0.9895255 0.2650844 0.9895255 0.2650844 0.9895483 0.264717 0.9896135 0.2636144 0.9895483 0.264717 0.9895706 0.2643495 0.9896135 0.2636144 0.9895706 0.2643495 0.9895924 0.263982 0.9896135 0.2636144 0.9896135 0.2636144 0.9896342 0.2632468 0.9896542 0.2628793 0.9896542 0.2628793 0.9896737 0.2625116 0.9896926 0.2621439 0.9896926 0.2621439 0.9897109 0.2617762 0.9897626 0.260673 0.9897109 0.2617762 0.9897287 0.2614085 0.9897626 0.260673 0.9897287 0.2614085 0.9897459 0.2610408 0.9897626 0.260673 0.9897626 0.260673 0.9897786 0.2603052 0.9897942 0.2599374 0.9897942 0.2599374 0.9898092 0.2595695 0.9897626 0.260673 0.9898092 0.2595695 0.9898235 0.2592016 0.9897626 0.260673 0.9898235 0.2592016 0.9898374 0.2588337 0.9898755 0.2577299 0.9898374 0.2588337 0.9898506 0.2584658 0.9898755 0.2577299 0.9898506 0.2584658 0.9898633 0.2580979 0.9898755 0.2577299 0.9898755 0.2577299 0.9898871 0.257362 0.9898981 0.256994 0.9898981 0.256994 0.9899085 0.256626 0.9898755 0.2577299 0.9899085 0.256626 0.9899184 0.2562579 0.9898755 0.2577299 0.9899184 0.2562579 0.9899277 0.2558899 0.9899365 0.2555218 0.9899365 0.2555218 0.9899446 0.2551538 0.9899184 0.2562579 0.9899446 0.2551538 0.9899523 0.2547857 0.9899184 0.2562579 0.9899523 0.2547857 0.9899594 0.2544176 0.9899659 0.2540495 0.9899659 0.2540495 0.9899718 0.2536814 0.9899523 0.2547857 0.9899718 0.2536814 0.9899771 0.2533133 0.9899523 0.2547857 0.9899771 0.2533133 0.989982 0.2529451 0.9899862 0.252577 0.9899862 0.252577 0.9899898 0.2522089 0.9899771 0.2533133 0.9899898 0.2522089 0.989993 0.2518408 0.9899771 0.2533133 0.989993 0.2518408 0.9899955 0.2514726 0.9899975 0.2511045 0.9899975 0.2511045 0.9899989 0.2507363 0.9899997 0.2503681 0.9899997 0.2503681 0.99 0.25 0.9899997 0.2496318 0.9899997 0.2496318 0.9899989 0.2492637 0.9899975 0.2488955 0.9899975 0.2488955 0.9899955 0.2485274 0.989993 0.2481592 0.989993 0.2481592 0.9899898 0.2477911 0.9899975 0.2488955 0.9899898 0.2477911 0.9899862 0.2474229 0.9899975 0.2488955 0.9899862 0.2474229 0.989982 0.2470548 0.9899771 0.2466867 0.9899771 0.2466867 0.9899718 0.2463186 0.9899659 0.2459505 0.9899659 0.2459505 0.9899594 0.2455824 0.9899523 0.2452143 0.9899523 0.2452143 0.9899446 0.2448462 0.9899659 0.2459505 0.9899446 0.2448462 0.9899365 0.2444781 0.9899659 0.2459505 0.9899365 0.2444781 0.9899277 0.2441101 0.9898981 0.243006 0.9899277 0.2441101 0.9899184 0.2437421 0.9898981 0.243006 0.9899184 0.2437421 0.9899085 0.243374 0.9898981 0.243006 0.9898981 0.243006 0.9898871 0.242638 0.9898506 0.2415342 0.9898871 0.242638 0.9898755 0.2422701 0.9898506 0.2415342 0.9898755 0.2422701 0.9898633 0.2419021 0.9898506 0.2415342 0.9898506 0.2415342 0.9898374 0.2411662 0.9897942 0.2400626 0.9898374 0.2411662 0.9898235 0.2407984 0.9897942 0.2400626 0.9898235 0.2407984 0.9898092 0.2404305 0.9897942 0.2400626 0.9897942 0.2400626 0.9897786 0.2396948 0.9897626 0.239327 0.9897626 0.239327 0.9897459 0.2389592 0.9897287 0.2385914 0.9897287 0.2385914 0.9897109 0.2382237 0.9896542 0.2371207 0.9897109 0.2382237 0.9896926 0.237856 0.9896542 0.2371207 0.9896926 0.237856 0.9896737 0.2374883 0.9896542 0.2371207 0.9896542 0.2371207 0.9896342 0.2367531 0.9896135 0.2363855 0.9896135 0.2363855 0.9895924 0.236018 0.9895706 0.2356505 0.9895706 0.2356505 0.9895483 0.235283 0.9894781 0.2341808 0.9895483 0.235283 0.9895255 0.2349156 0.9894781 0.2341808 0.9895255 0.2349156 0.9895021 0.2345482 0.9894781 0.2341808 0.9894781 0.2341808 0.9894536 0.2338134 0.9893765 0.2327117 0.9894536 0.2338134 0.9894284 0.2334461 0.9893765 0.2327117 0.9894284 0.2334461 0.9894028 0.2330788 0.9893765 0.2327117 0.9893765 0.2327117 0.9893497 0.2323445 0.9893223 0.2319774 0.9893223 0.2319774 0.9892944 0.2316102 0.9892659 0.2312432 0.9892659 0.2312432 0.9892368 0.2308762 0.9891464 0.2297754 0.9892368 0.2308762 0.9892073 0.2305092 0.9891464 0.2297754 0.9892073 0.2305092 0.9891771 0.2301423 0.9891464 0.2297754 0.9891464 0.2297754 0.989115 0.2294086 0.9890832 0.2290418 0.9890832 0.2290418 0.9890508 0.2286751 0.9890177 0.2283084 0.9890177 0.2283084 0.9889842 0.2279418 0.9888802 0.2268423 0.9889842 0.2279418 0.9889501 0.2275753 0.9888802 0.2268423 0.9889501 0.2275753 0.9889154 0.2272087 0.9888802 0.2268423 0.9888802 0.2268423 0.9888443 0.2264758 0.988808 0.2261095 0.988808 0.2261095 0.988771 0.2257432 0.9888802 0.2268423 0.988771 0.2257432 0.9887335 0.225377 0.9888802 0.2268423 0.9887335 0.225377 0.9886955 0.2250108 0.9886569 0.2246447 0.9886569 0.2246447 0.9886177 0.2242786 0.988578 0.2239126 0.988578 0.2239126 0.9885377 0.2235466 0.9884134 0.2224492 0.9885377 0.2235466 0.9884968 0.2231808 0.9884134 0.2224492 0.9884968 0.2231808 0.9884554 0.2228149 0.9884134 0.2224492 0.9884134 0.2224492 0.9883708 0.2220835 0.9882399 0.2209869 0.9883708 0.2220835 0.9883278 0.2217179 0.9882399 0.2209869 0.9883278 0.2217179 0.9882841 0.2213523 0.9882399 0.2209869 0.9882399 0.2209869 0.9881951 0.2206214 0.9881498 0.220256 0.9881498 0.220256 0.9881038 0.2198908 0.9882399 0.2209869 0.9881038 0.2198908 0.9880574 0.2195256 0.9882399 0.2209869 0.9880574 0.2195256 0.9880104 0.2191604 0.9879627 0.2187954 0.9879627 0.2187954 0.9879146 0.2184303 0.9880574 0.2195256 0.9879146 0.2184303 0.9878659 0.2180655 0.9880574 0.2195256 0.9878659 0.2180655 0.9878166 0.2177006 0.9877668 0.2173358 0.9877668 0.2173358 0.9877164 0.2169712 0.9876655 0.2166065 0.9876655 0.2166065 0.987614 0.216242 0.9874561 0.2151489 0.987614 0.216242 0.9875619 0.2158775 0.9874561 0.2151489 0.9875619 0.2158775 0.9875093 0.2155132 0.9874561 0.2151489 0.9874561 0.2151489 0.9874024 0.2147846 0.9873481 0.2144205 0.9873481 0.2144205 0.9872932 0.2140565 0.9872378 0.2136925 0.9872378 0.2136925 0.9871818 0.2133287 0.9870105 0.2122375 0.9871818 0.2133287 0.9871253 0.2129648 0.9870105 0.2122375 0.9871253 0.2129648 0.9870682 0.2126011 0.9870105 0.2122375 0.9870105 0.2122375 0.9869523 0.211874 0.9868935 0.2115106 0.9868935 0.2115106 0.9868342 0.2111473 0.9867744 0.210784 0.9867744 0.210784 0.986714 0.2104208 0.986653 0.2100577 0.986653 0.2100577 0.9865914 0.2096948 0.9865293 0.2093319 0.9865293 0.2093319 0.9864667 0.2089691 0.9864034 0.2086064 0.9864034 0.2086064 0.9863396 0.2082439 0.9865293 0.2093319 0.9863396 0.2082439 0.9862753 0.2078813 0.9865293 0.2093319 0.9862753 0.2078813 0.9862104 0.2075189 0.9860124 0.2064324 0.9862104 0.2075189 0.986145 0.2071567 0.9860124 0.2064324 0.986145 0.2071567 0.986079 0.2067945 0.9860124 0.2064324 0.9860124 0.2064324 0.9859454 0.2060704 0.9857407 0.2049851 0.9859454 0.2060704 0.9858776 0.2057085 0.9857407 0.2049851 0.9858776 0.2057085 0.9858095 0.2053467 0.9857407 0.2049851 0.9857407 0.2049851 0.9856714 0.2046235 0.9856014 0.204262 0.9856014 0.204262 0.985531 0.2039006 0.9854601 0.2035394 0.9854601 0.2035394 0.9853885 0.2031783 0.9853163 0.2028173 0.9853163 0.2028173 0.9852437 0.2024564 0.9851705 0.2020956 0.9851705 0.2020956 0.9850968 0.2017349 0.9850224 0.2013743 0.9850224 0.2013743 0.9849476 0.2010138 0.9851705 0.2020956 0.9849476 0.2010138 0.9848722 0.2006534 0.9851705 0.2020956 0.9848722 0.2006534 0.9847962 0.2002933 0.9847196 0.1999331 0.9847196 0.1999331 0.9846426 0.1995731 0.9845649 0.1992133 0.9845649 0.1992133 0.9844868 0.1988535 0.984408 0.1984938 0.984408 0.1984938 0.9843288 0.1981343 0.9842489 0.197775 0.9842489 0.197775 0.9841685 0.1974157 0.9840876 0.1970565 0.9840876 0.1970565 0.9840061 0.1966975 0.983924 0.1963386 0.983924 0.1963386 0.9838414 0.1959798 0.9835904 0.1949043 0.9838414 0.1959798 0.9837583 0.1956212 0.9835904 0.1949043 0.9837583 0.1956212 0.9836747 0.1952627 0.9835904 0.1949043 0.9835904 0.1949043 0.9835056 0.194546 0.9834203 0.1941879 0.9834203 0.1941879 0.9833344 0.1938299 0.9832479 0.193472 0.9832479 0.193472 0.9831609 0.1931143 0.9830734 0.1927567 0.9830734 0.1927567 0.9829853 0.1923993 0.9828967 0.1920419 0.9828967 0.1920419 0.9828075 0.1916847 0.9827178 0.1913277 0.9827178 0.1913277 0.9826275 0.1909708 0.9825367 0.190614 0.9825367 0.190614 0.9824453 0.1902573 0.9821679 0.1891883 0.9824453 0.1902573 0.9823534 0.1899008 0.9821679 0.1891883 0.9823534 0.1899008 0.982261 0.1895445 0.9821679 0.1891883 0.9821679 0.1891883 0.9820744 0.1888322 0.9819803 0.1884763 0.9819803 0.1884763 0.9818856 0.1881205 0.9821679 0.1891883 0.9818856 0.1881205 0.9817904 0.1877649 0.9821679 0.1891883 0.9817904 0.1877649 0.9816946 0.1874094 0.9815984 0.187054 0.9815984 0.187054 0.9815015 0.1866989 0.9814042 0.1863438 0.9814042 0.1863438 0.9813063 0.1859889 0.9812078 0.1856341 0.9812078 0.1856341 0.9811088 0.1852796 0.9810093 0.1849251 0.9810093 0.1849251 0.9809091 0.1845709 0.9808085 0.1842167 0.9808085 0.1842167 0.9807073 0.1838628 0.9806056 0.1835089 0.9806056 0.1835089 0.9805033 0.1831552 0.9804005 0.1828017 0.9804005 0.1828017 0.9802972 0.1824484 0.9801933 0.1820952 0.9801933 0.1820952 0.9800888 0.1817421 0.9797723 0.180684 0.9800888 0.1817421 0.9799839 0.1813893 0.9797723 0.180684 0.9799839 0.1813893 0.9798783 0.1810365 0.9797723 0.180684 0.9797723 0.180684 0.9796657 0.1803317 0.9795585 0.1799794 0.9795585 0.1799794 0.9794509 0.1796274 0.9793426 0.1792755 0.9793426 0.1792755 0.9792339 0.1789237 0.9791246 0.1785722 0.9791246 0.1785722 0.9790148 0.1782208 0.9789044 0.1778696 0.9789044 0.1778696 0.9787935 0.1775186 0.9784575 0.1764664 0.9787935 0.1775186 0.978682 0.1771677 0.9784575 0.1764664 0.978682 0.1771677 0.97857 0.1768169 0.9784575 0.1764664 0.9784575 0.1764664 0.9783444 0.1761161 0.9782308 0.1757659 0.9782308 0.1757659 0.9781166 0.1754159 0.978002 0.175066 0.978002 0.175066 0.9778867 0.1747164 0.9775379 0.1736685 0.9778867 0.1747164 0.9777711 0.1743668 0.9775379 0.1736685 0.9777711 0.1743668 0.9776547 0.1740176 0.9775379 0.1736685 0.9775379 0.1736685 0.9774206 0.1733195 0.9770653 0.1722737 0.9774206 0.1733195 0.9773027 0.1729707 0.9770653 0.1722737 0.9773027 0.1729707 0.9771842 0.1726222 0.9770653 0.1722737 0.9770653 0.1722737 0.9769458 0.1719255 0.9768257 0.1715775 0.9768257 0.1715775 0.9767051 0.1712296 0.9765841 0.1708819 0.9765841 0.1708819 0.9764624 0.1705344 0.9760944 0.1694931 0.9764624 0.1705344 0.9763402 0.1701872 0.9760944 0.1694931 0.9763402 0.1701872 0.9762176 0.16984 0.9760944 0.1694931 0.9760944 0.1694931 0.9759706 0.1691464 0.9758463 0.1687999 0.9758463 0.1687999 0.9757215 0.1684535 0.9755961 0.1681073 0.9755961 0.1681073 0.9754702 0.1677614 0.9750894 0.1667247 0.9754702 0.1677614 0.9753438 0.1674156 0.9750894 0.1667247 0.9753438 0.1674156 0.9752169 0.16707 0.9750894 0.1667247 0.9750894 0.1667247 0.9749614 0.1663795 0.9748328 0.1660345 0.9748328 0.1660345 0.9747037 0.1656897 0.9750894 0.1667247 0.9747037 0.1656897 0.9745742 0.1653451 0.9750894 0.1667247 0.9745742 0.1653451 0.974444 0.1650007 0.9743134 0.1646565 0.9743134 0.1646565 0.9741822 0.1643126 0.9740505 0.1639688 0.9740505 0.1639688 0.9739183 0.1636251 0.9737855 0.1632818 0.9737855 0.1632818 0.9736523 0.1629386 0.9735184 0.1625956 0.9735184 0.1625956 0.9733841 0.1622529 0.9732492 0.1619103 0.9732492 0.1619103 0.9731138 0.1615679 0.9729779 0.1612258 0.9729779 0.1612258 0.9728415 0.1608839 0.9727045 0.1605421 0.9727045 0.1605421 0.972567 0.1602006 0.9729779 0.1612258 0.972567 0.1602006 0.972429 0.1598593 0.9729779 0.1612258 0.972429 0.1598593 0.9722905 0.1595182 0.9721514 0.1591773 0.9721514 0.1591773 0.9720118 0.1588367 0.9718717 0.1584962 0.9718717 0.1584962 0.9717311 0.1581559 0.9715899 0.1578159 0.9715899 0.1578159 0.9714483 0.1574761 0.9713061 0.1571365 0.9713061 0.1571365 0.9711634 0.1567972 0.9710201 0.156458 0.9710201 0.156458 0.9708764 0.1561191 0.9713061 0.1571365 0.9708764 0.1561191 0.9707321 0.1557804 0.9713061 0.1571365 0.9707321 0.1557804 0.9705873 0.1554419 0.970442 0.1551036 0.970442 0.1551036 0.9702962 0.1547656 0.9707321 0.1557804 0.9702962 0.1547656 0.9701498 0.1544278 0.9707321 0.1557804 0.9701498 0.1544278 0.970003 0.1540902 0.9698556 0.1537528 0.9698556 0.1537528 0.9697077 0.1534156 0.9701498 0.1544278 0.9697077 0.1534156 0.9695593 0.1530787 0.9701498 0.1544278 0.9695593 0.1530787 0.9694103 0.152742 0.9689604 0.1517333 0.9694103 0.152742 0.9692609 0.1524056 0.9689604 0.1517333 0.9692609 0.1524056 0.9691109 0.1520694 0.9689604 0.1517333 0.9689604 0.1517333 0.9688094 0.1513976 0.968658 0.1510621 0.968658 0.1510621 0.9685059 0.1507267 0.9689604 0.1517333 0.9685059 0.1507267 0.9683534 0.1503917 0.9689604 0.1517333 0.9683534 0.1503917 0.9682003 0.1500568 0.9680467 0.1497223 0.9680467 0.1497223 0.9678927 0.1493879 0.9677381 0.1490538 0.9677381 0.1490538 0.967583 0.1487199 0.9674274 0.1483862 0.9674274 0.1483862 0.9672712 0.1480528 0.9671146 0.1477197 0.9671146 0.1477197 0.9669575 0.1473867 0.9667997 0.1470541 0.9667997 0.1470541 0.9666416 0.1467216 0.9664829 0.1463894 0.9664829 0.1463894 0.9663237 0.1460574 0.966164 0.1457257 0.966164 0.1457257 0.9660038 0.1453943 0.9658431 0.1450631 0.9658431 0.1450631 0.9656819 0.1447321 0.9655202 0.1444013 0.9655202 0.1444013 0.9653579 0.1440709 0.9658431 0.1450631 0.9653579 0.1440709 0.9651951 0.1437407 0.9658431 0.1450631 0.9651951 0.1437407 0.9650319 0.1434106 0.9648681 0.1430809 0.9648681 0.1430809 0.9647039 0.1427515 0.9651951 0.1437407 0.9647039 0.1427515 0.9645391 0.1424222 0.9651951 0.1437407 0.9645391 0.1424222 0.9643738 0.1420933 0.9642081 0.1417645 0.9642081 0.1417645 0.9640418 0.1414361 0.963875 0.1411079 0.963875 0.1411079 0.9637077 0.1407799 0.9635399 0.1404522 0.9635399 0.1404522 0.9633716 0.1401247 0.9632028 0.1397976 0.9632028 0.1397976 0.9630335 0.1394707 0.9628637 0.139144 0.9628637 0.139144 0.9626934 0.1388176 0.9625226 0.1384915 0.9625226 0.1384915 0.9623513 0.1381656 0.9621795 0.13784 0.9621795 0.13784 0.9620072 0.1375147 0.9625226 0.1384915 0.9620072 0.1375147 0.9618344 0.1371896 0.9625226 0.1384915 0.9618344 0.1371896 0.9616611 0.1368647 0.9611382 0.1358919 0.9616611 0.1368647 0.9614873 0.1365402 0.9611382 0.1358919 0.9614873 0.1365402 0.961313 0.1362159 0.9611382 0.1358919 0.9611382 0.1358919 0.960963 0.1355682 0.9607872 0.1352447 0.9607872 0.1352447 0.9606109 0.1349215 0.9611382 0.1358919 0.9606109 0.1349215 0.9604341 0.1345986 0.9611382 0.1358919 0.9604341 0.1345986 0.9602568 0.1342759 0.9600791 0.1339535 0.9600791 0.1339535 0.9599008 0.1336314 0.9597221 0.1333095 0.9597221 0.1333095 0.9595428 0.1329879 0.9593631 0.1326667 0.9593631 0.1326667 0.9591828 0.1323456 0.9590021 0.1320249 0.9590021 0.1320249 0.9588209 0.1317044 0.9582743 0.1307446 0.9588209 0.1317044 0.9586392 0.1313842 0.9582743 0.1307446 0.9586392 0.1313842 0.958457 0.1310643 0.9582743 0.1307446 0.9582743 0.1307446 0.9580911 0.1304253 0.9575386 0.129469 0.9580911 0.1304253 0.9579074 0.1301063 0.9575386 0.129469 0.9579074 0.1301063 0.9577233 0.1297875 0.9575386 0.129469 0.9575386 0.129469 0.9573535 0.1291508 0.9567952 0.1281978 0.9573535 0.1291508 0.9571679 0.1288328 0.9567952 0.1281978 0.9571679 0.1288328 0.9569818 0.1285152 0.9567952 0.1281978 0.9567952 0.1281978 0.9566081 0.1278807 0.9564205 0.127564 0.9564205 0.127564 0.9562324 0.1272475 0.9560439 0.1269312 0.9560439 0.1269312 0.9558549 0.1266153 0.9556654 0.1262997 0.9556654 0.1262997 0.9554753 0.1259843 0.9552849 0.1256693 0.9552849 0.1256693 0.9550939 0.1253545 0.9549025 0.1250401 0.9549025 0.1250401 0.9547106 0.1247259 0.9552849 0.1256693 0.9547106 0.1247259 0.9545181 0.124412 0.9552849 0.1256693 0.9545181 0.124412 0.9543253 0.1240984 0.9541319 0.1237851 0.9541319 0.1237851 0.953938 0.1234722 0.9537437 0.1231595 0.9537437 0.1231595 0.9535489 0.1228471 0.9533536 0.122535 0.9533536 0.122535 0.9531578 0.1222232 0.9529616 0.1219117 0.9529616 0.1219117 0.9527649 0.1216006 0.9525676 0.1212897 0.9525676 0.1212897 0.95237 0.1209791 0.9521718 0.1206688 0.9521718 0.1206688 0.9519732 0.1203588 0.9517741 0.1200491 0.9517741 0.1200491 0.9515745 0.1197398 0.9521718 0.1206688 0.9515745 0.1197398 0.9513745 0.1194307 0.9521718 0.1206688 0.9513745 0.1194307 0.9511739 0.119122 0.9505695 0.1181976 0.9511739 0.119122 0.9509729 0.1188135 0.9505695 0.1181976 0.9509729 0.1188135 0.9507715 0.1185054 0.9505695 0.1181976 0.9505695 0.1181976 0.9503671 0.1178901 0.949757 0.1169694 0.9503671 0.1178901 0.9501642 0.1175829 0.949757 0.1169694 0.9501642 0.1175829 0.9499608 0.117276 0.949757 0.1169694 0.949757 0.1169694 0.9495527 0.1166631 0.9493479 0.1163572 0.9493479 0.1163572 0.9491427 0.1160515 0.949757 0.1169694 0.9491427 0.1160515 0.948937 0.1157462 0.949757 0.1169694 0.948937 0.1157462 0.9487308 0.1154412 0.9481095 0.1145281 0.9487308 0.1154412 0.9485242 0.1151365 0.9481095 0.1145281 0.9485242 0.1151365 0.9483171 0.1148321 0.9481095 0.1145281 0.9481095 0.1145281 0.9479014 0.1142243 0.9476929 0.1139209 0.9476929 0.1139209 0.947484 0.1136178 0.9481095 0.1145281 0.947484 0.1136178 0.9472745 0.1133151 0.9481095 0.1145281 0.9472745 0.1133151 0.9470646 0.1130126 0.9468542 0.1127105 0.9468542 0.1127105 0.9466434 0.1124086 0.9464321 0.1121072 0.9464321 0.1121072 0.9462203 0.111806 0.9460082 0.1115052 0.9460082 0.1115052 0.9457954 0.1112046 0.9464321 0.1121072 0.9457954 0.1112046 0.9455823 0.1109045 0.9464321 0.1121072 0.9455823 0.1109045 0.9453687 0.1106046 0.9451547 0.1103051 0.9451547 0.1103051 0.9449402 0.1100059 0.9447252 0.109707 0.9447252 0.109707 0.9445098 0.1094085 0.9442939 0.1091103 0.9442939 0.1091103 0.9440775 0.1088124 0.9447252 0.109707 0.9440775 0.1088124 0.9438607 0.1085149 0.9447252 0.109707 0.9438607 0.1085149 0.9436434 0.1082177 0.9434257 0.1079208 0.9434257 0.1079208 0.9432075 0.1076242 0.9438607 0.1085149 0.9432075 0.1076242 0.9429889 0.107328 0.9438607 0.1085149 0.9429889 0.107328 0.9427698 0.1070321 0.9425503 0.1067366 0.9425503 0.1067366 0.9423303 0.1064414 0.9421098 0.1061465 0.9421098 0.1061465 0.9418889 0.105852 0.9416676 0.1055578 0.9416676 0.1055578 0.9414458 0.105264 0.9421098 0.1061465 0.9414458 0.105264 0.9412236 0.1049705 0.9421098 0.1061465 0.9412236 0.1049705 0.9410009 0.1046773 0.9407777 0.1043845 0.9407777 0.1043845 0.9405542 0.104092 0.9412236 0.1049705 0.9405542 0.104092 0.94033 0.1037999 0.9412236 0.1049705 0.94033 0.1037999 0.9401056 0.1035081 0.9398806 0.1032167 0.9398806 0.1032167 0.9396553 0.1029255 0.94033 0.1037999 0.9396553 0.1029255 0.9394294 0.1026348 0.94033 0.1037999 0.9394294 0.1026348 0.9392032 0.1023444 0.9389764 0.1020543 0.9389764 0.1020543 0.9387493 0.1017646 0.9385216 0.1014752 0.9385216 0.1014752 0.9382936 0.1011862 0.9380651 0.1008976 0.9380651 0.1008976 0.9378362 0.1006093 0.9385216 0.1014752 0.9378362 0.1006093 0.9376068 0.1003213 0.9385216 0.1014752 0.9376068 0.1003213 0.9373769 0.1000337 0.9371467 0.09974646 0.9371467 0.09974646 0.936916 0.09945952 0.9366848 0.099173 0.9366848 0.099173 0.9364532 0.09888678 0.9362212 0.09860098 0.9362212 0.09860098 0.9359887 0.09831547 0.9366848 0.099173 0.9359887 0.09831547 0.9357559 0.09803032 0.9366848 0.099173 0.9357559 0.09803032 0.9355225 0.09774559 0.9352887 0.09746116 0.9352887 0.09746116 0.9350546 0.09717714 0.9357559 0.09803032 0.9350546 0.09717714 0.9348199 0.09689342 0.9357559 0.09803032 0.9348199 0.09689342 0.9345848 0.09661012 0.9343493 0.09632712 0.9343493 0.09632712 0.9341133 0.09604454 0.9338769 0.09576231 0.9338769 0.09576231 0.9336401 0.09548038 0.9329271 0.09463691 0.9336401 0.09548038 0.9334029 0.09519886 0.9329271 0.09463691 0.9334029 0.09519886 0.9331652 0.09491771 0.9329271 0.09463691 0.9329271 0.09463691 0.9326885 0.09435653 0.9324496 0.09407645 0.9324496 0.09407645 0.9322102 0.09379678 0.9319704 0.09351742 0.9319704 0.09351742 0.9317301 0.09323847 0.9314894 0.09295994 0.9314894 0.09295994 0.9312483 0.0926817 0.9310068 0.09240382 0.9310068 0.09240382 0.9307649 0.09212636 0.9305225 0.09184926 0.9305225 0.09184926 0.9302796 0.09157252 0.9310068 0.09240382 0.9302796 0.09157252 0.9300364 0.09129619 0.9310068 0.09240382 0.9300364 0.09129619 0.9297928 0.09102016 0.9295486 0.09074455 0.9295486 0.09074455 0.9293041 0.09046936 0.9290592 0.09019446 0.9290592 0.09019446 0.9288139 0.08991998 0.9285681 0.08964586 0.9285681 0.08964586 0.9283219 0.08937215 0.9280753 0.08909881 0.9280753 0.08909881 0.9278283 0.08882582 0.9275808 0.08855324 0.9275808 0.08855324 0.9273329 0.08828103 0.9280753 0.08909881 0.9273329 0.08828103 0.9270847 0.08800917 0.9280753 0.08909881 0.9270847 0.08800917 0.926836 0.08773773 0.9265869 0.08746665 0.9265869 0.08746665 0.9263374 0.08719593 0.9260874 0.08692568 0.9260874 0.08692568 0.925837 0.08665573 0.9255862 0.0863862 0.9255862 0.0863862 0.9253351 0.08611702 0.9250835 0.08584827 0.9250835 0.08584827 0.9248315 0.08557987 0.924579 0.08531188 0.924579 0.08531188 0.9243262 0.08504432 0.9250835 0.08584827 0.9243262 0.08504432 0.9240729 0.08477705 0.9250835 0.08584827 0.9240729 0.08477705 0.9238193 0.08451026 0.9235652 0.08424383 0.9235652 0.08424383 0.9233108 0.08397775 0.9230559 0.0837121 0.9230559 0.0837121 0.9228006 0.08344686 0.9220323 0.08265334 0.9228006 0.08344686 0.9225449 0.08318191 0.9220323 0.08265334 0.9225449 0.08318191 0.9222888 0.08291745 0.9220323 0.08265334 0.9220323 0.08265334 0.9217754 0.08238965 0.9210023 0.08160096 0.9217754 0.08238965 0.9215181 0.08212637 0.9210023 0.08160096 0.9215181 0.08212637 0.9212604 0.08186346 0.9210023 0.08160096 0.9210023 0.08160096 0.9207437 0.08133882 0.9204848 0.08107709 0.9204848 0.08107709 0.9202255 0.08081579 0.9199658 0.0805549 0.9199658 0.0805549 0.9197056 0.08029437 0.9194451 0.08003425 0.9194451 0.08003425 0.9191842 0.07977449 0.9199658 0.0805549 0.9191842 0.07977449 0.9189229 0.07951515 0.9199658 0.0805549 0.9189229 0.07951515 0.9186611 0.07925623 0.918399 0.07899773 0.918399 0.07899773 0.9181365 0.07873958 0.9178736 0.07848191 0.9178736 0.07848191 0.9176103 0.07822459 0.9173466 0.0779677 0.9173466 0.0779677 0.9170826 0.07771116 0.916818 0.0774551 0.916818 0.0774551 0.9165531 0.07719939 0.9157562 0.07643473 0.9165531 0.07719939 0.9162879 0.07694411 0.9157562 0.07643473 0.9162879 0.07694411 0.9160223 0.07668924 0.9157562 0.07643473 0.9157562 0.07643473 0.9154897 0.07618069 0.9152229 0.07592701 0.9152229 0.07592701 0.9149557 0.07567381 0.9157562 0.07643473 0.9149557 0.07567381 0.9146881 0.07542097 0.9157562 0.07643473 0.9146881 0.07542097 0.9144201 0.07516855 0.9136138 0.07441371 0.9144201 0.07516855 0.9141517 0.07491654 0.9136138 0.07441371 0.9141517 0.07491654 0.913883 0.07466495 0.9136138 0.07441371 0.9136138 0.07441371 0.9133443 0.07416296 0.9130743 0.07391262 0.9130743 0.07391262 0.912804 0.07366263 0.9125334 0.07341313 0.9125334 0.07341313 0.9122623 0.07316398 0.9119908 0.07291531 0.9119908 0.07291531 0.911719 0.072667 0.9125334 0.07341313 0.911719 0.072667 0.9114468 0.07241916 0.9125334 0.07341313 0.9114468 0.07241916 0.9111742 0.07217168 0.9109012 0.07192468 0.9109012 0.07192468 0.9106279 0.07167804 0.9103541 0.07143187 0.9103541 0.07143187 0.91008 0.07118612 0.9098055 0.07094079 0.9098055 0.07094079 0.9095306 0.07069581 0.9092554 0.07045131 0.9092554 0.07045131 0.9089798 0.07020723 0.9087038 0.06996357 0.9087038 0.06996357 0.9084275 0.06972038 0.9092554 0.07045131 0.9084275 0.06972038 0.9081507 0.06947755 0.9092554 0.07045131 0.9081507 0.06947755 0.9078736 0.06923514 0.9075961 0.06899321 0.9075961 0.06899321 0.9073183 0.06875163 0.9070401 0.06851053 0.9070401 0.06851053 0.9067615 0.06826984 0.9064825 0.06802958 0.9064825 0.06802958 0.9062032 0.06778979 0.9070401 0.06851053 0.9062032 0.06778979 0.9059235 0.06755036 0.9070401 0.06851053 0.9059235 0.06755036 0.9056435 0.0673114 0.9048011 0.0665971 0.9056435 0.0673114 0.905363 0.06707286 0.9048011 0.0665971 0.905363 0.06707286 0.9050822 0.06683474 0.9048011 0.0665971 0.9048011 0.0665971 0.9045196 0.06635981 0.9036728 0.0656507 0.9045196 0.06635981 0.9042377 0.066123 0.9036728 0.0656507 0.9042377 0.066123 0.9039555 0.06588661 0.9036728 0.0656507 0.9036728 0.0656507 0.9033899 0.0654152 0.9031066 0.06518012 0.9031066 0.06518012 0.9028229 0.06494545 0.9036728 0.0656507 0.9028229 0.06494545 0.9025388 0.06471127 0.9036728 0.0656507 0.9025388 0.06471127 0.9022544 0.0644775 0.9019696 0.06424415 0.9019696 0.06424415 0.9016845 0.06401121 0.901399 0.06377875 0.901399 0.06377875 0.9011132 0.06354677 0.9002535 0.06285333 0.9011132 0.06354677 0.900827 0.06331515 0.9002535 0.06285333 0.900827 0.06331515 0.9005404 0.063084 0.9002535 0.06285333 0.9002535 0.06285333 0.8999663 0.06262302 0.8996787 0.06239324 0.8996787 0.06239324 0.8993907 0.06216382 0.9002535 0.06285333 0.8993907 0.06216382 0.8991024 0.06193488 0.9002535 0.06285333 0.8991024 0.06193488 0.8988137 0.06170636 0.8985248 0.06147837 0.8985248 0.06147837 0.8982354 0.06125074 0.8979457 0.06102359 0.8979457 0.06102359 0.8976556 0.06079685 0.8973652 0.06057053 0.8973652 0.06057053 0.8970744 0.06034475 0.8979457 0.06102359 0.8970744 0.06034475 0.8967834 0.06011933 0.8979457 0.06102359 0.8967834 0.06011933 0.8964919 0.05989438 0.8956155 0.05922228 0.8964919 0.05989438 0.8962001 0.05966991 0.8956155 0.05922228 0.8962001 0.05966991 0.8959079 0.05944585 0.8956155 0.05922228 0.8956155 0.05922228 0.8953226 0.05899912 0.8950295 0.05877643 0.8950295 0.05877643 0.894736 0.05855417 0.8944422 0.05833238 0.8944422 0.05833238 0.894148 0.05811107 0.8932633 0.05744969 0.894148 0.05811107 0.8938534 0.05789011 0.8932633 0.05744969 0.8938534 0.05789011 0.8935586 0.05766969 0.8932633 0.05744969 0.8932633 0.05744969 0.8929678 0.05723017 0.892672 0.05701106 0.892672 0.05701106 0.8923758 0.05679249 0.8920792 0.05657428 0.8920792 0.05657428 0.8917824 0.05635654 0.8914851 0.05613929 0.8914851 0.05613929 0.8911876 0.0559225 0.8920792 0.05657428 0.8911876 0.0559225 0.8908897 0.05570614 0.8920792 0.05657428 0.8908897 0.05570614 0.8905915 0.05549025 0.890293 0.05527484 0.890293 0.05527484 0.8899941 0.05505985 0.8896949 0.05484533 0.8896949 0.05484533 0.8893954 0.05463129 0.8890955 0.05441766 0.8890955 0.05441766 0.8887953 0.05420452 0.8896949 0.05484533 0.8887953 0.05420452 0.8884948 0.05399185 0.8896949 0.05484533 0.8884948 0.05399185 0.888194 0.0537796 0.8878929 0.05356788 0.8878929 0.05356788 0.8875913 0.05335658 0.8884948 0.05399185 0.8875913 0.05335658 0.8872895 0.05314576 0.8884948 0.05399185 0.8872895 0.05314576 0.8869874 0.05293536 0.8866849 0.05272549 0.8866849 0.05272549 0.8863822 0.05251604 0.8872895 0.05314576 0.8863822 0.05251604 0.8860791 0.05230706 0.8872895 0.05314576 0.8860791 0.05230706 0.8857756 0.05209857 0.8854719 0.05189049 0.8854719 0.05189049 0.8851678 0.05168294 0.8848635 0.05147582 0.8848635 0.05147582 0.8845588 0.05126917 0.8842537 0.051063 0.8842537 0.051063 0.8839485 0.0508573 0.8848635 0.05147582 0.8839485 0.0508573 0.8836428 0.05065202 0.8848635 0.05147582 0.8836428 0.05065202 0.8833369 0.05044728 0.8824171 0.0498358 0.8833369 0.05044728 0.8830306 0.05024296 0.8824171 0.0498358 0.8830306 0.05024296 0.8827241 0.05003911 0.8824171 0.0498358 0.8824171 0.0498358 0.8821099 0.0496329 0.8818024 0.04943048 0.8818024 0.04943048 0.8814946 0.04922854 0.8811864 0.04902702 0.8811864 0.04902702 0.880878 0.04882603 0.8805692 0.04862552 0.8805692 0.04862552 0.8802602 0.04842549 0.8811864 0.04902702 0.8802602 0.04842549 0.8799508 0.04822587 0.8811864 0.04902702 0.8799508 0.04822587 0.8796412 0.0480268 0.8793312 0.04782813 0.8793312 0.04782813 0.8790209 0.04763001 0.8799508 0.04822587 0.8790209 0.04763001 0.8787103 0.04743236 0.8799508 0.04822587 0.8787103 0.04743236 0.8783994 0.04723513 0.877465 0.04664641 0.8783994 0.04723513 0.8780882 0.04703837 0.877465 0.04664641 0.8780882 0.04703837 0.8777768 0.04684215 0.877465 0.04664641 0.877465 0.04664641 0.8771529 0.04645109 0.8762148 0.04586809 0.8771529 0.04645109 0.8768405 0.0462563 0.8762148 0.04586809 0.8768405 0.0462563 0.8765278 0.04606193 0.8762148 0.04586809 0.8762148 0.04586809 0.8759015 0.04567474 0.8755879 0.04548186 0.8755879 0.04548186 0.8752741 0.04528945 0.8762148 0.04586809 0.8752741 0.04528945 0.8749599 0.04509752 0.8762148 0.04586809 0.8749599 0.04509752 0.8746455 0.04490607 0.8743306 0.0447151 0.8743306 0.0447151 0.8740156 0.04452461 0.8737003 0.04433465 0.8737003 0.04433465 0.8733847 0.0441451 0.8724361 0.04357951 0.8733847 0.0441451 0.8730688 0.0439561 0.8724361 0.04357951 0.8730688 0.0439561 0.8727526 0.04376757 0.8724361 0.04357951 0.8724361 0.04357951 0.8721193 0.04339194 0.8711672 0.04283213 0.8721193 0.04339194 0.8718022 0.04320484 0.8711672 0.04283213 0.8718022 0.04320484 0.8714848 0.04301822 0.8711672 0.04283213 0.8711672 0.04283213 0.8708492 0.04264652 0.870531 0.04246133 0.870531 0.04246133 0.8702125 0.04227674 0.8698937 0.04209256 0.8698937 0.04209256 0.8695747 0.04190886 0.8686158 0.04136079 0.8695747 0.04190886 0.8692553 0.04172569 0.8686158 0.04136079 0.8692553 0.04172569 0.8689357 0.041543 0.8686158 0.04136079 0.8686158 0.04136079 0.8682956 0.04117912 0.8679751 0.04099792 0.8679751 0.04099792 0.8676544 0.04081714 0.8673334 0.04063695 0.8673334 0.04063695 0.867012 0.04045718 0.8666905 0.04027795 0.8666905 0.04027795 0.8663686 0.0400992 0.8660465 0.03992092 0.8660465 0.03992092 0.8657241 0.03974318 0.8654015 0.03956592 0.8654015 0.03956592 0.8650785 0.03938913 0.8647553 0.03921282 0.8647553 0.03921282 0.8644318 0.03903704 0.8641081 0.03886175 0.8641081 0.03886175 0.8637841 0.03868699 0.8634598 0.0385127 0.8634598 0.0385127 0.8631352 0.03833889 0.86216 0.03782045 0.8631352 0.03833889 0.8628104 0.03816556 0.86216 0.03782045 0.8628104 0.03816556 0.8624853 0.03799277 0.86216 0.03782045 0.86216 0.03782045 0.8618344 0.03764867 0.8615085 0.03747737 0.8615085 0.03747737 0.8611823 0.03730654 0.8608559 0.03713625 0.8608559 0.03713625 0.8605293 0.03696644 0.8602024 0.03679716 0.8602024 0.03679716 0.8598752 0.03662836 0.8595477 0.0364601 0.8595477 0.0364601 0.85922 0.03629225 0.8588921 0.036125 0.8588921 0.036125 0.8585639 0.03595823 0.8595477 0.0364601 0.8585639 0.03595823 0.8582354 0.03579193 0.8595477 0.0364601 0.8582354 0.03579193 0.8579067 0.03562617 0.8575778 0.03546088 0.8575778 0.03546088 0.8572486 0.03529608 0.8582354 0.03579193 0.8572486 0.03529608 0.8569191 0.03513181 0.8582354 0.03579193 0.8569191 0.03513181 0.8565893 0.03496807 0.8562594 0.03480482 0.8562594 0.03480482 0.8559291 0.0346421 0.8555986 0.03447985 0.8555986 0.03447985 0.8552679 0.03431808 0.8549369 0.03415685 0.8549369 0.03415685 0.8546057 0.03399616 0.8542742 0.03383594 0.8542742 0.03383594 0.8539425 0.03367626 0.8536106 0.03351706 0.8536106 0.03351706 0.8532783 0.03335839 0.8529459 0.0332002 0.8529459 0.0332002 0.8526132 0.03304255 0.8522803 0.03288543 0.8522803 0.03288543 0.8519471 0.03272879 0.8516137 0.03257262 0.8516137 0.03257262 0.8512801 0.03241699 0.8509462 0.0322619 0.8509462 0.0322619 0.8506121 0.03210729 0.8516137 0.03257262 0.8506121 0.03210729 0.8502777 0.03195321 0.8516137 0.03257262 0.8502777 0.03195321 0.8499431 0.03179967 0.8496083 0.0316466 0.8496083 0.0316466 0.8492732 0.03149408 0.8502777 0.03195321 0.8492732 0.03149408 0.8489379 0.03134202 0.8502777 0.03195321 0.8489379 0.03134202 0.8486024 0.03119051 0.8482666 0.03103953 0.8482666 0.03103953 0.8479306 0.03088903 0.8475944 0.03073906 0.8475944 0.03073906 0.8472579 0.03058964 0.8462472 0.03014439 0.8472579 0.03058964 0.8469212 0.03044068 0.8462472 0.03014439 0.8469212 0.03044068 0.8465843 0.03029227 0.8462472 0.03014439 0.8462472 0.03014439 0.8459098 0.02999699 0.8455722 0.02985012 0.8455722 0.02985012 0.8452344 0.02970379 0.8448964 0.02955794 0.8448964 0.02955794 0.8445581 0.02941262 0.8442196 0.02926784 0.8442196 0.02926784 0.8438809 0.0291236 0.8448964 0.02955794 0.8438809 0.0291236 0.843542 0.02897983 0.8448964 0.02955794 0.843542 0.02897983 0.8432028 0.0288366 0.8428635 0.02869391 0.8428635 0.02869391 0.8425239 0.02855169 0.8421841 0.02841007 0.8421841 0.02841007 0.841844 0.02826887 0.8408226 0.0278486 0.841844 0.02826887 0.8415038 0.02812826 0.8408226 0.0278486 0.8415038 0.02812826 0.8411633 0.02798813 0.8408226 0.0278486 0.8408226 0.0278486 0.8404818 0.02770954 0.8401407 0.02757096 0.8401407 0.02757096 0.8397994 0.02743297 0.8408226 0.0278486 0.8397994 0.02743297 0.8394579 0.02729547 0.8408226 0.0278486 0.8394579 0.02729547 0.8391161 0.02715849 0.8387742 0.02702206 0.8387742 0.02702206 0.838432 0.02688616 0.8394579 0.02729547 0.838432 0.02688616 0.8380897 0.0267508 0.8394579 0.02729547 0.8380897 0.0267508 0.8377471 0.02661591 0.8374044 0.02648156 0.8374044 0.02648156 0.8370614 0.02634775 0.8367182 0.02621448 0.8367182 0.02621448 0.8363748 0.02608168 0.8360312 0.02594947 0.8360312 0.02594947 0.8356875 0.02581775 0.8367182 0.02621448 0.8356875 0.02581775 0.8353434 0.02568662 0.8367182 0.02621448 0.8353434 0.02568662 0.8349993 0.0255559 0.8346549 0.02542579 0.8346549 0.02542579 0.8343103 0.02529621 0.8353434 0.02568662 0.8343103 0.02529621 0.8339655 0.02516716 0.8353434 0.02568662 0.8339655 0.02516716 0.8336205 0.02503859 0.8332753 0.02491062 0.8332753 0.02491062 0.8329299 0.02478313 0.8325843 0.02465617 0.8325843 0.02465617 0.8322386 0.02452975 0.8318926 0.02440387 0.8318926 0.02440387 0.8315464 0.02427852 0.8325843 0.02465617 0.8315464 0.02427852 0.8312001 0.0241537 0.8325843 0.02465617 0.8312001 0.0241537 0.8308536 0.02402943 0.8305069 0.02390563 0.8305069 0.02390563 0.8301599 0.02378243 0.8312001 0.0241537 0.8301599 0.02378243 0.8298128 0.0236597 0.8312001 0.0241537 0.8298128 0.0236597 0.8294655 0.02353757 0.8284225 0.02317428 0.8294655 0.02353757 0.829118 0.02341592 0.8284225 0.02317428 0.829118 0.02341592 0.8287703 0.0232948 0.8284225 0.02317428 0.8284225 0.02317428 0.8280745 0.02305424 0.8277263 0.02293473 0.8277263 0.02293473 0.8273779 0.02281576 0.8284225 0.02317428 0.8273779 0.02281576 0.8270292 0.02269732 0.8284225 0.02317428 0.8270292 0.02269732 0.8266805 0.02257943 0.8263316 0.02246206 0.8263316 0.02246206 0.8259824 0.02234524 0.8256331 0.02222895 0.8256331 0.02222895 0.8252837 0.0221132 0.824934 0.02199798 0.824934 0.02199798 0.8245841 0.0218833 0.8242341 0.02176916 0.8242341 0.02176916 0.8238839 0.02165555 0.8235335 0.02154248 0.8235335 0.02154248 0.823183 0.02142995 0.8242341 0.02176916 0.823183 0.02142995 0.8228323 0.02131801 0.8242341 0.02176916 0.8228323 0.02131801 0.8224814 0.02120655 0.8214278 0.02087539 0.8224814 0.02120655 0.8221304 0.02109563 0.8214278 0.02087539 0.8221304 0.02109563 0.8217791 0.02098524 0.8214278 0.02087539 0.8214278 0.02087539 0.8210762 0.02076607 0.8207245 0.02065736 0.8207245 0.02065736 0.8203726 0.02054911 0.8200206 0.02044147 0.8200206 0.02044147 0.8196683 0.0203343 0.8193159 0.02022767 0.8193159 0.02022767 0.8189634 0.02012163 0.8186107 0.02001613 0.8186107 0.02001613 0.8182578 0.01991117 0.8171982 0.01959949 0.8182578 0.01991117 0.8179048 0.01980668 0.8171982 0.01959949 0.8179048 0.01980668 0.8175516 0.01970279 0.8171982 0.01959949 0.8171982 0.01959949 0.8168447 0.01949667 0.8164911 0.01939439 0.8164911 0.01939439 0.8161373 0.01929265 0.8171982 0.01959949 0.8161373 0.01929265 0.8157833 0.0191915 0.8171982 0.01959949 0.8157833 0.0191915 0.8154292 0.01909083 0.8150749 0.01899075 0.8150749 0.01899075 0.8147204 0.01889121 0.8157833 0.0191915 0.8147204 0.01889121 0.8143658 0.01879221 0.8157833 0.0191915 0.8143658 0.01879221 0.8140111 0.01869374 0.8136562 0.01859581 0.8136562 0.01859581 0.8133012 0.01849842 0.8143658 0.01879221 0.8133012 0.01849842 0.812946 0.01840162 0.8143658 0.01879221 0.812946 0.01840162 0.8125906 0.0183053 0.8122351 0.01820957 0.8122351 0.01820957 0.8118795 0.01811438 0.812946 0.01840162 0.8118795 0.01811438 0.8115237 0.01801973 0.812946 0.01840162 0.8115237 0.01801973 0.8111678 0.01792562 0.8108117 0.0178321 0.8108117 0.0178321 0.8104555 0.01773905 0.8100991 0.01764661 0.8100991 0.01764661 0.8097426 0.0175547 0.8086723 0.01728218 0.8097426 0.0175547 0.809386 0.01746332 0.8086723 0.01728218 0.809386 0.01746332 0.8090292 0.01737248 0.8086723 0.01728218 0.8086723 0.01728218 0.8083153 0.01719248 0.8079581 0.01710331 0.8079581 0.01710331 0.8076007 0.01701468 0.8072433 0.01692658 0.8072433 0.01692658 0.8068857 0.01683902 0.8065279 0.01675206 0.8065279 0.01675206 0.8061701 0.01666563 0.8058121 0.01657974 0.8058121 0.01657974 0.805454 0.01649439 0.8050957 0.01640957 0.8050957 0.01640957 0.8047373 0.01632535 0.8043788 0.01624166 0.8043788 0.01624166 0.8040202 0.01615852 0.8029435 0.01591241 0.8040202 0.01615852 0.8036614 0.0160759 0.8029435 0.01591241 0.8036614 0.0160759 0.8033025 0.01599389 0.8029435 0.01591241 0.8029435 0.01591241 0.8025843 0.01583147 0.8015061 0.01559197 0.8025843 0.01583147 0.8022251 0.01575106 0.8015061 0.01559197 0.8022251 0.01575106 0.8018656 0.01567125 0.8015061 0.01559197 0.8015061 0.01559197 0.8011465 0.01551324 0.8007867 0.01543503 0.8007867 0.01543503 0.8004269 0.01535743 0.8000668 0.01528036 0.8000668 0.01528036 0.7997068 0.01520383 0.7993465 0.01512783 0.7993465 0.01512783 0.7989861 0.01505243 0.8000668 0.01528036 0.7989861 0.01505243 0.7986257 0.01497757 0.8000668 0.01528036 0.7986257 0.01497757 0.7982651 0.01490324 0.7979044 0.01482945 0.7979044 0.01482945 0.7975437 0.01475626 0.7986257 0.01497757 0.7975437 0.01475626 0.7971827 0.0146836 0.7986257 0.01497757 0.7971827 0.0146836 0.7968217 0.01461154 0.7957379 0.01439851 0.7968217 0.01461154 0.7964605 0.01453995 0.7957379 0.01439851 0.7964605 0.01453995 0.7960993 0.01446896 0.7957379 0.01439851 0.7957379 0.01439851 0.7953765 0.01432865 0.7950149 0.01425933 0.7950149 0.01425933 0.7946532 0.01419055 0.7942914 0.0141223 0.7942914 0.0141223 0.7939296 0.01405465 0.7935676 0.01398754 0.7935676 0.01398754 0.7932055 0.01392102 0.7928433 0.01385498 0.7928433 0.01385498 0.792481 0.01378959 0.7921186 0.01372468 0.7921186 0.01372468 0.7917562 0.01366037 0.7913935 0.01359653 0.7913935 0.01359653 0.7910309 0.01353335 0.7906681 0.0134707 0.7906681 0.0134707 0.7903052 0.0134086 0.7899422 0.01334702 0.7899422 0.01334702 0.7895792 0.01328605 0.789216 0.01322561 0.789216 0.01322561 0.7888528 0.01316571 0.7899422 0.01334702 0.7888528 0.01316571 0.7884894 0.0131064 0.7899422 0.01334702 0.7884894 0.0131064 0.7881259 0.01304763 0.7877624 0.01298946 0.7877624 0.01298946 0.7873988 0.01293176 0.7870351 0.01287472 0.7870351 0.01287472 0.7866714 0.01281815 0.7863075 0.01276218 0.7863075 0.01276218 0.7859435 0.01270675 0.7870351 0.01287472 0.7859435 0.01270675 0.7855795 0.01265192 0.7870351 0.01287472 0.7855795 0.01265192 0.7852153 0.01259762 0.7848511 0.01254385 0.7848511 0.01254385 0.7844868 0.01249068 0.7855795 0.01265192 0.7844868 0.01249068 0.7841224 0.01243805 0.7855795 0.01265192 0.7841224 0.01243805 0.783758 0.01238602 0.7826641 0.01223319 0.783758 0.01238602 0.7833935 0.01233452 0.7826641 0.01223319 0.7833935 0.01233452 0.7830289 0.01228356 0.7826641 0.01223319 0.7826641 0.01223319 0.7822994 0.01218336 0.7819345 0.01213407 0.7819345 0.01213407 0.7815696 0.01208537 0.7826641 0.01223319 0.7815696 0.01208537 0.7812046 0.01203721 0.7826641 0.01223319 0.7812046 0.01203721 0.7808396 0.01198965 0.7804744 0.01194262 0.7804744 0.01194262 0.7801092 0.01189613 0.7812046 0.01203721 0.7801092 0.01189613 0.7797439 0.01185023 0.7812046 0.01203721 0.7797439 0.01185023 0.7793785 0.01180487 0.7790132 0.01176011 0.7790132 0.01176011 0.7786477 0.01171588 0.7782821 0.01167219 0.7782821 0.01167219 0.7779165 0.0116291 0.7775508 0.0115866 0.7775508 0.0115866 0.777185 0.01154458 0.7782821 0.01167219 0.777185 0.01154458 0.7768192 0.01150315 0.7782821 0.01167219 0.7768192 0.01150315 0.7764533 0.01146233 0.7753553 0.01134312 0.7764533 0.01146233 0.7760874 0.01142203 0.7753553 0.01134312 0.7760874 0.01142203 0.7757214 0.01138228 0.7753553 0.01134312 0.7753553 0.01134312 0.7749892 0.01130449 0.774623 0.01126641 0.774623 0.01126641 0.7742568 0.01122897 0.7753553 0.01134312 0.7742568 0.01122897 0.7738905 0.01119202 0.7753553 0.01134312 0.7738905 0.01119202 0.7735241 0.01115566 0.7724247 0.01104992 0.7735241 0.01115566 0.7731577 0.01111984 0.7724247 0.01104992 0.7731577 0.01111984 0.7727913 0.01108461 0.7724247 0.01104992 0.7724247 0.01104992 0.7720581 0.01101583 0.7709581 0.01091682 0.7720581 0.01101583 0.7716915 0.01098221 0.7709581 0.01091682 0.7716915 0.01098221 0.7713249 0.01094925 0.7709581 0.01091682 0.7709581 0.01091682 0.7705914 0.01088494 0.7702245 0.01085364 0.7702245 0.01085364 0.7698577 0.01082289 0.7709581 0.01091682 0.7698577 0.01082289 0.7694907 0.01079273 0.7709581 0.01091682 0.7694907 0.01079273 0.7691238 0.0107631 0.7687568 0.01073408 0.7687568 0.01073408 0.7683897 0.01070559 0.7680227 0.01067763 0.7680227 0.01067763 0.7676555 0.01065027 0.7672883 0.01062345 0.7672883 0.01062345 0.7669211 0.01059722 0.7680227 0.01067763 0.7669211 0.01059722 0.7665538 0.01057153 0.7680227 0.01067763 0.7665538 0.01057153 0.7661865 0.01054644 0.7658192 0.01052188 0.7658192 0.01052188 0.7654519 0.01049792 0.7650845 0.0104745 0.7650845 0.0104745 0.764717 0.01045161 0.7636144 0.01038646 0.764717 0.01045161 0.7643495 0.01042932 0.7636144 0.01038646 0.7643495 0.01042932 0.763982 0.01040762 0.7636144 0.01038646 0.7636144 0.01038646 0.7632468 0.01036584 0.7628793 0.01034581 0.7628793 0.01034581 0.7625116 0.01032632 0.762144 0.01030743 0.762144 0.01030743 0.7617763 0.01028907 0.760673 0.01023739 0.7617763 0.01028907 0.7614085 0.01027131 0.760673 0.01023739 0.7614085 0.01027131 0.7610408 0.01025408 0.760673 0.01023739 0.760673 0.01023739 0.7603052 0.0102213 0.7599374 0.0102058 0.7599374 0.0102058 0.7595695 0.01019084 0.760673 0.01023739 0.7595695 0.01019084 0.7592017 0.01017642 0.760673 0.01023739 0.7592017 0.01017642 0.7588337 0.01016259 0.75773 0.0101245 0.7588337 0.01016259 0.7584658 0.01014935 0.75773 0.0101245 0.7584658 0.01014935 0.7580979 0.01013666 0.75773 0.0101245 0.75773 0.0101245 0.757362 0.01011294 0.756994 0.01010191 0.756994 0.01010191 0.756626 0.01009148 0.75773 0.0101245 0.756626 0.01009148 0.756258 0.01008158 0.75773 0.0101245 0.756258 0.01008158 0.7558899 0.01007229 0.7555218 0.01006352 0.7555218 0.01006352 0.7551538 0.0100553 0.756258 0.01008158 0.7551538 0.0100553 0.7547857 0.01004773 0.756258 0.01008158 0.7547857 0.01004773 0.7544176 0.01004064 0.7540495 0.01003414 0.7540495 0.01003414 0.7536814 0.01002824 0.7547857 0.01004773 0.7536814 0.01002824 0.7533133 0.01002287 0.7547857 0.01004773 0.7533133 0.01002287 0.7529452 0.01001805 0.7525771 0.01001381 0.7525771 0.01001381 0.7522089 0.01001018 0.7533133 0.01002287 0.7522089 0.01001018 0.7518408 0.01000702 0.7533133 0.01002287 0.7518408 0.01000702 0.7514726 0.01000452 0.7511045 0.01000255 0.7511045 0.01000255 0.7507363 0.01000112 0.7503682 0.01000028 0.7503682 0.01000028 0.75 0.00999999 0.7496318 0.01000028 0.7496318 0.01000028 0.7492637 0.01000112 0.7488955 0.01000255 0.7488955 0.01000255 0.7485274 0.01000452 0.7481592 0.01000702 0.7481592 0.01000702 0.7477911 0.01001018 0.7488955 0.01000255 0.7477911 0.01001018 0.7474229 0.01001381 0.7488955 0.01000255 0.7474229 0.01001381 0.7470548 0.01001805 0.7466867 0.01002287 0.7466867 0.01002287 0.7463186 0.01002824 0.7459505 0.01003414 0.7459505 0.01003414 0.7455824 0.01004064 0.7452143 0.01004773 0.7452143 0.01004773 0.7448462 0.0100553 0.7459505 0.01003414 0.7448462 0.0100553 0.7444782 0.01006352 0.7459505 0.01003414 0.7444782 0.01006352 0.7441101 0.01007229 0.7430061 0.01010191 0.7441101 0.01007229 0.7437421 0.01008158 0.7430061 0.01010191 0.7437421 0.01008158 0.7433741 0.01009148 0.7430061 0.01010191 0.7430061 0.01010191 0.7426381 0.01011294 0.7415342 0.01014935 0.7426381 0.01011294 0.7422701 0.0101245 0.7415342 0.01014935 0.7422701 0.0101245 0.7419021 0.01013666 0.7415342 0.01014935 0.7415342 0.01014935 0.7411663 0.01016259 0.7400627 0.0102058 0.7411663 0.01016259 0.7407984 0.01017642 0.7400627 0.0102058 0.7407984 0.01017642 0.7404305 0.01019084 0.7400627 0.0102058 0.7400627 0.0102058 0.7396948 0.0102213 0.739327 0.01023739 0.739327 0.01023739 0.7389593 0.01025408 0.7385915 0.01027131 0.7385915 0.01027131 0.7382237 0.01028907 0.7371208 0.01034581 0.7382237 0.01028907 0.737856 0.01030743 0.7371208 0.01034581 0.737856 0.01030743 0.7374884 0.01032632 0.7371208 0.01034581 0.7371208 0.01034581 0.7367532 0.01036584 0.7363856 0.01038646 0.7363856 0.01038646 0.736018 0.01040762 0.7356505 0.01042932 0.7356505 0.01042932 0.735283 0.01045161 0.7341808 0.01052188 0.735283 0.01045161 0.7349156 0.0104745 0.7341808 0.01052188 0.7349156 0.0104745 0.7345482 0.01049792 0.7341808 0.01052188 0.7341808 0.01052188 0.7338135 0.01054644 0.7327117 0.01062345 0.7338135 0.01054644 0.7334462 0.01057153 0.7327117 0.01062345 0.7334462 0.01057153 0.7330789 0.01059722 0.7327117 0.01062345 0.7327117 0.01062345 0.7323445 0.01065027 0.7319774 0.01067763 0.7319774 0.01067763 0.7316103 0.01070559 0.7312432 0.01073408 0.7312432 0.01073408 0.7308762 0.0107631 0.7297755 0.01085364 0.7308762 0.0107631 0.7305093 0.01079273 0.7297755 0.01085364 0.7305093 0.01079273 0.7301424 0.01082289 0.7297755 0.01085364 0.7297755 0.01085364 0.7294086 0.01088494 0.7290419 0.01091682 0.7290419 0.01091682 0.7286751 0.01094925 0.7283085 0.01098221 0.7283085 0.01098221 0.7279419 0.01101583 0.7268423 0.01111984 0.7279419 0.01101583 0.7275753 0.01104992 0.7268423 0.01111984 0.7275753 0.01104992 0.7272087 0.01108461 0.7268423 0.01111984 0.7268423 0.01111984 0.7264759 0.01115566 0.7261095 0.01119202 0.7261095 0.01119202 0.7257432 0.01122897 0.7268423 0.01111984 0.7257432 0.01122897 0.725377 0.01126641 0.7268423 0.01111984 0.725377 0.01126641 0.7250108 0.01130449 0.7246447 0.01134312 0.7246447 0.01134312 0.7242786 0.01138228 0.7239126 0.01142203 0.7239126 0.01142203 0.7235467 0.01146233 0.7224493 0.0115866 0.7235467 0.01146233 0.7231808 0.01150315 0.7224493 0.0115866 0.7231808 0.01150315 0.722815 0.01154458 0.7224493 0.0115866 0.7224493 0.0115866 0.7220835 0.0116291 0.7209869 0.01176011 0.7220835 0.0116291 0.7217179 0.01167219 0.7209869 0.01176011 0.7217179 0.01167219 0.7213523 0.01171588 0.7209869 0.01176011 0.7209869 0.01176011 0.7206215 0.01180487 0.7202561 0.01185023 0.7202561 0.01185023 0.7198908 0.01189613 0.7209869 0.01176011 0.7198908 0.01189613 0.7195256 0.01194262 0.7209869 0.01176011 0.7195256 0.01194262 0.7191604 0.01198965 0.7187954 0.01203721 0.7187954 0.01203721 0.7184304 0.01208537 0.7195256 0.01194262 0.7184304 0.01208537 0.7180655 0.01213407 0.7195256 0.01194262 0.7180655 0.01213407 0.7177006 0.01218336 0.7173359 0.01223319 0.7173359 0.01223319 0.7169712 0.01228356 0.7166066 0.01233452 0.7166066 0.01233452 0.716242 0.01238602 0.7151489 0.01254385 0.716242 0.01238602 0.7158776 0.01243805 0.7151489 0.01254385 0.7158776 0.01243805 0.7155132 0.01249068 0.7151489 0.01254385 0.7151489 0.01254385 0.7147847 0.01259762 0.7144206 0.01265192 0.7144206 0.01265192 0.7140565 0.01270675 0.7136926 0.01276218 0.7136926 0.01276218 0.7133287 0.01281815 0.7122376 0.01298946 0.7133287 0.01281815 0.7129649 0.01287472 0.7122376 0.01298946 0.7129649 0.01287472 0.7126012 0.01293176 0.7122376 0.01298946 0.7122376 0.01298946 0.7118741 0.01304763 0.7115106 0.0131064 0.7115106 0.0131064 0.7111473 0.01316571 0.710784 0.01322561 0.710784 0.01322561 0.7104209 0.01328605 0.7100578 0.01334702 0.7100578 0.01334702 0.7096948 0.0134086 0.7093319 0.0134707 0.7093319 0.0134707 0.7089691 0.01353335 0.7086065 0.01359653 0.7086065 0.01359653 0.7082439 0.01366037 0.7093319 0.0134707 0.7082439 0.01366037 0.7078814 0.01372468 0.7093319 0.0134707 0.7078814 0.01372468 0.707519 0.01378959 0.7064324 0.01398754 0.707519 0.01378959 0.7071567 0.01385498 0.7064324 0.01398754 0.7071567 0.01385498 0.7067945 0.01392102 0.7064324 0.01398754 0.7064324 0.01398754 0.7060704 0.01405465 0.7049851 0.01425933 0.7060704 0.01405465 0.7057086 0.0141223 0.7049851 0.01425933 0.7057086 0.0141223 0.7053468 0.01419055 0.7049851 0.01425933 0.7049851 0.01425933 0.7046235 0.01432865 0.7042621 0.01439851 0.7042621 0.01439851 0.7039007 0.01446896 0.7035395 0.01453995 0.7035395 0.01453995 0.7031784 0.01461154 0.7028173 0.0146836 0.7028173 0.0146836 0.7024564 0.01475626 0.7020956 0.01482945 0.7020956 0.01482945 0.7017349 0.01490324 0.7013743 0.01497757 0.7013743 0.01497757 0.7010139 0.01505243 0.7020956 0.01482945 0.7010139 0.01505243 0.7006535 0.01512783 0.7020956 0.01482945 0.7006535 0.01512783 0.7002933 0.01520383 0.6999332 0.01528036 0.6999332 0.01528036 0.6995732 0.01535743 0.6992133 0.01543503 0.6992133 0.01543503 0.6988535 0.01551324 0.6984939 0.01559197 0.6984939 0.01559197 0.6981344 0.01567125 0.697775 0.01575106 0.697775 0.01575106 0.6974157 0.01583147 0.6970565 0.01591241 0.6970565 0.01591241 0.6966975 0.01599389 0.6963387 0.0160759 0.6963387 0.0160759 0.6959798 0.01615852 0.6949043 0.01640957 0.6959798 0.01615852 0.6956212 0.01624166 0.6949043 0.01640957 0.6956212 0.01624166 0.6952627 0.01632535 0.6949043 0.01640957 0.6949043 0.01640957 0.6945461 0.01649439 0.6941879 0.01657974 0.6941879 0.01657974 0.69383 0.01666563 0.6934721 0.01675206 0.6934721 0.01675206 0.6931143 0.01683902 0.6927567 0.01692658 0.6927567 0.01692658 0.6923993 0.01701468 0.6920419 0.01710331 0.6920419 0.01710331 0.6916847 0.01719248 0.6913277 0.01728218 0.6913277 0.01728218 0.6909708 0.01737248 0.690614 0.01746332 0.690614 0.01746332 0.6902574 0.0175547 0.6891883 0.0178321 0.6902574 0.0175547 0.6899009 0.01764661 0.6891883 0.0178321 0.6899009 0.01764661 0.6895445 0.01773905 0.6891883 0.0178321 0.6891883 0.0178321 0.6888322 0.01792562 0.6884763 0.01801973 0.6884763 0.01801973 0.6881206 0.01811438 0.6891883 0.0178321 0.6881206 0.01811438 0.6877649 0.01820957 0.6891883 0.0178321 0.6877649 0.01820957 0.6874094 0.0183053 0.687054 0.01840162 0.687054 0.01840162 0.6866989 0.01849842 0.6863439 0.01859581 0.6863439 0.01859581 0.6859889 0.01869374 0.6856342 0.01879221 0.6856342 0.01879221 0.6852796 0.01889121 0.6849251 0.01899075 0.6849251 0.01899075 0.6845709 0.01909083 0.6842167 0.0191915 0.6842167 0.0191915 0.6838628 0.01929265 0.6835089 0.01939439 0.6835089 0.01939439 0.6831553 0.01949667 0.6828018 0.01959949 0.6828018 0.01959949 0.6824484 0.01970279 0.6820952 0.01980668 0.6820952 0.01980668 0.6817422 0.01991117 0.6806841 0.02022767 0.6817422 0.01991117 0.6813893 0.02001613 0.6806841 0.02022767 0.6813893 0.02001613 0.6810366 0.02012163 0.6806841 0.02022767 0.6806841 0.02022767 0.6803317 0.0203343 0.6799795 0.02044147 0.6799795 0.02044147 0.6796274 0.02054911 0.6792755 0.02065736 0.6792755 0.02065736 0.6789238 0.02076607 0.6785722 0.02087539 0.6785722 0.02087539 0.6782209 0.02098524 0.6778696 0.02109563 0.6778696 0.02109563 0.6775186 0.02120655 0.6764665 0.02154248 0.6775186 0.02120655 0.6771677 0.02131801 0.6764665 0.02154248 0.6771677 0.02131801 0.676817 0.02142995 0.6764665 0.02154248 0.6764665 0.02154248 0.6761161 0.02165555 0.6757659 0.02176916 0.6757659 0.02176916 0.6754159 0.0218833 0.6750661 0.02199798 0.6750661 0.02199798 0.6747164 0.0221132 0.6736685 0.02246206 0.6747164 0.0221132 0.6743669 0.02222895 0.6736685 0.02246206 0.6743669 0.02222895 0.6740176 0.02234524 0.6736685 0.02246206 0.6736685 0.02246206 0.6733195 0.02257943 0.6722738 0.02293473 0.6733195 0.02257943 0.6729708 0.02269732 0.6722738 0.02293473 0.6729708 0.02269732 0.6726222 0.02281576 0.6722738 0.02293473 0.6722738 0.02293473 0.6719256 0.02305424 0.6715775 0.02317428 0.6715775 0.02317428 0.6712297 0.0232948 0.670882 0.02341592 0.670882 0.02341592 0.6705345 0.02353757 0.6694931 0.02390563 0.6705345 0.02353757 0.6701872 0.0236597 0.6694931 0.02390563 0.6701872 0.0236597 0.6698401 0.02378243 0.6694931 0.02390563 0.6694931 0.02390563 0.6691464 0.02402943 0.6687999 0.0241537 0.6687999 0.0241537 0.6684536 0.02427852 0.6681074 0.02440387 0.6681074 0.02440387 0.6677615 0.02452975 0.6667247 0.02491062 0.6677615 0.02452975 0.6674157 0.02465617 0.6667247 0.02491062 0.6674157 0.02465617 0.6670701 0.02478313 0.6667247 0.02491062 0.6667247 0.02491062 0.6663795 0.02503859 0.6660345 0.02516716 0.6660345 0.02516716 0.6656897 0.02529621 0.6667247 0.02491062 0.6656897 0.02529621 0.6653451 0.02542579 0.6667247 0.02491062 0.6653451 0.02542579 0.6650007 0.0255559 0.6646566 0.02568662 0.6646566 0.02568662 0.6643126 0.02581775 0.6639688 0.02594947 0.6639688 0.02594947 0.6636252 0.02608168 0.6632818 0.02621448 0.6632818 0.02621448 0.6629386 0.02634775 0.6625956 0.02648156 0.6625956 0.02648156 0.6622529 0.02661591 0.6619103 0.0267508 0.6619103 0.0267508 0.661568 0.02688616 0.6612258 0.02702206 0.6612258 0.02702206 0.6608839 0.02715849 0.6605421 0.02729547 0.6605421 0.02729547 0.6602006 0.02743297 0.6612258 0.02702206 0.6602006 0.02743297 0.6598593 0.02757096 0.6612258 0.02702206 0.6598593 0.02757096 0.6595183 0.02770954 0.6591774 0.0278486 0.6591774 0.0278486 0.6588367 0.02798813 0.6584962 0.02812826 0.6584962 0.02812826 0.658156 0.02826887 0.6578159 0.02841007 0.6578159 0.02841007 0.6574761 0.02855169 0.6571366 0.02869391 0.6571366 0.02869391 0.6567972 0.0288366 0.656458 0.02897983 0.656458 0.02897983 0.6561191 0.0291236 0.6571366 0.02869391 0.6561191 0.0291236 0.6557804 0.02926784 0.6571366 0.02869391 0.6557804 0.02926784 0.6554419 0.02941262 0.6551036 0.02955794 0.6551036 0.02955794 0.6547656 0.02970379 0.6557804 0.02926784 0.6547656 0.02970379 0.6544278 0.02985012 0.6557804 0.02926784 0.6544278 0.02985012 0.6540902 0.02999699 0.6537528 0.03014439 0.6537528 0.03014439 0.6534157 0.03029227 0.6544278 0.02985012 0.6534157 0.03029227 0.6530788 0.03044068 0.6544278 0.02985012 0.6530788 0.03044068 0.6527421 0.03058964 0.6517334 0.03103953 0.6527421 0.03058964 0.6524056 0.03073906 0.6517334 0.03103953 0.6524056 0.03073906 0.6520694 0.03088903 0.6517334 0.03103953 0.6517334 0.03103953 0.6513977 0.03119051 0.6510621 0.03134202 0.6510621 0.03134202 0.6507268 0.03149408 0.6517334 0.03103953 0.6507268 0.03149408 0.6503918 0.0316466 0.6517334 0.03103953 0.6503918 0.0316466 0.6500569 0.03179967 0.6497223 0.03195321 0.6497223 0.03195321 0.649388 0.03210729 0.6490538 0.0322619 0.6490538 0.0322619 0.6487199 0.03241699 0.6483863 0.03257262 0.6483863 0.03257262 0.6480529 0.03272879 0.6477197 0.03288543 0.6477197 0.03288543 0.6473868 0.03304255 0.6470541 0.0332002 0.6470541 0.0332002 0.6467217 0.03335839 0.6463894 0.03351706 0.6463894 0.03351706 0.6460575 0.03367626 0.6457258 0.03383594 0.6457258 0.03383594 0.6453943 0.03399616 0.6450631 0.03415685 0.6450631 0.03415685 0.6447321 0.03431808 0.6444014 0.03447985 0.6444014 0.03447985 0.6440709 0.0346421 0.6450631 0.03415685 0.6440709 0.0346421 0.6437407 0.03480482 0.6450631 0.03415685 0.6437407 0.03480482 0.6434107 0.03496807 0.643081 0.03513181 0.643081 0.03513181 0.6427515 0.03529608 0.6437407 0.03480482 0.6427515 0.03529608 0.6424223 0.03546088 0.6437407 0.03480482 0.6424223 0.03546088 0.6420933 0.03562617 0.6417646 0.03579193 0.6417646 0.03579193 0.6414361 0.03595823 0.6411079 0.036125 0.6411079 0.036125 0.64078 0.03629225 0.6404523 0.0364601 0.6404523 0.0364601 0.6401248 0.03662836 0.6397976 0.03679716 0.6397976 0.03679716 0.6394707 0.03696644 0.6391441 0.03713625 0.6391441 0.03713625 0.6388177 0.03730654 0.6384915 0.03747737 0.6384915 0.03747737 0.6381657 0.03764867 0.63784 0.03782045 0.63784 0.03782045 0.6375147 0.03799277 0.6384915 0.03747737 0.6375147 0.03799277 0.6371896 0.03816556 0.6384915 0.03747737 0.6371896 0.03816556 0.6368648 0.03833889 0.6358919 0.03886175 0.6368648 0.03833889 0.6365402 0.0385127 0.6358919 0.03886175 0.6365402 0.0385127 0.6362159 0.03868699 0.6358919 0.03886175 0.6358919 0.03886175 0.6355682 0.03903704 0.6352447 0.03921282 0.6352447 0.03921282 0.6349215 0.03938913 0.6358919 0.03886175 0.6349215 0.03938913 0.6345986 0.03956592 0.6358919 0.03886175 0.6345986 0.03956592 0.6342759 0.03974318 0.6339535 0.03992092 0.6339535 0.03992092 0.6336314 0.0400992 0.6333096 0.04027795 0.6333096 0.04027795 0.632988 0.04045718 0.6326667 0.04063695 0.6326667 0.04063695 0.6323456 0.04081714 0.6320249 0.04099792 0.6320249 0.04099792 0.6317045 0.04117912 0.6307447 0.04172569 0.6317045 0.04117912 0.6313843 0.04136079 0.6307447 0.04172569 0.6313843 0.04136079 0.6310644 0.041543 0.6307447 0.04172569 0.6307447 0.04172569 0.6304253 0.04190886 0.629469 0.04246133 0.6304253 0.04190886 0.6301063 0.04209256 0.629469 0.04246133 0.6301063 0.04209256 0.6297875 0.04227674 0.629469 0.04246133 0.629469 0.04246133 0.6291508 0.04264652 0.6281979 0.04320484 0.6291508 0.04264652 0.6288328 0.04283213 0.6281979 0.04320484 0.6288328 0.04283213 0.6285152 0.04301822 0.6281979 0.04320484 0.6281979 0.04320484 0.6278808 0.04339194 0.627564 0.04357951 0.627564 0.04357951 0.6272475 0.04376757 0.6269313 0.0439561 0.6269313 0.0439561 0.6266154 0.0441451 0.6262997 0.04433465 0.6262997 0.04433465 0.6259844 0.04452461 0.6256694 0.0447151 0.6256694 0.0447151 0.6253545 0.04490607 0.6250401 0.04509752 0.6250401 0.04509752 0.6247259 0.04528945 0.6256694 0.0447151 0.6247259 0.04528945 0.6244121 0.04548186 0.6256694 0.0447151 0.6244121 0.04548186 0.6240985 0.04567474 0.6237852 0.04586809 0.6237852 0.04586809 0.6234722 0.04606193 0.6231595 0.0462563 0.6231595 0.0462563 0.6228471 0.04645109 0.6225351 0.04664641 0.6225351 0.04664641 0.6222233 0.04684215 0.6219118 0.04703837 0.6219118 0.04703837 0.6216006 0.04723513 0.6212897 0.04743236 0.6212897 0.04743236 0.6209791 0.04763001 0.6206688 0.04782813 0.6206688 0.04782813 0.6203588 0.0480268 0.6200492 0.04822587 0.6200492 0.04822587 0.6197398 0.04842549 0.6206688 0.04782813 0.6197398 0.04842549 0.6194308 0.04862552 0.6206688 0.04782813 0.6194308 0.04862552 0.619122 0.04882603 0.6181976 0.04943048 0.619122 0.04882603 0.6188136 0.04902702 0.6181976 0.04943048 0.6188136 0.04902702 0.6185054 0.04922854 0.6181976 0.04943048 0.6181976 0.04943048 0.6178901 0.0496329 0.6169694 0.05024296 0.6178901 0.0496329 0.6175829 0.0498358 0.6169694 0.05024296 0.6175829 0.0498358 0.617276 0.05003911 0.6169694 0.05024296 0.6169694 0.05024296 0.6166632 0.05044728 0.6163572 0.05065202 0.6163572 0.05065202 0.6160516 0.0508573 0.6169694 0.05024296 0.6160516 0.0508573 0.6157463 0.051063 0.6169694 0.05024296 0.6157463 0.051063 0.6154412 0.05126917 0.6145281 0.05189049 0.6154412 0.05126917 0.6151365 0.05147582 0.6145281 0.05189049 0.6151365 0.05147582 0.6148322 0.05168294 0.6145281 0.05189049 0.6145281 0.05189049 0.6142244 0.05209857 0.6139209 0.05230706 0.6139209 0.05230706 0.6136178 0.05251604 0.6145281 0.05189049 0.6136178 0.05251604 0.6133151 0.05272549 0.6145281 0.05189049 0.6133151 0.05272549 0.6130126 0.05293536 0.6127105 0.05314576 0.6127105 0.05314576 0.6124087 0.05335658 0.6121072 0.05356788 0.6121072 0.05356788 0.611806 0.0537796 0.6115052 0.05399185 0.6115052 0.05399185 0.6112047 0.05420452 0.6121072 0.05356788 0.6112047 0.05420452 0.6109045 0.05441766 0.6121072 0.05356788 0.6109045 0.05441766 0.6106047 0.05463129 0.6103051 0.05484533 0.6103051 0.05484533 0.6100059 0.05505985 0.6097071 0.05527484 0.6097071 0.05527484 0.6094085 0.05549025 0.6091103 0.05570614 0.6091103 0.05570614 0.6088125 0.0559225 0.6097071 0.05527484 0.6088125 0.0559225 0.6085149 0.05613929 0.6097071 0.05527484 0.6085149 0.05613929 0.6082177 0.05635654 0.6079208 0.05657428 0.6079208 0.05657428 0.6076242 0.05679249 0.6085149 0.05613929 0.6076242 0.05679249 0.6073281 0.05701106 0.6085149 0.05613929 0.6073281 0.05701106 0.6070322 0.05723017 0.6067367 0.05744969 0.6067367 0.05744969 0.6064414 0.05766969 0.6061466 0.05789011 0.6061466 0.05789011 0.605852 0.05811107 0.6055579 0.05833238 0.6055579 0.05833238 0.605264 0.05855417 0.6061466 0.05789011 0.605264 0.05855417 0.6049705 0.05877643 0.6061466 0.05789011 0.6049705 0.05877643 0.6046774 0.05899912 0.6043846 0.05922228 0.6043846 0.05922228 0.6040921 0.05944585 0.6049705 0.05877643 0.6040921 0.05944585 0.6037999 0.05966991 0.6049705 0.05877643 0.6037999 0.05966991 0.6035081 0.05989438 0.6032167 0.06011933 0.6032167 0.06011933 0.6029256 0.06034475 0.6037999 0.05966991 0.6029256 0.06034475 0.6026348 0.06057053 0.6037999 0.05966991 0.6026348 0.06057053 0.6023444 0.06079685 0.6020544 0.06102359 0.6020544 0.06102359 0.6017646 0.06125074 0.6014752 0.06147837 0.6014752 0.06147837 0.6011863 0.06170636 0.6008976 0.06193488 0.6008976 0.06193488 0.6006093 0.06216382 0.6014752 0.06147837 0.6006093 0.06216382 0.6003214 0.06239324 0.6014752 0.06147837 0.6003214 0.06239324 0.6000337 0.06262302 0.5997465 0.06285333 0.5997465 0.06285333 0.5994596 0.063084 0.599173 0.06331515 0.599173 0.06331515 0.5988869 0.06354677 0.598601 0.06377875 0.598601 0.06377875 0.5983155 0.06401121 0.599173 0.06331515 0.5983155 0.06401121 0.5980304 0.06424415 0.599173 0.06331515 0.5980304 0.06424415 0.5977456 0.0644775 0.5974612 0.06471127 0.5974612 0.06471127 0.5971772 0.06494545 0.5980304 0.06424415 0.5971772 0.06494545 0.5968934 0.06518012 0.5980304 0.06424415 0.5968934 0.06518012 0.5966101 0.0654152 0.5963272 0.0656507 0.5963272 0.0656507 0.5960446 0.06588661 0.5957623 0.066123 0.5957623 0.066123 0.5954805 0.06635981 0.594637 0.06707286 0.5954805 0.06635981 0.5951989 0.0665971 0.594637 0.06707286 0.5951989 0.0665971 0.5949178 0.06683474 0.594637 0.06707286 0.594637 0.06707286 0.5943565 0.0673114 0.5940765 0.06755036 0.5940765 0.06755036 0.5937968 0.06778979 0.5935175 0.06802958 0.5935175 0.06802958 0.5932385 0.06826984 0.59296 0.06851053 0.59296 0.06851053 0.5926817 0.06875163 0.5924039 0.06899321 0.5924039 0.06899321 0.5921264 0.06923514 0.5918493 0.06947755 0.5918493 0.06947755 0.5915725 0.06972038 0.5924039 0.06899321 0.5915725 0.06972038 0.5912962 0.06996357 0.5924039 0.06899321 0.5912962 0.06996357 0.5910202 0.07020723 0.5907446 0.07045131 0.5907446 0.07045131 0.5904694 0.07069581 0.5901945 0.07094079 0.5901945 0.07094079 0.5899201 0.07118612 0.5896459 0.07143187 0.5896459 0.07143187 0.5893722 0.07167804 0.5890988 0.07192468 0.5890988 0.07192468 0.5888258 0.07217168 0.5885533 0.07241916 0.5885533 0.07241916 0.588281 0.072667 0.5890988 0.07192468 0.588281 0.072667 0.5880092 0.07291531 0.5890988 0.07192468 0.5880092 0.07291531 0.5877377 0.07316398 0.5874667 0.07341313 0.5874667 0.07341313 0.587196 0.07366263 0.5869257 0.07391262 0.5869257 0.07391262 0.5866557 0.07416296 0.5863862 0.07441371 0.5863862 0.07441371 0.586117 0.07466495 0.5858483 0.07491654 0.5858483 0.07491654 0.5855799 0.07516855 0.5853119 0.07542097 0.5853119 0.07542097 0.5850443 0.07567381 0.5858483 0.07491654 0.5850443 0.07567381 0.5847771 0.07592701 0.5858483 0.07491654 0.5847771 0.07592701 0.5845103 0.07618069 0.5842438 0.07643473 0.5842438 0.07643473 0.5839778 0.07668924 0.5837121 0.07694411 0.5837121 0.07694411 0.5834469 0.07719939 0.5826534 0.0779677 0.5834469 0.07719939 0.583182 0.0774551 0.5826534 0.0779677 0.583182 0.0774551 0.5829175 0.07771116 0.5826534 0.0779677 0.5826534 0.0779677 0.5823897 0.07822459 0.581601 0.07899773 0.5823897 0.07822459 0.5821264 0.07848191 0.581601 0.07899773 0.5821264 0.07848191 0.5818635 0.07873958 0.581601 0.07899773 0.581601 0.07899773 0.5813389 0.07925623 0.5810772 0.07951515 0.5810772 0.07951515 0.5808158 0.07977449 0.5805549 0.08003425 0.5805549 0.08003425 0.5802944 0.08029437 0.5800343 0.0805549 0.5800343 0.0805549 0.5797745 0.08081579 0.5805549 0.08003425 0.5797745 0.08081579 0.5795152 0.08107709 0.5805549 0.08003425 0.5795152 0.08107709 0.5792563 0.08133882 0.5789977 0.08160096 0.5789977 0.08160096 0.5787397 0.08186346 0.5784819 0.08212637 0.5784819 0.08212637 0.5782246 0.08238965 0.5779677 0.08265334 0.5779677 0.08265334 0.5777112 0.08291745 0.5774551 0.08318191 0.5774551 0.08318191 0.5771994 0.08344686 0.5764348 0.08424383 0.5771994 0.08344686 0.5769441 0.0837121 0.5764348 0.08424383 0.5769441 0.0837121 0.5766893 0.08397775 0.5764348 0.08424383 0.5764348 0.08424383 0.5761807 0.08451026 0.5759271 0.08477705 0.5759271 0.08477705 0.5756738 0.08504432 0.5764348 0.08424383 0.5756738 0.08504432 0.575421 0.08531188 0.5764348 0.08424383 0.575421 0.08531188 0.5751686 0.08557987 0.5744138 0.0863862 0.5751686 0.08557987 0.5749166 0.08584827 0.5744138 0.0863862 0.5749166 0.08584827 0.574665 0.08611702 0.5744138 0.0863862 0.5744138 0.0863862 0.574163 0.08665573 0.5739126 0.08692568 0.5739126 0.08692568 0.5736626 0.08719593 0.5734131 0.08746665 0.5734131 0.08746665 0.5731641 0.08773773 0.5729153 0.08800917 0.5729153 0.08800917 0.5726671 0.08828103 0.5734131 0.08746665 0.5726671 0.08828103 0.5724192 0.08855324 0.5734131 0.08746665 0.5724192 0.08855324 0.5721718 0.08882582 0.5719247 0.08909881 0.5719247 0.08909881 0.5716781 0.08937215 0.5714319 0.08964586 0.5714319 0.08964586 0.5711861 0.08991998 0.5709408 0.09019446 0.5709408 0.09019446 0.5706959 0.09046936 0.5704514 0.09074455 0.5704514 0.09074455 0.5702072 0.09102016 0.5699636 0.09129619 0.5699636 0.09129619 0.5697204 0.09157252 0.5704514 0.09074455 0.5697204 0.09157252 0.5694776 0.09184926 0.5704514 0.09074455 0.5694776 0.09184926 0.5692352 0.09212636 0.5689932 0.09240382 0.5689932 0.09240382 0.5687517 0.0926817 0.5685106 0.09295994 0.5685106 0.09295994 0.5682699 0.09323847 0.5680297 0.09351742 0.5680297 0.09351742 0.5677898 0.09379678 0.5685106 0.09295994 0.5677898 0.09379678 0.5675504 0.09407645 0.5685106 0.09295994 0.5675504 0.09407645 0.5673115 0.09435653 0.5665971 0.09519886 0.5673115 0.09435653 0.5670729 0.09463691 0.5665971 0.09519886 0.5670729 0.09463691 0.5668348 0.09491771 0.5665971 0.09519886 0.5665971 0.09519886 0.5663599 0.09548038 0.5656507 0.09632712 0.5663599 0.09548038 0.5661231 0.09576231 0.5656507 0.09632712 0.5661231 0.09576231 0.5658867 0.09604454 0.5656507 0.09632712 0.5656507 0.09632712 0.5654152 0.09661012 0.5651801 0.09689342 0.5651801 0.09689342 0.5649455 0.09717714 0.5656507 0.09632712 0.5649455 0.09717714 0.5647113 0.09746116 0.5656507 0.09632712 0.5647113 0.09746116 0.5644775 0.09774559 0.5642442 0.09803032 0.5642442 0.09803032 0.5640113 0.09831547 0.5637788 0.09860098 0.5637788 0.09860098 0.5635468 0.09888678 0.5628533 0.09974646 0.5635468 0.09888678 0.5633152 0.099173 0.5628533 0.09974646 0.5633152 0.099173 0.563084 0.09945952 0.5628533 0.09974646 0.5628533 0.09974646 0.5626231 0.1000337 0.5623933 0.1003213 0.5623933 0.1003213 0.5621638 0.1006093 0.5628533 0.09974646 0.5621638 0.1006093 0.561935 0.1008976 0.5628533 0.09974646 0.561935 0.1008976 0.5617064 0.1011862 0.5614784 0.1014752 0.5614784 0.1014752 0.5612508 0.1017646 0.5610236 0.1020543 0.5610236 0.1020543 0.5607969 0.1023444 0.5605706 0.1026348 0.5605706 0.1026348 0.5603448 0.1029255 0.5610236 0.1020543 0.5603448 0.1029255 0.5601194 0.1032167 0.5610236 0.1020543 0.5601194 0.1032167 0.5598945 0.1035081 0.5592223 0.1043845 0.5598945 0.1035081 0.55967 0.1037999 0.5592223 0.1043845 0.55967 0.1037999 0.5594459 0.104092 0.5592223 0.1043845 0.5592223 0.1043845 0.5589991 0.1046773 0.5587764 0.1049705 0.5587764 0.1049705 0.5585542 0.105264 0.5583325 0.1055578 0.5583325 0.1055578 0.5581111 0.105852 0.5574498 0.1067366 0.5581111 0.105852 0.5578902 0.1061465 0.5574498 0.1067366 0.5578902 0.1061465 0.5576698 0.1064414 0.5574498 0.1067366 0.5574498 0.1067366 0.5572302 0.1070321 0.5570111 0.107328 0.5570111 0.107328 0.5567925 0.1076242 0.5565744 0.1079208 0.5565744 0.1079208 0.5563566 0.1082177 0.5561394 0.1085149 0.5561394 0.1085149 0.5559225 0.1088124 0.5565744 0.1079208 0.5559225 0.1088124 0.5557062 0.1091103 0.5565744 0.1079208 0.5557062 0.1091103 0.5554903 0.1094085 0.5552749 0.109707 0.5552749 0.109707 0.5550599 0.1100059 0.5548453 0.1103051 0.5548453 0.1103051 0.5546313 0.1106046 0.5544177 0.1109045 0.5544177 0.1109045 0.5542046 0.1112046 0.5548453 0.1103051 0.5542046 0.1112046 0.5539919 0.1115052 0.5548453 0.1103051 0.5539919 0.1115052 0.5537797 0.111806 0.5535679 0.1121072 0.5535679 0.1121072 0.5533566 0.1124086 0.5539919 0.1115052 0.5533566 0.1124086 0.5531458 0.1127105 0.5539919 0.1115052 0.5531458 0.1127105 0.5529354 0.1130126 0.5527255 0.1133151 0.5527255 0.1133151 0.5525161 0.1136178 0.5531458 0.1127105 0.5525161 0.1136178 0.5523071 0.1139209 0.5531458 0.1127105 0.5523071 0.1139209 0.5520986 0.1142243 0.5518906 0.1145281 0.5518906 0.1145281 0.551683 0.1148321 0.5514758 0.1151365 0.5514758 0.1151365 0.5512692 0.1154412 0.551063 0.1157462 0.551063 0.1157462 0.5508573 0.1160515 0.5514758 0.1151365 0.5508573 0.1160515 0.5506521 0.1163572 0.5514758 0.1151365 0.5506521 0.1163572 0.5504473 0.1166631 0.5498358 0.1175829 0.5504473 0.1166631 0.550243 0.1169694 0.5498358 0.1175829 0.550243 0.1169694 0.5500392 0.117276 0.5498358 0.1175829 0.5498358 0.1175829 0.5496329 0.1178901 0.5494305 0.1181976 0.5494305 0.1181976 0.5492286 0.1185054 0.5490271 0.1188135 0.5490271 0.1188135 0.5488261 0.119122 0.5486255 0.1194307 0.5486255 0.1194307 0.5484255 0.1197398 0.5490271 0.1188135 0.5484255 0.1197398 0.5482259 0.1200491 0.5490271 0.1188135 0.5482259 0.1200491 0.5480268 0.1203588 0.5478282 0.1206688 0.5478282 0.1206688 0.54763 0.1209791 0.5482259 0.1200491 0.54763 0.1209791 0.5474324 0.1212897 0.5482259 0.1200491 0.5474324 0.1212897 0.5472351 0.1216006 0.5466464 0.122535 0.5472351 0.1216006 0.5470384 0.1219117 0.5466464 0.122535 0.5470384 0.1219117 0.5468422 0.1222232 0.5466464 0.122535 0.5466464 0.122535 0.5464511 0.1228471 0.5458682 0.1237851 0.5464511 0.1228471 0.5462563 0.1231595 0.5458682 0.1237851 0.5462563 0.1231595 0.546062 0.1234722 0.5458682 0.1237851 0.5458682 0.1237851 0.5456748 0.1240984 0.5454819 0.124412 0.5454819 0.124412 0.5452895 0.1247259 0.5458682 0.1237851 0.5452895 0.1247259 0.5450975 0.1250401 0.5458682 0.1237851 0.5450975 0.1250401 0.5449061 0.1253545 0.5447151 0.1256693 0.5447151 0.1256693 0.5445247 0.1259843 0.5443347 0.1262997 0.5443347 0.1262997 0.5441451 0.1266153 0.5435795 0.127564 0.5441451 0.1266153 0.5439561 0.1269312 0.5435795 0.127564 0.5439561 0.1269312 0.5437676 0.1272475 0.5435795 0.127564 0.5435795 0.127564 0.543392 0.1278807 0.5428321 0.1288328 0.543392 0.1278807 0.5432049 0.1281978 0.5428321 0.1288328 0.5432049 0.1281978 0.5430182 0.1285152 0.5428321 0.1288328 0.5428321 0.1288328 0.5426465 0.1291508 0.5424614 0.129469 0.5424614 0.129469 0.5422767 0.1297875 0.5420926 0.1301063 0.5420926 0.1301063 0.5419089 0.1304253 0.5413609 0.1313842 0.5419089 0.1304253 0.5417258 0.1307446 0.5413609 0.1313842 0.5417258 0.1307446 0.541543 0.1310643 0.5413609 0.1313842 0.5413609 0.1313842 0.5411791 0.1317044 0.5409979 0.1320249 0.5409979 0.1320249 0.5408172 0.1323456 0.540637 0.1326667 0.540637 0.1326667 0.5404572 0.1329879 0.540278 0.1333095 0.540278 0.1333095 0.5400992 0.1336314 0.5399209 0.1339535 0.5399209 0.1339535 0.5397432 0.1342759 0.5395659 0.1345986 0.5395659 0.1345986 0.5393891 0.1349215 0.5392128 0.1352447 0.5392128 0.1352447 0.5390371 0.1355682 0.5388618 0.1358919 0.5388618 0.1358919 0.538687 0.1362159 0.5385127 0.1365402 0.5385127 0.1365402 0.5383389 0.1368647 0.5378205 0.13784 0.5383389 0.1368647 0.5381656 0.1371896 0.5378205 0.13784 0.5381656 0.1371896 0.5379928 0.1375147 0.5378205 0.13784 0.5378205 0.13784 0.5376487 0.1381656 0.5374774 0.1384915 0.5374774 0.1384915 0.5373066 0.1388176 0.5371363 0.139144 0.5371363 0.139144 0.5369665 0.1394707 0.5367972 0.1397976 0.5367972 0.1397976 0.5366284 0.1401247 0.5364601 0.1404522 0.5364601 0.1404522 0.5362923 0.1407799 0.536125 0.1411079 0.536125 0.1411079 0.5359582 0.1414361 0.5364601 0.1404522 0.5359582 0.1414361 0.5357919 0.1417645 0.5364601 0.1404522 0.5357919 0.1417645 0.5356262 0.1420933 0.5354609 0.1424222 0.5354609 0.1424222 0.5352962 0.1427515 0.5357919 0.1417645 0.5352962 0.1427515 0.5351319 0.1430809 0.5357919 0.1417645 0.5351319 0.1430809 0.5349681 0.1434106 0.5348049 0.1437407 0.5348049 0.1437407 0.5346421 0.1440709 0.5344799 0.1444013 0.5344799 0.1444013 0.5343182 0.1447321 0.5341569 0.1450631 0.5341569 0.1450631 0.5339962 0.1453943 0.533836 0.1457257 0.533836 0.1457257 0.5336763 0.1460574 0.5335171 0.1463894 0.5335171 0.1463894 0.5333584 0.1467216 0.5332003 0.1470541 0.5332003 0.1470541 0.5330426 0.1473867 0.5328854 0.1477197 0.5328854 0.1477197 0.5327288 0.1480528 0.5325726 0.1483862 0.5325726 0.1483862 0.5324171 0.1487199 0.5322619 0.1490538 0.5322619 0.1490538 0.5321074 0.1493879 0.5325726 0.1483862 0.5321074 0.1493879 0.5319533 0.1497223 0.5325726 0.1483862 0.5319533 0.1497223 0.5317997 0.1500568 0.5316466 0.1503917 0.5316466 0.1503917 0.5314941 0.1507267 0.5319533 0.1497223 0.5314941 0.1507267 0.531342 0.1510621 0.5319533 0.1497223 0.531342 0.1510621 0.5311906 0.1513976 0.5310396 0.1517333 0.5310396 0.1517333 0.5308891 0.1520694 0.5307391 0.1524056 0.5307391 0.1524056 0.5305897 0.152742 0.5301444 0.1537528 0.5305897 0.152742 0.5304408 0.1530787 0.5301444 0.1537528 0.5304408 0.1530787 0.5302923 0.1534156 0.5301444 0.1537528 0.5301444 0.1537528 0.529997 0.1540902 0.5298502 0.1544278 0.5298502 0.1544278 0.5297039 0.1547656 0.529558 0.1551036 0.529558 0.1551036 0.5294127 0.1554419 0.5292679 0.1557804 0.5292679 0.1557804 0.5291236 0.1561191 0.529558 0.1551036 0.5291236 0.1561191 0.5289799 0.156458 0.529558 0.1551036 0.5289799 0.156458 0.5288366 0.1567972 0.5286939 0.1571365 0.5286939 0.1571365 0.5285518 0.1574761 0.5284101 0.1578159 0.5284101 0.1578159 0.5282689 0.1581559 0.5278486 0.1591773 0.5282689 0.1581559 0.5281283 0.1584962 0.5278486 0.1591773 0.5281283 0.1584962 0.5279882 0.1588367 0.5278486 0.1591773 0.5278486 0.1591773 0.5277096 0.1595182 0.527571 0.1598593 0.527571 0.1598593 0.527433 0.1602006 0.5278486 0.1591773 0.527433 0.1602006 0.5272955 0.1605421 0.5278486 0.1591773 0.5272955 0.1605421 0.5271586 0.1608839 0.5270221 0.1612258 0.5270221 0.1612258 0.5268862 0.1615679 0.5272955 0.1605421 0.5268862 0.1615679 0.5267508 0.1619103 0.5272955 0.1605421 0.5267508 0.1619103 0.5266159 0.1622529 0.5264816 0.1625956 0.5264816 0.1625956 0.5263478 0.1629386 0.5262145 0.1632818 0.5262145 0.1632818 0.5260818 0.1636251 0.5259495 0.1639688 0.5259495 0.1639688 0.5258178 0.1643126 0.5262145 0.1632818 0.5258178 0.1643126 0.5256866 0.1646565 0.5262145 0.1632818 0.5256866 0.1646565 0.525556 0.1650007 0.5254259 0.1653451 0.5254259 0.1653451 0.5252963 0.1656897 0.5256866 0.1646565 0.5252963 0.1656897 0.5251672 0.1660345 0.5256866 0.1646565 0.5251672 0.1660345 0.5250387 0.1663795 0.5249106 0.1667247 0.5249106 0.1667247 0.5247831 0.16707 0.5246562 0.1674156 0.5246562 0.1674156 0.5245298 0.1677614 0.5244039 0.1681073 0.5244039 0.1681073 0.5242785 0.1684535 0.5246562 0.1674156 0.5242785 0.1684535 0.5241537 0.1687999 0.5246562 0.1674156 0.5241537 0.1687999 0.5240294 0.1691464 0.5239056 0.1694931 0.5239056 0.1694931 0.5237824 0.16984 0.5241537 0.1687999 0.5237824 0.16984 0.5236598 0.1701872 0.5241537 0.1687999 0.5236598 0.1701872 0.5235376 0.1705344 0.5231743 0.1715775 0.5235376 0.1705344 0.5234159 0.1708819 0.5231743 0.1715775 0.5234159 0.1708819 0.5232949 0.1712296 0.5231743 0.1715775 0.5231743 0.1715775 0.5230543 0.1719255 0.5229347 0.1722737 0.5229347 0.1722737 0.5228158 0.1726222 0.5231743 0.1715775 0.5228158 0.1726222 0.5226973 0.1729707 0.5231743 0.1715775 0.5226973 0.1729707 0.5225794 0.1733195 0.5224621 0.1736685 0.5224621 0.1736685 0.5223453 0.1740176 0.522229 0.1743668 0.522229 0.1743668 0.5221133 0.1747164 0.5219981 0.175066 0.5219981 0.175066 0.5218834 0.1754159 0.5217692 0.1757659 0.5217692 0.1757659 0.5216556 0.1761161 0.5215426 0.1764664 0.5215426 0.1764664 0.52143 0.1768169 0.5217692 0.1757659 0.52143 0.1768169 0.521318 0.1771677 0.5217692 0.1757659 0.521318 0.1771677 0.5212066 0.1775186 0.5208755 0.1785722 0.5212066 0.1775186 0.5210956 0.1778696 0.5208755 0.1785722 0.5210956 0.1778696 0.5209853 0.1782208 0.5208755 0.1785722 0.5208755 0.1785722 0.5207661 0.1789237 0.5206574 0.1792755 0.5206574 0.1792755 0.5205491 0.1796274 0.5204415 0.1799794 0.5204415 0.1799794 0.5203343 0.1803317 0.5202277 0.180684 0.5202277 0.180684 0.5201217 0.1810365 0.5200161 0.1813893 0.5200161 0.1813893 0.5199112 0.1817421 0.5195995 0.1828017 0.5199112 0.1817421 0.5198068 0.1820952 0.5195995 0.1828017 0.5198068 0.1820952 0.5197029 0.1824484 0.5195995 0.1828017 0.5195995 0.1828017 0.5194967 0.1831552 0.5193944 0.1835089 0.5193944 0.1835089 0.5192927 0.1838628 0.5195995 0.1828017 0.5192927 0.1838628 0.5191915 0.1842167 0.5195995 0.1828017 0.5191915 0.1842167 0.5190909 0.1845709 0.5189908 0.1849251 0.5189908 0.1849251 0.5188912 0.1852796 0.5191915 0.1842167 0.5188912 0.1852796 0.5187922 0.1856341 0.5191915 0.1842167 0.5187922 0.1856341 0.5186938 0.1859889 0.5185958 0.1863438 0.5185958 0.1863438 0.5184985 0.1866989 0.5187922 0.1856341 0.5184985 0.1866989 0.5184016 0.187054 0.5187922 0.1856341 0.5184016 0.187054 0.5183054 0.1874094 0.5182096 0.1877649 0.5182096 0.1877649 0.5181144 0.1881205 0.5184016 0.187054 0.5181144 0.1881205 0.5180197 0.1884763 0.5184016 0.187054 0.5180197 0.1884763 0.5179256 0.1888322 0.5178321 0.1891883 0.5178321 0.1891883 0.5177391 0.1895445 0.5176466 0.1899008 0.5176466 0.1899008 0.5175547 0.1902573 0.5172823 0.1913277 0.5175547 0.1902573 0.5174633 0.190614 0.5172823 0.1913277 0.5174633 0.190614 0.5173725 0.1909708 0.5172823 0.1913277 0.5172823 0.1913277 0.5171925 0.1916847 0.5171033 0.1920419 0.5171033 0.1920419 0.5170147 0.1923993 0.5169267 0.1927567 0.5169267 0.1927567 0.5168391 0.1931143 0.5167521 0.193472 0.5167521 0.193472 0.5166656 0.1938299 0.5165798 0.1941879 0.5165798 0.1941879 0.5164944 0.194546 0.5164096 0.1949043 0.5164096 0.1949043 0.5163254 0.1952627 0.5162417 0.1956212 0.5162417 0.1956212 0.5161586 0.1959798 0.5159124 0.1970565 0.5161586 0.1959798 0.516076 0.1963386 0.5159124 0.1970565 0.516076 0.1963386 0.515994 0.1966975 0.5159124 0.1970565 0.5159124 0.1970565 0.5158315 0.1974157 0.515592 0.1984938 0.5158315 0.1974157 0.5157511 0.197775 0.515592 0.1984938 0.5157511 0.197775 0.5156713 0.1981343 0.515592 0.1984938 0.515592 0.1984938 0.5155133 0.1988535 0.5154351 0.1992133 0.5154351 0.1992133 0.5153574 0.1995731 0.5152804 0.1999331 0.5152804 0.1999331 0.5152038 0.2002933 0.5151278 0.2006534 0.5151278 0.2006534 0.5150524 0.2010138 0.5152804 0.1999331 0.5150524 0.2010138 0.5149776 0.2013743 0.5152804 0.1999331 0.5149776 0.2013743 0.5149033 0.2017349 0.5148295 0.2020956 0.5148295 0.2020956 0.5147563 0.2024564 0.5149776 0.2013743 0.5147563 0.2024564 0.5146837 0.2028173 0.5149776 0.2013743 0.5146837 0.2028173 0.5146116 0.2031783 0.5143986 0.204262 0.5146116 0.2031783 0.51454 0.2035394 0.5143986 0.204262 0.51454 0.2035394 0.514469 0.2039006 0.5143986 0.204262 0.5143986 0.204262 0.5143287 0.2046235 0.5142593 0.2049851 0.5142593 0.2049851 0.5141906 0.2053467 0.5141224 0.2057085 0.5141224 0.2057085 0.5140547 0.2060704 0.5139876 0.2064324 0.5139876 0.2064324 0.513921 0.2067945 0.513855 0.2071567 0.513855 0.2071567 0.5137896 0.2075189 0.5137247 0.2078813 0.5137247 0.2078813 0.5136604 0.2082439 0.5135966 0.2086064 0.5135966 0.2086064 0.5135334 0.2089691 0.5134707 0.2093319 0.5134707 0.2093319 0.5134086 0.2096948 0.513347 0.2100577 0.513347 0.2100577 0.5132861 0.2104208 0.5132256 0.210784 0.5132256 0.210784 0.5131658 0.2111473 0.513347 0.2100577 0.5131658 0.2111473 0.5131065 0.2115106 0.513347 0.2100577 0.5131065 0.2115106 0.5130477 0.211874 0.5129895 0.2122375 0.5129895 0.2122375 0.5129318 0.2126011 0.5128747 0.2129648 0.5128747 0.2129648 0.5128182 0.2133287 0.5127622 0.2136925 0.5127622 0.2136925 0.5127068 0.2140565 0.5128747 0.2129648 0.5127068 0.2140565 0.5126519 0.2144205 0.5128747 0.2129648 0.5126519 0.2144205 0.5125976 0.2147846 0.5125439 0.2151489 0.5125439 0.2151489 0.5124908 0.2155132 0.5126519 0.2144205 0.5124908 0.2155132 0.5124381 0.2158775 0.5126519 0.2144205 0.5124381 0.2158775 0.512386 0.216242 0.5122332 0.2173358 0.512386 0.216242 0.5123345 0.2166065 0.5122332 0.2173358 0.5123345 0.2166065 0.5122836 0.2169712 0.5122332 0.2173358 0.5122332 0.2173358 0.5121834 0.2177006 0.5121341 0.2180655 0.5121341 0.2180655 0.5120854 0.2184303 0.5122332 0.2173358 0.5120854 0.2184303 0.5120373 0.2187954 0.5122332 0.2173358 0.5120373 0.2187954 0.5119897 0.2191604 0.5119426 0.2195256 0.5119426 0.2195256 0.5118962 0.2198908 0.5120373 0.2187954 0.5118962 0.2198908 0.5118502 0.220256 0.5120373 0.2187954 0.5118502 0.220256 0.5118049 0.2206214 0.5117601 0.2209869 0.5117601 0.2209869 0.5117159 0.2213523 0.5116723 0.2217179 0.5116723 0.2217179 0.5116292 0.2220835 0.5115866 0.2224492 0.5115866 0.2224492 0.5115446 0.2228149 0.5116723 0.2217179 0.5115446 0.2228149 0.5115032 0.2231808 0.5116723 0.2217179 0.5115032 0.2231808 0.5114623 0.2235466 0.5113431 0.2246447 0.5114623 0.2235466 0.511422 0.2239126 0.5113431 0.2246447 0.511422 0.2239126 0.5113823 0.2242786 0.5113431 0.2246447 0.5113431 0.2246447 0.5113045 0.2250108 0.5112665 0.225377 0.5112665 0.225377 0.511229 0.2257432 0.5113431 0.2246447 0.511229 0.2257432 0.511192 0.2261095 0.5113431 0.2246447 0.511192 0.2261095 0.5111557 0.2264758 0.5110499 0.2275753 0.5111557 0.2264758 0.5111199 0.2268423 0.5110499 0.2275753 0.5111199 0.2268423 0.5110846 0.2272087 0.5110499 0.2275753 0.5110499 0.2275753 0.5110158 0.2279418 0.5109168 0.2290418 0.5110158 0.2279418 0.5109823 0.2283084 0.5109168 0.2290418 0.5109823 0.2283084 0.5109493 0.2286751 0.5109168 0.2290418 0.5109168 0.2290418 0.510885 0.2294086 0.5108537 0.2297754 0.5108537 0.2297754 0.510823 0.2301423 0.5109168 0.2290418 0.510823 0.2301423 0.5107927 0.2305092 0.5109168 0.2290418 0.5107927 0.2305092 0.5107632 0.2308762 0.5107341 0.2312432 0.5107341 0.2312432 0.5107056 0.2316102 0.5106777 0.2319774 0.5106777 0.2319774 0.5106503 0.2323445 0.5106235 0.2327117 0.5106235 0.2327117 0.5105972 0.2330788 0.5106777 0.2319774 0.5105972 0.2330788 0.5105716 0.2334461 0.5106777 0.2319774 0.5105716 0.2334461 0.5105465 0.2338134 0.510522 0.2341808 0.510522 0.2341808 0.5104979 0.2345482 0.5104745 0.2349156 0.5104745 0.2349156 0.5104517 0.235283 0.5103865 0.2363855 0.5104517 0.235283 0.5104294 0.2356505 0.5103865 0.2363855 0.5104294 0.2356505 0.5104076 0.236018 0.5103865 0.2363855 0.5103865 0.2363855 0.5103659 0.2367531 0.5103458 0.2371207 0.5103458 0.2371207 0.5103263 0.2374883 0.5103074 0.237856 0.5103074 0.237856 0.5102891 0.2382237 0.5102375 0.239327 0.5102891 0.2382237 0.5102713 0.2385914 0.5102375 0.239327 0.5102713 0.2385914 0.5102541 0.2389592 0.5102375 0.239327 0.5102375 0.239327 0.5102214 0.2396948 0.5102058 0.2400626 0.5102058 0.2400626 0.5101909 0.2404305 0.5102375 0.239327 0.5101909 0.2404305 0.5101765 0.2407984 0.5102375 0.239327 0.5101765 0.2407984 0.5101627 0.2411662 0.5101245 0.2422701 0.5101627 0.2411662 0.5101494 0.2415342 0.5101245 0.2422701 0.5101494 0.2415342 0.5101367 0.2419021 0.5101245 0.2422701 0.5101245 0.2422701 0.510113 0.242638 0.5101019 0.243006 0.5101019 0.243006 0.5100915 0.243374 0.5101245 0.2422701 0.5100915 0.243374 0.5100816 0.2437421 0.5101245 0.2422701 0.5100816 0.2437421 0.5100723 0.2441101 0.5100635 0.2444781 0.5100635 0.2444781 0.5100554 0.2448462 0.5100816 0.2437421 0.5100554 0.2448462 0.5100477 0.2452143 0.5100816 0.2437421 0.5100477 0.2452143 0.5100407 0.2455824 0.5100342 0.2459505 0.5100342 0.2459505 0.5100283 0.2463186 0.5100477 0.2452143 0.5100283 0.2463186 0.5100229 0.2466867 0.5100477 0.2452143 0.5100229 0.2466867 0.5100181 0.2470548 0.5100138 0.2474229 0.5100138 0.2474229 0.5100102 0.2477911 0.5100229 0.2466867 0.5100102 0.2477911 0.510007 0.2481592 0.5100229 0.2466867 0.510007 0.2481592 0.5100045 0.2485274 0.5100026 0.2488955 0.5100026 0.2488955 0.5100011 0.2492637 0.5100003 0.2496318 0.5100003 0.2496318 0.51 0.25 0.5100003 0.2503681 0.5100003 0.2503681 0.5100011 0.2507363 0.5100026 0.2511045 0.5100026 0.2511045 0.5100045 0.2514726 0.510007 0.2518408 0.510007 0.2518408 0.5100102 0.2522089 0.5100026 0.2511045 0.5100102 0.2522089 0.5100138 0.252577 0.5100026 0.2511045 0.5100138 0.252577 0.5100181 0.2529451 0.5100229 0.2533133 0.5100229 0.2533133 0.5100283 0.2536814 0.5100342 0.2540495 0.5100342 0.2540495 0.5100407 0.2544176 0.5100477 0.2547857 0.5100477 0.2547857 0.5100554 0.2551538 0.5100342 0.2540495 0.5100554 0.2551538 0.5100635 0.2555218 0.5100342 0.2540495 0.5100635 0.2555218 0.5100723 0.2558899 0.5101019 0.256994 0.5100723 0.2558899 0.5100816 0.2562579 0.5101019 0.256994 0.5100816 0.2562579 0.5100915 0.256626 0.5101019 0.256994 0.5101019 0.256994 0.510113 0.257362 0.5101494 0.2584658 0.510113 0.257362 0.5101245 0.2577299 0.5101494 0.2584658 0.5101245 0.2577299 0.5101367 0.2580979 0.5101494 0.2584658 0.5101494 0.2584658 0.5101627 0.2588337 0.5102058 0.2599374 0.5101627 0.2588337 0.5101765 0.2592016 0.5102058 0.2599374 0.5101765 0.2592016 0.5101909 0.2595695 0.5102058 0.2599374 0.5102058 0.2599374 0.5102214 0.2603052 0.5102375 0.260673 0.5102375 0.260673 0.5102541 0.2610408 0.5102713 0.2614085 0.5102713 0.2614085 0.5102891 0.2617762 0.5103458 0.2628793 0.5102891 0.2617762 0.5103074 0.2621439 0.5103458 0.2628793 0.5103074 0.2621439 0.5103263 0.2625116 0.5103458 0.2628793 0.5103458 0.2628793 0.5103659 0.2632468 0.5103865 0.2636144 0.5103865 0.2636144 0.5104076 0.263982 0.5104294 0.2643495 0.5104294 0.2643495 0.5104517 0.264717 0.510522 0.2658192 0.5104517 0.264717 0.5104745 0.2650844 0.510522 0.2658192 0.5104745 0.2650844 0.5104979 0.2654518 0.510522 0.2658192 0.510522 0.2658192 0.5105465 0.2661865 0.5106235 0.2672883 0.5105465 0.2661865 0.5105716 0.2665538 0.5106235 0.2672883 0.5105716 0.2665538 0.5105972 0.2669211 0.5106235 0.2672883 0.5106235 0.2672883 0.5106503 0.2676555 0.5106777 0.2680226 0.5106777 0.2680226 0.5107056 0.2683897 0.5107341 0.2687568 0.5107341 0.2687568 0.5107632 0.2691238 0.5108537 0.2702245 0.5107632 0.2691238 0.5107927 0.2694907 0.5108537 0.2702245 0.5107927 0.2694907 0.510823 0.2698577 0.5108537 0.2702245 0.5108537 0.2702245 0.510885 0.2705913 0.5109168 0.2709581 0.5109168 0.2709581 0.5109493 0.2713248 0.5109823 0.2716915 0.5109823 0.2716915 0.5110158 0.2720581 0.5111199 0.2731577 0.5110158 0.2720581 0.5110499 0.2724247 0.5111199 0.2731577 0.5110499 0.2724247 0.5110846 0.2727912 0.5111199 0.2731577 0.5111199 0.2731577 0.5111557 0.2735241 0.511192 0.2738904 0.511192 0.2738904 0.511229 0.2742568 0.5111199 0.2731577 0.511229 0.2742568 0.5112665 0.274623 0.5111199 0.2731577 0.5112665 0.274623 0.5113045 0.2749892 0.5113431 0.2753553 0.5113431 0.2753553 0.5113823 0.2757214 0.511422 0.2760874 0.511422 0.2760874 0.5114623 0.2764533 0.5115866 0.2775508 0.5114623 0.2764533 0.5115032 0.2768192 0.5115866 0.2775508 0.5115032 0.2768192 0.5115446 0.277185 0.5115866 0.2775508 0.5115866 0.2775508 0.5116292 0.2779164 0.5117601 0.2790132 0.5116292 0.2779164 0.5116723 0.2782821 0.5117601 0.2790132 0.5116723 0.2782821 0.5117159 0.2786477 0.5117601 0.2790132 0.5117601 0.2790132 0.5118049 0.2793785 0.5118502 0.2797439 0.5118502 0.2797439 0.5118962 0.2801092 0.5117601 0.2790132 0.5118962 0.2801092 0.5119426 0.2804744 0.5117601 0.2790132 0.5119426 0.2804744 0.5119897 0.2808396 0.5120373 0.2812046 0.5120373 0.2812046 0.5120854 0.2815696 0.5119426 0.2804744 0.5120854 0.2815696 0.5121341 0.2819345 0.5119426 0.2804744 0.5121341 0.2819345 0.5121834 0.2822993 0.5122332 0.2826641 0.5122332 0.2826641 0.5122836 0.2830289 0.5123345 0.2833935 0.5123345 0.2833935 0.512386 0.283758 0.5125439 0.2848511 0.512386 0.283758 0.5124381 0.2841224 0.5125439 0.2848511 0.5124381 0.2841224 0.5124908 0.2844868 0.5125439 0.2848511 0.5125439 0.2848511 0.5125976 0.2852153 0.5126519 0.2855795 0.5126519 0.2855795 0.5127068 0.2859435 0.5127622 0.2863075 0.5127622 0.2863075 0.5128182 0.2866714 0.5129895 0.2877624 0.5128182 0.2866714 0.5128747 0.2870351 0.5129895 0.2877624 0.5128747 0.2870351 0.5129318 0.2873988 0.5129895 0.2877624 0.5129895 0.2877624 0.5130477 0.2881259 0.5131065 0.2884894 0.5131065 0.2884894 0.5131658 0.2888527 0.5132256 0.289216 0.5132256 0.289216 0.5132861 0.2895792 0.513347 0.2899422 0.513347 0.2899422 0.5134086 0.2903052 0.5134707 0.2906681 0.5134707 0.2906681 0.5135334 0.2910308 0.5135966 0.2913935 0.5135966 0.2913935 0.5136604 0.2917561 0.5134707 0.2906681 0.5136604 0.2917561 0.5137247 0.2921186 0.5134707 0.2906681 0.5137247 0.2921186 0.5137896 0.292481 0.5139876 0.2935676 0.5137896 0.292481 0.513855 0.2928433 0.5139876 0.2935676 0.513855 0.2928433 0.513921 0.2932055 0.5139876 0.2935676 0.5139876 0.2935676 0.5140547 0.2939296 0.5142593 0.2950149 0.5140547 0.2939296 0.5141224 0.2942914 0.5142593 0.2950149 0.5141224 0.2942914 0.5141906 0.2946532 0.5142593 0.2950149 0.5142593 0.2950149 0.5143287 0.2953765 0.5143986 0.2957379 0.5143986 0.2957379 0.514469 0.2960993 0.51454 0.2964605 0.51454 0.2964605 0.5146116 0.2968217 0.5146837 0.2971827 0.5146837 0.2971827 0.5147563 0.2975436 0.5148295 0.2979044 0.5148295 0.2979044 0.5149033 0.2982651 0.5149776 0.2986257 0.5149776 0.2986257 0.5150524 0.2989861 0.5148295 0.2979044 0.5150524 0.2989861 0.5151278 0.2993465 0.5148295 0.2979044 0.5151278 0.2993465 0.5152038 0.2997067 0.5152804 0.3000668 0.5152804 0.3000668 0.5153574 0.3004269 0.5154351 0.3007867 0.5154351 0.3007867 0.5155133 0.3011465 0.515592 0.3015061 0.515592 0.3015061 0.5156713 0.3018656 0.5157511 0.302225 0.5157511 0.302225 0.5158315 0.3025843 0.5159124 0.3029434 0.5159124 0.3029434 0.515994 0.3033025 0.516076 0.3036614 0.516076 0.3036614 0.5161586 0.3040201 0.5164096 0.3050957 0.5161586 0.3040201 0.5162417 0.3043788 0.5164096 0.3050957 0.5162417 0.3043788 0.5163254 0.3047373 0.5164096 0.3050957 0.5164096 0.3050957 0.5164944 0.305454 0.5165798 0.3058121 0.5165798 0.3058121 0.5166656 0.3061701 0.5167521 0.3065279 0.5167521 0.3065279 0.5168391 0.3068857 0.5169267 0.3072432 0.5169267 0.3072432 0.5170147 0.3076007 0.5171033 0.3079581 0.5171033 0.3079581 0.5171925 0.3083152 0.5172823 0.3086723 0.5172823 0.3086723 0.5173725 0.3090292 0.5174633 0.309386 0.5174633 0.309386 0.5175547 0.3097426 0.5178321 0.3108117 0.5175547 0.3097426 0.5176466 0.3100991 0.5178321 0.3108117 0.5176466 0.3100991 0.5177391 0.3104555 0.5178321 0.3108117 0.5178321 0.3108117 0.5179256 0.3111678 0.5180197 0.3115237 0.5180197 0.3115237 0.5181144 0.3118795 0.5178321 0.3108117 0.5181144 0.3118795 0.5182096 0.3122351 0.5178321 0.3108117 0.5182096 0.3122351 0.5183054 0.3125906 0.5184016 0.3129459 0.5184016 0.3129459 0.5184985 0.3133011 0.5185958 0.3136562 0.5185958 0.3136562 0.5186938 0.314011 0.5187922 0.3143658 0.5187922 0.3143658 0.5188912 0.3147204 0.5189908 0.3150748 0.5189908 0.3150748 0.5190909 0.3154291 0.5191915 0.3157833 0.5191915 0.3157833 0.5192927 0.3161373 0.5193944 0.3164911 0.5193944 0.3164911 0.5194967 0.3168447 0.5195995 0.3171982 0.5195995 0.3171982 0.5197029 0.3175516 0.5198068 0.3179048 0.5198068 0.3179048 0.5199112 0.3182578 0.5202277 0.3193159 0.5199112 0.3182578 0.5200161 0.3186107 0.5202277 0.3193159 0.5200161 0.3186107 0.5201217 0.3189634 0.5202277 0.3193159 0.5202277 0.3193159 0.5203343 0.3196683 0.5204415 0.3200206 0.5204415 0.3200206 0.5205491 0.3203726 0.5206574 0.3207245 0.5206574 0.3207245 0.5207661 0.3210762 0.5208755 0.3214278 0.5208755 0.3214278 0.5209853 0.3217791 0.5210956 0.3221304 0.5210956 0.3221304 0.5212066 0.3224814 0.5215426 0.3235335 0.5212066 0.3224814 0.521318 0.3228323 0.5215426 0.3235335 0.521318 0.3228323 0.52143 0.323183 0.5215426 0.3235335 0.5215426 0.3235335 0.5216556 0.3238839 0.5217692 0.3242341 0.5217692 0.3242341 0.5218834 0.3245841 0.5219981 0.324934 0.5219981 0.324934 0.5221133 0.3252836 0.5224621 0.3263316 0.5221133 0.3252836 0.522229 0.3256331 0.5224621 0.3263316 0.522229 0.3256331 0.5223453 0.3259824 0.5224621 0.3263316 0.5224621 0.3263316 0.5225794 0.3266805 0.5229347 0.3277263 0.5225794 0.3266805 0.5226973 0.3270292 0.5229347 0.3277263 0.5226973 0.3270292 0.5228158 0.3273779 0.5229347 0.3277263 0.5229347 0.3277263 0.5230543 0.3280745 0.5231743 0.3284225 0.5231743 0.3284225 0.5232949 0.3287703 0.5234159 0.329118 0.5234159 0.329118 0.5235376 0.3294655 0.5239056 0.3305068 0.5235376 0.3294655 0.5236598 0.3298128 0.5239056 0.3305068 0.5236598 0.3298128 0.5237824 0.3301599 0.5239056 0.3305068 0.5239056 0.3305068 0.5240294 0.3308536 0.5241537 0.3312001 0.5241537 0.3312001 0.5242785 0.3315464 0.5244039 0.3318926 0.5244039 0.3318926 0.5245298 0.3322386 0.5249106 0.3332753 0.5245298 0.3322386 0.5246562 0.3325843 0.5249106 0.3332753 0.5246562 0.3325843 0.5247831 0.3329299 0.5249106 0.3332753 0.5249106 0.3332753 0.5250387 0.3336205 0.5251672 0.3339655 0.5251672 0.3339655 0.5252963 0.3343102 0.5249106 0.3332753 0.5252963 0.3343102 0.5254259 0.3346549 0.5249106 0.3332753 0.5254259 0.3346549 0.525556 0.3349993 0.5256866 0.3353434 0.5256866 0.3353434 0.5258178 0.3356874 0.5259495 0.3360312 0.5259495 0.3360312 0.5260818 0.3363748 0.5262145 0.3367182 0.5262145 0.3367182 0.5263478 0.3370614 0.5264816 0.3374043 0.5264816 0.3374043 0.5266159 0.3377471 0.5267508 0.3380897 0.5267508 0.3380897 0.5268862 0.338432 0.5270221 0.3387742 0.5270221 0.3387742 0.5271586 0.3391161 0.5272955 0.3394579 0.5272955 0.3394579 0.527433 0.3397994 0.5270221 0.3387742 0.527433 0.3397994 0.527571 0.3401407 0.5270221 0.3387742 0.527571 0.3401407 0.5277096 0.3404818 0.5278486 0.3408226 0.5278486 0.3408226 0.5279882 0.3411633 0.5281283 0.3415038 0.5281283 0.3415038 0.5282689 0.341844 0.5284101 0.342184 0.5284101 0.342184 0.5285518 0.3425239 0.5286939 0.3428635 0.5286939 0.3428635 0.5288366 0.3432028 0.5289799 0.3435419 0.5289799 0.3435419 0.5291236 0.3438809 0.5286939 0.3428635 0.5291236 0.3438809 0.5292679 0.3442196 0.5286939 0.3428635 0.5292679 0.3442196 0.5294127 0.3445581 0.529558 0.3448964 0.529558 0.3448964 0.5297039 0.3452344 0.5292679 0.3442196 0.5297039 0.3452344 0.5298502 0.3455722 0.5292679 0.3442196 0.5298502 0.3455722 0.529997 0.3459098 0.5301444 0.3462471 0.5301444 0.3462471 0.5302923 0.3465843 0.5298502 0.3455722 0.5302923 0.3465843 0.5304408 0.3469212 0.5298502 0.3455722 0.5304408 0.3469212 0.5305897 0.3472579 0.5310396 0.3482666 0.5305897 0.3472579 0.5307391 0.3475944 0.5310396 0.3482666 0.5307391 0.3475944 0.5308891 0.3479306 0.5310396 0.3482666 0.5310396 0.3482666 0.5311906 0.3486024 0.531342 0.3489379 0.531342 0.3489379 0.5314941 0.3492732 0.5310396 0.3482666 0.5314941 0.3492732 0.5316466 0.3496083 0.5310396 0.3482666 0.5316466 0.3496083 0.5317997 0.3499431 0.5319533 0.3502777 0.5319533 0.3502777 0.5321074 0.3506121 0.5322619 0.3509462 0.5322619 0.3509462 0.5324171 0.35128 0.5325726 0.3516137 0.5325726 0.3516137 0.5327288 0.3519471 0.5328854 0.3522803 0.5328854 0.3522803 0.5330426 0.3526132 0.5332003 0.3529459 0.5332003 0.3529459 0.5333584 0.3532783 0.5335171 0.3536105 0.5335171 0.3536105 0.5336763 0.3539425 0.533836 0.3542742 0.533836 0.3542742 0.5339962 0.3546057 0.5341569 0.3549369 0.5341569 0.3549369 0.5343182 0.3552679 0.5344799 0.3555986 0.5344799 0.3555986 0.5346421 0.3559291 0.5341569 0.3549369 0.5346421 0.3559291 0.5348049 0.3562594 0.5341569 0.3549369 0.5348049 0.3562594 0.5349681 0.3565893 0.5351319 0.3569191 0.5351319 0.3569191 0.5352962 0.3572485 0.5348049 0.3562594 0.5352962 0.3572485 0.5354609 0.3575778 0.5348049 0.3562594 0.5354609 0.3575778 0.5356262 0.3579067 0.5357919 0.3582354 0.5357919 0.3582354 0.5359582 0.3585639 0.536125 0.3588921 0.536125 0.3588921 0.5362923 0.35922 0.5364601 0.3595477 0.5364601 0.3595477 0.5366284 0.3598752 0.5367972 0.3602024 0.5367972 0.3602024 0.5369665 0.3605293 0.5371363 0.3608559 0.5371363 0.3608559 0.5373066 0.3611823 0.5374774 0.3615085 0.5374774 0.3615085 0.5376487 0.3618344 0.5378205 0.36216 0.5378205 0.36216 0.5379928 0.3624853 0.5374774 0.3615085 0.5379928 0.3624853 0.5381656 0.3628104 0.5374774 0.3615085 0.5381656 0.3628104 0.5383389 0.3631352 0.5388618 0.364108 0.5383389 0.3631352 0.5385127 0.3634598 0.5388618 0.364108 0.5385127 0.3634598 0.538687 0.363784 0.5388618 0.364108 0.5388618 0.364108 0.5390371 0.3644318 0.5392128 0.3647553 0.5392128 0.3647553 0.5393891 0.3650785 0.5388618 0.364108 0.5393891 0.3650785 0.5395659 0.3654015 0.5388618 0.364108 0.5395659 0.3654015 0.5397432 0.3657241 0.5399209 0.3660465 0.5399209 0.3660465 0.5400992 0.3663686 0.540278 0.3666905 0.540278 0.3666905 0.5404572 0.367012 0.540637 0.3673334 0.540637 0.3673334 0.5408172 0.3676543 0.5409979 0.3679751 0.5409979 0.3679751 0.5411791 0.3682956 0.5417258 0.3692553 0.5411791 0.3682956 0.5413609 0.3686158 0.5417258 0.3692553 0.5413609 0.3686158 0.541543 0.3689357 0.5417258 0.3692553 0.5417258 0.3692553 0.5419089 0.3695746 0.5424614 0.370531 0.5419089 0.3695746 0.5420926 0.3698937 0.5424614 0.370531 0.5420926 0.3698937 0.5422767 0.3702125 0.5424614 0.370531 0.5424614 0.370531 0.5426465 0.3708492 0.5432049 0.3718022 0.5426465 0.3708492 0.5428321 0.3711671 0.5432049 0.3718022 0.5428321 0.3711671 0.5430182 0.3714848 0.5432049 0.3718022 0.5432049 0.3718022 0.543392 0.3721193 0.5435795 0.3724361 0.5435795 0.3724361 0.5437676 0.3727526 0.5439561 0.3730688 0.5439561 0.3730688 0.5441451 0.3733847 0.5443347 0.3737003 0.5443347 0.3737003 0.5445247 0.3740156 0.5447151 0.3743306 0.5447151 0.3743306 0.5449061 0.3746454 0.5450975 0.3749599 0.5450975 0.3749599 0.5452895 0.3752741 0.5447151 0.3743306 0.5452895 0.3752741 0.5454819 0.3755879 0.5447151 0.3743306 0.5454819 0.3755879 0.5456748 0.3759015 0.5458682 0.3762148 0.5458682 0.3762148 0.546062 0.3765278 0.5462563 0.3768405 0.5462563 0.3768405 0.5464511 0.3771529 0.5466464 0.377465 0.5466464 0.377465 0.5468422 0.3777768 0.5470384 0.3780882 0.5470384 0.3780882 0.5472351 0.3783994 0.5474324 0.3787103 0.5474324 0.3787103 0.54763 0.3790209 0.5478282 0.3793312 0.5478282 0.3793312 0.5480268 0.3796412 0.5482259 0.3799508 0.5482259 0.3799508 0.5484255 0.3802602 0.5478282 0.3793312 0.5484255 0.3802602 0.5486255 0.3805692 0.5478282 0.3793312 0.5486255 0.3805692 0.5488261 0.380878 0.5494305 0.3818024 0.5488261 0.380878 0.5490271 0.3811864 0.5494305 0.3818024 0.5490271 0.3811864 0.5492286 0.3814946 0.5494305 0.3818024 0.5494305 0.3818024 0.5496329 0.3821099 0.550243 0.3830306 0.5496329 0.3821099 0.5498358 0.3824171 0.550243 0.3830306 0.5498358 0.3824171 0.5500392 0.382724 0.550243 0.3830306 0.550243 0.3830306 0.5504473 0.3833369 0.5506521 0.3836428 0.5506521 0.3836428 0.5508573 0.3839485 0.550243 0.3830306 0.5508573 0.3839485 0.551063 0.3842537 0.550243 0.3830306 0.551063 0.3842537 0.5512692 0.3845588 0.5518906 0.3854719 0.5512692 0.3845588 0.5514758 0.3848634 0.5518906 0.3854719 0.5514758 0.3848634 0.551683 0.3851678 0.5518906 0.3854719 0.5518906 0.3854719 0.5520986 0.3857756 0.5523071 0.3860791 0.5523071 0.3860791 0.5525161 0.3863822 0.5518906 0.3854719 0.5525161 0.3863822 0.5527255 0.3866849 0.5518906 0.3854719 0.5527255 0.3866849 0.5529354 0.3869874 0.5531458 0.3872895 0.5531458 0.3872895 0.5533566 0.3875913 0.5535679 0.3878928 0.5535679 0.3878928 0.5537797 0.388194 0.5539919 0.3884948 0.5539919 0.3884948 0.5542046 0.3887953 0.5535679 0.3878928 0.5542046 0.3887953 0.5544177 0.3890955 0.5535679 0.3878928 0.5544177 0.3890955 0.5546313 0.3893954 0.5548453 0.3896949 0.5548453 0.3896949 0.5550599 0.3899941 0.5552749 0.390293 0.5552749 0.390293 0.5554903 0.3905915 0.5557062 0.3908897 0.5557062 0.3908897 0.5559225 0.3911876 0.5552749 0.390293 0.5559225 0.3911876 0.5561394 0.3914851 0.5552749 0.390293 0.5561394 0.3914851 0.5563566 0.3917824 0.5565744 0.3920792 0.5565744 0.3920792 0.5567925 0.3923758 0.5561394 0.3914851 0.5567925 0.3923758 0.5570111 0.392672 0.5561394 0.3914851 0.5570111 0.392672 0.5572302 0.3929678 0.5574498 0.3932633 0.5574498 0.3932633 0.5576698 0.3935586 0.5578902 0.3938534 0.5578902 0.3938534 0.5581111 0.3941479 0.5583325 0.3944422 0.5583325 0.3944422 0.5585542 0.394736 0.5578902 0.3938534 0.5585542 0.394736 0.5587764 0.3950295 0.5578902 0.3938534 0.5587764 0.3950295 0.5589991 0.3953226 0.5592223 0.3956155 0.5592223 0.3956155 0.5594459 0.3959079 0.5587764 0.3950295 0.5594459 0.3959079 0.55967 0.3962001 0.5587764 0.3950295 0.55967 0.3962001 0.5598945 0.3964919 0.5601194 0.3967833 0.5601194 0.3967833 0.5603448 0.3970744 0.55967 0.3962001 0.5603448 0.3970744 0.5605706 0.3973652 0.55967 0.3962001 0.5605706 0.3973652 0.5607969 0.3976556 0.5610236 0.3979457 0.5610236 0.3979457 0.5612508 0.3982354 0.5614784 0.3985247 0.5614784 0.3985247 0.5617064 0.3988137 0.561935 0.3991024 0.561935 0.3991024 0.5621638 0.3993907 0.5614784 0.3985247 0.5621638 0.3993907 0.5623933 0.3996787 0.5614784 0.3985247 0.5623933 0.3996787 0.5626231 0.3999663 0.5628533 0.4002535 0.5628533 0.4002535 0.563084 0.4005404 0.5633152 0.400827 0.5633152 0.400827 0.5635468 0.4011132 0.5637788 0.401399 0.5637788 0.401399 0.5640113 0.4016845 0.5633152 0.400827 0.5640113 0.4016845 0.5642442 0.4019696 0.5633152 0.400827 0.5642442 0.4019696 0.5644775 0.4022544 0.5647113 0.4025388 0.5647113 0.4025388 0.5649455 0.4028229 0.5642442 0.4019696 0.5649455 0.4028229 0.5651801 0.4031065 0.5642442 0.4019696 0.5651801 0.4031065 0.5654152 0.4033899 0.5656507 0.4036728 0.5656507 0.4036728 0.5658867 0.4039555 0.5661231 0.4042377 0.5661231 0.4042377 0.5663599 0.4045196 0.5670729 0.405363 0.5663599 0.4045196 0.5665971 0.4048011 0.5670729 0.405363 0.5665971 0.4048011 0.5668348 0.4050822 0.5670729 0.405363 0.5670729 0.405363 0.5673115 0.4056435 0.5675504 0.4059235 0.5675504 0.4059235 0.5677898 0.4062032 0.5680297 0.4064825 0.5680297 0.4064825 0.5682699 0.4067615 0.5685106 0.4070401 0.5685106 0.4070401 0.5687517 0.4073183 0.5689932 0.4075961 0.5689932 0.4075961 0.5692352 0.4078736 0.5694776 0.4081507 0.5694776 0.4081507 0.5697204 0.4084274 0.5689932 0.4075961 0.5697204 0.4084274 0.5699636 0.4087038 0.5689932 0.4075961 0.5699636 0.4087038 0.5702072 0.4089798 0.5704514 0.4092554 0.5704514 0.4092554 0.5706959 0.4095306 0.5709408 0.4098055 0.5709408 0.4098055 0.5711861 0.41008 0.5714319 0.4103541 0.5714319 0.4103541 0.5716781 0.4106279 0.5719247 0.4109011 0.5719247 0.4109011 0.5721718 0.4111741 0.5724192 0.4114468 0.5724192 0.4114468 0.5726671 0.411719 0.5719247 0.4109011 0.5726671 0.411719 0.5729153 0.4119908 0.5719247 0.4109011 0.5729153 0.4119908 0.5731641 0.4122623 0.5734131 0.4125334 0.5734131 0.4125334 0.5736626 0.412804 0.5739126 0.4130743 0.5739126 0.4130743 0.574163 0.4133442 0.5744138 0.4136138 0.5744138 0.4136138 0.574665 0.4138829 0.5749166 0.4141517 0.5749166 0.4141517 0.5751686 0.4144201 0.575421 0.4146881 0.575421 0.4146881 0.5756738 0.4149557 0.5749166 0.4141517 0.5756738 0.4149557 0.5759271 0.4152229 0.5749166 0.4141517 0.5759271 0.4152229 0.5761807 0.4154897 0.5764348 0.4157562 0.5764348 0.4157562 0.5766893 0.4160223 0.5769441 0.4162879 0.5769441 0.4162879 0.5771994 0.4165531 0.5779677 0.4173466 0.5771994 0.4165531 0.5774551 0.416818 0.5779677 0.4173466 0.5774551 0.416818 0.5777112 0.4170825 0.5779677 0.4173466 0.5779677 0.4173466 0.5782246 0.4176103 0.5789977 0.418399 0.5782246 0.4176103 0.5784819 0.4178736 0.5789977 0.418399 0.5784819 0.4178736 0.5787397 0.4181365 0.5789977 0.418399 0.5789977 0.418399 0.5792563 0.4186611 0.5795152 0.4189229 0.5795152 0.4189229 0.5797745 0.4191842 0.5800343 0.4194451 0.5800343 0.4194451 0.5802944 0.4197056 0.5805549 0.4199658 0.5805549 0.4199658 0.5808158 0.4202255 0.5800343 0.4194451 0.5808158 0.4202255 0.5810772 0.4204848 0.5800343 0.4194451 0.5810772 0.4204848 0.5813389 0.4207437 0.581601 0.4210023 0.581601 0.4210023 0.5818635 0.4212604 0.5821264 0.4215181 0.5821264 0.4215181 0.5823897 0.4217754 0.5826534 0.4220323 0.5826534 0.4220323 0.5829175 0.4222888 0.583182 0.4225449 0.583182 0.4225449 0.5834469 0.4228006 0.5842438 0.4235652 0.5834469 0.4228006 0.5837121 0.4230559 0.5842438 0.4235652 0.5837121 0.4230559 0.5839778 0.4233108 0.5842438 0.4235652 0.5842438 0.4235652 0.5845103 0.4238193 0.5847771 0.4240729 0.5847771 0.4240729 0.5850443 0.4243262 0.5842438 0.4235652 0.5850443 0.4243262 0.5853119 0.424579 0.5842438 0.4235652 0.5853119 0.424579 0.5855799 0.4248315 0.5863862 0.4255862 0.5855799 0.4248315 0.5858483 0.4250835 0.5863862 0.4255862 0.5858483 0.4250835 0.586117 0.4253351 0.5863862 0.4255862 0.5863862 0.4255862 0.5866557 0.425837 0.5869257 0.4260874 0.5869257 0.4260874 0.587196 0.4263373 0.5874667 0.4265869 0.5874667 0.4265869 0.5877377 0.426836 0.5880092 0.4270847 0.5880092 0.4270847 0.588281 0.4273329 0.5874667 0.4265869 0.588281 0.4273329 0.5885533 0.4275808 0.5874667 0.4265869 0.5885533 0.4275808 0.5888258 0.4278283 0.5890988 0.4280753 0.5890988 0.4280753 0.5893722 0.4283219 0.5896459 0.4285681 0.5896459 0.4285681 0.5899201 0.4288139 0.5901945 0.4290592 0.5901945 0.4290592 0.5904694 0.4293041 0.5907446 0.4295486 0.5907446 0.4295486 0.5910202 0.4297927 0.5912962 0.4300364 0.5912962 0.4300364 0.5915725 0.4302796 0.5907446 0.4295486 0.5915725 0.4302796 0.5918493 0.4305225 0.5907446 0.4295486 0.5918493 0.4305225 0.5921264 0.4307649 0.5924039 0.4310068 0.5924039 0.4310068 0.5926817 0.4312483 0.59296 0.4314894 0.59296 0.4314894 0.5932385 0.4317301 0.5935175 0.4319704 0.5935175 0.4319704 0.5937968 0.4322102 0.59296 0.4314894 0.5937968 0.4322102 0.5940765 0.4324496 0.59296 0.4314894 0.5940765 0.4324496 0.5943565 0.4326885 0.5951989 0.4334029 0.5943565 0.4326885 0.594637 0.4329271 0.5951989 0.4334029 0.594637 0.4329271 0.5949178 0.4331652 0.5951989 0.4334029 0.5951989 0.4334029 0.5954805 0.4336401 0.5963272 0.4343493 0.5954805 0.4336401 0.5957623 0.4338769 0.5963272 0.4343493 0.5957623 0.4338769 0.5960446 0.4341133 0.5963272 0.4343493 0.5963272 0.4343493 0.5966101 0.4345848 0.5968934 0.4348199 0.5968934 0.4348199 0.5971772 0.4350546 0.5963272 0.4343493 0.5971772 0.4350546 0.5974612 0.4352887 0.5963272 0.4343493 0.5974612 0.4352887 0.5977456 0.4355225 0.5980304 0.4357559 0.5980304 0.4357559 0.5983155 0.4359887 0.598601 0.4362212 0.598601 0.4362212 0.5988869 0.4364532 0.5997465 0.4371467 0.5988869 0.4364532 0.599173 0.4366848 0.5997465 0.4371467 0.599173 0.4366848 0.5994596 0.4369159 0.5997465 0.4371467 0.5997465 0.4371467 0.6000337 0.4373769 0.6003214 0.4376068 0.6003214 0.4376068 0.6006093 0.4378361 0.5997465 0.4371467 0.6006093 0.4378361 0.6008976 0.4380651 0.5997465 0.4371467 0.6008976 0.4380651 0.6011863 0.4382936 0.6014752 0.4385216 0.6014752 0.4385216 0.6017646 0.4387493 0.6020544 0.4389764 0.6020544 0.4389764 0.6023444 0.4392032 0.6026348 0.4394294 0.6026348 0.4394294 0.6029256 0.4396553 0.6020544 0.4389764 0.6029256 0.4396553 0.6032167 0.4398806 0.6020544 0.4389764 0.6032167 0.4398806 0.6035081 0.4401056 0.6043846 0.4407777 0.6035081 0.4401056 0.6037999 0.44033 0.6043846 0.4407777 0.6037999 0.44033 0.6040921 0.4405541 0.6043846 0.4407777 0.6043846 0.4407777 0.6046774 0.4410009 0.6049705 0.4412236 0.6049705 0.4412236 0.605264 0.4414458 0.6055579 0.4416676 0.6055579 0.4416676 0.605852 0.4418889 0.6067367 0.4425503 0.605852 0.4418889 0.6061466 0.4421098 0.6067367 0.4425503 0.6061466 0.4421098 0.6064414 0.4423303 0.6067367 0.4425503 0.6067367 0.4425503 0.6070322 0.4427698 0.6073281 0.4429889 0.6073281 0.4429889 0.6076242 0.4432075 0.6079208 0.4434257 0.6079208 0.4434257 0.6082177 0.4436434 0.6085149 0.4438607 0.6085149 0.4438607 0.6088125 0.4440775 0.6079208 0.4434257 0.6088125 0.4440775 0.6091103 0.4442939 0.6079208 0.4434257 0.6091103 0.4442939 0.6094085 0.4445097 0.6097071 0.4447252 0.6097071 0.4447252 0.6100059 0.4449402 0.6103051 0.4451547 0.6103051 0.4451547 0.6106047 0.4453687 0.6109045 0.4455823 0.6109045 0.4455823 0.6112047 0.4457954 0.6103051 0.4451547 0.6112047 0.4457954 0.6115052 0.4460082 0.6103051 0.4451547 0.6115052 0.4460082 0.611806 0.4462203 0.6121072 0.4464321 0.6121072 0.4464321 0.6124087 0.4466434 0.6115052 0.4460082 0.6124087 0.4466434 0.6127105 0.4468542 0.6115052 0.4460082 0.6127105 0.4468542 0.6130126 0.4470646 0.6133151 0.4472745 0.6133151 0.4472745 0.6136178 0.447484 0.6127105 0.4468542 0.6136178 0.447484 0.6139209 0.4476929 0.6127105 0.4468542 0.6139209 0.4476929 0.6142244 0.4479014 0.6145281 0.4481095 0.6145281 0.4481095 0.6148322 0.4483171 0.6151365 0.4485242 0.6151365 0.4485242 0.6154412 0.4487308 0.6157463 0.448937 0.6157463 0.448937 0.6160516 0.4491427 0.6151365 0.4485242 0.6160516 0.4491427 0.6163572 0.4493479 0.6151365 0.4485242 0.6163572 0.4493479 0.6166632 0.4495527 0.6175829 0.4501642 0.6166632 0.4495527 0.6169694 0.449757 0.6175829 0.4501642 0.6169694 0.449757 0.617276 0.4499608 0.6175829 0.4501642 0.6175829 0.4501642 0.6178901 0.4503671 0.6181976 0.4505695 0.6181976 0.4505695 0.6185054 0.4507715 0.6188136 0.4509729 0.6188136 0.4509729 0.619122 0.4511739 0.6194308 0.4513745 0.6194308 0.4513745 0.6197398 0.4515745 0.6188136 0.4509729 0.6197398 0.4515745 0.6200492 0.4517741 0.6188136 0.4509729 0.6200492 0.4517741 0.6203588 0.4519732 0.6206688 0.4521718 0.6206688 0.4521718 0.6209791 0.45237 0.6200492 0.4517741 0.6209791 0.45237 0.6212897 0.4525676 0.6200492 0.4517741 0.6212897 0.4525676 0.6216006 0.4527649 0.6225351 0.4533536 0.6216006 0.4527649 0.6219118 0.4529616 0.6225351 0.4533536 0.6219118 0.4529616 0.6222233 0.4531578 0.6225351 0.4533536 0.6225351 0.4533536 0.6228471 0.4535489 0.6237852 0.4541319 0.6228471 0.4535489 0.6231595 0.4537437 0.6237852 0.4541319 0.6231595 0.4537437 0.6234722 0.453938 0.6237852 0.4541319 0.6237852 0.4541319 0.6240985 0.4543253 0.6244121 0.4545181 0.6244121 0.4545181 0.6247259 0.4547106 0.6237852 0.4541319 0.6247259 0.4547106 0.6250401 0.4549025 0.6237852 0.4541319 0.6250401 0.4549025 0.6253545 0.4550939 0.6256694 0.4552849 0.6256694 0.4552849 0.6259844 0.4554753 0.6262997 0.4556654 0.6262997 0.4556654 0.6266154 0.4558548 0.627564 0.4564205 0.6266154 0.4558548 0.6269313 0.4560439 0.627564 0.4564205 0.6269313 0.4560439 0.6272475 0.4562324 0.627564 0.4564205 0.627564 0.4564205 0.6278808 0.4566081 0.6288328 0.4571679 0.6278808 0.4566081 0.6281979 0.4567952 0.6288328 0.4571679 0.6281979 0.4567952 0.6285152 0.4569817 0.6288328 0.4571679 0.6288328 0.4571679 0.6291508 0.4573535 0.629469 0.4575386 0.629469 0.4575386 0.6297875 0.4577233 0.6301063 0.4579074 0.6301063 0.4579074 0.6304253 0.4580911 0.6313843 0.4586392 0.6304253 0.4580911 0.6307447 0.4582743 0.6313843 0.4586392 0.6307447 0.4582743 0.6310644 0.4584569 0.6313843 0.4586392 0.6313843 0.4586392 0.6317045 0.4588209 0.6320249 0.4590021 0.6320249 0.4590021 0.6323456 0.4591828 0.6326667 0.4593631 0.6326667 0.4593631 0.632988 0.4595428 0.6333096 0.4597221 0.6333096 0.4597221 0.6336314 0.4599008 0.6339535 0.460079 0.6339535 0.460079 0.6342759 0.4602568 0.6345986 0.4604341 0.6345986 0.4604341 0.6349215 0.4606109 0.6352447 0.4607871 0.6352447 0.4607871 0.6355682 0.460963 0.6358919 0.4611382 0.6358919 0.4611382 0.6362159 0.461313 0.6365402 0.4614873 0.6365402 0.4614873 0.6368648 0.4616611 0.63784 0.4621795 0.6368648 0.4616611 0.6371896 0.4618344 0.63784 0.4621795 0.6371896 0.4618344 0.6375147 0.4620072 0.63784 0.4621795 0.63784 0.4621795 0.6381657 0.4623513 0.6384915 0.4625226 0.6384915 0.4625226 0.6388177 0.4626934 0.6391441 0.4628637 0.6391441 0.4628637 0.6394707 0.4630335 0.6397976 0.4632028 0.6397976 0.4632028 0.6401248 0.4633716 0.6404523 0.4635399 0.6404523 0.4635399 0.64078 0.4637077 0.6411079 0.463875 0.6411079 0.463875 0.6414361 0.4640418 0.6404523 0.4635399 0.6414361 0.4640418 0.6417646 0.4642081 0.6404523 0.4635399 0.6417646 0.4642081 0.6420933 0.4643738 0.6424223 0.4645391 0.6424223 0.4645391 0.6427515 0.4647039 0.6417646 0.4642081 0.6427515 0.4647039 0.643081 0.4648681 0.6417646 0.4642081 0.643081 0.4648681 0.6434107 0.4650319 0.6437407 0.4651951 0.6437407 0.4651951 0.6440709 0.4653579 0.6444014 0.4655202 0.6444014 0.4655202 0.6447321 0.4656819 0.6450631 0.4658431 0.6450631 0.4658431 0.6453943 0.4660038 0.6457258 0.466164 0.6457258 0.466164 0.6460575 0.4663237 0.6463894 0.4664829 0.6463894 0.4664829 0.6467217 0.4666416 0.6470541 0.4667997 0.6470541 0.4667997 0.6473868 0.4669575 0.6477197 0.4671146 0.6477197 0.4671146 0.6480529 0.4672712 0.6483863 0.4674273 0.6483863 0.4674273 0.6487199 0.467583 0.6490538 0.4677381 0.6490538 0.4677381 0.649388 0.4678927 0.6483863 0.4674273 0.649388 0.4678927 0.6497223 0.4680467 0.6483863 0.4674273 0.6497223 0.4680467 0.6500569 0.4682003 0.6503918 0.4683533 0.6503918 0.4683533 0.6507268 0.4685059 0.6497223 0.4680467 0.6507268 0.4685059 0.6510621 0.4686579 0.6497223 0.4680467 0.6510621 0.4686579 0.6513977 0.4688094 0.6517334 0.4689604 0.6517334 0.4689604 0.6520694 0.4691109 0.6524056 0.4692609 0.6524056 0.4692609 0.6527421 0.4694103 0.6537528 0.4698556 0.6527421 0.4694103 0.6530788 0.4695593 0.6537528 0.4698556 0.6530788 0.4695593 0.6534157 0.4697077 0.6537528 0.4698556 0.6537528 0.4698556 0.6540902 0.470003 0.6544278 0.4701498 0.6544278 0.4701498 0.6547656 0.4702962 0.6551036 0.470442 0.6551036 0.470442 0.6554419 0.4705873 0.6557804 0.4707321 0.6557804 0.4707321 0.6561191 0.4708764 0.6551036 0.470442 0.6561191 0.4708764 0.656458 0.4710201 0.6551036 0.470442 0.656458 0.4710201 0.6567972 0.4711633 0.6571366 0.4713061 0.6571366 0.4713061 0.6574761 0.4714483 0.6578159 0.4715899 0.6578159 0.4715899 0.658156 0.4717311 0.6591774 0.4721514 0.658156 0.4717311 0.6584962 0.4718717 0.6591774 0.4721514 0.6584962 0.4718717 0.6588367 0.4720118 0.6591774 0.4721514 0.6591774 0.4721514 0.6595183 0.4722905 0.6598593 0.472429 0.6598593 0.472429 0.6602006 0.472567 0.6591774 0.4721514 0.6602006 0.472567 0.6605421 0.4727045 0.6591774 0.4721514 0.6605421 0.4727045 0.6608839 0.4728415 0.6612258 0.4729779 0.6612258 0.4729779 0.661568 0.4731138 0.6605421 0.4727045 0.661568 0.4731138 0.6619103 0.4732492 0.6605421 0.4727045 0.6619103 0.4732492 0.6622529 0.4733841 0.6625956 0.4735184 0.6625956 0.4735184 0.6629386 0.4736523 0.6632818 0.4737855 0.6632818 0.4737855 0.6636252 0.4739183 0.6639688 0.4740505 0.6639688 0.4740505 0.6643126 0.4741822 0.6632818 0.4737855 0.6643126 0.4741822 0.6646566 0.4743134 0.6632818 0.4737855 0.6646566 0.4743134 0.6650007 0.474444 0.6653451 0.4745742 0.6653451 0.4745742 0.6656897 0.4747037 0.6646566 0.4743134 0.6656897 0.4747037 0.6660345 0.4748328 0.6646566 0.4743134 0.6660345 0.4748328 0.6663795 0.4749614 0.6667247 0.4750894 0.6667247 0.4750894 0.6670701 0.4752169 0.6674157 0.4753438 0.6674157 0.4753438 0.6677615 0.4754702 0.6681074 0.4755961 0.6681074 0.4755961 0.6684536 0.4757214 0.6674157 0.4753438 0.6684536 0.4757214 0.6687999 0.4758463 0.6674157 0.4753438 0.6687999 0.4758463 0.6691464 0.4759706 0.6694931 0.4760943 0.6694931 0.4760943 0.6698401 0.4762176 0.6687999 0.4758463 0.6698401 0.4762176 0.6701872 0.4763402 0.6687999 0.4758463 0.6701872 0.4763402 0.6705345 0.4764624 0.6715775 0.4768257 0.6705345 0.4764624 0.670882 0.4765841 0.6715775 0.4768257 0.670882 0.4765841 0.6712297 0.4767051 0.6715775 0.4768257 0.6715775 0.4768257 0.6719256 0.4769458 0.6722738 0.4770653 0.6722738 0.4770653 0.6726222 0.4771842 0.6715775 0.4768257 0.6726222 0.4771842 0.6729708 0.4773026 0.6715775 0.4768257 0.6729708 0.4773026 0.6733195 0.4774205 0.6736685 0.4775379 0.6736685 0.4775379 0.6740176 0.4776547 0.6743669 0.477771 0.6743669 0.477771 0.6747164 0.4778867 0.6750661 0.478002 0.6750661 0.478002 0.6754159 0.4781166 0.6757659 0.4782308 0.6757659 0.4782308 0.6761161 0.4783444 0.6764665 0.4784575 0.6764665 0.4784575 0.676817 0.47857 0.6757659 0.4782308 0.676817 0.47857 0.6771677 0.478682 0.6757659 0.4782308 0.6771677 0.478682 0.6775186 0.4787935 0.6785722 0.4791246 0.6775186 0.4787935 0.6778696 0.4789044 0.6785722 0.4791246 0.6778696 0.4789044 0.6782209 0.4790148 0.6785722 0.4791246 0.6785722 0.4791246 0.6789238 0.4792339 0.6792755 0.4793426 0.6792755 0.4793426 0.6796274 0.4794509 0.6799795 0.4795585 0.6799795 0.4795585 0.6803317 0.4796657 0.6806841 0.4797723 0.6806841 0.4797723 0.6810366 0.4798783 0.6813893 0.4799839 0.6813893 0.4799839 0.6817422 0.4800888 0.6828018 0.4804005 0.6817422 0.4800888 0.6820952 0.4801933 0.6828018 0.4804005 0.6820952 0.4801933 0.6824484 0.4802972 0.6828018 0.4804005 0.6828018 0.4804005 0.6831553 0.4805033 0.6835089 0.4806056 0.6835089 0.4806056 0.6838628 0.4807073 0.6828018 0.4804005 0.6838628 0.4807073 0.6842167 0.4808085 0.6828018 0.4804005 0.6842167 0.4808085 0.6845709 0.4809091 0.6849251 0.4810093 0.6849251 0.4810093 0.6852796 0.4811088 0.6842167 0.4808085 0.6852796 0.4811088 0.6856342 0.4812078 0.6842167 0.4808085 0.6856342 0.4812078 0.6859889 0.4813063 0.6863439 0.4814042 0.6863439 0.4814042 0.6866989 0.4815015 0.6856342 0.4812078 0.6866989 0.4815015 0.687054 0.4815984 0.6856342 0.4812078 0.687054 0.4815984 0.6874094 0.4816946 0.6877649 0.4817904 0.6877649 0.4817904 0.6881206 0.4818856 0.687054 0.4815984 0.6881206 0.4818856 0.6884763 0.4819803 0.687054 0.4815984 0.6884763 0.4819803 0.6888322 0.4820743 0.6891883 0.4821679 0.6891883 0.4821679 0.6895445 0.4822609 0.6899009 0.4823534 0.6899009 0.4823534 0.6902574 0.4824453 0.6913277 0.4827178 0.6902574 0.4824453 0.690614 0.4825367 0.6913277 0.4827178 0.690614 0.4825367 0.6909708 0.4826275 0.6913277 0.4827178 0.6913277 0.4827178 0.6916847 0.4828075 0.6920419 0.4828967 0.6920419 0.4828967 0.6923993 0.4829853 0.6927567 0.4830734 0.6927567 0.4830734 0.6931143 0.4831609 0.6934721 0.4832479 0.6934721 0.4832479 0.69383 0.4833344 0.6941879 0.4834203 0.6941879 0.4834203 0.6945461 0.4835056 0.6949043 0.4835904 0.6949043 0.4835904 0.6952627 0.4836746 0.6956212 0.4837583 0.6956212 0.4837583 0.6959798 0.4838414 0.6970565 0.4840875 0.6959798 0.4838414 0.6963387 0.483924 0.6970565 0.4840875 0.6963387 0.483924 0.6966975 0.4840061 0.6970565 0.4840875 0.6970565 0.4840875 0.6974157 0.4841685 0.6984939 0.484408 0.6974157 0.4841685 0.697775 0.4842489 0.6984939 0.484408 0.697775 0.4842489 0.6981344 0.4843288 0.6984939 0.484408 0.6984939 0.484408 0.6988535 0.4844868 0.6992133 0.4845649 0.6992133 0.4845649 0.6995732 0.4846426 0.6999332 0.4847196 0.6999332 0.4847196 0.7002933 0.4847962 0.7006535 0.4848722 0.7006535 0.4848722 0.7010139 0.4849476 0.6999332 0.4847196 0.7010139 0.4849476 0.7013743 0.4850224 0.6999332 0.4847196 0.7013743 0.4850224 0.7017349 0.4850968 0.7020956 0.4851705 0.7020956 0.4851705 0.7024564 0.4852437 0.7013743 0.4850224 0.7024564 0.4852437 0.7028173 0.4853163 0.7013743 0.4850224 0.7028173 0.4853163 0.7031784 0.4853885 0.7042621 0.4856014 0.7031784 0.4853885 0.7035395 0.48546 0.7042621 0.4856014 0.7035395 0.48546 0.7039007 0.485531 0.7042621 0.4856014 0.7042621 0.4856014 0.7046235 0.4856714 0.7049851 0.4857407 0.7049851 0.4857407 0.7053468 0.4858095 0.7057086 0.4858776 0.7057086 0.4858776 0.7060704 0.4859453 0.7064324 0.4860124 0.7064324 0.4860124 0.7067945 0.486079 0.7071567 0.486145 0.7071567 0.486145 0.707519 0.4862104 0.7078814 0.4862753 0.7078814 0.4862753 0.7082439 0.4863396 0.7086065 0.4864034 0.7086065 0.4864034 0.7089691 0.4864667 0.7093319 0.4865293 0.7093319 0.4865293 0.7096948 0.4865914 0.7100578 0.4866529 0.7100578 0.4866529 0.7104209 0.486714 0.710784 0.4867744 0.710784 0.4867744 0.7111473 0.4868342 0.7100578 0.4866529 0.7111473 0.4868342 0.7115106 0.4868935 0.7100578 0.4866529 0.7115106 0.4868935 0.7118741 0.4869523 0.7122376 0.4870105 0.7122376 0.4870105 0.7126012 0.4870682 0.7129649 0.4871253 0.7129649 0.4871253 0.7133287 0.4871818 0.7136926 0.4872378 0.7136926 0.4872378 0.7140565 0.4872932 0.7129649 0.4871253 0.7140565 0.4872932 0.7144206 0.487348 0.7129649 0.4871253 0.7144206 0.487348 0.7147847 0.4874024 0.7151489 0.4874561 0.7151489 0.4874561 0.7155132 0.4875093 0.7144206 0.487348 0.7155132 0.4875093 0.7158776 0.4875619 0.7144206 0.487348 0.7158776 0.4875619 0.716242 0.487614 0.7173359 0.4877668 0.716242 0.487614 0.7166066 0.4876655 0.7173359 0.4877668 0.7166066 0.4876655 0.7169712 0.4877164 0.7173359 0.4877668 0.7173359 0.4877668 0.7177006 0.4878166 0.7180655 0.4878659 0.7180655 0.4878659 0.7184304 0.4879146 0.7173359 0.4877668 0.7184304 0.4879146 0.7187954 0.4879627 0.7173359 0.4877668 0.7187954 0.4879627 0.7191604 0.4880104 0.7195256 0.4880574 0.7195256 0.4880574 0.7198908 0.4881038 0.7187954 0.4879627 0.7198908 0.4881038 0.7202561 0.4881498 0.7187954 0.4879627 0.7202561 0.4881498 0.7206215 0.4881951 0.7209869 0.4882399 0.7209869 0.4882399 0.7213523 0.4882841 0.7217179 0.4883278 0.7217179 0.4883278 0.7220835 0.4883708 0.7224493 0.4884134 0.7224493 0.4884134 0.722815 0.4884554 0.7217179 0.4883278 0.722815 0.4884554 0.7231808 0.4884968 0.7217179 0.4883278 0.7231808 0.4884968 0.7235467 0.4885377 0.7246447 0.4886569 0.7235467 0.4885377 0.7239126 0.488578 0.7246447 0.4886569 0.7239126 0.488578 0.7242786 0.4886177 0.7246447 0.4886569 0.7246447 0.4886569 0.7250108 0.4886955 0.725377 0.4887335 0.725377 0.4887335 0.7257432 0.488771 0.7246447 0.4886569 0.7257432 0.488771 0.7261095 0.488808 0.7246447 0.4886569 0.7261095 0.488808 0.7264759 0.4888443 0.7275753 0.4889501 0.7264759 0.4888443 0.7268423 0.4888801 0.7275753 0.4889501 0.7268423 0.4888801 0.7272087 0.4889154 0.7275753 0.4889501 0.7275753 0.4889501 0.7279419 0.4889842 0.7290419 0.4890832 0.7279419 0.4889842 0.7283085 0.4890177 0.7290419 0.4890832 0.7283085 0.4890177 0.7286751 0.4890507 0.7290419 0.4890832 0.7290419 0.4890832 0.7294086 0.489115 0.7297755 0.4891463 0.7297755 0.4891463 0.7301424 0.4891771 0.7290419 0.4890832 0.7301424 0.4891771 0.7305093 0.4892073 0.7290419 0.4890832 0.7305093 0.4892073 0.7308762 0.4892368 0.7312432 0.4892659 0.7312432 0.4892659 0.7316103 0.4892944 0.7319774 0.4893223 0.7319774 0.4893223 0.7323445 0.4893497 0.7327117 0.4893765 0.7327117 0.4893765 0.7330789 0.4894027 0.7319774 0.4893223 0.7330789 0.4894027 0.7334462 0.4894284 0.7319774 0.4893223 0.7334462 0.4894284 0.7338135 0.4894535 0.7341808 0.4894781 0.7341808 0.4894781 0.7345482 0.4895021 0.7349156 0.4895255 0.7349156 0.4895255 0.735283 0.4895483 0.7363856 0.4896135 0.735283 0.4895483 0.7356505 0.4895706 0.7363856 0.4896135 0.7356505 0.4895706 0.736018 0.4895924 0.7363856 0.4896135 0.7363856 0.4896135 0.7367532 0.4896341 0.7371208 0.4896542 0.7371208 0.4896542 0.7374884 0.4896737 0.737856 0.4896926 0.737856 0.4896926 0.7382237 0.4897109 0.739327 0.4897626 0.7382237 0.4897109 0.7385915 0.4897287 0.739327 0.4897626 0.7385915 0.4897287 0.7389593 0.4897459 0.739327 0.4897626 0.739327 0.4897626 0.7396948 0.4897786 0.7400627 0.4897942 0.7400627 0.4897942 0.7404305 0.4898092 0.739327 0.4897626 0.7404305 0.4898092 0.7407984 0.4898235 0.739327 0.4897626 0.7407984 0.4898235 0.7411663 0.4898374 0.7422701 0.4898755 0.7411663 0.4898374 0.7415342 0.4898506 0.7422701 0.4898755 0.7415342 0.4898506 0.7419021 0.4898633 0.7422701 0.4898755 0.7422701 0.4898755 0.7426381 0.4898871 0.7430061 0.4898981 0.7430061 0.4898981 0.7433741 0.4899085 0.7422701 0.4898755 0.7433741 0.4899085 0.7437421 0.4899184 0.7422701 0.4898755 0.7437421 0.4899184 0.7441101 0.4899277 0.7444782 0.4899365 0.7444782 0.4899365 0.7448462 0.4899446 0.7437421 0.4899184 0.7448462 0.4899446 0.7452143 0.4899523 0.7437421 0.4899184 0.7452143 0.4899523 0.7455824 0.4899594 0.7459505 0.4899659 0.7459505 0.4899659 0.7463186 0.4899718 0.7452143 0.4899523 0.7463186 0.4899718 0.7466867 0.4899771 0.7452143 0.4899523 0.7466867 0.4899771 0.7470548 0.489982 0.7474229 0.4899862 0.7474229 0.4899862 0.7477911 0.4899898 0.7466867 0.4899771 0.7477911 0.4899898 0.7481592 0.4899929 0.7466867 0.4899771 0.7481592 0.4899929 0.7485274 0.4899955 0.7488955 0.4899975 0.7488955 0.4899975 0.7492637 0.4899989 0.7496318 0.4899997 0.7496318 0.4899997 0.7503682 0.4899997 0.7511045 0.4899975 0.7525771 0.4899862 0.7533133 0.4899771 0.7555218 0.4899365 0.7533133 0.4899771 0.7540495 0.4899659 0.7555218 0.4899365 0.7599374 0.4897942 0.760673 0.4897626 0.7614085 0.4897287 0.7628793 0.4896542 0.7636144 0.4896135 0.7614085 0.4897287 0.7636144 0.4896135 0.7643495 0.4895706 0.7614085 0.4897287 0.7672883 0.4893765 0.7680227 0.4893223 0.7702245 0.4891463 0.7680227 0.4893223 0.7687568 0.4892659 0.7702245 0.4891463 0.7702245 0.4891463 0.7709581 0.4890832 0.7731577 0.4888801 0.7709581 0.4890832 0.7716915 0.4890177 0.7731577 0.4888801 0.774623 0.4887335 0.7753553 0.4886569 0.7731577 0.4888801 0.7753553 0.4886569 0.7760874 0.488578 0.7731577 0.4888801 0.7819345 0.4878659 0.7826641 0.4877668 0.7848511 0.4874561 0.7826641 0.4877668 0.7833935 0.4876655 0.7848511 0.4874561 0.7848511 0.4874561 0.7855795 0.487348 0.7877624 0.4870105 0.7855795 0.487348 0.7863075 0.4872378 0.7877624 0.4870105 0.7877624 0.4870105 0.7884894 0.4868935 0.7906681 0.4865293 0.7884894 0.4868935 0.789216 0.4867744 0.7906681 0.4865293 0.789216 0.4867744 0.7899422 0.4866529 0.7906681 0.4865293 0.7950149 0.4857407 0.7957379 0.4856014 0.7964605 0.48546 0.7964605 0.48546 0.7971827 0.4853163 0.7993465 0.4848722 0.7971827 0.4853163 0.7979044 0.4851705 0.7993465 0.4848722 0.7993465 0.4848722 0.8000668 0.4847196 0.8007867 0.4845649 0.8007867 0.4845649 0.8015061 0.484408 0.8022251 0.4842489 0.8022251 0.4842489 0.8029435 0.4840875 0.8050957 0.4835904 0.8029435 0.4840875 0.8036614 0.483924 0.8050957 0.4835904 0.8050957 0.4835904 0.8058121 0.4834203 0.8065279 0.4832479 0.8065279 0.4832479 0.8072433 0.4830734 0.8079581 0.4828967 0.8079581 0.4828967 0.8086723 0.4827178 0.8108117 0.4821679 0.8086723 0.4827178 0.809386 0.4825367 0.8108117 0.4821679 0.8122351 0.4817904 0.812946 0.4815984 0.8108117 0.4821679 0.812946 0.4815984 0.8136562 0.4814042 0.8108117 0.4821679 0.8136562 0.4814042 0.8143658 0.4812078 0.8150749 0.4810093 0.8150749 0.4810093 0.8157833 0.4808085 0.8136562 0.4814042 0.8157833 0.4808085 0.8164911 0.4806056 0.8136562 0.4814042 0.8164911 0.4806056 0.8171982 0.4804005 0.8193159 0.4797723 0.8171982 0.4804005 0.8179048 0.4801933 0.8193159 0.4797723 0.8193159 0.4797723 0.8200206 0.4795585 0.8207245 0.4793426 0.8207245 0.4793426 0.8214278 0.4791246 0.8221304 0.4789044 0.8235335 0.4784575 0.8242341 0.4782308 0.8221304 0.4789044 0.8242341 0.4782308 0.824934 0.478002 0.8221304 0.4789044 0.8277263 0.4770653 0.8284225 0.4768257 0.8305069 0.4760943 0.8284225 0.4768257 0.829118 0.4765841 0.8305069 0.4760943 0.8305069 0.4760943 0.8312001 0.4758463 0.8332753 0.4750894 0.8312001 0.4758463 0.8318926 0.4755961 0.8332753 0.4750894 0.8346549 0.4745742 0.8353434 0.4743134 0.8332753 0.4750894 0.8353434 0.4743134 0.8360312 0.4740505 0.8332753 0.4750894 0.8360312 0.4740505 0.8367182 0.4737855 0.8374044 0.4735184 0.8374044 0.4735184 0.8380897 0.4732492 0.8387742 0.4729779 0.8401407 0.472429 0.8408226 0.4721514 0.8387742 0.4729779 0.8408226 0.4721514 0.8415038 0.4718717 0.8387742 0.4729779 0.8415038 0.4718717 0.8421841 0.4715899 0.8442196 0.4707321 0.8421841 0.4715899 0.8428635 0.4713061 0.8442196 0.4707321 0.8496083 0.4683533 0.8502777 0.4680467 0.8522803 0.4671146 0.8502777 0.4680467 0.8509462 0.4677381 0.8522803 0.4671146 0.8509462 0.4677381 0.8516137 0.4674273 0.8522803 0.4671146 0.8522803 0.4671146 0.8529459 0.4667997 0.8536106 0.4664829 0.8536106 0.4664829 0.8542742 0.466164 0.8549369 0.4658431 0.8575778 0.4645391 0.8582354 0.4642081 0.8602024 0.4632028 0.8582354 0.4642081 0.8588921 0.463875 0.8602024 0.4632028 0.8588921 0.463875 0.8595477 0.4635399 0.8602024 0.4632028 0.8602024 0.4632028 0.8608559 0.4628637 0.8615085 0.4625226 0.8654015 0.4604341 0.8660465 0.460079 0.8679751 0.4590021 0.8660465 0.460079 0.8666905 0.4597221 0.8679751 0.4590021 0.8666905 0.4597221 0.8673334 0.4593631 0.8679751 0.4590021 0.8718022 0.4567952 0.8724361 0.4564205 0.870531 0.4575386 0.8724361 0.4564205 0.8730688 0.4560439 0.870531 0.4575386 0.8730688 0.4560439 0.8737003 0.4556654 0.8743306 0.4552849 0.8755879 0.4545181 0.8762148 0.4541319 0.8768405 0.4537437 0.8768405 0.4537437 0.877465 0.4533536 0.8755879 0.4545181 0.877465 0.4533536 0.8780882 0.4529616 0.8755879 0.4545181 0.8780882 0.4529616 0.8787103 0.4525676 0.8805692 0.4513745 0.8787103 0.4525676 0.8793312 0.4521718 0.8805692 0.4513745 0.8866849 0.4472745 0.8872895 0.4468542 0.8854719 0.4481095 0.8872895 0.4468542 0.8878929 0.4464321 0.8854719 0.4481095 0.8890955 0.4455823 0.8896949 0.4451547 0.8878929 0.4464321 0.8896949 0.4451547 0.890293 0.4447252 0.8878929 0.4464321 0.892672 0.4429889 0.8932633 0.4425503 0.8950295 0.4412236 0.8932633 0.4425503 0.8938534 0.4421098 0.8950295 0.4412236 0.8973652 0.4394294 0.8979457 0.4389764 0.8996787 0.4376068 0.8979457 0.4389764 0.8985248 0.4385216 0.8996787 0.4376068 0.8996787 0.4376068 0.9002535 0.4371467 0.9019696 0.4357559 0.9002535 0.4371467 0.900827 0.4366848 0.9019696 0.4357559 0.9031066 0.4348199 0.9036728 0.4343493 0.9019696 0.4357559 0.9036728 0.4343493 0.9042377 0.4338769 0.9019696 0.4357559 0.905363 0.4329271 0.9059235 0.4324496 0.9042377 0.4338769 0.9059235 0.4324496 0.9064825 0.4319704 0.9042377 0.4338769 0.9064825 0.4319704 0.9070401 0.4314894 0.9087038 0.4300364 0.9070401 0.4314894 0.9075961 0.4310068 0.9087038 0.4300364 0.9087038 0.4300364 0.9092554 0.4295486 0.9098055 0.4290592 0.9098055 0.4290592 0.9103541 0.4285681 0.9109012 0.4280753 0.9119908 0.4270847 0.9125334 0.4265869 0.9109012 0.4280753 0.9125334 0.4265869 0.9130743 0.4260874 0.9109012 0.4280753 0.9130743 0.4260874 0.9136138 0.4255862 0.9141517 0.4250835 0.9152229 0.4240729 0.9157562 0.4235652 0.9173466 0.4220323 0.9157562 0.4235652 0.9162879 0.4230559 0.9173466 0.4220323 0.918399 0.4210023 0.9189229 0.4204848 0.9173466 0.4220323 0.9189229 0.4204848 0.9194451 0.4199658 0.9173466 0.4220323 0.9204848 0.4189229 0.9210023 0.418399 0.9215181 0.4178736 0.9215181 0.4178736 0.9220323 0.4173466 0.9235652 0.4157562 0.9220323 0.4173466 0.9225449 0.416818 0.9235652 0.4157562 0.9255862 0.4136138 0.9260874 0.4130743 0.9275808 0.4114468 0.9260874 0.4130743 0.9265869 0.4125334 0.9275808 0.4114468 0.9275808 0.4114468 0.9280753 0.4109011 0.9285681 0.4103541 0.9285681 0.4103541 0.9290592 0.4098055 0.9295486 0.4092554 0.9305225 0.4081507 0.9310068 0.4075961 0.9314894 0.4070401 0.9352887 0.4025388 0.9357559 0.4019696 0.9371467 0.4002535 0.9357559 0.4019696 0.9362212 0.401399 0.9371467 0.4002535 0.9380651 0.3991024 0.9385216 0.3985247 0.9371467 0.4002535 0.9385216 0.3985247 0.9389764 0.3979457 0.9371467 0.4002535 0.9407777 0.3956155 0.9412236 0.3950295 0.9425503 0.3932633 0.9412236 0.3950295 0.9416676 0.3944422 0.9425503 0.3932633 0.9425503 0.3932633 0.9429889 0.392672 0.9442939 0.3908897 0.9429889 0.392672 0.9434257 0.3920792 0.9442939 0.3908897 0.9442939 0.3908897 0.9447252 0.390293 0.9451547 0.3896949 0.9476929 0.3860791 0.9481095 0.3854719 0.9493479 0.3836428 0.9481095 0.3854719 0.9485242 0.3848634 0.9493479 0.3836428 0.9501642 0.3824171 0.9505695 0.3818024 0.9493479 0.3836428 0.9505695 0.3818024 0.9509729 0.3811864 0.9493479 0.3836428 0.9549025 0.3749599 0.9552849 0.3743306 0.9541319 0.3762148 0.9552849 0.3743306 0.9556654 0.3737003 0.9541319 0.3762148 0.9571679 0.3711671 0.9575386 0.370531 0.9586392 0.3686158 0.9575386 0.370531 0.9579074 0.3698937 0.9586392 0.3686158 0.9586392 0.3686158 0.9590021 0.3679751 0.9600791 0.3660465 0.9590021 0.3679751 0.9593631 0.3673334 0.9600791 0.3660465 0.9593631 0.3673334 0.9597221 0.3666905 0.9600791 0.3660465 0.9600791 0.3660465 0.9604341 0.3654015 0.9607872 0.3647553 0.9607872 0.3647553 0.9611382 0.364108 0.9600791 0.3660465 0.9611382 0.364108 0.9614873 0.3634598 0.9600791 0.3660465 0.9621795 0.36216 0.9625226 0.3615085 0.9628637 0.3608559 0.9628637 0.3608559 0.9632028 0.3602024 0.9642081 0.3582354 0.9632028 0.3602024 0.9635399 0.3595477 0.9642081 0.3582354 0.9648681 0.3569191 0.9651951 0.3562594 0.9642081 0.3582354 0.9651951 0.3562594 0.9655202 0.3555986 0.9642081 0.3582354 0.9655202 0.3555986 0.9658431 0.3549369 0.966164 0.3542742 0.966164 0.3542742 0.9664829 0.3536105 0.9667997 0.3529459 0.9667997 0.3529459 0.9671146 0.3522803 0.9674274 0.3516137 0.968658 0.3489379 0.9689604 0.3482666 0.9680467 0.3502777 0.9689604 0.3482666 0.9692609 0.3475944 0.9680467 0.3502777 0.9698556 0.3462471 0.9701498 0.3455722 0.9692609 0.3475944 0.9701498 0.3455722 0.970442 0.3448964 0.9692609 0.3475944 0.9710201 0.3435419 0.9713061 0.3428635 0.9715899 0.342184 0.9732492 0.3380897 0.9735184 0.3374043 0.9737855 0.3367182 0.9748328 0.3339655 0.9750894 0.3332753 0.9758463 0.3312001 0.9750894 0.3332753 0.9753438 0.3325843 0.9758463 0.3312001 0.9773027 0.3270292 0.9775379 0.3263316 0.9768257 0.3284225 0.9775379 0.3263316 0.9777711 0.3256331 0.9768257 0.3284225 0.9777711 0.3256331 0.978002 0.324934 0.978682 0.3228323 0.978002 0.324934 0.9782308 0.3242341 0.978682 0.3228323 0.9791246 0.3214278 0.9793426 0.3207245 0.978682 0.3228323 0.9793426 0.3207245 0.9795585 0.3200206 0.978682 0.3228323 0.9795585 0.3200206 0.9797723 0.3193159 0.9799839 0.3186107 0.9819803 0.3115237 0.9821679 0.3108117 0.9827178 0.3086723 0.9821679 0.3108117 0.9823534 0.3100991 0.9827178 0.3086723 0.9827178 0.3086723 0.9828967 0.3079581 0.9830734 0.3072432 0.9830734 0.3072432 0.9832479 0.3065279 0.9834203 0.3058121 0.9834203 0.3058121 0.9835904 0.3050957 0.9837583 0.3043788 0.984408 0.3015061 0.9845649 0.3007867 0.9840876 0.3029434 0.9845649 0.3007867 0.9847196 0.3000668 0.9840876 0.3029434 0.9856014 0.2957379 0.9857407 0.2950149 0.9853163 0.2971827 0.9857407 0.2950149 0.9858776 0.2942914 0.9853163 0.2971827 0.9858776 0.2942914 0.9860124 0.2935676 0.986145 0.2928433 0.986145 0.2928433 0.9862753 0.2921186 0.9858776 0.2942914 0.9862753 0.2921186 0.9864034 0.2913935 0.9858776 0.2942914 0.9864034 0.2913935 0.9865293 0.2906681 0.9868935 0.2884894 0.9865293 0.2906681 0.986653 0.2899422 0.9868935 0.2884894 0.9868935 0.2884894 0.9870105 0.2877624 0.9873481 0.2855795 0.9870105 0.2877624 0.9871253 0.2870351 0.9873481 0.2855795 0.9881498 0.2797439 0.9882399 0.2790132 0.9883278 0.2782821 0.9892073 0.2694907 0.9892659 0.2687568 0.9890832 0.2709581 0.9892659 0.2687568 0.9893223 0.2680226 0.9890832 0.2709581 0.9894284 0.2665538 0.9894781 0.2658192 0.9893223 0.2680226 0.9894781 0.2658192 0.9895255 0.2650844 0.9893223 0.2680226 0.9896135 0.2636144 0.9896542 0.2628793 0.9895255 0.2650844 0.9896542 0.2628793 0.9896926 0.2621439 0.9895255 0.2650844 0.989993 0.2518408 0.9899975 0.2511045 0.9899771 0.2533133 0.9899975 0.2511045 0.9899997 0.2503681 0.9899771 0.2533133 0.9899997 0.2503681 0.9899997 0.2496318 0.9899975 0.2488955 0.9899862 0.2474229 0.9899771 0.2466867 0.9899365 0.2444781 0.9899771 0.2466867 0.9899659 0.2459505 0.9899365 0.2444781 0.9897942 0.2400626 0.9897626 0.239327 0.9897287 0.2385914 0.9896542 0.2371207 0.9896135 0.2363855 0.9897287 0.2385914 0.9896135 0.2363855 0.9895706 0.2356505 0.9897287 0.2385914 0.9893765 0.2327117 0.9893223 0.2319774 0.9891464 0.2297754 0.9893223 0.2319774 0.9892659 0.2312432 0.9891464 0.2297754 0.9891464 0.2297754 0.9890832 0.2290418 0.9888802 0.2268423 0.9890832 0.2290418 0.9890177 0.2283084 0.9888802 0.2268423 0.9887335 0.225377 0.9886569 0.2246447 0.9888802 0.2268423 0.9886569 0.2246447 0.988578 0.2239126 0.9888802 0.2268423 0.9878659 0.2180655 0.9877668 0.2173358 0.9874561 0.2151489 0.9877668 0.2173358 0.9876655 0.2166065 0.9874561 0.2151489 0.9874561 0.2151489 0.9873481 0.2144205 0.9870105 0.2122375 0.9873481 0.2144205 0.9872378 0.2136925 0.9870105 0.2122375 0.9870105 0.2122375 0.9868935 0.2115106 0.9865293 0.2093319 0.9868935 0.2115106 0.9867744 0.210784 0.9865293 0.2093319 0.9867744 0.210784 0.986653 0.2100577 0.9865293 0.2093319 0.9857407 0.2049851 0.9856014 0.204262 0.9854601 0.2035394 0.9854601 0.2035394 0.9853163 0.2028173 0.9848722 0.2006534 0.9853163 0.2028173 0.9851705 0.2020956 0.9848722 0.2006534 0.9848722 0.2006534 0.9847196 0.1999331 0.9845649 0.1992133 0.9845649 0.1992133 0.984408 0.1984938 0.9842489 0.197775 0.9842489 0.197775 0.9840876 0.1970565 0.9835904 0.1949043 0.9840876 0.1970565 0.983924 0.1963386 0.9835904 0.1949043 0.9835904 0.1949043 0.9834203 0.1941879 0.9832479 0.193472 0.9832479 0.193472 0.9830734 0.1927567 0.9828967 0.1920419 0.9828967 0.1920419 0.9827178 0.1913277 0.9821679 0.1891883 0.9827178 0.1913277 0.9825367 0.190614 0.9821679 0.1891883 0.9817904 0.1877649 0.9815984 0.187054 0.9821679 0.1891883 0.9815984 0.187054 0.9814042 0.1863438 0.9821679 0.1891883 0.9814042 0.1863438 0.9812078 0.1856341 0.9810093 0.1849251 0.9810093 0.1849251 0.9808085 0.1842167 0.9814042 0.1863438 0.9808085 0.1842167 0.9806056 0.1835089 0.9814042 0.1863438 0.9806056 0.1835089 0.9804005 0.1828017 0.9797723 0.180684 0.9804005 0.1828017 0.9801933 0.1820952 0.9797723 0.180684 0.9797723 0.180684 0.9795585 0.1799794 0.9793426 0.1792755 0.9793426 0.1792755 0.9791246 0.1785722 0.9789044 0.1778696 0.9784575 0.1764664 0.9782308 0.1757659 0.9789044 0.1778696 0.9782308 0.1757659 0.978002 0.175066 0.9789044 0.1778696 0.9770653 0.1722737 0.9768257 0.1715775 0.9760944 0.1694931 0.9768257 0.1715775 0.9765841 0.1708819 0.9760944 0.1694931 0.9760944 0.1694931 0.9758463 0.1687999 0.9750894 0.1667247 0.9758463 0.1687999 0.9755961 0.1681073 0.9750894 0.1667247 0.9745742 0.1653451 0.9743134 0.1646565 0.9750894 0.1667247 0.9743134 0.1646565 0.9740505 0.1639688 0.9750894 0.1667247 0.9740505 0.1639688 0.9737855 0.1632818 0.9735184 0.1625956 0.9735184 0.1625956 0.9732492 0.1619103 0.9729779 0.1612258 0.972429 0.1598593 0.9721514 0.1591773 0.9729779 0.1612258 0.9721514 0.1591773 0.9718717 0.1584962 0.9729779 0.1612258 0.9718717 0.1584962 0.9715899 0.1578159 0.9707321 0.1557804 0.9715899 0.1578159 0.9713061 0.1571365 0.9707321 0.1557804 0.9683534 0.1503917 0.9680467 0.1497223 0.9671146 0.1477197 0.9680467 0.1497223 0.9677381 0.1490538 0.9671146 0.1477197 0.9677381 0.1490538 0.9674274 0.1483862 0.9671146 0.1477197 0.9671146 0.1477197 0.9667997 0.1470541 0.9664829 0.1463894 0.9664829 0.1463894 0.966164 0.1457257 0.9658431 0.1450631 0.9645391 0.1424222 0.9642081 0.1417645 0.9632028 0.1397976 0.9642081 0.1417645 0.963875 0.1411079 0.9632028 0.1397976 0.963875 0.1411079 0.9635399 0.1404522 0.9632028 0.1397976 0.9632028 0.1397976 0.9628637 0.139144 0.9625226 0.1384915 0.9604341 0.1345986 0.9600791 0.1339535 0.9590021 0.1320249 0.9600791 0.1339535 0.9597221 0.1333095 0.9590021 0.1320249 0.9597221 0.1333095 0.9593631 0.1326667 0.9590021 0.1320249 0.9567952 0.1281978 0.9564205 0.127564 0.9575386 0.129469 0.9564205 0.127564 0.9560439 0.1269312 0.9575386 0.129469 0.9560439 0.1269312 0.9556654 0.1262997 0.9552849 0.1256693 0.9545181 0.124412 0.9541319 0.1237851 0.9537437 0.1231595 0.9537437 0.1231595 0.9533536 0.122535 0.9545181 0.124412 0.9533536 0.122535 0.9529616 0.1219117 0.9545181 0.124412 0.9529616 0.1219117 0.9525676 0.1212897 0.9513745 0.1194307 0.9525676 0.1212897 0.9521718 0.1206688 0.9513745 0.1194307 0.9472745 0.1133151 0.9468542 0.1127105 0.9481095 0.1145281 0.9468542 0.1127105 0.9464321 0.1121072 0.9481095 0.1145281 0.9455823 0.1109045 0.9451547 0.1103051 0.9464321 0.1121072 0.9451547 0.1103051 0.9447252 0.109707 0.9464321 0.1121072 0.9429889 0.107328 0.9425503 0.1067366 0.9412236 0.1049705 0.9425503 0.1067366 0.9421098 0.1061465 0.9412236 0.1049705 0.9394294 0.1026348 0.9389764 0.1020543 0.9376068 0.1003213 0.9389764 0.1020543 0.9385216 0.1014752 0.9376068 0.1003213 0.9376068 0.1003213 0.9371467 0.09974646 0.9357559 0.09803032 0.9371467 0.09974646 0.9366848 0.099173 0.9357559 0.09803032 0.9348199 0.09689342 0.9343493 0.09632712 0.9357559 0.09803032 0.9343493 0.09632712 0.9338769 0.09576231 0.9357559 0.09803032 0.9329271 0.09463691 0.9324496 0.09407645 0.9338769 0.09576231 0.9324496 0.09407645 0.9319704 0.09351742 0.9338769 0.09576231 0.9319704 0.09351742 0.9314894 0.09295994 0.9300364 0.09129619 0.9314894 0.09295994 0.9310068 0.09240382 0.9300364 0.09129619 0.9300364 0.09129619 0.9295486 0.09074455 0.9290592 0.09019446 0.9290592 0.09019446 0.9285681 0.08964586 0.9280753 0.08909881 0.9270847 0.08800917 0.9265869 0.08746665 0.9280753 0.08909881 0.9265869 0.08746665 0.9260874 0.08692568 0.9280753 0.08909881 0.9260874 0.08692568 0.9255862 0.0863862 0.9250835 0.08584827 0.9240729 0.08477705 0.9235652 0.08424383 0.9220323 0.08265334 0.9235652 0.08424383 0.9230559 0.0837121 0.9220323 0.08265334 0.9210023 0.08160096 0.9204848 0.08107709 0.9220323 0.08265334 0.9204848 0.08107709 0.9199658 0.0805549 0.9220323 0.08265334 0.9189229 0.07951515 0.918399 0.07899773 0.9178736 0.07848191 0.9178736 0.07848191 0.9173466 0.0779677 0.9157562 0.07643473 0.9173466 0.0779677 0.916818 0.0774551 0.9157562 0.07643473 0.9136138 0.07441371 0.9130743 0.07391262 0.9114468 0.07241916 0.9130743 0.07391262 0.9125334 0.07341313 0.9114468 0.07241916 0.9114468 0.07241916 0.9109012 0.07192468 0.9103541 0.07143187 0.9103541 0.07143187 0.9098055 0.07094079 0.9092554 0.07045131 0.9081507 0.06947755 0.9075961 0.06899321 0.9070401 0.06851053 0.9025388 0.06471127 0.9019696 0.06424415 0.9002535 0.06285333 0.9019696 0.06424415 0.901399 0.06377875 0.9002535 0.06285333 0.8991024 0.06193488 0.8985248 0.06147837 0.9002535 0.06285333 0.8985248 0.06147837 0.8979457 0.06102359 0.9002535 0.06285333 0.8956155 0.05922228 0.8950295 0.05877643 0.8932633 0.05744969 0.8950295 0.05877643 0.8944422 0.05833238 0.8932633 0.05744969 0.8932633 0.05744969 0.892672 0.05701106 0.8908897 0.05570614 0.892672 0.05701106 0.8920792 0.05657428 0.8908897 0.05570614 0.8908897 0.05570614 0.890293 0.05527484 0.8896949 0.05484533 0.8860791 0.05230706 0.8854719 0.05189049 0.8836428 0.05065202 0.8854719 0.05189049 0.8848635 0.05147582 0.8836428 0.05065202 0.8824171 0.0498358 0.8818024 0.04943048 0.8836428 0.05065202 0.8818024 0.04943048 0.8811864 0.04902702 0.8836428 0.05065202 0.8749599 0.04509752 0.8743306 0.0447151 0.8762148 0.04586809 0.8743306 0.0447151 0.8737003 0.04433465 0.8762148 0.04586809 0.8711672 0.04283213 0.870531 0.04246133 0.8686158 0.04136079 0.870531 0.04246133 0.8698937 0.04209256 0.8686158 0.04136079 0.8686158 0.04136079 0.8679751 0.04099792 0.8660465 0.03992092 0.8679751 0.04099792 0.8673334 0.04063695 0.8660465 0.03992092 0.8673334 0.04063695 0.8666905 0.04027795 0.8660465 0.03992092 0.8660465 0.03992092 0.8654015 0.03956592 0.8647553 0.03921282 0.8647553 0.03921282 0.8641081 0.03886175 0.8660465 0.03992092 0.8641081 0.03886175 0.8634598 0.0385127 0.8660465 0.03992092 0.86216 0.03782045 0.8615085 0.03747737 0.8608559 0.03713625 0.8608559 0.03713625 0.8602024 0.03679716 0.8582354 0.03579193 0.8602024 0.03679716 0.8595477 0.0364601 0.8582354 0.03579193 0.8569191 0.03513181 0.8562594 0.03480482 0.8582354 0.03579193 0.8562594 0.03480482 0.8555986 0.03447985 0.8582354 0.03579193 0.8555986 0.03447985 0.8549369 0.03415685 0.8542742 0.03383594 0.8542742 0.03383594 0.8536106 0.03351706 0.8529459 0.0332002 0.8529459 0.0332002 0.8522803 0.03288543 0.8516137 0.03257262 0.8489379 0.03134202 0.8482666 0.03103953 0.8502777 0.03195321 0.8482666 0.03103953 0.8475944 0.03073906 0.8502777 0.03195321 0.8462472 0.03014439 0.8455722 0.02985012 0.8475944 0.03073906 0.8455722 0.02985012 0.8448964 0.02955794 0.8475944 0.03073906 0.843542 0.02897983 0.8428635 0.02869391 0.8421841 0.02841007 0.8380897 0.0267508 0.8374044 0.02648156 0.8367182 0.02621448 0.8339655 0.02516716 0.8332753 0.02491062 0.8312001 0.0241537 0.8332753 0.02491062 0.8325843 0.02465617 0.8312001 0.0241537 0.8270292 0.02269732 0.8263316 0.02246206 0.8284225 0.02317428 0.8263316 0.02246206 0.8256331 0.02222895 0.8284225 0.02317428 0.8256331 0.02222895 0.824934 0.02199798 0.8228323 0.02131801 0.824934 0.02199798 0.8242341 0.02176916 0.8228323 0.02131801 0.8214278 0.02087539 0.8207245 0.02065736 0.8228323 0.02131801 0.8207245 0.02065736 0.8200206 0.02044147 0.8228323 0.02131801 0.8200206 0.02044147 0.8193159 0.02022767 0.8186107 0.02001613 0.8115237 0.01801973 0.8108117 0.0178321 0.8086723 0.01728218 0.8108117 0.0178321 0.8100991 0.01764661 0.8086723 0.01728218 0.8086723 0.01728218 0.8079581 0.01710331 0.8072433 0.01692658 0.8072433 0.01692658 0.8065279 0.01675206 0.8058121 0.01657974 0.8058121 0.01657974 0.8050957 0.01640957 0.8043788 0.01624166 0.8015061 0.01559197 0.8007867 0.01543503 0.8029435 0.01591241 0.8007867 0.01543503 0.8000668 0.01528036 0.8029435 0.01591241 0.7957379 0.01439851 0.7950149 0.01425933 0.7971827 0.0146836 0.7950149 0.01425933 0.7942914 0.0141223 0.7971827 0.0146836 0.7942914 0.0141223 0.7935676 0.01398754 0.7928433 0.01385498 0.7928433 0.01385498 0.7921186 0.01372468 0.7942914 0.0141223 0.7921186 0.01372468 0.7913935 0.01359653 0.7942914 0.0141223 0.7913935 0.01359653 0.7906681 0.0134707 0.7884894 0.0131064 0.7906681 0.0134707 0.7899422 0.01334702 0.7884894 0.0131064 0.7884894 0.0131064 0.7877624 0.01298946 0.7855795 0.01265192 0.7877624 0.01298946 0.7870351 0.01287472 0.7855795 0.01265192 0.7797439 0.01185023 0.7790132 0.01176011 0.7782821 0.01167219 0.7694907 0.01079273 0.7687568 0.01073408 0.7709581 0.01091682 0.7687568 0.01073408 0.7680227 0.01067763 0.7709581 0.01091682 0.7665538 0.01057153 0.7658192 0.01052188 0.7680227 0.01067763 0.7658192 0.01052188 0.7650845 0.0104745 0.7680227 0.01067763 0.7636144 0.01038646 0.7628793 0.01034581 0.7650845 0.0104745 0.7628793 0.01034581 0.762144 0.01030743 0.7650845 0.0104745 0.7518408 0.01000702 0.7511045 0.01000255 0.7533133 0.01002287 0.7511045 0.01000255 0.7503682 0.01000028 0.7533133 0.01002287 0.7503682 0.01000028 0.7496318 0.01000028 0.7488955 0.01000255 0.7474229 0.01001381 0.7466867 0.01002287 0.7444782 0.01006352 0.7466867 0.01002287 0.7459505 0.01003414 0.7444782 0.01006352 0.7400627 0.0102058 0.739327 0.01023739 0.7385915 0.01027131 0.7371208 0.01034581 0.7363856 0.01038646 0.7385915 0.01027131 0.7363856 0.01038646 0.7356505 0.01042932 0.7385915 0.01027131 0.7327117 0.01062345 0.7319774 0.01067763 0.7297755 0.01085364 0.7319774 0.01067763 0.7312432 0.01073408 0.7297755 0.01085364 0.7297755 0.01085364 0.7290419 0.01091682 0.7268423 0.01111984 0.7290419 0.01091682 0.7283085 0.01098221 0.7268423 0.01111984 0.725377 0.01126641 0.7246447 0.01134312 0.7268423 0.01111984 0.7246447 0.01134312 0.7239126 0.01142203 0.7268423 0.01111984 0.7180655 0.01213407 0.7173359 0.01223319 0.7151489 0.01254385 0.7173359 0.01223319 0.7166066 0.01233452 0.7151489 0.01254385 0.7151489 0.01254385 0.7144206 0.01265192 0.7122376 0.01298946 0.7144206 0.01265192 0.7136926 0.01276218 0.7122376 0.01298946 0.7122376 0.01298946 0.7115106 0.0131064 0.7093319 0.0134707 0.7115106 0.0131064 0.710784 0.01322561 0.7093319 0.0134707 0.710784 0.01322561 0.7100578 0.01334702 0.7093319 0.0134707 0.7049851 0.01425933 0.7042621 0.01439851 0.7035395 0.01453995 0.7035395 0.01453995 0.7028173 0.0146836 0.7006535 0.01512783 0.7028173 0.0146836 0.7020956 0.01482945 0.7006535 0.01512783 0.7006535 0.01512783 0.6999332 0.01528036 0.6992133 0.01543503 0.6992133 0.01543503 0.6984939 0.01559197 0.697775 0.01575106 0.697775 0.01575106 0.6970565 0.01591241 0.6949043 0.01640957 0.6970565 0.01591241 0.6963387 0.0160759 0.6949043 0.01640957 0.6949043 0.01640957 0.6941879 0.01657974 0.6934721 0.01675206 0.6934721 0.01675206 0.6927567 0.01692658 0.6920419 0.01710331 0.6920419 0.01710331 0.6913277 0.01728218 0.6891883 0.0178321 0.6913277 0.01728218 0.690614 0.01746332 0.6891883 0.0178321 0.6877649 0.01820957 0.687054 0.01840162 0.6891883 0.0178321 0.687054 0.01840162 0.6863439 0.01859581 0.6891883 0.0178321 0.6863439 0.01859581 0.6856342 0.01879221 0.6849251 0.01899075 0.6849251 0.01899075 0.6842167 0.0191915 0.6863439 0.01859581 0.6842167 0.0191915 0.6835089 0.01939439 0.6863439 0.01859581 0.6835089 0.01939439 0.6828018 0.01959949 0.6806841 0.02022767 0.6828018 0.01959949 0.6820952 0.01980668 0.6806841 0.02022767 0.6806841 0.02022767 0.6799795 0.02044147 0.6792755 0.02065736 0.6792755 0.02065736 0.6785722 0.02087539 0.6778696 0.02109563 0.6764665 0.02154248 0.6757659 0.02176916 0.6778696 0.02109563 0.6757659 0.02176916 0.6750661 0.02199798 0.6778696 0.02109563 0.6722738 0.02293473 0.6715775 0.02317428 0.6694931 0.02390563 0.6715775 0.02317428 0.670882 0.02341592 0.6694931 0.02390563 0.6694931 0.02390563 0.6687999 0.0241537 0.6667247 0.02491062 0.6687999 0.0241537 0.6681074 0.02440387 0.6667247 0.02491062 0.6653451 0.02542579 0.6646566 0.02568662 0.6667247 0.02491062 0.6646566 0.02568662 0.6639688 0.02594947 0.6667247 0.02491062 0.6639688 0.02594947 0.6632818 0.02621448 0.6625956 0.02648156 0.6625956 0.02648156 0.6619103 0.0267508 0.6612258 0.02702206 0.6598593 0.02757096 0.6591774 0.0278486 0.6612258 0.02702206 0.6591774 0.0278486 0.6584962 0.02812826 0.6612258 0.02702206 0.6584962 0.02812826 0.6578159 0.02841007 0.6557804 0.02926784 0.6578159 0.02841007 0.6571366 0.02869391 0.6557804 0.02926784 0.6503918 0.0316466 0.6497223 0.03195321 0.6477197 0.03288543 0.6497223 0.03195321 0.6490538 0.0322619 0.6477197 0.03288543 0.6490538 0.0322619 0.6483863 0.03257262 0.6477197 0.03288543 0.6477197 0.03288543 0.6470541 0.0332002 0.6463894 0.03351706 0.6463894 0.03351706 0.6457258 0.03383594 0.6450631 0.03415685 0.6424223 0.03546088 0.6417646 0.03579193 0.6397976 0.03679716 0.6417646 0.03579193 0.6411079 0.036125 0.6397976 0.03679716 0.6411079 0.036125 0.6404523 0.0364601 0.6397976 0.03679716 0.6397976 0.03679716 0.6391441 0.03713625 0.6384915 0.03747737 0.6345986 0.03956592 0.6339535 0.03992092 0.6320249 0.04099792 0.6339535 0.03992092 0.6333096 0.04027795 0.6320249 0.04099792 0.6333096 0.04027795 0.6326667 0.04063695 0.6320249 0.04099792 0.6281979 0.04320484 0.627564 0.04357951 0.629469 0.04246133 0.627564 0.04357951 0.6269313 0.0439561 0.629469 0.04246133 0.6269313 0.0439561 0.6262997 0.04433465 0.6256694 0.0447151 0.6244121 0.04548186 0.6237852 0.04586809 0.6231595 0.0462563 0.6231595 0.0462563 0.6225351 0.04664641 0.6244121 0.04548186 0.6225351 0.04664641 0.6219118 0.04703837 0.6244121 0.04548186 0.6219118 0.04703837 0.6212897 0.04743236 0.6194308 0.04862552 0.6212897 0.04743236 0.6206688 0.04782813 0.6194308 0.04862552 0.6133151 0.05272549 0.6127105 0.05314576 0.6145281 0.05189049 0.6127105 0.05314576 0.6121072 0.05356788 0.6145281 0.05189049 0.6109045 0.05441766 0.6103051 0.05484533 0.6121072 0.05356788 0.6103051 0.05484533 0.6097071 0.05527484 0.6121072 0.05356788 0.6073281 0.05701106 0.6067367 0.05744969 0.6049705 0.05877643 0.6067367 0.05744969 0.6061466 0.05789011 0.6049705 0.05877643 0.6026348 0.06057053 0.6020544 0.06102359 0.6003214 0.06239324 0.6020544 0.06102359 0.6014752 0.06147837 0.6003214 0.06239324 0.6003214 0.06239324 0.5997465 0.06285333 0.5980304 0.06424415 0.5997465 0.06285333 0.599173 0.06331515 0.5980304 0.06424415 0.5968934 0.06518012 0.5963272 0.0656507 0.5980304 0.06424415 0.5963272 0.0656507 0.5957623 0.066123 0.5980304 0.06424415 0.594637 0.06707286 0.5940765 0.06755036 0.5957623 0.066123 0.5940765 0.06755036 0.5935175 0.06802958 0.5957623 0.066123 0.5935175 0.06802958 0.59296 0.06851053 0.5912962 0.06996357 0.59296 0.06851053 0.5924039 0.06899321 0.5912962 0.06996357 0.5912962 0.06996357 0.5907446 0.07045131 0.5901945 0.07094079 0.5901945 0.07094079 0.5896459 0.07143187 0.5890988 0.07192468 0.5880092 0.07291531 0.5874667 0.07341313 0.5890988 0.07192468 0.5874667 0.07341313 0.5869257 0.07391262 0.5890988 0.07192468 0.5869257 0.07391262 0.5863862 0.07441371 0.5858483 0.07491654 0.5847771 0.07592701 0.5842438 0.07643473 0.5826534 0.0779677 0.5842438 0.07643473 0.5837121 0.07694411 0.5826534 0.0779677 0.581601 0.07899773 0.5810772 0.07951515 0.5826534 0.0779677 0.5810772 0.07951515 0.5805549 0.08003425 0.5826534 0.0779677 0.5795152 0.08107709 0.5789977 0.08160096 0.5784819 0.08212637 0.5784819 0.08212637 0.5779677 0.08265334 0.5764348 0.08424383 0.5779677 0.08265334 0.5774551 0.08318191 0.5764348 0.08424383 0.5744138 0.0863862 0.5739126 0.08692568 0.5724192 0.08855324 0.5739126 0.08692568 0.5734131 0.08746665 0.5724192 0.08855324 0.5724192 0.08855324 0.5719247 0.08909881 0.5714319 0.08964586 0.5714319 0.08964586 0.5709408 0.09019446 0.5704514 0.09074455 0.5694776 0.09184926 0.5689932 0.09240382 0.5685106 0.09295994 0.5647113 0.09746116 0.5642442 0.09803032 0.5628533 0.09974646 0.5642442 0.09803032 0.5637788 0.09860098 0.5628533 0.09974646 0.561935 0.1008976 0.5614784 0.1014752 0.5628533 0.09974646 0.5614784 0.1014752 0.5610236 0.1020543 0.5628533 0.09974646 0.5592223 0.1043845 0.5587764 0.1049705 0.5574498 0.1067366 0.5587764 0.1049705 0.5583325 0.1055578 0.5574498 0.1067366 0.5574498 0.1067366 0.5570111 0.107328 0.5557062 0.1091103 0.5570111 0.107328 0.5565744 0.1079208 0.5557062 0.1091103 0.5557062 0.1091103 0.5552749 0.109707 0.5548453 0.1103051 0.5523071 0.1139209 0.5518906 0.1145281 0.5506521 0.1163572 0.5518906 0.1145281 0.5514758 0.1151365 0.5506521 0.1163572 0.5498358 0.1175829 0.5494305 0.1181976 0.5506521 0.1163572 0.5494305 0.1181976 0.5490271 0.1188135 0.5506521 0.1163572 0.5450975 0.1250401 0.5447151 0.1256693 0.5458682 0.1237851 0.5447151 0.1256693 0.5443347 0.1262997 0.5458682 0.1237851 0.5428321 0.1288328 0.5424614 0.129469 0.5413609 0.1313842 0.5424614 0.129469 0.5420926 0.1301063 0.5413609 0.1313842 0.5413609 0.1313842 0.5409979 0.1320249 0.5399209 0.1339535 0.5409979 0.1320249 0.540637 0.1326667 0.5399209 0.1339535 0.540637 0.1326667 0.540278 0.1333095 0.5399209 0.1339535 0.5399209 0.1339535 0.5395659 0.1345986 0.5392128 0.1352447 0.5392128 0.1352447 0.5388618 0.1358919 0.5399209 0.1339535 0.5388618 0.1358919 0.5385127 0.1365402 0.5399209 0.1339535 0.5378205 0.13784 0.5374774 0.1384915 0.5371363 0.139144 0.5371363 0.139144 0.5367972 0.1397976 0.5357919 0.1417645 0.5367972 0.1397976 0.5364601 0.1404522 0.5357919 0.1417645 0.5351319 0.1430809 0.5348049 0.1437407 0.5357919 0.1417645 0.5348049 0.1437407 0.5344799 0.1444013 0.5357919 0.1417645 0.5344799 0.1444013 0.5341569 0.1450631 0.533836 0.1457257 0.533836 0.1457257 0.5335171 0.1463894 0.5332003 0.1470541 0.5332003 0.1470541 0.5328854 0.1477197 0.5325726 0.1483862 0.531342 0.1510621 0.5310396 0.1517333 0.5319533 0.1497223 0.5310396 0.1517333 0.5307391 0.1524056 0.5319533 0.1497223 0.5301444 0.1537528 0.5298502 0.1544278 0.5307391 0.1524056 0.5298502 0.1544278 0.529558 0.1551036 0.5307391 0.1524056 0.5289799 0.156458 0.5286939 0.1571365 0.5284101 0.1578159 0.5267508 0.1619103 0.5264816 0.1625956 0.5262145 0.1632818 0.5251672 0.1660345 0.5249106 0.1667247 0.5241537 0.1687999 0.5249106 0.1667247 0.5246562 0.1674156 0.5241537 0.1687999 0.5226973 0.1729707 0.5224621 0.1736685 0.5231743 0.1715775 0.5224621 0.1736685 0.522229 0.1743668 0.5231743 0.1715775 0.522229 0.1743668 0.5219981 0.175066 0.521318 0.1771677 0.5219981 0.175066 0.5217692 0.1757659 0.521318 0.1771677 0.5208755 0.1785722 0.5206574 0.1792755 0.521318 0.1771677 0.5206574 0.1792755 0.5204415 0.1799794 0.521318 0.1771677 0.5204415 0.1799794 0.5202277 0.180684 0.5200161 0.1813893 0.5180197 0.1884763 0.5178321 0.1891883 0.5172823 0.1913277 0.5178321 0.1891883 0.5176466 0.1899008 0.5172823 0.1913277 0.5172823 0.1913277 0.5171033 0.1920419 0.5169267 0.1927567 0.5169267 0.1927567 0.5167521 0.193472 0.5165798 0.1941879 0.5165798 0.1941879 0.5164096 0.1949043 0.5162417 0.1956212 0.515592 0.1984938 0.5154351 0.1992133 0.5159124 0.1970565 0.5154351 0.1992133 0.5152804 0.1999331 0.5159124 0.1970565 0.5143986 0.204262 0.5142593 0.2049851 0.5146837 0.2028173 0.5142593 0.2049851 0.5141224 0.2057085 0.5146837 0.2028173 0.5141224 0.2057085 0.5139876 0.2064324 0.513855 0.2071567 0.513855 0.2071567 0.5137247 0.2078813 0.5141224 0.2057085 0.5137247 0.2078813 0.5135966 0.2086064 0.5141224 0.2057085 0.5135966 0.2086064 0.5134707 0.2093319 0.5131065 0.2115106 0.5134707 0.2093319 0.513347 0.2100577 0.5131065 0.2115106 0.5131065 0.2115106 0.5129895 0.2122375 0.5126519 0.2144205 0.5129895 0.2122375 0.5128747 0.2129648 0.5126519 0.2144205 0.5118502 0.220256 0.5117601 0.2209869 0.5116723 0.2217179 0.5107927 0.2305092 0.5107341 0.2312432 0.5109168 0.2290418 0.5107341 0.2312432 0.5106777 0.2319774 0.5109168 0.2290418 0.5105716 0.2334461 0.510522 0.2341808 0.5106777 0.2319774 0.510522 0.2341808 0.5104745 0.2349156 0.5106777 0.2319774 0.5103865 0.2363855 0.5103458 0.2371207 0.5104745 0.2349156 0.5103458 0.2371207 0.5103074 0.237856 0.5104745 0.2349156 0.510007 0.2481592 0.5100026 0.2488955 0.5100229 0.2466867 0.5100026 0.2488955 0.5100003 0.2496318 0.5100229 0.2466867 0.5100003 0.2496318 0.5100003 0.2503681 0.5100026 0.2511045 0.5100138 0.252577 0.5100229 0.2533133 0.5100635 0.2555218 0.5100229 0.2533133 0.5100342 0.2540495 0.5100635 0.2555218 0.5102058 0.2599374 0.5102375 0.260673 0.5102713 0.2614085 0.5103458 0.2628793 0.5103865 0.2636144 0.5102713 0.2614085 0.5103865 0.2636144 0.5104294 0.2643495 0.5102713 0.2614085 0.5106235 0.2672883 0.5106777 0.2680226 0.5108537 0.2702245 0.5106777 0.2680226 0.5107341 0.2687568 0.5108537 0.2702245 0.5108537 0.2702245 0.5109168 0.2709581 0.5111199 0.2731577 0.5109168 0.2709581 0.5109823 0.2716915 0.5111199 0.2731577 0.5112665 0.274623 0.5113431 0.2753553 0.5111199 0.2731577 0.5113431 0.2753553 0.511422 0.2760874 0.5111199 0.2731577 0.5121341 0.2819345 0.5122332 0.2826641 0.5125439 0.2848511 0.5122332 0.2826641 0.5123345 0.2833935 0.5125439 0.2848511 0.5125439 0.2848511 0.5126519 0.2855795 0.5129895 0.2877624 0.5126519 0.2855795 0.5127622 0.2863075 0.5129895 0.2877624 0.5129895 0.2877624 0.5131065 0.2884894 0.5134707 0.2906681 0.5131065 0.2884894 0.5132256 0.289216 0.5134707 0.2906681 0.5132256 0.289216 0.513347 0.2899422 0.5134707 0.2906681 0.5142593 0.2950149 0.5143986 0.2957379 0.51454 0.2964605 0.51454 0.2964605 0.5146837 0.2971827 0.5151278 0.2993465 0.5146837 0.2971827 0.5148295 0.2979044 0.5151278 0.2993465 0.5151278 0.2993465 0.5152804 0.3000668 0.5154351 0.3007867 0.5154351 0.3007867 0.515592 0.3015061 0.5157511 0.302225 0.5157511 0.302225 0.5159124 0.3029434 0.5164096 0.3050957 0.5159124 0.3029434 0.516076 0.3036614 0.5164096 0.3050957 0.5164096 0.3050957 0.5165798 0.3058121 0.5167521 0.3065279 0.5167521 0.3065279 0.5169267 0.3072432 0.5171033 0.3079581 0.5171033 0.3079581 0.5172823 0.3086723 0.5178321 0.3108117 0.5172823 0.3086723 0.5174633 0.309386 0.5178321 0.3108117 0.5182096 0.3122351 0.5184016 0.3129459 0.5178321 0.3108117 0.5184016 0.3129459 0.5185958 0.3136562 0.5178321 0.3108117 0.5185958 0.3136562 0.5187922 0.3143658 0.5189908 0.3150748 0.5189908 0.3150748 0.5191915 0.3157833 0.5185958 0.3136562 0.5191915 0.3157833 0.5193944 0.3164911 0.5185958 0.3136562 0.5193944 0.3164911 0.5195995 0.3171982 0.5202277 0.3193159 0.5195995 0.3171982 0.5198068 0.3179048 0.5202277 0.3193159 0.5202277 0.3193159 0.5204415 0.3200206 0.5206574 0.3207245 0.5206574 0.3207245 0.5208755 0.3214278 0.5210956 0.3221304 0.5215426 0.3235335 0.5217692 0.3242341 0.5210956 0.3221304 0.5217692 0.3242341 0.5219981 0.324934 0.5210956 0.3221304 0.5229347 0.3277263 0.5231743 0.3284225 0.5239056 0.3305068 0.5231743 0.3284225 0.5234159 0.329118 0.5239056 0.3305068 0.5239056 0.3305068 0.5241537 0.3312001 0.5249106 0.3332753 0.5241537 0.3312001 0.5244039 0.3318926 0.5249106 0.3332753 0.5254259 0.3346549 0.5256866 0.3353434 0.5249106 0.3332753 0.5256866 0.3353434 0.5259495 0.3360312 0.5249106 0.3332753 0.5259495 0.3360312 0.5262145 0.3367182 0.5264816 0.3374043 0.5264816 0.3374043 0.5267508 0.3380897 0.5270221 0.3387742 0.527571 0.3401407 0.5278486 0.3408226 0.5270221 0.3387742 0.5278486 0.3408226 0.5281283 0.3415038 0.5270221 0.3387742 0.5281283 0.3415038 0.5284101 0.342184 0.5292679 0.3442196 0.5284101 0.342184 0.5286939 0.3428635 0.5292679 0.3442196 0.5316466 0.3496083 0.5319533 0.3502777 0.5328854 0.3522803 0.5319533 0.3502777 0.5322619 0.3509462 0.5328854 0.3522803 0.5322619 0.3509462 0.5325726 0.3516137 0.5328854 0.3522803 0.5328854 0.3522803 0.5332003 0.3529459 0.5335171 0.3536105 0.5335171 0.3536105 0.533836 0.3542742 0.5341569 0.3549369 0.5354609 0.3575778 0.5357919 0.3582354 0.5367972 0.3602024 0.5357919 0.3582354 0.536125 0.3588921 0.5367972 0.3602024 0.536125 0.3588921 0.5364601 0.3595477 0.5367972 0.3602024 0.5367972 0.3602024 0.5371363 0.3608559 0.5374774 0.3615085 0.5395659 0.3654015 0.5399209 0.3660465 0.5409979 0.3679751 0.5399209 0.3660465 0.540278 0.3666905 0.5409979 0.3679751 0.540278 0.3666905 0.540637 0.3673334 0.5409979 0.3679751 0.5432049 0.3718022 0.5435795 0.3724361 0.5424614 0.370531 0.5435795 0.3724361 0.5439561 0.3730688 0.5424614 0.370531 0.5439561 0.3730688 0.5443347 0.3737003 0.5447151 0.3743306 0.5454819 0.3755879 0.5458682 0.3762148 0.5462563 0.3768405 0.5462563 0.3768405 0.5466464 0.377465 0.5454819 0.3755879 0.5466464 0.377465 0.5470384 0.3780882 0.5454819 0.3755879 0.5470384 0.3780882 0.5474324 0.3787103 0.5486255 0.3805692 0.5474324 0.3787103 0.5478282 0.3793312 0.5486255 0.3805692 0.5527255 0.3866849 0.5531458 0.3872895 0.5518906 0.3854719 0.5531458 0.3872895 0.5535679 0.3878928 0.5518906 0.3854719 0.5544177 0.3890955 0.5548453 0.3896949 0.5535679 0.3878928 0.5548453 0.3896949 0.5552749 0.390293 0.5535679 0.3878928 0.5570111 0.392672 0.5574498 0.3932633 0.5587764 0.3950295 0.5574498 0.3932633 0.5578902 0.3938534 0.5587764 0.3950295 0.5605706 0.3973652 0.5610236 0.3979457 0.5623933 0.3996787 0.5610236 0.3979457 0.5614784 0.3985247 0.5623933 0.3996787 0.5623933 0.3996787 0.5628533 0.4002535 0.5642442 0.4019696 0.5628533 0.4002535 0.5633152 0.400827 0.5642442 0.4019696 0.5651801 0.4031065 0.5656507 0.4036728 0.5642442 0.4019696 0.5656507 0.4036728 0.5661231 0.4042377 0.5642442 0.4019696 0.5670729 0.405363 0.5675504 0.4059235 0.5661231 0.4042377 0.5675504 0.4059235 0.5680297 0.4064825 0.5661231 0.4042377 0.5680297 0.4064825 0.5685106 0.4070401 0.5699636 0.4087038 0.5685106 0.4070401 0.5689932 0.4075961 0.5699636 0.4087038 0.5699636 0.4087038 0.5704514 0.4092554 0.5709408 0.4098055 0.5709408 0.4098055 0.5714319 0.4103541 0.5719247 0.4109011 0.5729153 0.4119908 0.5734131 0.4125334 0.5719247 0.4109011 0.5734131 0.4125334 0.5739126 0.4130743 0.5719247 0.4109011 0.5739126 0.4130743 0.5744138 0.4136138 0.5749166 0.4141517 0.5759271 0.4152229 0.5764348 0.4157562 0.5779677 0.4173466 0.5764348 0.4157562 0.5769441 0.4162879 0.5779677 0.4173466 0.5789977 0.418399 0.5795152 0.4189229 0.5779677 0.4173466 0.5795152 0.4189229 0.5800343 0.4194451 0.5779677 0.4173466 0.5810772 0.4204848 0.581601 0.4210023 0.5821264 0.4215181 0.5821264 0.4215181 0.5826534 0.4220323 0.5842438 0.4235652 0.5826534 0.4220323 0.583182 0.4225449 0.5842438 0.4235652 0.5863862 0.4255862 0.5869257 0.4260874 0.5885533 0.4275808 0.5869257 0.4260874 0.5874667 0.4265869 0.5885533 0.4275808 0.5885533 0.4275808 0.5890988 0.4280753 0.5896459 0.4285681 0.5896459 0.4285681 0.5901945 0.4290592 0.5907446 0.4295486 0.5918493 0.4305225 0.5924039 0.4310068 0.59296 0.4314894 0.5974612 0.4352887 0.5980304 0.4357559 0.5997465 0.4371467 0.5980304 0.4357559 0.598601 0.4362212 0.5997465 0.4371467 0.6008976 0.4380651 0.6014752 0.4385216 0.5997465 0.4371467 0.6014752 0.4385216 0.6020544 0.4389764 0.5997465 0.4371467 0.6043846 0.4407777 0.6049705 0.4412236 0.6067367 0.4425503 0.6049705 0.4412236 0.6055579 0.4416676 0.6067367 0.4425503 0.6067367 0.4425503 0.6073281 0.4429889 0.6091103 0.4442939 0.6073281 0.4429889 0.6079208 0.4434257 0.6091103 0.4442939 0.6091103 0.4442939 0.6097071 0.4447252 0.6103051 0.4451547 0.6139209 0.4476929 0.6145281 0.4481095 0.6163572 0.4493479 0.6145281 0.4481095 0.6151365 0.4485242 0.6163572 0.4493479 0.6175829 0.4501642 0.6181976 0.4505695 0.6163572 0.4493479 0.6181976 0.4505695 0.6188136 0.4509729 0.6163572 0.4493479 0.6250401 0.4549025 0.6256694 0.4552849 0.6237852 0.4541319 0.6256694 0.4552849 0.6262997 0.4556654 0.6237852 0.4541319 0.6288328 0.4571679 0.629469 0.4575386 0.6313843 0.4586392 0.629469 0.4575386 0.6301063 0.4579074 0.6313843 0.4586392 0.6313843 0.4586392 0.6320249 0.4590021 0.6339535 0.460079 0.6320249 0.4590021 0.6326667 0.4593631 0.6339535 0.460079 0.6326667 0.4593631 0.6333096 0.4597221 0.6339535 0.460079 0.6339535 0.460079 0.6345986 0.4604341 0.6352447 0.4607871 0.6352447 0.4607871 0.6358919 0.4611382 0.6339535 0.460079 0.6358919 0.4611382 0.6365402 0.4614873 0.6339535 0.460079 0.63784 0.4621795 0.6384915 0.4625226 0.6391441 0.4628637 0.6391441 0.4628637 0.6397976 0.4632028 0.6417646 0.4642081 0.6397976 0.4632028 0.6404523 0.4635399 0.6417646 0.4642081 0.643081 0.4648681 0.6437407 0.4651951 0.6417646 0.4642081 0.6437407 0.4651951 0.6444014 0.4655202 0.6417646 0.4642081 0.6444014 0.4655202 0.6450631 0.4658431 0.6457258 0.466164 0.6457258 0.466164 0.6463894 0.4664829 0.6470541 0.4667997 0.6470541 0.4667997 0.6477197 0.4671146 0.6483863 0.4674273 0.6510621 0.4686579 0.6517334 0.4689604 0.6497223 0.4680467 0.6517334 0.4689604 0.6524056 0.4692609 0.6497223 0.4680467 0.6537528 0.4698556 0.6544278 0.4701498 0.6524056 0.4692609 0.6544278 0.4701498 0.6551036 0.470442 0.6524056 0.4692609 0.656458 0.4710201 0.6571366 0.4713061 0.6578159 0.4715899 0.6619103 0.4732492 0.6625956 0.4735184 0.6632818 0.4737855 0.6660345 0.4748328 0.6667247 0.4750894 0.6687999 0.4758463 0.6667247 0.4750894 0.6674157 0.4753438 0.6687999 0.4758463 0.6729708 0.4773026 0.6736685 0.4775379 0.6715775 0.4768257 0.6736685 0.4775379 0.6743669 0.477771 0.6715775 0.4768257 0.6743669 0.477771 0.6750661 0.478002 0.6771677 0.478682 0.6750661 0.478002 0.6757659 0.4782308 0.6771677 0.478682 0.6785722 0.4791246 0.6792755 0.4793426 0.6771677 0.478682 0.6792755 0.4793426 0.6799795 0.4795585 0.6771677 0.478682 0.6799795 0.4795585 0.6806841 0.4797723 0.6813893 0.4799839 0.6884763 0.4819803 0.6891883 0.4821679 0.6913277 0.4827178 0.6891883 0.4821679 0.6899009 0.4823534 0.6913277 0.4827178 0.6913277 0.4827178 0.6920419 0.4828967 0.6927567 0.4830734 0.6927567 0.4830734 0.6934721 0.4832479 0.6941879 0.4834203 0.6941879 0.4834203 0.6949043 0.4835904 0.6956212 0.4837583 0.6984939 0.484408 0.6992133 0.4845649 0.6970565 0.4840875 0.6992133 0.4845649 0.6999332 0.4847196 0.6970565 0.4840875 0.7042621 0.4856014 0.7049851 0.4857407 0.7028173 0.4853163 0.7049851 0.4857407 0.7057086 0.4858776 0.7028173 0.4853163 0.7057086 0.4858776 0.7064324 0.4860124 0.7071567 0.486145 0.7071567 0.486145 0.7078814 0.4862753 0.7057086 0.4858776 0.7078814 0.4862753 0.7086065 0.4864034 0.7057086 0.4858776 0.7086065 0.4864034 0.7093319 0.4865293 0.7115106 0.4868935 0.7093319 0.4865293 0.7100578 0.4866529 0.7115106 0.4868935 0.7115106 0.4868935 0.7122376 0.4870105 0.7144206 0.487348 0.7122376 0.4870105 0.7129649 0.4871253 0.7144206 0.487348 0.7202561 0.4881498 0.7209869 0.4882399 0.7217179 0.4883278 0.7305093 0.4892073 0.7312432 0.4892659 0.7290419 0.4890832 0.7312432 0.4892659 0.7319774 0.4893223 0.7290419 0.4890832 0.7334462 0.4894284 0.7341808 0.4894781 0.7319774 0.4893223 0.7341808 0.4894781 0.7349156 0.4895255 0.7319774 0.4893223 0.7363856 0.4896135 0.7371208 0.4896542 0.7349156 0.4895255 0.7371208 0.4896542 0.737856 0.4896926 0.7349156 0.4895255 0.7481592 0.4899929 0.7488955 0.4899975 0.7466867 0.4899771 0.7488955 0.4899975 0.7496318 0.4899997 0.7466867 0.4899771 0.7496318 0.4899997 0.7511045 0.4899975 0.7555218 0.4899365 0.7511045 0.4899975 0.7525771 0.4899862 0.7555218 0.4899365 0.7555218 0.4899365 0.756994 0.4898981 0.7584658 0.4898506 0.7584658 0.4898506 0.7599374 0.4897942 0.7614085 0.4897287 0.7643495 0.4895706 0.7658192 0.4894781 0.7614085 0.4897287 0.7658192 0.4894781 0.7672883 0.4893765 0.7614085 0.4897287 0.7760874 0.488578 0.7775508 0.4884134 0.7731577 0.4888801 0.7775508 0.4884134 0.7790132 0.4882399 0.7731577 0.4888801 0.7790132 0.4882399 0.7804744 0.4880574 0.7848511 0.4874561 0.7804744 0.4880574 0.7819345 0.4878659 0.7848511 0.4874561 0.7906681 0.4865293 0.7921186 0.4862753 0.7935676 0.4860124 0.7935676 0.4860124 0.7950149 0.4857407 0.7906681 0.4865293 0.7950149 0.4857407 0.7964605 0.48546 0.7906681 0.4865293 0.7993465 0.4848722 0.8007867 0.4845649 0.7964605 0.48546 0.8007867 0.4845649 0.8022251 0.4842489 0.7964605 0.48546 0.8050957 0.4835904 0.8065279 0.4832479 0.8022251 0.4842489 0.8065279 0.4832479 0.8079581 0.4828967 0.8022251 0.4842489 0.8193159 0.4797723 0.8207245 0.4793426 0.824934 0.478002 0.8207245 0.4793426 0.8221304 0.4789044 0.824934 0.478002 0.824934 0.478002 0.8263316 0.4775379 0.8277263 0.4770653 0.8360312 0.4740505 0.8374044 0.4735184 0.8415038 0.4718717 0.8374044 0.4735184 0.8387742 0.4729779 0.8415038 0.4718717 0.8442196 0.4707321 0.8455722 0.4701498 0.8469212 0.4695593 0.8469212 0.4695593 0.8482666 0.4689604 0.8522803 0.4671146 0.8482666 0.4689604 0.8496083 0.4683533 0.8522803 0.4671146 0.8522803 0.4671146 0.8536106 0.4664829 0.8549369 0.4658431 0.8549369 0.4658431 0.8562594 0.4651951 0.8522803 0.4671146 0.8562594 0.4651951 0.8575778 0.4645391 0.8522803 0.4671146 0.8602024 0.4632028 0.8615085 0.4625226 0.8628104 0.4618344 0.8628104 0.4618344 0.8641081 0.4611382 0.8679751 0.4590021 0.8641081 0.4611382 0.8654015 0.4604341 0.8679751 0.4590021 0.8679751 0.4590021 0.8692553 0.4582743 0.870531 0.4575386 0.8730688 0.4560439 0.8743306 0.4552849 0.8780882 0.4529616 0.8743306 0.4552849 0.8755879 0.4545181 0.8780882 0.4529616 0.8805692 0.4513745 0.8818024 0.4505695 0.8780882 0.4529616 0.8818024 0.4505695 0.8830306 0.449757 0.8780882 0.4529616 0.8830306 0.449757 0.8842537 0.448937 0.8854719 0.4481095 0.890293 0.4447252 0.8914851 0.4438607 0.892672 0.4429889 0.8950295 0.4412236 0.8962001 0.44033 0.8973652 0.4394294 0.9087038 0.4300364 0.9098055 0.4290592 0.9064825 0.4319704 0.9098055 0.4290592 0.9109012 0.4280753 0.9064825 0.4319704 0.9130743 0.4260874 0.9141517 0.4250835 0.9152229 0.4240729 0.9194451 0.4199658 0.9204848 0.4189229 0.9235652 0.4157562 0.9204848 0.4189229 0.9215181 0.4178736 0.9235652 0.4157562 0.9235652 0.4157562 0.924579 0.4146881 0.9255862 0.4136138 0.9275808 0.4114468 0.9285681 0.4103541 0.9314894 0.4070401 0.9285681 0.4103541 0.9295486 0.4092554 0.9314894 0.4070401 0.9295486 0.4092554 0.9305225 0.4081507 0.9314894 0.4070401 0.9314894 0.4070401 0.9324496 0.4059235 0.9352887 0.4025388 0.9324496 0.4059235 0.9334029 0.4048011 0.9352887 0.4025388 0.9334029 0.4048011 0.9343493 0.4036728 0.9352887 0.4025388 0.9389764 0.3979457 0.9398806 0.3967833 0.9407777 0.3956155 0.9442939 0.3908897 0.9451547 0.3896949 0.9425503 0.3932633 0.9451547 0.3896949 0.9460082 0.3884948 0.9425503 0.3932633 0.9460082 0.3884948 0.9468542 0.3872895 0.9493479 0.3836428 0.9468542 0.3872895 0.9476929 0.3860791 0.9493479 0.3836428 0.9509729 0.3811864 0.9517741 0.3799508 0.9493479 0.3836428 0.9517741 0.3799508 0.9525676 0.3787103 0.9493479 0.3836428 0.9525676 0.3787103 0.9533536 0.377465 0.9556654 0.3737003 0.9533536 0.377465 0.9541319 0.3762148 0.9556654 0.3737003 0.9556654 0.3737003 0.9564205 0.3724361 0.9571679 0.3711671 0.9614873 0.3634598 0.9621795 0.36216 0.9642081 0.3582354 0.9621795 0.36216 0.9628637 0.3608559 0.9642081 0.3582354 0.9655202 0.3555986 0.966164 0.3542742 0.9642081 0.3582354 0.966164 0.3542742 0.9667997 0.3529459 0.9642081 0.3582354 0.9667997 0.3529459 0.9674274 0.3516137 0.9680467 0.3502777 0.970442 0.3448964 0.9710201 0.3435419 0.9692609 0.3475944 0.9710201 0.3435419 0.9715899 0.342184 0.9692609 0.3475944 0.9715899 0.342184 0.9721514 0.3408226 0.9727045 0.3394579 0.9727045 0.3394579 0.9732492 0.3380897 0.9737855 0.3367182 0.9737855 0.3367182 0.9743134 0.3353434 0.9758463 0.3312001 0.9743134 0.3353434 0.9748328 0.3339655 0.9758463 0.3312001 0.9758463 0.3312001 0.9763402 0.3298128 0.9768257 0.3284225 0.9795585 0.3200206 0.9799839 0.3186107 0.9804005 0.3171982 0.9804005 0.3171982 0.9808085 0.3157833 0.9812078 0.3143658 0.9812078 0.3143658 0.9815984 0.3129459 0.9827178 0.3086723 0.9815984 0.3129459 0.9819803 0.3115237 0.9827178 0.3086723 0.9827178 0.3086723 0.9830734 0.3072432 0.9840876 0.3029434 0.9830734 0.3072432 0.9834203 0.3058121 0.9840876 0.3029434 0.9834203 0.3058121 0.9837583 0.3043788 0.9840876 0.3029434 0.9847196 0.3000668 0.9850224 0.2986257 0.9853163 0.2971827 0.9873481 0.2855795 0.9875619 0.2841224 0.9877668 0.2826641 0.9877668 0.2826641 0.9879627 0.2812046 0.9881498 0.2797439 0.9881498 0.2797439 0.9883278 0.2782821 0.988808 0.2738904 0.9883278 0.2782821 0.9884968 0.2768192 0.988808 0.2738904 0.9884968 0.2768192 0.9886569 0.2753553 0.988808 0.2738904 0.988808 0.2738904 0.9889501 0.2724247 0.9890832 0.2709581 0.9896926 0.2621439 0.9897626 0.260673 0.9899184 0.2562579 0.9897626 0.260673 0.9898235 0.2592016 0.9899184 0.2562579 0.9898235 0.2592016 0.9898755 0.2577299 0.9899184 0.2562579 0.9899184 0.2562579 0.9899523 0.2547857 0.9899771 0.2533133 0.9899997 0.2503681 0.9899975 0.2488955 0.9899365 0.2444781 0.9899975 0.2488955 0.9899862 0.2474229 0.9899365 0.2444781 0.9899365 0.2444781 0.9898981 0.243006 0.9898506 0.2415342 0.9898506 0.2415342 0.9897942 0.2400626 0.9897287 0.2385914 0.9895706 0.2356505 0.9894781 0.2341808 0.9897287 0.2385914 0.9894781 0.2341808 0.9893765 0.2327117 0.9897287 0.2385914 0.988578 0.2239126 0.9884134 0.2224492 0.9888802 0.2268423 0.9884134 0.2224492 0.9882399 0.2209869 0.9888802 0.2268423 0.9882399 0.2209869 0.9880574 0.2195256 0.9874561 0.2151489 0.9880574 0.2195256 0.9878659 0.2180655 0.9874561 0.2151489 0.9865293 0.2093319 0.9862753 0.2078813 0.9860124 0.2064324 0.9860124 0.2064324 0.9857407 0.2049851 0.9865293 0.2093319 0.9857407 0.2049851 0.9854601 0.2035394 0.9865293 0.2093319 0.9848722 0.2006534 0.9845649 0.1992133 0.9854601 0.2035394 0.9845649 0.1992133 0.9842489 0.197775 0.9854601 0.2035394 0.9835904 0.1949043 0.9832479 0.193472 0.9842489 0.197775 0.9832479 0.193472 0.9828967 0.1920419 0.9842489 0.197775 0.9797723 0.180684 0.9793426 0.1792755 0.978002 0.175066 0.9793426 0.1792755 0.9789044 0.1778696 0.978002 0.175066 0.978002 0.175066 0.9775379 0.1736685 0.9770653 0.1722737 0.9740505 0.1639688 0.9735184 0.1625956 0.9718717 0.1584962 0.9735184 0.1625956 0.9729779 0.1612258 0.9718717 0.1584962 0.9707321 0.1557804 0.9701498 0.1544278 0.9695593 0.1530787 0.9695593 0.1530787 0.9689604 0.1517333 0.9671146 0.1477197 0.9689604 0.1517333 0.9683534 0.1503917 0.9671146 0.1477197 0.9671146 0.1477197 0.9664829 0.1463894 0.9658431 0.1450631 0.9658431 0.1450631 0.9651951 0.1437407 0.9671146 0.1477197 0.9651951 0.1437407 0.9645391 0.1424222 0.9671146 0.1477197 0.9632028 0.1397976 0.9625226 0.1384915 0.9618344 0.1371896 0.9618344 0.1371896 0.9611382 0.1358919 0.9590021 0.1320249 0.9611382 0.1358919 0.9604341 0.1345986 0.9590021 0.1320249 0.9590021 0.1320249 0.9582743 0.1307446 0.9575386 0.129469 0.9560439 0.1269312 0.9552849 0.1256693 0.9529616 0.1219117 0.9552849 0.1256693 0.9545181 0.124412 0.9529616 0.1219117 0.9513745 0.1194307 0.9505695 0.1181976 0.9529616 0.1219117 0.9505695 0.1181976 0.949757 0.1169694 0.9529616 0.1219117 0.949757 0.1169694 0.948937 0.1157462 0.9481095 0.1145281 0.9447252 0.109707 0.9438607 0.1085149 0.9429889 0.107328 0.9412236 0.1049705 0.94033 0.1037999 0.9394294 0.1026348 0.9300364 0.09129619 0.9290592 0.09019446 0.9319704 0.09351742 0.9290592 0.09019446 0.9280753 0.08909881 0.9319704 0.09351742 0.9260874 0.08692568 0.9250835 0.08584827 0.9240729 0.08477705 0.9199658 0.0805549 0.9189229 0.07951515 0.9157562 0.07643473 0.9189229 0.07951515 0.9178736 0.07848191 0.9157562 0.07643473 0.9157562 0.07643473 0.9146881 0.07542097 0.9136138 0.07441371 0.9114468 0.07241916 0.9103541 0.07143187 0.9070401 0.06851053 0.9103541 0.07143187 0.9092554 0.07045131 0.9070401 0.06851053 0.9092554 0.07045131 0.9081507 0.06947755 0.9070401 0.06851053 0.9070401 0.06851053 0.9059235 0.06755036 0.9025388 0.06471127 0.9059235 0.06755036 0.9048011 0.0665971 0.9025388 0.06471127 0.9048011 0.0665971 0.9036728 0.0656507 0.9025388 0.06471127 0.8979457 0.06102359 0.8967834 0.06011933 0.8956155 0.05922228 0.8908897 0.05570614 0.8896949 0.05484533 0.8932633 0.05744969 0.8896949 0.05484533 0.8884948 0.05399185 0.8932633 0.05744969 0.8884948 0.05399185 0.8872895 0.05314576 0.8836428 0.05065202 0.8872895 0.05314576 0.8860791 0.05230706 0.8836428 0.05065202 0.8811864 0.04902702 0.8799508 0.04822587 0.8836428 0.05065202 0.8799508 0.04822587 0.8787103 0.04743236 0.8836428 0.05065202 0.8787103 0.04743236 0.877465 0.04664641 0.8737003 0.04433465 0.877465 0.04664641 0.8762148 0.04586809 0.8737003 0.04433465 0.8737003 0.04433465 0.8724361 0.04357951 0.8711672 0.04283213 0.8634598 0.0385127 0.86216 0.03782045 0.8582354 0.03579193 0.86216 0.03782045 0.8608559 0.03713625 0.8582354 0.03579193 0.8555986 0.03447985 0.8542742 0.03383594 0.8582354 0.03579193 0.8542742 0.03383594 0.8529459 0.0332002 0.8582354 0.03579193 0.8529459 0.0332002 0.8516137 0.03257262 0.8502777 0.03195321 0.8448964 0.02955794 0.843542 0.02897983 0.8475944 0.03073906 0.843542 0.02897983 0.8421841 0.02841007 0.8475944 0.03073906 0.8421841 0.02841007 0.8408226 0.0278486 0.8394579 0.02729547 0.8394579 0.02729547 0.8380897 0.0267508 0.8367182 0.02621448 0.8367182 0.02621448 0.8353434 0.02568662 0.8312001 0.0241537 0.8353434 0.02568662 0.8339655 0.02516716 0.8312001 0.0241537 0.8312001 0.0241537 0.8298128 0.0236597 0.8284225 0.02317428 0.8200206 0.02044147 0.8186107 0.02001613 0.8171982 0.01959949 0.8171982 0.01959949 0.8157833 0.0191915 0.8143658 0.01879221 0.8143658 0.01879221 0.812946 0.01840162 0.8086723 0.01728218 0.812946 0.01840162 0.8115237 0.01801973 0.8086723 0.01728218 0.8086723 0.01728218 0.8072433 0.01692658 0.8029435 0.01591241 0.8072433 0.01692658 0.8058121 0.01657974 0.8029435 0.01591241 0.8058121 0.01657974 0.8043788 0.01624166 0.8029435 0.01591241 0.8000668 0.01528036 0.7986257 0.01497757 0.7971827 0.0146836 0.7855795 0.01265192 0.7841224 0.01243805 0.7826641 0.01223319 0.7826641 0.01223319 0.7812046 0.01203721 0.7797439 0.01185023 0.7797439 0.01185023 0.7782821 0.01167219 0.7738905 0.01119202 0.7782821 0.01167219 0.7768192 0.01150315 0.7738905 0.01119202 0.7768192 0.01150315 0.7753553 0.01134312 0.7738905 0.01119202 0.7738905 0.01119202 0.7724247 0.01104992 0.7709581 0.01091682 0.762144 0.01030743 0.760673 0.01023739 0.756258 0.01008158 0.760673 0.01023739 0.7592017 0.01017642 0.756258 0.01008158 0.7592017 0.01017642 0.75773 0.0101245 0.756258 0.01008158 0.756258 0.01008158 0.7547857 0.01004773 0.7533133 0.01002287 0.7503682 0.01000028 0.7488955 0.01000255 0.7444782 0.01006352 0.7488955 0.01000255 0.7474229 0.01001381 0.7444782 0.01006352 0.7444782 0.01006352 0.7430061 0.01010191 0.7415342 0.01014935 0.7415342 0.01014935 0.7400627 0.0102058 0.7385915 0.01027131 0.7356505 0.01042932 0.7341808 0.01052188 0.7385915 0.01027131 0.7341808 0.01052188 0.7327117 0.01062345 0.7385915 0.01027131 0.7239126 0.01142203 0.7224493 0.0115866 0.7268423 0.01111984 0.7224493 0.0115866 0.7209869 0.01176011 0.7268423 0.01111984 0.7209869 0.01176011 0.7195256 0.01194262 0.7151489 0.01254385 0.7195256 0.01194262 0.7180655 0.01213407 0.7151489 0.01254385 0.7093319 0.0134707 0.7078814 0.01372468 0.7064324 0.01398754 0.7064324 0.01398754 0.7049851 0.01425933 0.7093319 0.0134707 0.7049851 0.01425933 0.7035395 0.01453995 0.7093319 0.0134707 0.7006535 0.01512783 0.6992133 0.01543503 0.7035395 0.01453995 0.6992133 0.01543503 0.697775 0.01575106 0.7035395 0.01453995 0.6949043 0.01640957 0.6934721 0.01675206 0.697775 0.01575106 0.6934721 0.01675206 0.6920419 0.01710331 0.697775 0.01575106 0.6806841 0.02022767 0.6792755 0.02065736 0.6750661 0.02199798 0.6792755 0.02065736 0.6778696 0.02109563 0.6750661 0.02199798 0.6750661 0.02199798 0.6736685 0.02246206 0.6722738 0.02293473 0.6639688 0.02594947 0.6625956 0.02648156 0.6584962 0.02812826 0.6625956 0.02648156 0.6612258 0.02702206 0.6584962 0.02812826 0.6557804 0.02926784 0.6544278 0.02985012 0.6530788 0.03044068 0.6530788 0.03044068 0.6517334 0.03103953 0.6477197 0.03288543 0.6517334 0.03103953 0.6503918 0.0316466 0.6477197 0.03288543 0.6477197 0.03288543 0.6463894 0.03351706 0.6450631 0.03415685 0.6450631 0.03415685 0.6437407 0.03480482 0.6477197 0.03288543 0.6437407 0.03480482 0.6424223 0.03546088 0.6477197 0.03288543 0.6397976 0.03679716 0.6384915 0.03747737 0.6371896 0.03816556 0.6371896 0.03816556 0.6358919 0.03886175 0.6320249 0.04099792 0.6358919 0.03886175 0.6345986 0.03956592 0.6320249 0.04099792 0.6320249 0.04099792 0.6307447 0.04172569 0.629469 0.04246133 0.6269313 0.0439561 0.6256694 0.0447151 0.6219118 0.04703837 0.6256694 0.0447151 0.6244121 0.04548186 0.6219118 0.04703837 0.6194308 0.04862552 0.6181976 0.04943048 0.6219118 0.04703837 0.6181976 0.04943048 0.6169694 0.05024296 0.6219118 0.04703837 0.6169694 0.05024296 0.6157463 0.051063 0.6145281 0.05189049 0.6097071 0.05527484 0.6085149 0.05613929 0.6073281 0.05701106 0.6049705 0.05877643 0.6037999 0.05966991 0.6026348 0.06057053 0.5912962 0.06996357 0.5901945 0.07094079 0.5935175 0.06802958 0.5901945 0.07094079 0.5890988 0.07192468 0.5935175 0.06802958 0.5869257 0.07391262 0.5858483 0.07491654 0.5847771 0.07592701 0.5805549 0.08003425 0.5795152 0.08107709 0.5764348 0.08424383 0.5795152 0.08107709 0.5784819 0.08212637 0.5764348 0.08424383 0.5764348 0.08424383 0.575421 0.08531188 0.5744138 0.0863862 0.5724192 0.08855324 0.5714319 0.08964586 0.5685106 0.09295994 0.5714319 0.08964586 0.5704514 0.09074455 0.5685106 0.09295994 0.5704514 0.09074455 0.5694776 0.09184926 0.5685106 0.09295994 0.5685106 0.09295994 0.5675504 0.09407645 0.5647113 0.09746116 0.5675504 0.09407645 0.5665971 0.09519886 0.5647113 0.09746116 0.5665971 0.09519886 0.5656507 0.09632712 0.5647113 0.09746116 0.5610236 0.1020543 0.5601194 0.1032167 0.5592223 0.1043845 0.5557062 0.1091103 0.5548453 0.1103051 0.5574498 0.1067366 0.5548453 0.1103051 0.5539919 0.1115052 0.5574498 0.1067366 0.5539919 0.1115052 0.5531458 0.1127105 0.5506521 0.1163572 0.5531458 0.1127105 0.5523071 0.1139209 0.5506521 0.1163572 0.5490271 0.1188135 0.5482259 0.1200491 0.5506521 0.1163572 0.5482259 0.1200491 0.5474324 0.1212897 0.5506521 0.1163572 0.5474324 0.1212897 0.5466464 0.122535 0.5443347 0.1262997 0.5466464 0.122535 0.5458682 0.1237851 0.5443347 0.1262997 0.5443347 0.1262997 0.5435795 0.127564 0.5428321 0.1288328 0.5385127 0.1365402 0.5378205 0.13784 0.5357919 0.1417645 0.5378205 0.13784 0.5371363 0.139144 0.5357919 0.1417645 0.5344799 0.1444013 0.533836 0.1457257 0.5357919 0.1417645 0.533836 0.1457257 0.5332003 0.1470541 0.5357919 0.1417645 0.5332003 0.1470541 0.5325726 0.1483862 0.5319533 0.1497223 0.529558 0.1551036 0.5289799 0.156458 0.5307391 0.1524056 0.5289799 0.156458 0.5284101 0.1578159 0.5307391 0.1524056 0.5284101 0.1578159 0.5278486 0.1591773 0.5272955 0.1605421 0.5272955 0.1605421 0.5267508 0.1619103 0.5262145 0.1632818 0.5262145 0.1632818 0.5256866 0.1646565 0.5241537 0.1687999 0.5256866 0.1646565 0.5251672 0.1660345 0.5241537 0.1687999 0.5241537 0.1687999 0.5236598 0.1701872 0.5231743 0.1715775 0.5204415 0.1799794 0.5200161 0.1813893 0.5195995 0.1828017 0.5195995 0.1828017 0.5191915 0.1842167 0.5187922 0.1856341 0.5187922 0.1856341 0.5184016 0.187054 0.5172823 0.1913277 0.5184016 0.187054 0.5180197 0.1884763 0.5172823 0.1913277 0.5172823 0.1913277 0.5169267 0.1927567 0.5159124 0.1970565 0.5169267 0.1927567 0.5165798 0.1941879 0.5159124 0.1970565 0.5165798 0.1941879 0.5162417 0.1956212 0.5159124 0.1970565 0.5152804 0.1999331 0.5149776 0.2013743 0.5146837 0.2028173 0.5126519 0.2144205 0.5124381 0.2158775 0.5122332 0.2173358 0.5122332 0.2173358 0.5120373 0.2187954 0.5118502 0.220256 0.5118502 0.220256 0.5116723 0.2217179 0.511192 0.2261095 0.5116723 0.2217179 0.5115032 0.2231808 0.511192 0.2261095 0.5115032 0.2231808 0.5113431 0.2246447 0.511192 0.2261095 0.511192 0.2261095 0.5110499 0.2275753 0.5109168 0.2290418 0.5103074 0.237856 0.5102375 0.239327 0.5100816 0.2437421 0.5102375 0.239327 0.5101765 0.2407984 0.5100816 0.2437421 0.5101765 0.2407984 0.5101245 0.2422701 0.5100816 0.2437421 0.5100816 0.2437421 0.5100477 0.2452143 0.5100229 0.2466867 0.5100003 0.2496318 0.5100026 0.2511045 0.5100635 0.2555218 0.5100026 0.2511045 0.5100138 0.252577 0.5100635 0.2555218 0.5100635 0.2555218 0.5101019 0.256994 0.5101494 0.2584658 0.5101494 0.2584658 0.5102058 0.2599374 0.5102713 0.2614085 0.5104294 0.2643495 0.510522 0.2658192 0.5102713 0.2614085 0.510522 0.2658192 0.5106235 0.2672883 0.5102713 0.2614085 0.511422 0.2760874 0.5115866 0.2775508 0.5111199 0.2731577 0.5115866 0.2775508 0.5117601 0.2790132 0.5111199 0.2731577 0.5117601 0.2790132 0.5119426 0.2804744 0.5125439 0.2848511 0.5119426 0.2804744 0.5121341 0.2819345 0.5125439 0.2848511 0.5134707 0.2906681 0.5137247 0.2921186 0.5139876 0.2935676 0.5139876 0.2935676 0.5142593 0.2950149 0.5134707 0.2906681 0.5142593 0.2950149 0.51454 0.2964605 0.5134707 0.2906681 0.5151278 0.2993465 0.5154351 0.3007867 0.51454 0.2964605 0.5154351 0.3007867 0.5157511 0.302225 0.51454 0.2964605 0.5164096 0.3050957 0.5167521 0.3065279 0.5157511 0.302225 0.5167521 0.3065279 0.5171033 0.3079581 0.5157511 0.302225 0.5202277 0.3193159 0.5206574 0.3207245 0.5219981 0.324934 0.5206574 0.3207245 0.5210956 0.3221304 0.5219981 0.324934 0.5219981 0.324934 0.5224621 0.3263316 0.5229347 0.3277263 0.5259495 0.3360312 0.5264816 0.3374043 0.5281283 0.3415038 0.5264816 0.3374043 0.5270221 0.3387742 0.5281283 0.3415038 0.5292679 0.3442196 0.5298502 0.3455722 0.5304408 0.3469212 0.5304408 0.3469212 0.5310396 0.3482666 0.5328854 0.3522803 0.5310396 0.3482666 0.5316466 0.3496083 0.5328854 0.3522803 0.5328854 0.3522803 0.5335171 0.3536105 0.5341569 0.3549369 0.5341569 0.3549369 0.5348049 0.3562594 0.5328854 0.3522803 0.5348049 0.3562594 0.5354609 0.3575778 0.5328854 0.3522803 0.5367972 0.3602024 0.5374774 0.3615085 0.5381656 0.3628104 0.5381656 0.3628104 0.5388618 0.364108 0.5409979 0.3679751 0.5388618 0.364108 0.5395659 0.3654015 0.5409979 0.3679751 0.5409979 0.3679751 0.5417258 0.3692553 0.5424614 0.370531 0.5439561 0.3730688 0.5447151 0.3743306 0.5470384 0.3780882 0.5447151 0.3743306 0.5454819 0.3755879 0.5470384 0.3780882 0.5486255 0.3805692 0.5494305 0.3818024 0.5470384 0.3780882 0.5494305 0.3818024 0.550243 0.3830306 0.5470384 0.3780882 0.550243 0.3830306 0.551063 0.3842537 0.5518906 0.3854719 0.5552749 0.390293 0.5561394 0.3914851 0.5570111 0.392672 0.5587764 0.3950295 0.55967 0.3962001 0.5605706 0.3973652 0.5699636 0.4087038 0.5709408 0.4098055 0.5680297 0.4064825 0.5709408 0.4098055 0.5719247 0.4109011 0.5680297 0.4064825 0.5739126 0.4130743 0.5749166 0.4141517 0.5759271 0.4152229 0.5800343 0.4194451 0.5810772 0.4204848 0.5842438 0.4235652 0.5810772 0.4204848 0.5821264 0.4215181 0.5842438 0.4235652 0.5842438 0.4235652 0.5853119 0.424579 0.5863862 0.4255862 0.5885533 0.4275808 0.5896459 0.4285681 0.59296 0.4314894 0.5896459 0.4285681 0.5907446 0.4295486 0.59296 0.4314894 0.5907446 0.4295486 0.5918493 0.4305225 0.59296 0.4314894 0.59296 0.4314894 0.5940765 0.4324496 0.5974612 0.4352887 0.5940765 0.4324496 0.5951989 0.4334029 0.5974612 0.4352887 0.5951989 0.4334029 0.5963272 0.4343493 0.5974612 0.4352887 0.6020544 0.4389764 0.6032167 0.4398806 0.6043846 0.4407777 0.6091103 0.4442939 0.6103051 0.4451547 0.6067367 0.4425503 0.6103051 0.4451547 0.6115052 0.4460082 0.6067367 0.4425503 0.6115052 0.4460082 0.6127105 0.4468542 0.6163572 0.4493479 0.6127105 0.4468542 0.6139209 0.4476929 0.6163572 0.4493479 0.6188136 0.4509729 0.6200492 0.4517741 0.6163572 0.4493479 0.6200492 0.4517741 0.6212897 0.4525676 0.6163572 0.4493479 0.6212897 0.4525676 0.6225351 0.4533536 0.6262997 0.4556654 0.6225351 0.4533536 0.6237852 0.4541319 0.6262997 0.4556654 0.6262997 0.4556654 0.627564 0.4564205 0.6288328 0.4571679 0.6365402 0.4614873 0.63784 0.4621795 0.6417646 0.4642081 0.63784 0.4621795 0.6391441 0.4628637 0.6417646 0.4642081 0.6444014 0.4655202 0.6457258 0.466164 0.6417646 0.4642081 0.6457258 0.466164 0.6470541 0.4667997 0.6417646 0.4642081 0.6470541 0.4667997 0.6483863 0.4674273 0.6497223 0.4680467 0.6551036 0.470442 0.656458 0.4710201 0.6524056 0.4692609 0.656458 0.4710201 0.6578159 0.4715899 0.6524056 0.4692609 0.6578159 0.4715899 0.6591774 0.4721514 0.6605421 0.4727045 0.6605421 0.4727045 0.6619103 0.4732492 0.6632818 0.4737855 0.6632818 0.4737855 0.6646566 0.4743134 0.6687999 0.4758463 0.6646566 0.4743134 0.6660345 0.4748328 0.6687999 0.4758463 0.6687999 0.4758463 0.6701872 0.4763402 0.6715775 0.4768257 0.6799795 0.4795585 0.6813893 0.4799839 0.6828018 0.4804005 0.6828018 0.4804005 0.6842167 0.4808085 0.6856342 0.4812078 0.6856342 0.4812078 0.687054 0.4815984 0.6913277 0.4827178 0.687054 0.4815984 0.6884763 0.4819803 0.6913277 0.4827178 0.6913277 0.4827178 0.6927567 0.4830734 0.6970565 0.4840875 0.6927567 0.4830734 0.6941879 0.4834203 0.6970565 0.4840875 0.6941879 0.4834203 0.6956212 0.4837583 0.6970565 0.4840875 0.6999332 0.4847196 0.7013743 0.4850224 0.7028173 0.4853163 0.7144206 0.487348 0.7158776 0.4875619 0.7173359 0.4877668 0.7173359 0.4877668 0.7187954 0.4879627 0.7202561 0.4881498 0.7202561 0.4881498 0.7217179 0.4883278 0.7261095 0.488808 0.7217179 0.4883278 0.7231808 0.4884968 0.7261095 0.488808 0.7231808 0.4884968 0.7246447 0.4886569 0.7261095 0.488808 0.7261095 0.488808 0.7275753 0.4889501 0.7290419 0.4890832 0.737856 0.4896926 0.739327 0.4897626 0.7437421 0.4899184 0.739327 0.4897626 0.7407984 0.4898235 0.7437421 0.4899184 0.7407984 0.4898235 0.7422701 0.4898755 0.7437421 0.4899184 0.7437421 0.4899184 0.7452143 0.4899523 0.7466867 0.4899771 0.7555218 0.4899365 0.7584658 0.4898506 0.7496318 0.4899997 0.7584658 0.4898506 0.7614085 0.4897287 0.7496318 0.4899997 0.7672883 0.4893765 0.7702245 0.4891463 0.7614085 0.4897287 0.7702245 0.4891463 0.7731577 0.4888801 0.7614085 0.4897287 0.7848511 0.4874561 0.7877624 0.4870105 0.7906681 0.4865293 0.8079581 0.4828967 0.8108117 0.4821679 0.8136562 0.4814042 0.8136562 0.4814042 0.8164911 0.4806056 0.8193159 0.4797723 0.824934 0.478002 0.8277263 0.4770653 0.8305069 0.4760943 0.8305069 0.4760943 0.8332753 0.4750894 0.8415038 0.4718717 0.8332753 0.4750894 0.8360312 0.4740505 0.8415038 0.4718717 0.8415038 0.4718717 0.8442196 0.4707321 0.8522803 0.4671146 0.8442196 0.4707321 0.8469212 0.4695593 0.8522803 0.4671146 0.8575778 0.4645391 0.8602024 0.4632028 0.8522803 0.4671146 0.8602024 0.4632028 0.8628104 0.4618344 0.8522803 0.4671146 0.8679751 0.4590021 0.870531 0.4575386 0.8730688 0.4560439 0.8830306 0.449757 0.8854719 0.4481095 0.8878929 0.4464321 0.8878929 0.4464321 0.890293 0.4447252 0.8830306 0.449757 0.890293 0.4447252 0.892672 0.4429889 0.8830306 0.449757 0.892672 0.4429889 0.8950295 0.4412236 0.9019696 0.4357559 0.8950295 0.4412236 0.8973652 0.4394294 0.9019696 0.4357559 0.8973652 0.4394294 0.8996787 0.4376068 0.9019696 0.4357559 0.9019696 0.4357559 0.9042377 0.4338769 0.9064825 0.4319704 0.9109012 0.4280753 0.9130743 0.4260874 0.9152229 0.4240729 0.9152229 0.4240729 0.9173466 0.4220323 0.9194451 0.4199658 0.9235652 0.4157562 0.9255862 0.4136138 0.9275808 0.4114468 0.9352887 0.4025388 0.9371467 0.4002535 0.9425503 0.3932633 0.9371467 0.4002535 0.9389764 0.3979457 0.9425503 0.3932633 0.9389764 0.3979457 0.9407777 0.3956155 0.9425503 0.3932633 0.9556654 0.3737003 0.9571679 0.3711671 0.9586392 0.3686158 0.9586392 0.3686158 0.9600791 0.3660465 0.9556654 0.3737003 0.9600791 0.3660465 0.9614873 0.3634598 0.9556654 0.3737003 0.9667997 0.3529459 0.9680467 0.3502777 0.9715899 0.342184 0.9680467 0.3502777 0.9692609 0.3475944 0.9715899 0.342184 0.9715899 0.342184 0.9727045 0.3394579 0.9758463 0.3312001 0.9727045 0.3394579 0.9737855 0.3367182 0.9758463 0.3312001 0.9758463 0.3312001 0.9768257 0.3284225 0.9795585 0.3200206 0.9768257 0.3284225 0.9777711 0.3256331 0.9795585 0.3200206 0.9777711 0.3256331 0.978682 0.3228323 0.9795585 0.3200206 0.9795585 0.3200206 0.9804005 0.3171982 0.9827178 0.3086723 0.9804005 0.3171982 0.9812078 0.3143658 0.9827178 0.3086723 0.9840876 0.3029434 0.9847196 0.3000668 0.9827178 0.3086723 0.9847196 0.3000668 0.9853163 0.2971827 0.9827178 0.3086723 0.9853163 0.2971827 0.9858776 0.2942914 0.9864034 0.2913935 0.9864034 0.2913935 0.9868935 0.2884894 0.9853163 0.2971827 0.9868935 0.2884894 0.9873481 0.2855795 0.9853163 0.2971827 0.9873481 0.2855795 0.9877668 0.2826641 0.988808 0.2738904 0.9877668 0.2826641 0.9881498 0.2797439 0.988808 0.2738904 0.988808 0.2738904 0.9890832 0.2709581 0.9893223 0.2680226 0.9893223 0.2680226 0.9895255 0.2650844 0.9896926 0.2621439 0.9899184 0.2562579 0.9899771 0.2533133 0.9896926 0.2621439 0.9899771 0.2533133 0.9899997 0.2503681 0.9896926 0.2621439 0.9899365 0.2444781 0.9898506 0.2415342 0.9899997 0.2503681 0.9898506 0.2415342 0.9897287 0.2385914 0.9899997 0.2503681 0.9893765 0.2327117 0.9891464 0.2297754 0.9897287 0.2385914 0.9891464 0.2297754 0.9888802 0.2268423 0.9897287 0.2385914 0.9874561 0.2151489 0.9870105 0.2122375 0.9865293 0.2093319 0.9828967 0.1920419 0.9821679 0.1891883 0.9814042 0.1863438 0.9814042 0.1863438 0.9806056 0.1835089 0.9797723 0.180684 0.978002 0.175066 0.9770653 0.1722737 0.9760944 0.1694931 0.9760944 0.1694931 0.9750894 0.1667247 0.9718717 0.1584962 0.9750894 0.1667247 0.9740505 0.1639688 0.9718717 0.1584962 0.9718717 0.1584962 0.9707321 0.1557804 0.9671146 0.1477197 0.9707321 0.1557804 0.9695593 0.1530787 0.9671146 0.1477197 0.9645391 0.1424222 0.9632028 0.1397976 0.9671146 0.1477197 0.9632028 0.1397976 0.9618344 0.1371896 0.9671146 0.1477197 0.9590021 0.1320249 0.9575386 0.129469 0.9560439 0.1269312 0.949757 0.1169694 0.9481095 0.1145281 0.9464321 0.1121072 0.9464321 0.1121072 0.9447252 0.109707 0.949757 0.1169694 0.9447252 0.109707 0.9429889 0.107328 0.949757 0.1169694 0.9429889 0.107328 0.9412236 0.1049705 0.9357559 0.09803032 0.9412236 0.1049705 0.9394294 0.1026348 0.9357559 0.09803032 0.9394294 0.1026348 0.9376068 0.1003213 0.9357559 0.09803032 0.9357559 0.09803032 0.9338769 0.09576231 0.9319704 0.09351742 0.9280753 0.08909881 0.9260874 0.08692568 0.9240729 0.08477705 0.9240729 0.08477705 0.9220323 0.08265334 0.9199658 0.0805549 0.9157562 0.07643473 0.9136138 0.07441371 0.9114468 0.07241916 0.9025388 0.06471127 0.9002535 0.06285333 0.8932633 0.05744969 0.9002535 0.06285333 0.8979457 0.06102359 0.8932633 0.05744969 0.8979457 0.06102359 0.8956155 0.05922228 0.8932633 0.05744969 0.8737003 0.04433465 0.8711672 0.04283213 0.8686158 0.04136079 0.8686158 0.04136079 0.8660465 0.03992092 0.8737003 0.04433465 0.8660465 0.03992092 0.8634598 0.0385127 0.8737003 0.04433465 0.8529459 0.0332002 0.8502777 0.03195321 0.8421841 0.02841007 0.8502777 0.03195321 0.8475944 0.03073906 0.8421841 0.02841007 0.8421841 0.02841007 0.8394579 0.02729547 0.8312001 0.0241537 0.8394579 0.02729547 0.8367182 0.02621448 0.8312001 0.0241537 0.8312001 0.0241537 0.8284225 0.02317428 0.8200206 0.02044147 0.8284225 0.02317428 0.8256331 0.02222895 0.8200206 0.02044147 0.8256331 0.02222895 0.8228323 0.02131801 0.8200206 0.02044147 0.8200206 0.02044147 0.8171982 0.01959949 0.8086723 0.01728218 0.8171982 0.01959949 0.8143658 0.01879221 0.8086723 0.01728218 0.8029435 0.01591241 0.8000668 0.01528036 0.8086723 0.01728218 0.8000668 0.01528036 0.7971827 0.0146836 0.8086723 0.01728218 0.7971827 0.0146836 0.7942914 0.0141223 0.7913935 0.01359653 0.7913935 0.01359653 0.7884894 0.0131064 0.7971827 0.0146836 0.7884894 0.0131064 0.7855795 0.01265192 0.7971827 0.0146836 0.7855795 0.01265192 0.7826641 0.01223319 0.7738905 0.01119202 0.7826641 0.01223319 0.7797439 0.01185023 0.7738905 0.01119202 0.7738905 0.01119202 0.7709581 0.01091682 0.7680227 0.01067763 0.7680227 0.01067763 0.7650845 0.0104745 0.762144 0.01030743 0.756258 0.01008158 0.7533133 0.01002287 0.762144 0.01030743 0.7533133 0.01002287 0.7503682 0.01000028 0.762144 0.01030743 0.7444782 0.01006352 0.7415342 0.01014935 0.7503682 0.01000028 0.7415342 0.01014935 0.7385915 0.01027131 0.7503682 0.01000028 0.7327117 0.01062345 0.7297755 0.01085364 0.7385915 0.01027131 0.7297755 0.01085364 0.7268423 0.01111984 0.7385915 0.01027131 0.7151489 0.01254385 0.7122376 0.01298946 0.7093319 0.0134707 0.6920419 0.01710331 0.6891883 0.0178321 0.6863439 0.01859581 0.6863439 0.01859581 0.6835089 0.01939439 0.6806841 0.02022767 0.6750661 0.02199798 0.6722738 0.02293473 0.6694931 0.02390563 0.6694931 0.02390563 0.6667247 0.02491062 0.6584962 0.02812826 0.6667247 0.02491062 0.6639688 0.02594947 0.6584962 0.02812826 0.6584962 0.02812826 0.6557804 0.02926784 0.6477197 0.03288543 0.6557804 0.02926784 0.6530788 0.03044068 0.6477197 0.03288543 0.6424223 0.03546088 0.6397976 0.03679716 0.6477197 0.03288543 0.6397976 0.03679716 0.6371896 0.03816556 0.6477197 0.03288543 0.6320249 0.04099792 0.629469 0.04246133 0.6269313 0.0439561 0.6169694 0.05024296 0.6145281 0.05189049 0.6121072 0.05356788 0.6121072 0.05356788 0.6097071 0.05527484 0.6169694 0.05024296 0.6097071 0.05527484 0.6073281 0.05701106 0.6169694 0.05024296 0.6073281 0.05701106 0.6049705 0.05877643 0.5980304 0.06424415 0.6049705 0.05877643 0.6026348 0.06057053 0.5980304 0.06424415 0.6026348 0.06057053 0.6003214 0.06239324 0.5980304 0.06424415 0.5980304 0.06424415 0.5957623 0.066123 0.5935175 0.06802958 0.5890988 0.07192468 0.5869257 0.07391262 0.5847771 0.07592701 0.5847771 0.07592701 0.5826534 0.0779677 0.5805549 0.08003425 0.5764348 0.08424383 0.5744138 0.0863862 0.5724192 0.08855324 0.5647113 0.09746116 0.5628533 0.09974646 0.5574498 0.1067366 0.5628533 0.09974646 0.5610236 0.1020543 0.5574498 0.1067366 0.5610236 0.1020543 0.5592223 0.1043845 0.5574498 0.1067366 0.5443347 0.1262997 0.5428321 0.1288328 0.5413609 0.1313842 0.5413609 0.1313842 0.5399209 0.1339535 0.5443347 0.1262997 0.5399209 0.1339535 0.5385127 0.1365402 0.5443347 0.1262997 0.5332003 0.1470541 0.5319533 0.1497223 0.5284101 0.1578159 0.5319533 0.1497223 0.5307391 0.1524056 0.5284101 0.1578159 0.5284101 0.1578159 0.5272955 0.1605421 0.5241537 0.1687999 0.5272955 0.1605421 0.5262145 0.1632818 0.5241537 0.1687999 0.5241537 0.1687999 0.5231743 0.1715775 0.5204415 0.1799794 0.5231743 0.1715775 0.522229 0.1743668 0.5204415 0.1799794 0.522229 0.1743668 0.521318 0.1771677 0.5204415 0.1799794 0.5204415 0.1799794 0.5195995 0.1828017 0.5172823 0.1913277 0.5195995 0.1828017 0.5187922 0.1856341 0.5172823 0.1913277 0.5159124 0.1970565 0.5152804 0.1999331 0.5172823 0.1913277 0.5152804 0.1999331 0.5146837 0.2028173 0.5172823 0.1913277 0.5146837 0.2028173 0.5141224 0.2057085 0.5135966 0.2086064 0.5135966 0.2086064 0.5131065 0.2115106 0.5146837 0.2028173 0.5131065 0.2115106 0.5126519 0.2144205 0.5146837 0.2028173 0.5126519 0.2144205 0.5122332 0.2173358 0.511192 0.2261095 0.5122332 0.2173358 0.5118502 0.220256 0.511192 0.2261095 0.511192 0.2261095 0.5109168 0.2290418 0.5106777 0.2319774 0.5106777 0.2319774 0.5104745 0.2349156 0.5103074 0.237856 0.5100816 0.2437421 0.5100229 0.2466867 0.5103074 0.237856 0.5100229 0.2466867 0.5100003 0.2496318 0.5103074 0.237856 0.5100635 0.2555218 0.5101494 0.2584658 0.5100003 0.2496318 0.5101494 0.2584658 0.5102713 0.2614085 0.5100003 0.2496318 0.5106235 0.2672883 0.5108537 0.2702245 0.5102713 0.2614085 0.5108537 0.2702245 0.5111199 0.2731577 0.5102713 0.2614085 0.5125439 0.2848511 0.5129895 0.2877624 0.5134707 0.2906681 0.5171033 0.3079581 0.5178321 0.3108117 0.5185958 0.3136562 0.5185958 0.3136562 0.5193944 0.3164911 0.5202277 0.3193159 0.5219981 0.324934 0.5229347 0.3277263 0.5239056 0.3305068 0.5239056 0.3305068 0.5249106 0.3332753 0.5281283 0.3415038 0.5249106 0.3332753 0.5259495 0.3360312 0.5281283 0.3415038 0.5281283 0.3415038 0.5292679 0.3442196 0.5328854 0.3522803 0.5292679 0.3442196 0.5304408 0.3469212 0.5328854 0.3522803 0.5354609 0.3575778 0.5367972 0.3602024 0.5328854 0.3522803 0.5367972 0.3602024 0.5381656 0.3628104 0.5328854 0.3522803 0.5409979 0.3679751 0.5424614 0.370531 0.5439561 0.3730688 0.550243 0.3830306 0.5518906 0.3854719 0.5535679 0.3878928 0.5535679 0.3878928 0.5552749 0.390293 0.550243 0.3830306 0.5552749 0.390293 0.5570111 0.392672 0.550243 0.3830306 0.5570111 0.392672 0.5587764 0.3950295 0.5642442 0.4019696 0.5587764 0.3950295 0.5605706 0.3973652 0.5642442 0.4019696 0.5605706 0.3973652 0.5623933 0.3996787 0.5642442 0.4019696 0.5642442 0.4019696 0.5661231 0.4042377 0.5680297 0.4064825 0.5719247 0.4109011 0.5739126 0.4130743 0.5759271 0.4152229 0.5759271 0.4152229 0.5779677 0.4173466 0.5800343 0.4194451 0.5842438 0.4235652 0.5863862 0.4255862 0.5885533 0.4275808 0.5974612 0.4352887 0.5997465 0.4371467 0.6067367 0.4425503 0.5997465 0.4371467 0.6020544 0.4389764 0.6067367 0.4425503 0.6020544 0.4389764 0.6043846 0.4407777 0.6067367 0.4425503 0.6262997 0.4556654 0.6288328 0.4571679 0.6313843 0.4586392 0.6313843 0.4586392 0.6339535 0.460079 0.6262997 0.4556654 0.6339535 0.460079 0.6365402 0.4614873 0.6262997 0.4556654 0.6470541 0.4667997 0.6497223 0.4680467 0.6578159 0.4715899 0.6497223 0.4680467 0.6524056 0.4692609 0.6578159 0.4715899 0.6578159 0.4715899 0.6605421 0.4727045 0.6687999 0.4758463 0.6605421 0.4727045 0.6632818 0.4737855 0.6687999 0.4758463 0.6687999 0.4758463 0.6715775 0.4768257 0.6799795 0.4795585 0.6715775 0.4768257 0.6743669 0.477771 0.6799795 0.4795585 0.6743669 0.477771 0.6771677 0.478682 0.6799795 0.4795585 0.6799795 0.4795585 0.6828018 0.4804005 0.6913277 0.4827178 0.6828018 0.4804005 0.6856342 0.4812078 0.6913277 0.4827178 0.6970565 0.4840875 0.6999332 0.4847196 0.6913277 0.4827178 0.6999332 0.4847196 0.7028173 0.4853163 0.6913277 0.4827178 0.7028173 0.4853163 0.7057086 0.4858776 0.7086065 0.4864034 0.7086065 0.4864034 0.7115106 0.4868935 0.7028173 0.4853163 0.7115106 0.4868935 0.7144206 0.487348 0.7028173 0.4853163 0.7144206 0.487348 0.7173359 0.4877668 0.7261095 0.488808 0.7173359 0.4877668 0.7202561 0.4881498 0.7261095 0.488808 0.7261095 0.488808 0.7290419 0.4890832 0.7319774 0.4893223 0.7319774 0.4893223 0.7349156 0.4895255 0.737856 0.4896926 0.7437421 0.4899184 0.7466867 0.4899771 0.737856 0.4896926 0.7466867 0.4899771 0.7496318 0.4899997 0.737856 0.4896926 0.7731577 0.4888801 0.7790132 0.4882399 0.7964605 0.48546 0.7790132 0.4882399 0.7848511 0.4874561 0.7964605 0.48546 0.7848511 0.4874561 0.7906681 0.4865293 0.7964605 0.48546 0.7964605 0.48546 0.8022251 0.4842489 0.8079581 0.4828967 0.8079581 0.4828967 0.8136562 0.4814042 0.7964605 0.48546 0.8136562 0.4814042 0.8193159 0.4797723 0.7964605 0.48546 0.8193159 0.4797723 0.824934 0.478002 0.8415038 0.4718717 0.824934 0.478002 0.8305069 0.4760943 0.8415038 0.4718717 0.8628104 0.4618344 0.8679751 0.4590021 0.8830306 0.449757 0.8679751 0.4590021 0.8730688 0.4560439 0.8830306 0.449757 0.8730688 0.4560439 0.8780882 0.4529616 0.8830306 0.449757 0.9019696 0.4357559 0.9064825 0.4319704 0.9109012 0.4280753 0.9109012 0.4280753 0.9152229 0.4240729 0.9019696 0.4357559 0.9152229 0.4240729 0.9194451 0.4199658 0.9019696 0.4357559 0.9194451 0.4199658 0.9235652 0.4157562 0.9275808 0.4114468 0.9275808 0.4114468 0.9314894 0.4070401 0.9194451 0.4199658 0.9314894 0.4070401 0.9352887 0.4025388 0.9194451 0.4199658 0.9425503 0.3932633 0.9460082 0.3884948 0.9493479 0.3836428 0.9493479 0.3836428 0.9525676 0.3787103 0.9614873 0.3634598 0.9525676 0.3787103 0.9556654 0.3737003 0.9614873 0.3634598 0.9614873 0.3634598 0.9642081 0.3582354 0.9715899 0.342184 0.9642081 0.3582354 0.9667997 0.3529459 0.9715899 0.342184 0.988808 0.2738904 0.9893223 0.2680226 0.9899997 0.2503681 0.9893223 0.2680226 0.9896926 0.2621439 0.9899997 0.2503681 0.9888802 0.2268423 0.9882399 0.2209869 0.9854601 0.2035394 0.9882399 0.2209869 0.9874561 0.2151489 0.9854601 0.2035394 0.9874561 0.2151489 0.9865293 0.2093319 0.9854601 0.2035394 0.9854601 0.2035394 0.9842489 0.197775 0.9828967 0.1920419 0.9828967 0.1920419 0.9814042 0.1863438 0.9854601 0.2035394 0.9814042 0.1863438 0.9797723 0.180684 0.9854601 0.2035394 0.9797723 0.180684 0.978002 0.175066 0.9718717 0.1584962 0.978002 0.175066 0.9760944 0.1694931 0.9718717 0.1584962 0.9618344 0.1371896 0.9590021 0.1320249 0.949757 0.1169694 0.9590021 0.1320249 0.9560439 0.1269312 0.949757 0.1169694 0.9560439 0.1269312 0.9529616 0.1219117 0.949757 0.1169694 0.9357559 0.09803032 0.9319704 0.09351742 0.9280753 0.08909881 0.9280753 0.08909881 0.9240729 0.08477705 0.9357559 0.09803032 0.9240729 0.08477705 0.9199658 0.0805549 0.9357559 0.09803032 0.9199658 0.0805549 0.9157562 0.07643473 0.9114468 0.07241916 0.9114468 0.07241916 0.9070401 0.06851053 0.9199658 0.0805549 0.9070401 0.06851053 0.9025388 0.06471127 0.9199658 0.0805549 0.8932633 0.05744969 0.8884948 0.05399185 0.8836428 0.05065202 0.8836428 0.05065202 0.8787103 0.04743236 0.8634598 0.0385127 0.8787103 0.04743236 0.8737003 0.04433465 0.8634598 0.0385127 0.8634598 0.0385127 0.8582354 0.03579193 0.8421841 0.02841007 0.8582354 0.03579193 0.8529459 0.0332002 0.8421841 0.02841007 0.7738905 0.01119202 0.7680227 0.01067763 0.7503682 0.01000028 0.7680227 0.01067763 0.762144 0.01030743 0.7503682 0.01000028 0.7268423 0.01111984 0.7209869 0.01176011 0.7035395 0.01453995 0.7209869 0.01176011 0.7151489 0.01254385 0.7035395 0.01453995 0.7151489 0.01254385 0.7093319 0.0134707 0.7035395 0.01453995 0.7035395 0.01453995 0.697775 0.01575106 0.6920419 0.01710331 0.6920419 0.01710331 0.6863439 0.01859581 0.7035395 0.01453995 0.6863439 0.01859581 0.6806841 0.02022767 0.7035395 0.01453995 0.6806841 0.02022767 0.6750661 0.02199798 0.6584962 0.02812826 0.6750661 0.02199798 0.6694931 0.02390563 0.6584962 0.02812826 0.6371896 0.03816556 0.6320249 0.04099792 0.6169694 0.05024296 0.6320249 0.04099792 0.6269313 0.0439561 0.6169694 0.05024296 0.6269313 0.0439561 0.6219118 0.04703837 0.6169694 0.05024296 0.5980304 0.06424415 0.5935175 0.06802958 0.5890988 0.07192468 0.5890988 0.07192468 0.5847771 0.07592701 0.5980304 0.06424415 0.5847771 0.07592701 0.5805549 0.08003425 0.5980304 0.06424415 0.5805549 0.08003425 0.5764348 0.08424383 0.5724192 0.08855324 0.5724192 0.08855324 0.5685106 0.09295994 0.5805549 0.08003425 0.5685106 0.09295994 0.5647113 0.09746116 0.5805549 0.08003425 0.5574498 0.1067366 0.5539919 0.1115052 0.5506521 0.1163572 0.5506521 0.1163572 0.5474324 0.1212897 0.5385127 0.1365402 0.5474324 0.1212897 0.5443347 0.1262997 0.5385127 0.1365402 0.5385127 0.1365402 0.5357919 0.1417645 0.5284101 0.1578159 0.5357919 0.1417645 0.5332003 0.1470541 0.5284101 0.1578159 0.511192 0.2261095 0.5106777 0.2319774 0.5100003 0.2496318 0.5106777 0.2319774 0.5103074 0.237856 0.5100003 0.2496318 0.5111199 0.2731577 0.5117601 0.2790132 0.51454 0.2964605 0.5117601 0.2790132 0.5125439 0.2848511 0.51454 0.2964605 0.5125439 0.2848511 0.5134707 0.2906681 0.51454 0.2964605 0.51454 0.2964605 0.5157511 0.302225 0.5171033 0.3079581 0.5171033 0.3079581 0.5185958 0.3136562 0.51454 0.2964605 0.5185958 0.3136562 0.5202277 0.3193159 0.51454 0.2964605 0.5202277 0.3193159 0.5219981 0.324934 0.5281283 0.3415038 0.5219981 0.324934 0.5239056 0.3305068 0.5281283 0.3415038 0.5381656 0.3628104 0.5409979 0.3679751 0.550243 0.3830306 0.5409979 0.3679751 0.5439561 0.3730688 0.550243 0.3830306 0.5439561 0.3730688 0.5470384 0.3780882 0.550243 0.3830306 0.5642442 0.4019696 0.5680297 0.4064825 0.5719247 0.4109011 0.5719247 0.4109011 0.5759271 0.4152229 0.5642442 0.4019696 0.5759271 0.4152229 0.5800343 0.4194451 0.5642442 0.4019696 0.5800343 0.4194451 0.5842438 0.4235652 0.5885533 0.4275808 0.5885533 0.4275808 0.59296 0.4314894 0.5800343 0.4194451 0.59296 0.4314894 0.5974612 0.4352887 0.5800343 0.4194451 0.6067367 0.4425503 0.6115052 0.4460082 0.6163572 0.4493479 0.6163572 0.4493479 0.6212897 0.4525676 0.6365402 0.4614873 0.6212897 0.4525676 0.6262997 0.4556654 0.6365402 0.4614873 0.6365402 0.4614873 0.6417646 0.4642081 0.6578159 0.4715899 0.6417646 0.4642081 0.6470541 0.4667997 0.6578159 0.4715899 0.7261095 0.488808 0.7319774 0.4893223 0.7496318 0.4899997 0.7319774 0.4893223 0.737856 0.4896926 0.7496318 0.4899997 0.7496318 0.4899997 0.7614085 0.4897287 0.7964605 0.48546 0.7614085 0.4897287 0.7731577 0.4888801 0.7964605 0.48546 0.8415038 0.4718717 0.8522803 0.4671146 0.8830306 0.449757 0.8522803 0.4671146 0.8628104 0.4618344 0.8830306 0.449757 0.8830306 0.449757 0.892672 0.4429889 0.9019696 0.4357559 0.9352887 0.4025388 0.9425503 0.3932633 0.9194451 0.4199658 0.9425503 0.3932633 0.9493479 0.3836428 0.9194451 0.4199658 0.9715899 0.342184 0.9758463 0.3312001 0.9795585 0.3200206 0.9795585 0.3200206 0.9827178 0.3086723 0.9715899 0.342184 0.9827178 0.3086723 0.9853163 0.2971827 0.9715899 0.342184 0.9853163 0.2971827 0.9873481 0.2855795 0.9899997 0.2503681 0.9873481 0.2855795 0.988808 0.2738904 0.9899997 0.2503681 0.9899997 0.2503681 0.9897287 0.2385914 0.9854601 0.2035394 0.9897287 0.2385914 0.9888802 0.2268423 0.9854601 0.2035394 0.9718717 0.1584962 0.9671146 0.1477197 0.949757 0.1169694 0.9671146 0.1477197 0.9618344 0.1371896 0.949757 0.1169694 0.949757 0.1169694 0.9429889 0.107328 0.9357559 0.09803032 0.9025388 0.06471127 0.8932633 0.05744969 0.9199658 0.0805549 0.8932633 0.05744969 0.8836428 0.05065202 0.9199658 0.0805549 0.8421841 0.02841007 0.8312001 0.0241537 0.8200206 0.02044147 0.8200206 0.02044147 0.8086723 0.01728218 0.8421841 0.02841007 0.8086723 0.01728218 0.7971827 0.0146836 0.8421841 0.02841007 0.7971827 0.0146836 0.7855795 0.01265192 0.7503682 0.01000028 0.7855795 0.01265192 0.7738905 0.01119202 0.7503682 0.01000028 0.7503682 0.01000028 0.7385915 0.01027131 0.7035395 0.01453995 0.7385915 0.01027131 0.7268423 0.01111984 0.7035395 0.01453995 0.6584962 0.02812826 0.6477197 0.03288543 0.6169694 0.05024296 0.6477197 0.03288543 0.6371896 0.03816556 0.6169694 0.05024296 0.6169694 0.05024296 0.6073281 0.05701106 0.5980304 0.06424415 0.5647113 0.09746116 0.5574498 0.1067366 0.5805549 0.08003425 0.5574498 0.1067366 0.5506521 0.1163572 0.5805549 0.08003425 0.5284101 0.1578159 0.5241537 0.1687999 0.5204415 0.1799794 0.5204415 0.1799794 0.5172823 0.1913277 0.5284101 0.1578159 0.5172823 0.1913277 0.5146837 0.2028173 0.5284101 0.1578159 0.5146837 0.2028173 0.5126519 0.2144205 0.5100003 0.2496318 0.5126519 0.2144205 0.511192 0.2261095 0.5100003 0.2496318 0.5100003 0.2496318 0.5102713 0.2614085 0.51454 0.2964605 0.5102713 0.2614085 0.5111199 0.2731577 0.51454 0.2964605 0.5281283 0.3415038 0.5328854 0.3522803 0.550243 0.3830306 0.5328854 0.3522803 0.5381656 0.3628104 0.550243 0.3830306 0.550243 0.3830306 0.5570111 0.392672 0.5642442 0.4019696 0.5974612 0.4352887 0.6067367 0.4425503 0.5800343 0.4194451 0.6067367 0.4425503 0.6163572 0.4493479 0.5800343 0.4194451 0.6578159 0.4715899 0.6687999 0.4758463 0.6799795 0.4795585 0.6799795 0.4795585 0.6913277 0.4827178 0.6578159 0.4715899 0.6913277 0.4827178 0.7028173 0.4853163 0.6578159 0.4715899 0.7028173 0.4853163 0.7144206 0.487348 0.7496318 0.4899997 0.7144206 0.487348 0.7261095 0.488808 0.7496318 0.4899997 0.7964605 0.48546 0.8193159 0.4797723 0.8415038 0.4718717 0.8830306 0.449757 0.9019696 0.4357559 0.9194451 0.4199658 0.9493479 0.3836428 0.9614873 0.3634598 0.9194451 0.4199658 0.9614873 0.3634598 0.9715899 0.342184 0.9194451 0.4199658 0.9854601 0.2035394 0.9797723 0.180684 0.9718717 0.1584962 0.949757 0.1169694 0.9357559 0.09803032 0.9199658 0.0805549 0.8836428 0.05065202 0.8634598 0.0385127 0.9199658 0.0805549 0.8634598 0.0385127 0.8421841 0.02841007 0.9199658 0.0805549 0.7035395 0.01453995 0.6806841 0.02022767 0.6584962 0.02812826 0.6169694 0.05024296 0.5980304 0.06424415 0.5805549 0.08003425 0.5506521 0.1163572 0.5385127 0.1365402 0.5805549 0.08003425 0.5385127 0.1365402 0.5284101 0.1578159 0.5805549 0.08003425 0.51454 0.2964605 0.5202277 0.3193159 0.5281283 0.3415038 0.550243 0.3830306 0.5642442 0.4019696 0.5800343 0.4194451 0.6163572 0.4493479 0.6365402 0.4614873 0.5800343 0.4194451 0.6365402 0.4614873 0.6578159 0.4715899 0.5800343 0.4194451 0.7496318 0.4899997 0.7964605 0.48546 0.8415038 0.4718717 0.8415038 0.4718717 0.8830306 0.449757 0.7496318 0.4899997 0.8830306 0.449757 0.9194451 0.4199658 0.7496318 0.4899997 0.9715899 0.342184 0.9853163 0.2971827 0.9899997 0.2503681 0.9899997 0.2503681 0.9854601 0.2035394 0.9718717 0.1584962 0.9718717 0.1584962 0.949757 0.1169694 0.9899997 0.2503681 0.949757 0.1169694 0.9199658 0.0805549 0.9899997 0.2503681 0.8421841 0.02841007 0.7971827 0.0146836 0.7503682 0.01000028 0.7503682 0.01000028 0.7035395 0.01453995 0.6584962 0.02812826 0.6584962 0.02812826 0.6169694 0.05024296 0.7503682 0.01000028 0.6169694 0.05024296 0.5805549 0.08003425 0.7503682 0.01000028 0.5284101 0.1578159 0.5146837 0.2028173 0.5100003 0.2496318 0.5100003 0.2496318 0.51454 0.2964605 0.5281283 0.3415038 0.5281283 0.3415038 0.550243 0.3830306 0.5100003 0.2496318 0.550243 0.3830306 0.5800343 0.4194451 0.5100003 0.2496318 0.6578159 0.4715899 0.7028173 0.4853163 0.7496318 0.4899997 0.9194451 0.4199658 0.9715899 0.342184 0.7496318 0.4899997 0.9715899 0.342184 0.9899997 0.2503681 0.7496318 0.4899997 0.9199658 0.0805549 0.8421841 0.02841007 0.9899997 0.2503681 0.8421841 0.02841007 0.7503682 0.01000028 0.9899997 0.2503681 0.5805549 0.08003425 0.5284101 0.1578159 0.7503682 0.01000028 0.5284101 0.1578159 0.5100003 0.2496318 0.7503682 0.01000028 0.5800343 0.4194451 0.6578159 0.4715899 0.5100003 0.2496318 0.6578159 0.4715899 0.7496318 0.4899997 0.5100003 0.2496318 0.7496318 0.4899997 0.9899997 0.2503681 0.7503682 0.01000028 + + + + + + + + + + + + + + +

1 0 0 2 0 1 0 0 2 3 1 3 4 1 4 2 1 5 5 2 6 6 2 7 4 2 8 7 3 9 8 3 10 6 3 11 9 4 12 10 4 13 8 4 14 11 5 15 12 5 16 10 5 17 13 6 18 14 6 19 12 6 20 15 7 21 16 7 22 14 7 23 17 8 24 18 8 25 16 8 26 19 9 27 20 9 28 18 9 29 21 10 30 22 10 31 20 10 32 23 11 33 24 11 34 22 11 35 25 12 36 26 12 37 24 12 38 27 13 39 28 13 40 26 13 41 29 14 42 30 14 43 28 14 44 31 15 45 32 15 46 30 15 47 33 16 48 34 16 49 32 16 50 35 17 51 36 17 52 34 17 53 37 18 54 38 18 55 36 18 56 39 19 57 40 19 58 38 19 59 41 20 60 42 20 61 40 20 62 43 21 63 44 21 64 42 21 65 45 22 66 46 22 67 44 22 68 47 23 69 48 23 70 46 23 71 49 24 72 50 24 73 48 24 74 51 25 75 52 25 76 50 25 77 53 26 78 54 26 79 52 26 80 55 27 81 56 27 82 54 27 83 57 28 84 58 28 85 56 28 86 59 29 87 60 29 88 58 29 89 61 30 90 62 30 91 60 30 92 63 31 93 64 31 94 62 31 95 65 32 96 66 32 97 64 32 98 67 33 99 68 33 100 66 33 101 69 34 102 70 34 103 68 34 104 71 35 105 72 35 106 70 35 107 73 36 108 74 36 109 72 36 110 75 37 111 76 37 112 74 37 113 77 38 114 78 38 115 76 38 116 79 39 117 80 39 118 78 39 119 81 40 120 82 40 121 80 40 122 83 41 123 84 41 124 82 41 125 85 42 126 86 42 127 84 42 128 87 43 129 88 43 130 86 43 131 89 44 132 90 44 133 88 44 134 91 45 135 92 45 136 90 45 137 93 46 138 94 46 139 92 46 140 95 47 141 96 47 142 94 47 143 97 48 144 98 48 145 96 48 146 99 49 147 100 49 148 98 49 149 101 50 150 102 50 151 100 50 152 103 51 153 104 51 154 102 51 155 105 52 156 106 52 157 104 52 158 107 53 159 108 53 160 106 53 161 109 54 162 110 54 163 108 54 164 111 55 165 112 55 166 110 55 167 113 56 168 114 56 169 112 56 170 115 57 171 116 57 172 114 57 173 117 58 174 118 58 175 116 58 176 119 59 177 120 59 178 118 59 179 121 60 180 122 60 181 120 60 182 123 61 183 124 61 184 122 61 185 125 62 186 126 62 187 124 62 188 127 63 189 128 63 190 126 63 191 129 64 192 130 64 193 128 64 194 131 65 195 132 65 196 130 65 197 133 66 198 134 66 199 132 66 200 135 67 201 136 67 202 134 67 203 137 68 204 138 68 205 136 68 206 139 69 207 140 69 208 138 69 209 141 70 210 142 70 211 140 70 212 143 71 213 144 71 214 142 71 215 145 72 216 146 72 217 144 72 218 147 73 219 148 73 220 146 73 221 149 74 222 150 74 223 148 74 224 151 75 225 152 75 226 150 75 227 153 76 228 154 76 229 152 76 230 155 77 231 156 77 232 154 77 233 157 78 234 158 78 235 156 78 236 159 79 237 160 79 238 158 79 239 161 80 240 162 80 241 160 80 242 163 81 243 164 81 244 162 81 245 165 82 246 166 82 247 164 82 248 167 83 249 168 83 250 166 83 251 169 84 252 170 84 253 168 84 254 171 85 255 172 85 256 170 85 257 173 86 258 174 86 259 172 86 260 175 87 261 176 87 262 174 87 263 177 88 264 178 88 265 176 88 266 179 89 267 180 89 268 178 89 269 181 90 270 182 90 271 180 90 272 183 91 273 184 91 274 182 91 275 185 92 276 186 92 277 184 92 278 187 93 279 188 93 280 186 93 281 189 94 282 190 94 283 188 94 284 191 95 285 192 95 286 190 95 287 193 96 288 194 96 289 192 96 290 195 97 291 196 97 292 194 97 293 197 98 294 198 98 295 196 98 296 199 99 297 200 99 298 198 99 299 201 100 300 202 100 301 200 100 302 203 101 303 204 101 304 202 101 305 205 102 306 206 102 307 204 102 308 207 103 309 208 103 310 206 103 311 209 104 312 210 104 313 208 104 314 211 105 315 212 105 316 210 105 317 213 106 318 214 106 319 212 106 320 215 107 321 216 107 322 214 107 323 217 108 324 218 108 325 216 108 326 219 109 327 220 109 328 218 109 329 221 110 330 222 110 331 220 110 332 223 111 333 224 111 334 222 111 335 225 112 336 226 112 337 224 112 338 227 113 339 228 113 340 226 113 341 229 114 342 230 114 343 228 114 344 231 115 345 232 115 346 230 115 347 233 116 348 234 116 349 232 116 350 235 117 351 236 117 352 234 117 353 237 118 354 238 118 355 236 118 356 239 119 357 240 119 358 238 119 359 241 120 360 242 120 361 240 120 362 243 121 363 244 121 364 242 121 365 245 122 366 246 122 367 244 122 368 247 123 369 248 123 370 246 123 371 249 124 372 250 124 373 248 124 374 251 125 375 252 125 376 250 125 377 253 126 378 254 126 379 252 126 380 255 127 381 256 127 382 254 127 383 257 128 384 258 128 385 256 128 386 259 129 387 260 129 388 258 129 389 261 130 390 262 130 391 260 130 392 263 131 393 264 131 394 262 131 395 265 132 396 266 132 397 264 132 398 267 133 399 268 133 400 266 133 401 269 134 402 270 134 403 268 134 404 271 135 405 272 135 406 270 135 407 273 136 408 274 136 409 272 136 410 275 137 411 276 137 412 274 137 413 277 138 414 278 138 415 276 138 416 279 139 417 280 139 418 278 139 419 281 140 420 282 140 421 280 140 422 283 141 423 284 141 424 282 141 425 285 142 426 286 142 427 284 142 428 287 143 429 288 143 430 286 143 431 289 144 432 290 144 433 288 144 434 291 145 435 292 145 436 290 145 437 293 146 438 294 146 439 292 146 440 295 147 441 296 147 442 294 147 443 297 148 444 298 148 445 296 148 446 299 149 447 300 149 448 298 149 449 301 150 450 302 150 451 300 150 452 303 151 453 304 151 454 302 151 455 305 152 456 306 152 457 304 152 458 307 153 459 308 153 460 306 153 461 309 154 462 310 154 463 308 154 464 311 155 465 312 155 466 310 155 467 313 156 468 314 156 469 312 156 470 315 157 471 316 157 472 314 157 473 317 158 474 318 158 475 316 158 476 319 159 477 320 159 478 318 159 479 321 160 480 322 160 481 320 160 482 323 161 483 324 161 484 322 161 485 325 162 486 326 162 487 324 162 488 327 163 489 328 163 490 326 163 491 329 164 492 330 164 493 328 164 494 331 165 495 332 165 496 330 165 497 333 166 498 334 166 499 332 166 500 335 167 501 336 167 502 334 167 503 337 168 504 338 168 505 336 168 506 339 169 507 340 169 508 338 169 509 341 170 510 342 170 511 340 170 512 343 171 513 344 171 514 342 171 515 345 172 516 346 172 517 344 172 518 347 173 519 348 173 520 346 173 521 349 174 522 350 174 523 348 174 524 351 175 525 352 175 526 350 175 527 353 176 528 354 176 529 352 176 530 355 177 531 356 177 532 354 177 533 357 178 534 358 178 535 356 178 536 359 179 537 360 179 538 358 179 539 361 180 540 362 180 541 360 180 542 363 181 543 364 181 544 362 181 545 365 182 546 366 182 547 364 182 548 367 183 549 368 183 550 366 183 551 369 184 552 370 184 553 368 184 554 371 185 555 372 185 556 370 185 557 373 186 558 374 186 559 372 186 560 375 187 561 376 187 562 374 187 563 377 188 564 378 188 565 376 188 566 379 189 567 380 189 568 378 189 569 381 190 570 382 190 571 380 190 572 383 191 573 384 191 574 382 191 575 385 192 576 386 192 577 384 192 578 387 193 579 388 193 580 386 193 581 389 194 582 390 194 583 388 194 584 391 195 585 392 195 586 390 195 587 393 196 588 394 196 589 392 196 590 395 197 591 396 197 592 394 197 593 397 198 594 398 198 595 396 198 596 399 199 597 400 199 598 398 199 599 401 200 600 402 200 601 400 200 602 403 201 603 404 201 604 402 201 605 405 202 606 406 202 607 404 202 608 407 203 609 408 203 610 406 203 611 409 204 612 410 204 613 408 204 614 411 205 615 412 205 616 410 205 617 413 206 618 414 206 619 412 206 620 415 207 621 416 207 622 414 207 623 417 208 624 418 208 625 416 208 626 419 209 627 420 209 628 418 209 629 421 210 630 422 210 631 420 210 632 423 211 633 424 211 634 422 211 635 425 212 636 426 212 637 424 212 638 427 213 639 428 213 640 426 213 641 429 214 642 430 214 643 428 214 644 431 215 645 432 215 646 430 215 647 433 216 648 434 216 649 432 216 650 435 217 651 436 217 652 434 217 653 437 218 654 438 218 655 436 218 656 439 219 657 440 219 658 438 219 659 441 220 660 442 220 661 440 220 662 443 221 663 444 221 664 442 221 665 445 222 666 446 222 667 444 222 668 447 223 669 448 223 670 446 223 671 449 224 672 450 224 673 448 224 674 451 225 675 452 225 676 450 225 677 453 226 678 454 226 679 452 226 680 455 227 681 456 227 682 454 227 683 457 228 684 458 228 685 456 228 686 459 229 687 460 229 688 458 229 689 461 230 690 462 230 691 460 230 692 463 231 693 464 231 694 462 231 695 465 232 696 466 232 697 464 232 698 467 233 699 468 233 700 466 233 701 469 234 702 470 234 703 468 234 704 471 235 705 472 235 706 470 235 707 473 236 708 474 236 709 472 236 710 475 237 711 476 237 712 474 237 713 477 238 714 478 238 715 476 238 716 479 239 717 480 239 718 478 239 719 481 240 720 482 240 721 480 240 722 483 241 723 484 241 724 482 241 725 485 242 726 486 242 727 484 242 728 487 243 729 488 243 730 486 243 731 489 244 732 490 244 733 488 244 734 491 245 735 492 245 736 490 245 737 493 246 738 494 246 739 492 246 740 495 247 741 496 247 742 494 247 743 497 248 744 498 248 745 496 248 746 499 249 747 500 249 748 498 249 749 501 250 750 502 250 751 500 250 752 503 251 753 504 251 754 502 251 755 505 252 756 506 252 757 504 252 758 507 253 759 508 253 760 506 253 761 509 254 762 510 254 763 508 254 764 511 255 765 512 255 766 510 255 767 513 256 768 514 256 769 512 256 770 515 257 771 516 257 772 514 257 773 517 258 774 518 258 775 516 258 776 519 259 777 520 259 778 518 259 779 521 260 780 522 260 781 520 260 782 523 261 783 524 261 784 522 261 785 525 262 786 526 262 787 524 262 788 527 263 789 528 263 790 526 263 791 529 264 792 530 264 793 528 264 794 531 265 795 532 265 796 530 265 797 533 266 798 534 266 799 532 266 800 535 267 801 536 267 802 534 267 803 537 268 804 538 268 805 536 268 806 539 269 807 540 269 808 538 269 809 541 270 810 542 270 811 540 270 812 543 271 813 544 271 814 542 271 815 545 272 816 546 272 817 544 272 818 547 273 819 548 273 820 546 273 821 549 274 822 550 274 823 548 274 824 551 275 825 552 275 826 550 275 827 553 276 828 554 276 829 552 276 830 555 277 831 556 277 832 554 277 833 557 278 834 558 278 835 556 278 836 559 279 837 560 279 838 558 279 839 561 280 840 562 280 841 560 280 842 563 281 843 564 281 844 562 281 845 565 282 846 566 282 847 564 282 848 567 283 849 568 283 850 566 283 851 569 284 852 570 284 853 568 284 854 571 285 855 572 285 856 570 285 857 573 286 858 574 286 859 572 286 860 575 287 861 576 287 862 574 287 863 577 288 864 578 288 865 576 288 866 579 289 867 580 289 868 578 289 869 581 290 870 582 290 871 580 290 872 583 291 873 584 291 874 582 291 875 585 292 876 586 292 877 584 292 878 587 293 879 588 293 880 586 293 881 589 294 882 590 294 883 588 294 884 591 295 885 592 295 886 590 295 887 593 296 888 594 296 889 592 296 890 595 297 891 596 297 892 594 297 893 597 298 894 598 298 895 596 298 896 599 299 897 600 299 898 598 299 899 601 300 900 602 300 901 600 300 902 603 301 903 604 301 904 602 301 905 605 302 906 606 302 907 604 302 908 607 303 909 608 303 910 606 303 911 609 304 912 610 304 913 608 304 914 611 305 915 612 305 916 610 305 917 613 306 918 614 306 919 612 306 920 615 307 921 616 307 922 614 307 923 617 308 924 618 308 925 616 308 926 619 309 927 620 309 928 618 309 929 621 310 930 622 310 931 620 310 932 623 311 933 624 311 934 622 311 935 625 312 936 626 312 937 624 312 938 627 313 939 628 313 940 626 313 941 629 314 942 630 314 943 628 314 944 631 315 945 632 315 946 630 315 947 633 316 948 634 316 949 632 316 950 635 317 951 636 317 952 634 317 953 637 318 954 638 318 955 636 318 956 639 319 957 640 319 958 638 319 959 641 320 960 642 320 961 640 320 962 643 321 963 644 321 964 642 321 965 645 322 966 646 322 967 644 322 968 647 323 969 648 323 970 646 323 971 649 324 972 650 324 973 648 324 974 651 325 975 652 325 976 650 325 977 653 326 978 654 326 979 652 326 980 655 327 981 656 327 982 654 327 983 657 328 984 658 328 985 656 328 986 659 329 987 660 329 988 658 329 989 661 330 990 662 330 991 660 330 992 663 331 993 664 331 994 662 331 995 665 332 996 666 332 997 664 332 998 667 333 999 668 333 1000 666 333 1001 669 334 1002 670 334 1003 668 334 1004 671 335 1005 672 335 1006 670 335 1007 673 336 1008 674 336 1009 672 336 1010 675 337 1011 676 337 1012 674 337 1013 677 338 1014 678 338 1015 676 338 1016 679 339 1017 680 339 1018 678 339 1019 681 340 1020 682 340 1021 680 340 1022 683 341 1023 684 341 1024 682 341 1025 685 342 1026 686 342 1027 684 342 1028 687 343 1029 688 343 1030 686 343 1031 689 344 1032 690 344 1033 688 344 1034 691 345 1035 692 345 1036 690 345 1037 693 346 1038 694 346 1039 692 346 1040 695 347 1041 696 347 1042 694 347 1043 697 348 1044 698 348 1045 696 348 1046 699 349 1047 700 349 1048 698 349 1049 701 350 1050 702 350 1051 700 350 1052 703 351 1053 704 351 1054 702 351 1055 705 352 1056 706 352 1057 704 352 1058 707 353 1059 708 353 1060 706 353 1061 709 354 1062 710 354 1063 708 354 1064 711 355 1065 712 355 1066 710 355 1067 713 356 1068 714 356 1069 712 356 1070 715 357 1071 716 357 1072 714 357 1073 717 358 1074 718 358 1075 716 358 1076 719 359 1077 720 359 1078 718 359 1079 721 360 1080 722 360 1081 720 360 1082 723 361 1083 724 361 1084 722 361 1085 725 362 1086 726 362 1087 724 362 1088 727 363 1089 728 363 1090 726 363 1091 729 364 1092 730 364 1093 728 364 1094 731 365 1095 732 365 1096 730 365 1097 733 366 1098 734 366 1099 732 366 1100 735 367 1101 736 367 1102 734 367 1103 737 368 1104 738 368 1105 736 368 1106 739 369 1107 740 369 1108 738 369 1109 741 370 1110 742 370 1111 740 370 1112 743 371 1113 744 371 1114 742 371 1115 745 372 1116 746 372 1117 744 372 1118 747 373 1119 748 373 1120 746 373 1121 749 374 1122 750 374 1123 748 374 1124 751 375 1125 752 375 1126 750 375 1127 753 376 1128 754 376 1129 752 376 1130 755 377 1131 756 377 1132 754 377 1133 757 378 1134 758 378 1135 756 378 1136 759 379 1137 760 379 1138 758 379 1139 761 380 1140 762 380 1141 760 380 1142 763 381 1143 764 381 1144 762 381 1145 765 382 1146 766 382 1147 764 382 1148 767 383 1149 768 383 1150 766 383 1151 769 384 1152 770 384 1153 768 384 1154 771 385 1155 772 385 1156 770 385 1157 773 386 1158 774 386 1159 772 386 1160 775 387 1161 776 387 1162 774 387 1163 777 388 1164 778 388 1165 776 388 1166 779 389 1167 780 389 1168 778 389 1169 781 390 1170 782 390 1171 780 390 1172 783 391 1173 784 391 1174 782 391 1175 785 392 1176 786 392 1177 784 392 1178 787 393 1179 788 393 1180 786 393 1181 789 394 1182 790 394 1183 788 394 1184 791 395 1185 792 395 1186 790 395 1187 793 396 1188 794 396 1189 792 396 1190 795 397 1191 796 397 1192 794 397 1193 797 398 1194 798 398 1195 796 398 1196 799 399 1197 800 399 1198 798 399 1199 801 400 1200 802 400 1201 800 400 1202 803 401 1203 804 401 1204 802 401 1205 805 402 1206 806 402 1207 804 402 1208 807 403 1209 808 403 1210 806 403 1211 809 404 1212 810 404 1213 808 404 1214 811 405 1215 812 405 1216 810 405 1217 813 406 1218 814 406 1219 812 406 1220 815 407 1221 816 407 1222 814 407 1223 817 408 1224 818 408 1225 816 408 1226 819 409 1227 820 409 1228 818 409 1229 821 410 1230 822 410 1231 820 410 1232 823 411 1233 824 411 1234 822 411 1235 825 412 1236 826 412 1237 824 412 1238 827 413 1239 828 413 1240 826 413 1241 829 414 1242 830 414 1243 828 414 1244 831 415 1245 832 415 1246 830 415 1247 833 416 1248 834 416 1249 832 416 1250 835 417 1251 836 417 1252 834 417 1253 837 418 1254 838 418 1255 836 418 1256 839 419 1257 840 419 1258 838 419 1259 841 420 1260 842 420 1261 840 420 1262 843 421 1263 844 421 1264 842 421 1265 845 422 1266 846 422 1267 844 422 1268 847 423 1269 848 423 1270 846 423 1271 849 424 1272 850 424 1273 848 424 1274 851 425 1275 852 425 1276 850 425 1277 853 426 1278 854 426 1279 852 426 1280 855 427 1281 856 427 1282 854 427 1283 857 428 1284 858 428 1285 856 428 1286 859 429 1287 860 429 1288 858 429 1289 861 430 1290 862 430 1291 860 430 1292 863 431 1293 864 431 1294 862 431 1295 865 432 1296 866 432 1297 864 432 1298 867 433 1299 868 433 1300 866 433 1301 869 434 1302 870 434 1303 868 434 1304 871 435 1305 872 435 1306 870 435 1307 873 436 1308 874 436 1309 872 436 1310 875 437 1311 876 437 1312 874 437 1313 877 438 1314 878 438 1315 876 438 1316 879 439 1317 880 439 1318 878 439 1319 881 440 1320 882 440 1321 880 440 1322 883 441 1323 884 441 1324 882 441 1325 885 442 1326 886 442 1327 884 442 1328 887 443 1329 888 443 1330 886 443 1331 889 444 1332 890 444 1333 888 444 1334 891 445 1335 892 445 1336 890 445 1337 893 446 1338 894 446 1339 892 446 1340 895 447 1341 896 447 1342 894 447 1343 897 448 1344 898 448 1345 896 448 1346 899 449 1347 900 449 1348 898 449 1349 901 450 1350 902 450 1351 900 450 1352 903 451 1353 904 451 1354 902 451 1355 905 452 1356 906 452 1357 904 452 1358 907 453 1359 908 453 1360 906 453 1361 909 454 1362 910 454 1363 908 454 1364 911 455 1365 912 455 1366 910 455 1367 913 456 1368 914 456 1369 912 456 1370 915 457 1371 916 457 1372 914 457 1373 917 458 1374 918 458 1375 916 458 1376 919 459 1377 920 459 1378 918 459 1379 921 460 1380 922 460 1381 920 460 1382 923 461 1383 924 461 1384 922 461 1385 925 462 1386 926 462 1387 924 462 1388 927 463 1389 928 463 1390 926 463 1391 929 464 1392 930 464 1393 928 464 1394 931 465 1395 932 465 1396 930 465 1397 933 466 1398 934 466 1399 932 466 1400 935 467 1401 936 467 1402 934 467 1403 937 468 1404 938 468 1405 936 468 1406 939 469 1407 940 469 1408 938 469 1409 941 470 1410 942 470 1411 940 470 1412 943 471 1413 944 471 1414 942 471 1415 945 472 1416 946 472 1417 944 472 1418 947 473 1419 948 473 1420 946 473 1421 949 474 1422 950 474 1423 948 474 1424 951 475 1425 952 475 1426 950 475 1427 953 476 1428 954 476 1429 952 476 1430 955 477 1431 956 477 1432 954 477 1433 957 478 1434 958 478 1435 956 478 1436 959 479 1437 960 479 1438 958 479 1439 961 480 1440 962 480 1441 960 480 1442 963 481 1443 964 481 1444 962 481 1445 965 482 1446 966 482 1447 964 482 1448 967 483 1449 968 483 1450 966 483 1451 969 484 1452 970 484 1453 968 484 1454 971 485 1455 972 485 1456 970 485 1457 973 486 1458 974 486 1459 972 486 1460 975 487 1461 976 487 1462 974 487 1463 977 488 1464 978 488 1465 976 488 1466 979 489 1467 980 489 1468 978 489 1469 981 490 1470 982 490 1471 980 490 1472 983 491 1473 984 491 1474 982 491 1475 985 492 1476 986 492 1477 984 492 1478 987 493 1479 988 493 1480 986 493 1481 989 494 1482 990 494 1483 988 494 1484 991 495 1485 992 495 1486 990 495 1487 993 496 1488 994 496 1489 992 496 1490 995 497 1491 996 497 1492 994 497 1493 997 498 1494 998 498 1495 996 498 1496 999 499 1497 1000 499 1498 998 499 1499 1001 500 1500 1002 500 1501 1000 500 1502 1003 501 1503 1004 501 1504 1002 501 1505 1005 502 1506 1006 502 1507 1004 502 1508 1007 503 1509 1008 503 1510 1006 503 1511 1009 504 1512 1010 504 1513 1008 504 1514 1011 505 1515 1012 505 1516 1010 505 1517 1013 506 1518 1014 506 1519 1012 506 1520 1015 507 1521 1016 507 1522 1014 507 1523 1017 508 1524 1018 508 1525 1016 508 1526 1019 509 1527 1020 509 1528 1018 509 1529 1021 510 1530 1022 510 1531 1020 510 1532 1023 511 1533 1024 511 1534 1022 511 1535 1025 512 1536 1026 512 1537 1024 512 1538 1027 513 1539 1028 513 1540 1026 513 1541 1029 514 1542 1030 514 1543 1028 514 1544 1031 515 1545 1032 515 1546 1030 515 1547 1033 516 1548 1034 516 1549 1032 516 1550 1035 517 1551 1036 517 1552 1034 517 1553 1037 518 1554 1038 518 1555 1036 518 1556 1039 519 1557 1040 519 1558 1038 519 1559 1041 520 1560 1042 520 1561 1040 520 1562 1043 521 1563 1044 521 1564 1042 521 1565 1045 522 1566 1046 522 1567 1044 522 1568 1047 523 1569 1048 523 1570 1046 523 1571 1049 524 1572 1050 524 1573 1048 524 1574 1051 525 1575 1052 525 1576 1050 525 1577 1053 526 1578 1054 526 1579 1052 526 1580 1055 527 1581 1056 527 1582 1054 527 1583 1057 528 1584 1058 528 1585 1056 528 1586 1059 529 1587 1060 529 1588 1058 529 1589 1061 530 1590 1062 530 1591 1060 530 1592 1063 531 1593 1064 531 1594 1062 531 1595 1065 532 1596 1066 532 1597 1064 532 1598 1067 533 1599 1068 533 1600 1066 533 1601 1069 534 1602 1070 534 1603 1068 534 1604 1071 535 1605 1072 535 1606 1070 535 1607 1073 536 1608 1074 536 1609 1072 536 1610 1075 537 1611 1076 537 1612 1074 537 1613 1077 538 1614 1078 538 1615 1076 538 1616 1079 539 1617 1080 539 1618 1078 539 1619 1081 540 1620 1082 540 1621 1080 540 1622 1083 541 1623 1084 541 1624 1082 541 1625 1085 542 1626 1086 542 1627 1084 542 1628 1087 543 1629 1088 543 1630 1086 543 1631 1089 544 1632 1090 544 1633 1088 544 1634 1091 545 1635 1092 545 1636 1090 545 1637 1093 546 1638 1094 546 1639 1092 546 1640 1095 547 1641 1096 547 1642 1094 547 1643 1097 548 1644 1098 548 1645 1096 548 1646 1099 549 1647 1100 549 1648 1098 549 1649 1101 550 1650 1102 550 1651 1100 550 1652 1103 551 1653 1104 551 1654 1102 551 1655 1105 552 1656 1106 552 1657 1104 552 1658 1107 553 1659 1108 553 1660 1106 553 1661 1109 554 1662 1110 554 1663 1108 554 1664 1111 555 1665 1112 555 1666 1110 555 1667 1113 556 1668 1114 556 1669 1112 556 1670 1115 557 1671 1116 557 1672 1114 557 1673 1117 558 1674 1118 558 1675 1116 558 1676 1119 559 1677 1120 559 1678 1118 559 1679 1121 560 1680 1122 560 1681 1120 560 1682 1123 561 1683 1124 561 1684 1122 561 1685 1125 562 1686 1126 562 1687 1124 562 1688 1127 563 1689 1128 563 1690 1126 563 1691 1129 564 1692 1130 564 1693 1128 564 1694 1131 565 1695 1132 565 1696 1130 565 1697 1133 566 1698 1134 566 1699 1132 566 1700 1135 567 1701 1136 567 1702 1134 567 1703 1137 568 1704 1138 568 1705 1136 568 1706 1139 569 1707 1140 569 1708 1138 569 1709 1141 570 1710 1142 570 1711 1140 570 1712 1143 571 1713 1144 571 1714 1142 571 1715 1145 572 1716 1146 572 1717 1144 572 1718 1147 573 1719 1148 573 1720 1146 573 1721 1149 574 1722 1150 574 1723 1148 574 1724 1151 575 1725 1152 575 1726 1150 575 1727 1153 576 1728 1154 576 1729 1152 576 1730 1155 577 1731 1156 577 1732 1154 577 1733 1157 578 1734 1158 578 1735 1156 578 1736 1159 579 1737 1160 579 1738 1158 579 1739 1161 580 1740 1162 580 1741 1160 580 1742 1163 581 1743 1164 581 1744 1162 581 1745 1165 582 1746 1166 582 1747 1164 582 1748 1167 583 1749 1168 583 1750 1166 583 1751 1169 584 1752 1170 584 1753 1168 584 1754 1171 585 1755 1172 585 1756 1170 585 1757 1173 586 1758 1174 586 1759 1172 586 1760 1175 587 1761 1176 587 1762 1174 587 1763 1177 588 1764 1178 588 1765 1176 588 1766 1179 589 1767 1180 589 1768 1178 589 1769 1181 590 1770 1182 590 1771 1180 590 1772 1183 591 1773 1184 591 1774 1182 591 1775 1185 592 1776 1186 592 1777 1184 592 1778 1187 593 1779 1188 593 1780 1186 593 1781 1189 594 1782 1190 594 1783 1188 594 1784 1191 595 1785 1192 595 1786 1190 595 1787 1193 596 1788 1194 596 1789 1192 596 1790 1195 597 1791 1196 597 1792 1194 597 1793 1197 598 1794 1198 598 1795 1196 598 1796 1199 599 1797 1200 599 1798 1198 599 1799 1201 600 1800 1202 600 1801 1200 600 1802 1203 601 1803 1204 601 1804 1202 601 1805 1205 602 1806 1206 602 1807 1204 602 1808 1207 603 1809 1208 603 1810 1206 603 1811 1209 604 1812 1210 604 1813 1208 604 1814 1211 605 1815 1212 605 1816 1210 605 1817 1213 606 1818 1214 606 1819 1212 606 1820 1215 607 1821 1216 607 1822 1214 607 1823 1217 608 1824 1218 608 1825 1216 608 1826 1219 609 1827 1220 609 1828 1218 609 1829 1221 610 1830 1222 610 1831 1220 610 1832 1223 611 1833 1224 611 1834 1222 611 1835 1225 612 1836 1226 612 1837 1224 612 1838 1227 613 1839 1228 613 1840 1226 613 1841 1229 614 1842 1230 614 1843 1228 614 1844 1231 615 1845 1232 615 1846 1230 615 1847 1233 616 1848 1234 616 1849 1232 616 1850 1235 617 1851 1236 617 1852 1234 617 1853 1237 618 1854 1238 618 1855 1236 618 1856 1239 619 1857 1240 619 1858 1238 619 1859 1241 620 1860 1242 620 1861 1240 620 1862 1243 621 1863 1244 621 1864 1242 621 1865 1245 622 1866 1246 622 1867 1244 622 1868 1247 623 1869 1248 623 1870 1246 623 1871 1249 624 1872 1250 624 1873 1248 624 1874 1251 625 1875 1252 625 1876 1250 625 1877 1253 626 1878 1254 626 1879 1252 626 1880 1255 627 1881 1256 627 1882 1254 627 1883 1257 628 1884 1258 628 1885 1256 628 1886 1259 629 1887 1260 629 1888 1258 629 1889 1261 630 1890 1262 630 1891 1260 630 1892 1263 631 1893 1264 631 1894 1262 631 1895 1265 632 1896 1266 632 1897 1264 632 1898 1267 633 1899 1268 633 1900 1266 633 1901 1269 634 1902 1270 634 1903 1268 634 1904 1271 635 1905 1272 635 1906 1270 635 1907 1273 636 1908 1274 636 1909 1272 636 1910 1275 637 1911 1276 637 1912 1274 637 1913 1277 638 1914 1278 638 1915 1276 638 1916 1279 639 1917 1280 639 1918 1278 639 1919 1281 640 1920 1282 640 1921 1280 640 1922 1283 641 1923 1284 641 1924 1282 641 1925 1285 642 1926 1286 642 1927 1284 642 1928 1287 643 1929 1288 643 1930 1286 643 1931 1289 644 1932 1290 644 1933 1288 644 1934 1291 645 1935 1292 645 1936 1290 645 1937 1293 646 1938 1294 646 1939 1292 646 1940 1295 647 1941 1296 647 1942 1294 647 1943 1297 648 1944 1298 648 1945 1296 648 1946 1299 649 1947 1300 649 1948 1298 649 1949 1301 650 1950 1302 650 1951 1300 650 1952 1303 651 1953 1304 651 1954 1302 651 1955 1305 652 1956 1306 652 1957 1304 652 1958 1307 653 1959 1308 653 1960 1306 653 1961 1309 654 1962 1310 654 1963 1308 654 1964 1311 655 1965 1312 655 1966 1310 655 1967 1313 656 1968 1314 656 1969 1312 656 1970 1315 657 1971 1316 657 1972 1314 657 1973 1317 658 1974 1318 658 1975 1316 658 1976 1319 659 1977 1320 659 1978 1318 659 1979 1321 660 1980 1322 660 1981 1320 660 1982 1323 661 1983 1324 661 1984 1322 661 1985 1325 662 1986 1326 662 1987 1324 662 1988 1327 663 1989 1328 663 1990 1326 663 1991 1329 664 1992 1330 664 1993 1328 664 1994 1331 665 1995 1332 665 1996 1330 665 1997 1333 666 1998 1334 666 1999 1332 666 2000 1335 667 2001 1336 667 2002 1334 667 2003 1337 668 2004 1338 668 2005 1336 668 2006 1339 669 2007 1340 669 2008 1338 669 2009 1341 670 2010 1342 670 2011 1340 670 2012 1343 671 2013 1344 671 2014 1342 671 2015 1345 672 2016 1346 672 2017 1344 672 2018 1347 673 2019 1348 673 2020 1346 673 2021 1349 674 2022 1350 674 2023 1348 674 2024 1351 675 2025 1352 675 2026 1350 675 2027 1353 676 2028 1354 676 2029 1352 676 2030 1355 677 2031 1356 677 2032 1354 677 2033 1357 678 2034 1358 678 2035 1356 678 2036 1359 679 2037 1360 679 2038 1358 679 2039 1361 680 2040 1362 680 2041 1360 680 2042 1363 681 2043 1364 681 2044 1362 681 2045 1365 682 2046 1366 682 2047 1364 682 2048 1367 683 2049 1368 683 2050 1366 683 2051 1369 684 2052 1370 684 2053 1368 684 2054 1371 685 2055 1372 685 2056 1370 685 2057 1373 686 2058 1374 686 2059 1372 686 2060 1375 687 2061 1376 687 2062 1374 687 2063 1377 688 2064 1378 688 2065 1376 688 2066 1379 689 2067 1380 689 2068 1378 689 2069 1381 690 2070 1382 690 2071 1380 690 2072 1383 691 2073 1384 691 2074 1382 691 2075 1385 692 2076 1386 692 2077 1384 692 2078 1387 693 2079 1388 693 2080 1386 693 2081 1389 694 2082 1390 694 2083 1388 694 2084 1391 695 2085 1392 695 2086 1390 695 2087 1393 696 2088 1394 696 2089 1392 696 2090 1395 697 2091 1396 697 2092 1394 697 2093 1397 698 2094 1398 698 2095 1396 698 2096 1399 699 2097 1400 699 2098 1398 699 2099 1401 700 2100 1402 700 2101 1400 700 2102 1403 701 2103 1404 701 2104 1402 701 2105 1405 702 2106 1406 702 2107 1404 702 2108 1407 703 2109 1408 703 2110 1406 703 2111 1409 704 2112 1410 704 2113 1408 704 2114 1411 705 2115 1412 705 2116 1410 705 2117 1413 706 2118 1414 706 2119 1412 706 2120 1415 707 2121 1416 707 2122 1414 707 2123 1417 708 2124 1418 708 2125 1416 708 2126 1419 709 2127 1420 709 2128 1418 709 2129 1421 710 2130 1422 710 2131 1420 710 2132 1423 711 2133 1424 711 2134 1422 711 2135 1425 712 2136 1426 712 2137 1424 712 2138 1427 713 2139 1428 713 2140 1426 713 2141 1429 714 2142 1430 714 2143 1428 714 2144 1431 715 2145 1432 715 2146 1430 715 2147 1433 716 2148 1434 716 2149 1432 716 2150 1435 717 2151 1436 717 2152 1434 717 2153 1437 718 2154 1438 718 2155 1436 718 2156 1439 719 2157 1440 719 2158 1438 719 2159 1441 720 2160 1442 720 2161 1440 720 2162 1443 721 2163 1444 721 2164 1442 721 2165 1445 722 2166 1446 722 2167 1444 722 2168 1447 723 2169 1448 723 2170 1446 723 2171 1449 724 2172 1450 724 2173 1448 724 2174 1451 725 2175 1452 725 2176 1450 725 2177 1453 726 2178 1454 726 2179 1452 726 2180 1455 727 2181 1456 727 2182 1454 727 2183 1457 728 2184 1458 728 2185 1456 728 2186 1459 729 2187 1460 729 2188 1458 729 2189 1461 730 2190 1462 730 2191 1460 730 2192 1463 731 2193 1464 731 2194 1462 731 2195 1465 732 2196 1466 732 2197 1464 732 2198 1467 733 2199 1468 733 2200 1466 733 2201 1469 734 2202 1470 734 2203 1468 734 2204 1471 735 2205 1472 735 2206 1470 735 2207 1473 736 2208 1474 736 2209 1472 736 2210 1475 737 2211 1476 737 2212 1474 737 2213 1477 738 2214 1478 738 2215 1476 738 2216 1479 739 2217 1480 739 2218 1478 739 2219 1481 740 2220 1482 740 2221 1480 740 2222 1483 741 2223 1484 741 2224 1482 741 2225 1485 742 2226 1486 742 2227 1484 742 2228 1487 743 2229 1488 743 2230 1486 743 2231 1489 744 2232 1490 744 2233 1488 744 2234 1491 745 2235 1492 745 2236 1490 745 2237 1493 746 2238 1494 746 2239 1492 746 2240 1495 747 2241 1496 747 2242 1494 747 2243 1497 748 2244 1498 748 2245 1496 748 2246 1499 749 2247 1500 749 2248 1498 749 2249 1501 750 2250 1502 750 2251 1500 750 2252 1503 751 2253 1504 751 2254 1502 751 2255 1505 752 2256 1506 752 2257 1504 752 2258 1507 753 2259 1508 753 2260 1506 753 2261 1509 754 2262 1510 754 2263 1508 754 2264 1511 755 2265 1512 755 2266 1510 755 2267 1513 756 2268 1514 756 2269 1512 756 2270 1515 757 2271 1516 757 2272 1514 757 2273 1517 758 2274 1518 758 2275 1516 758 2276 1519 759 2277 1520 759 2278 1518 759 2279 1521 760 2280 1522 760 2281 1520 760 2282 1523 761 2283 1524 761 2284 1522 761 2285 1525 762 2286 1526 762 2287 1524 762 2288 1527 763 2289 1528 763 2290 1526 763 2291 1529 764 2292 1530 764 2293 1528 764 2294 1531 765 2295 1532 765 2296 1530 765 2297 1533 766 2298 1534 766 2299 1532 766 2300 1535 767 2301 1536 767 2302 1534 767 2303 1537 768 2304 1538 768 2305 1536 768 2306 1539 769 2307 1540 769 2308 1538 769 2309 1541 770 2310 1542 770 2311 1540 770 2312 1543 771 2313 1544 771 2314 1542 771 2315 1545 772 2316 1546 772 2317 1544 772 2318 1547 773 2319 1548 773 2320 1546 773 2321 1549 774 2322 1550 774 2323 1548 774 2324 1551 775 2325 1552 775 2326 1550 775 2327 1553 776 2328 1554 776 2329 1552 776 2330 1555 777 2331 1556 777 2332 1554 777 2333 1557 778 2334 1558 778 2335 1556 778 2336 1559 779 2337 1560 779 2338 1558 779 2339 1561 780 2340 1562 780 2341 1560 780 2342 1563 781 2343 1564 781 2344 1562 781 2345 1565 782 2346 1566 782 2347 1564 782 2348 1567 783 2349 1568 783 2350 1566 783 2351 1569 784 2352 1570 784 2353 1568 784 2354 1571 785 2355 1572 785 2356 1570 785 2357 1573 786 2358 1574 786 2359 1572 786 2360 1575 787 2361 1576 787 2362 1574 787 2363 1577 788 2364 1578 788 2365 1576 788 2366 1579 789 2367 1580 789 2368 1578 789 2369 1581 790 2370 1582 790 2371 1580 790 2372 1583 791 2373 1584 791 2374 1582 791 2375 1585 792 2376 1586 792 2377 1584 792 2378 1587 793 2379 1588 793 2380 1586 793 2381 1589 794 2382 1590 794 2383 1588 794 2384 1591 795 2385 1592 795 2386 1590 795 2387 1593 796 2388 1594 796 2389 1592 796 2390 1595 797 2391 1596 797 2392 1594 797 2393 1597 798 2394 1598 798 2395 1596 798 2396 1599 799 2397 1600 799 2398 1598 799 2399 1601 800 2400 1602 800 2401 1600 800 2402 1603 801 2403 1604 801 2404 1602 801 2405 1605 802 2406 1606 802 2407 1604 802 2408 1607 803 2409 1608 803 2410 1606 803 2411 1609 804 2412 1610 804 2413 1608 804 2414 1611 805 2415 1612 805 2416 1610 805 2417 1613 806 2418 1614 806 2419 1612 806 2420 1615 807 2421 1616 807 2422 1614 807 2423 1617 808 2424 1618 808 2425 1616 808 2426 1619 809 2427 1620 809 2428 1618 809 2429 1621 810 2430 1622 810 2431 1620 810 2432 1623 811 2433 1624 811 2434 1622 811 2435 1625 812 2436 1626 812 2437 1624 812 2438 1627 813 2439 1628 813 2440 1626 813 2441 1629 814 2442 1630 814 2443 1628 814 2444 1631 815 2445 1632 815 2446 1630 815 2447 1633 816 2448 1634 816 2449 1632 816 2450 1635 817 2451 1636 817 2452 1634 817 2453 1637 818 2454 1638 818 2455 1636 818 2456 1639 819 2457 1640 819 2458 1638 819 2459 1641 820 2460 1642 820 2461 1640 820 2462 1643 821 2463 1644 821 2464 1642 821 2465 1645 822 2466 1646 822 2467 1644 822 2468 1647 823 2469 1648 823 2470 1646 823 2471 1649 824 2472 1650 824 2473 1648 824 2474 1651 825 2475 1652 825 2476 1650 825 2477 1653 826 2478 1654 826 2479 1652 826 2480 1655 827 2481 1656 827 2482 1654 827 2483 1657 828 2484 1658 828 2485 1656 828 2486 1659 829 2487 1660 829 2488 1658 829 2489 1661 830 2490 1662 830 2491 1660 830 2492 1663 831 2493 1664 831 2494 1662 831 2495 1665 832 2496 1666 832 2497 1664 832 2498 1667 833 2499 1668 833 2500 1666 833 2501 1669 834 2502 1670 834 2503 1668 834 2504 1671 835 2505 1672 835 2506 1670 835 2507 1673 836 2508 1674 836 2509 1672 836 2510 1675 837 2511 1676 837 2512 1674 837 2513 1677 838 2514 1678 838 2515 1676 838 2516 1679 839 2517 1680 839 2518 1678 839 2519 1681 840 2520 1682 840 2521 1680 840 2522 1683 841 2523 1684 841 2524 1682 841 2525 1685 842 2526 1686 842 2527 1684 842 2528 1687 843 2529 1688 843 2530 1686 843 2531 1689 844 2532 1690 844 2533 1688 844 2534 1691 845 2535 1692 845 2536 1690 845 2537 1693 846 2538 1694 846 2539 1692 846 2540 1695 847 2541 1696 847 2542 1694 847 2543 1697 848 2544 1698 848 2545 1696 848 2546 1699 849 2547 1700 849 2548 1698 849 2549 1701 850 2550 1702 850 2551 1700 850 2552 1703 851 2553 1704 851 2554 1702 851 2555 1705 852 2556 1706 852 2557 1704 852 2558 1707 853 2559 1708 853 2560 1706 853 2561 1709 854 2562 1710 854 2563 1708 854 2564 1711 855 2565 1712 855 2566 1710 855 2567 1713 856 2568 1714 856 2569 1712 856 2570 1715 857 2571 1716 857 2572 1714 857 2573 1717 858 2574 1718 858 2575 1716 858 2576 1719 859 2577 1720 859 2578 1718 859 2579 1721 860 2580 1722 860 2581 1720 860 2582 1723 861 2583 1724 861 2584 1722 861 2585 1725 862 2586 1726 862 2587 1724 862 2588 1727 863 2589 1728 863 2590 1726 863 2591 1729 864 2592 1730 864 2593 1728 864 2594 1731 865 2595 1732 865 2596 1730 865 2597 1733 866 2598 1734 866 2599 1732 866 2600 1735 867 2601 1736 867 2602 1734 867 2603 1737 868 2604 1738 868 2605 1736 868 2606 1739 869 2607 1740 869 2608 1738 869 2609 1741 870 2610 1742 870 2611 1740 870 2612 1743 871 2613 1744 871 2614 1742 871 2615 1745 872 2616 1746 872 2617 1744 872 2618 1747 873 2619 1748 873 2620 1746 873 2621 1749 874 2622 1750 874 2623 1748 874 2624 1751 875 2625 1752 875 2626 1750 875 2627 1753 876 2628 1754 876 2629 1752 876 2630 1755 877 2631 1756 877 2632 1754 877 2633 1757 878 2634 1758 878 2635 1756 878 2636 1759 879 2637 1760 879 2638 1758 879 2639 1761 880 2640 1762 880 2641 1760 880 2642 1763 881 2643 1764 881 2644 1762 881 2645 1765 882 2646 1766 882 2647 1764 882 2648 1767 883 2649 1768 883 2650 1766 883 2651 1769 884 2652 1770 884 2653 1768 884 2654 1771 885 2655 1772 885 2656 1770 885 2657 1773 886 2658 1774 886 2659 1772 886 2660 1775 887 2661 1776 887 2662 1774 887 2663 1777 888 2664 1778 888 2665 1776 888 2666 1779 889 2667 1780 889 2668 1778 889 2669 1781 890 2670 1782 890 2671 1780 890 2672 1783 891 2673 1784 891 2674 1782 891 2675 1785 892 2676 1786 892 2677 1784 892 2678 1787 893 2679 1788 893 2680 1786 893 2681 1789 894 2682 1790 894 2683 1788 894 2684 1791 895 2685 1792 895 2686 1790 895 2687 1793 896 2688 1794 896 2689 1792 896 2690 1795 897 2691 1796 897 2692 1794 897 2693 1797 898 2694 1798 898 2695 1796 898 2696 1799 899 2697 1800 899 2698 1798 899 2699 1801 900 2700 1802 900 2701 1800 900 2702 1803 901 2703 1804 901 2704 1802 901 2705 1805 902 2706 1806 902 2707 1804 902 2708 1807 903 2709 1808 903 2710 1806 903 2711 1809 904 2712 1810 904 2713 1808 904 2714 1811 905 2715 1812 905 2716 1810 905 2717 1813 906 2718 1814 906 2719 1812 906 2720 1815 907 2721 1816 907 2722 1814 907 2723 1817 908 2724 1818 908 2725 1816 908 2726 1819 909 2727 1820 909 2728 1818 909 2729 1821 910 2730 1822 910 2731 1820 910 2732 1823 911 2733 1824 911 2734 1822 911 2735 1825 912 2736 1826 912 2737 1824 912 2738 1827 913 2739 1828 913 2740 1826 913 2741 1829 914 2742 1830 914 2743 1828 914 2744 1831 915 2745 1832 915 2746 1830 915 2747 1833 916 2748 1834 916 2749 1832 916 2750 1835 917 2751 1836 917 2752 1834 917 2753 1837 918 2754 1838 918 2755 1836 918 2756 1839 919 2757 1840 919 2758 1838 919 2759 1841 920 2760 1842 920 2761 1840 920 2762 1843 921 2763 1844 921 2764 1842 921 2765 1845 922 2766 1846 922 2767 1844 922 2768 1847 923 2769 1848 923 2770 1846 923 2771 1849 924 2772 1850 924 2773 1848 924 2774 1851 925 2775 1852 925 2776 1850 925 2777 1853 926 2778 1854 926 2779 1852 926 2780 1855 927 2781 1856 927 2782 1854 927 2783 1857 928 2784 1858 928 2785 1856 928 2786 1859 929 2787 1860 929 2788 1858 929 2789 1861 930 2790 1862 930 2791 1860 930 2792 1863 931 2793 1864 931 2794 1862 931 2795 1865 932 2796 1866 932 2797 1864 932 2798 1867 933 2799 1868 933 2800 1866 933 2801 1869 934 2802 1870 934 2803 1868 934 2804 1871 935 2805 1872 935 2806 1870 935 2807 1873 936 2808 1874 936 2809 1872 936 2810 1875 937 2811 1876 937 2812 1874 937 2813 1877 938 2814 1878 938 2815 1876 938 2816 1879 939 2817 1880 939 2818 1878 939 2819 1881 940 2820 1882 940 2821 1880 940 2822 1883 941 2823 1884 941 2824 1882 941 2825 1885 942 2826 1886 942 2827 1884 942 2828 1887 943 2829 1888 943 2830 1886 943 2831 1889 944 2832 1890 944 2833 1888 944 2834 1891 945 2835 1892 945 2836 1890 945 2837 1893 946 2838 1894 946 2839 1892 946 2840 1895 947 2841 1896 947 2842 1894 947 2843 1897 948 2844 1898 948 2845 1896 948 2846 1899 949 2847 1900 949 2848 1898 949 2849 1901 950 2850 1902 950 2851 1900 950 2852 1903 951 2853 1904 951 2854 1902 951 2855 1905 952 2856 1906 952 2857 1904 952 2858 1907 953 2859 1908 953 2860 1906 953 2861 1909 954 2862 1910 954 2863 1908 954 2864 1911 955 2865 1912 955 2866 1910 955 2867 1913 956 2868 1914 956 2869 1912 956 2870 1915 957 2871 1916 957 2872 1914 957 2873 1917 958 2874 1918 958 2875 1916 958 2876 1919 959 2877 1920 959 2878 1918 959 2879 1921 960 2880 1922 960 2881 1920 960 2882 1923 961 2883 1924 961 2884 1922 961 2885 1925 962 2886 1926 962 2887 1924 962 2888 1927 963 2889 1928 963 2890 1926 963 2891 1929 964 2892 1930 964 2893 1928 964 2894 1931 965 2895 1932 965 2896 1930 965 2897 1933 966 2898 1934 966 2899 1932 966 2900 1935 967 2901 1936 967 2902 1934 967 2903 1937 968 2904 1938 968 2905 1936 968 2906 1939 969 2907 1940 969 2908 1938 969 2909 1941 970 2910 1942 970 2911 1940 970 2912 1943 971 2913 1944 971 2914 1942 971 2915 1945 972 2916 1946 972 2917 1944 972 2918 1947 973 2919 1948 973 2920 1946 973 2921 1949 974 2922 1950 974 2923 1948 974 2924 1951 975 2925 1952 975 2926 1950 975 2927 1953 976 2928 1954 976 2929 1952 976 2930 1955 977 2931 1956 977 2932 1954 977 2933 1957 978 2934 1958 978 2935 1956 978 2936 1959 979 2937 1960 979 2938 1958 979 2939 1961 980 2940 1962 980 2941 1960 980 2942 1963 981 2943 1964 981 2944 1962 981 2945 1965 982 2946 1966 982 2947 1964 982 2948 1967 983 2949 1968 983 2950 1966 983 2951 1969 984 2952 1970 984 2953 1968 984 2954 1971 985 2955 1972 985 2956 1970 985 2957 1973 986 2958 1974 986 2959 1972 986 2960 1975 987 2961 1976 987 2962 1974 987 2963 1977 988 2964 1978 988 2965 1976 988 2966 1979 989 2967 1980 989 2968 1978 989 2969 1981 990 2970 1982 990 2971 1980 990 2972 1983 991 2973 1984 991 2974 1982 991 2975 1985 992 2976 1986 992 2977 1984 992 2978 1987 993 2979 1988 993 2980 1986 993 2981 1989 994 2982 1990 994 2983 1988 994 2984 1991 995 2985 1992 995 2986 1990 995 2987 1993 996 2988 1994 996 2989 1992 996 2990 1995 997 2991 1996 997 2992 1994 997 2993 1997 998 2994 1998 998 2995 1996 998 2996 1999 999 2997 2000 999 2998 1998 999 2999 2001 1000 3000 2002 1000 3001 2000 1000 3002 2003 1001 3003 2004 1001 3004 2002 1001 3005 2005 1002 3006 2006 1002 3007 2004 1002 3008 2007 1003 3009 2008 1003 3010 2006 1003 3011 2009 1004 3012 2010 1004 3013 2008 1004 3014 2011 1005 3015 2012 1005 3016 2010 1005 3017 2013 1006 3018 2014 1006 3019 2012 1006 3020 2015 1007 3021 2016 1007 3022 2014 1007 3023 2017 1008 3024 2018 1008 3025 2016 1008 3026 2019 1009 3027 2020 1009 3028 2018 1009 3029 2021 1010 3030 2022 1010 3031 2020 1010 3032 2023 1011 3033 2024 1011 3034 2022 1011 3035 2025 1012 3036 2026 1012 3037 2024 1012 3038 2027 1013 3039 2028 1013 3040 2026 1013 3041 2029 1014 3042 2030 1014 3043 2028 1014 3044 2031 1015 3045 2032 1015 3046 2030 1015 3047 2033 1016 3048 2034 1016 3049 2032 1016 3050 2035 1017 3051 2036 1017 3052 2034 1017 3053 2037 1018 3054 2038 1018 3055 2036 1018 3056 2039 1019 3057 2040 1019 3058 2038 1019 3059 2041 1020 3060 2042 1020 3061 2040 1020 3062 2043 1021 3063 2044 1021 3064 2042 1021 3065 2045 1022 3066 2046 1022 3067 2044 1022 3068 2047 1023 3069 2048 1023 3070 2046 1023 3071 2049 1024 3072 2050 1024 3073 2048 1024 3074 2051 1025 3075 2052 1025 3076 2050 1025 3077 2053 1026 3078 2054 1026 3079 2052 1026 3080 2055 1027 3081 2056 1027 3082 2054 1027 3083 2057 1028 3084 2058 1028 3085 2056 1028 3086 2059 1029 3087 2060 1029 3088 2058 1029 3089 2061 1030 3090 2062 1030 3091 2060 1030 3092 2063 1031 3093 2064 1031 3094 2062 1031 3095 2065 1032 3096 2066 1032 3097 2064 1032 3098 2067 1033 3099 2068 1033 3100 2066 1033 3101 2069 1034 3102 2070 1034 3103 2068 1034 3104 2071 1035 3105 2072 1035 3106 2070 1035 3107 2073 1036 3108 2074 1036 3109 2072 1036 3110 2075 1037 3111 2076 1037 3112 2074 1037 3113 2077 1038 3114 2078 1038 3115 2076 1038 3116 2079 1039 3117 2080 1039 3118 2078 1039 3119 2081 1040 3120 2082 1040 3121 2080 1040 3122 2083 1041 3123 2084 1041 3124 2082 1041 3125 2085 1042 3126 2086 1042 3127 2084 1042 3128 2087 1043 3129 2088 1043 3130 2086 1043 3131 2089 1044 3132 2090 1044 3133 2088 1044 3134 2091 1045 3135 2092 1045 3136 2090 1045 3137 2093 1046 3138 2094 1046 3139 2092 1046 3140 2095 1047 3141 2096 1047 3142 2094 1047 3143 2097 1048 3144 2098 1048 3145 2096 1048 3146 2099 1049 3147 2100 1049 3148 2098 1049 3149 2101 1050 3150 2102 1050 3151 2100 1050 3152 2103 1051 3153 2104 1051 3154 2102 1051 3155 2105 1052 3156 2106 1052 3157 2104 1052 3158 2107 1053 3159 2108 1053 3160 2106 1053 3161 2109 1054 3162 2110 1054 3163 2108 1054 3164 2111 1055 3165 2112 1055 3166 2110 1055 3167 2113 1056 3168 2114 1056 3169 2112 1056 3170 2115 1057 3171 2116 1057 3172 2114 1057 3173 2117 1058 3174 2118 1058 3175 2116 1058 3176 2119 1059 3177 2120 1059 3178 2118 1059 3179 2121 1060 3180 2122 1060 3181 2120 1060 3182 2123 1061 3183 2124 1061 3184 2122 1061 3185 2125 1062 3186 2126 1062 3187 2124 1062 3188 2127 1063 3189 2128 1063 3190 2126 1063 3191 2129 1064 3192 2130 1064 3193 2128 1064 3194 2131 1065 3195 2132 1065 3196 2130 1065 3197 2133 1066 3198 2134 1066 3199 2132 1066 3200 2135 1067 3201 2136 1067 3202 2134 1067 3203 2137 1068 3204 2138 1068 3205 2136 1068 3206 2139 1069 3207 2140 1069 3208 2138 1069 3209 2141 1070 3210 2142 1070 3211 2140 1070 3212 2143 1071 3213 2144 1071 3214 2142 1071 3215 2145 1072 3216 2146 1072 3217 2144 1072 3218 2147 1073 3219 2148 1073 3220 2146 1073 3221 2149 1074 3222 2150 1074 3223 2148 1074 3224 2151 1075 3225 2152 1075 3226 2150 1075 3227 2153 1076 3228 2154 1076 3229 2152 1076 3230 2155 1077 3231 2156 1077 3232 2154 1077 3233 2157 1078 3234 2158 1078 3235 2156 1078 3236 2159 1079 3237 2160 1079 3238 2158 1079 3239 2161 1080 3240 2162 1080 3241 2160 1080 3242 2163 1081 3243 2164 1081 3244 2162 1081 3245 2165 1082 3246 2166 1082 3247 2164 1082 3248 2167 1083 3249 2168 1083 3250 2166 1083 3251 2169 1084 3252 2170 1084 3253 2168 1084 3254 2171 1085 3255 2172 1085 3256 2170 1085 3257 2173 1086 3258 2174 1086 3259 2172 1086 3260 2175 1087 3261 2176 1087 3262 2174 1087 3263 2177 1088 3264 2178 1088 3265 2176 1088 3266 2179 1089 3267 2180 1089 3268 2178 1089 3269 2181 1090 3270 2182 1090 3271 2180 1090 3272 2183 1091 3273 2184 1091 3274 2182 1091 3275 2185 1092 3276 2186 1092 3277 2184 1092 3278 2187 1093 3279 2188 1093 3280 2186 1093 3281 2189 1094 3282 2190 1094 3283 2188 1094 3284 2191 1095 3285 2192 1095 3286 2190 1095 3287 2193 1096 3288 2194 1096 3289 2192 1096 3290 2195 1097 3291 2196 1097 3292 2194 1097 3293 2197 1098 3294 2198 1098 3295 2196 1098 3296 2199 1099 3297 2200 1099 3298 2198 1099 3299 2201 1100 3300 2202 1100 3301 2200 1100 3302 2203 1101 3303 2204 1101 3304 2202 1101 3305 2205 1102 3306 2206 1102 3307 2204 1102 3308 2207 1103 3309 2208 1103 3310 2206 1103 3311 2209 1104 3312 2210 1104 3313 2208 1104 3314 2211 1105 3315 2212 1105 3316 2210 1105 3317 2213 1106 3318 2214 1106 3319 2212 1106 3320 2215 1107 3321 2216 1107 3322 2214 1107 3323 2217 1108 3324 2218 1108 3325 2216 1108 3326 2219 1109 3327 2220 1109 3328 2218 1109 3329 2221 1110 3330 2222 1110 3331 2220 1110 3332 2223 1111 3333 2224 1111 3334 2222 1111 3335 2225 1112 3336 2226 1112 3337 2224 1112 3338 2227 1113 3339 2228 1113 3340 2226 1113 3341 2229 1114 3342 2230 1114 3343 2228 1114 3344 2231 1115 3345 2232 1115 3346 2230 1115 3347 2233 1116 3348 2234 1116 3349 2232 1116 3350 2235 1117 3351 2236 1117 3352 2234 1117 3353 2237 1118 3354 2238 1118 3355 2236 1118 3356 2239 1119 3357 2240 1119 3358 2238 1119 3359 2241 1120 3360 2242 1120 3361 2240 1120 3362 2243 1121 3363 2244 1121 3364 2242 1121 3365 2245 1122 3366 2246 1122 3367 2244 1122 3368 2247 1123 3369 2248 1123 3370 2246 1123 3371 2249 1124 3372 2250 1124 3373 2248 1124 3374 2251 1125 3375 2252 1125 3376 2250 1125 3377 2253 1126 3378 2254 1126 3379 2252 1126 3380 2255 1127 3381 2256 1127 3382 2254 1127 3383 2257 1128 3384 2258 1128 3385 2256 1128 3386 2259 1129 3387 2260 1129 3388 2258 1129 3389 2261 1130 3390 2262 1130 3391 2260 1130 3392 2263 1131 3393 2264 1131 3394 2262 1131 3395 2265 1132 3396 2266 1132 3397 2264 1132 3398 2267 1133 3399 2268 1133 3400 2266 1133 3401 2269 1134 3402 2270 1134 3403 2268 1134 3404 2271 1135 3405 2272 1135 3406 2270 1135 3407 2273 1136 3408 2274 1136 3409 2272 1136 3410 2275 1137 3411 2276 1137 3412 2274 1137 3413 2277 1138 3414 2278 1138 3415 2276 1138 3416 2279 1139 3417 2280 1139 3418 2278 1139 3419 2281 1140 3420 2282 1140 3421 2280 1140 3422 2283 1141 3423 2284 1141 3424 2282 1141 3425 2285 1142 3426 2286 1142 3427 2284 1142 3428 2287 1143 3429 2288 1143 3430 2286 1143 3431 2289 1144 3432 2290 1144 3433 2288 1144 3434 2291 1145 3435 2292 1145 3436 2290 1145 3437 2293 1146 3438 2294 1146 3439 2292 1146 3440 2295 1147 3441 2296 1147 3442 2294 1147 3443 2297 1148 3444 2298 1148 3445 2296 1148 3446 2299 1149 3447 2300 1149 3448 2298 1149 3449 2301 1150 3450 2302 1150 3451 2300 1150 3452 2303 1151 3453 2304 1151 3454 2302 1151 3455 2305 1152 3456 2306 1152 3457 2304 1152 3458 2307 1153 3459 2308 1153 3460 2306 1153 3461 2309 1154 3462 2310 1154 3463 2308 1154 3464 2311 1155 3465 2312 1155 3466 2310 1155 3467 2313 1156 3468 2314 1156 3469 2312 1156 3470 2315 1157 3471 2316 1157 3472 2314 1157 3473 2317 1158 3474 2318 1158 3475 2316 1158 3476 2319 1159 3477 2320 1159 3478 2318 1159 3479 2321 1160 3480 2322 1160 3481 2320 1160 3482 2323 1161 3483 2324 1161 3484 2322 1161 3485 2325 1162 3486 2326 1162 3487 2324 1162 3488 2327 1163 3489 2328 1163 3490 2326 1163 3491 2329 1164 3492 2330 1164 3493 2328 1164 3494 2331 1165 3495 2332 1165 3496 2330 1165 3497 2333 1166 3498 2334 1166 3499 2332 1166 3500 2335 1167 3501 2336 1167 3502 2334 1167 3503 2337 1168 3504 2338 1168 3505 2336 1168 3506 2339 1169 3507 2340 1169 3508 2338 1169 3509 2341 1170 3510 2342 1170 3511 2340 1170 3512 2343 1171 3513 2344 1171 3514 2342 1171 3515 2345 1172 3516 2346 1172 3517 2344 1172 3518 2347 1173 3519 2348 1173 3520 2346 1173 3521 2349 1174 3522 2350 1174 3523 2348 1174 3524 2351 1175 3525 2352 1175 3526 2350 1175 3527 2353 1176 3528 2354 1176 3529 2352 1176 3530 2355 1177 3531 2356 1177 3532 2354 1177 3533 2357 1178 3534 2358 1178 3535 2356 1178 3536 2359 1179 3537 2360 1179 3538 2358 1179 3539 2361 1180 3540 2362 1180 3541 2360 1180 3542 2363 1181 3543 2364 1181 3544 2362 1181 3545 2365 1182 3546 2366 1182 3547 2364 1182 3548 2367 1183 3549 2368 1183 3550 2366 1183 3551 2369 1184 3552 2370 1184 3553 2368 1184 3554 2371 1185 3555 2372 1185 3556 2370 1185 3557 2373 1186 3558 2374 1186 3559 2372 1186 3560 2375 1187 3561 2376 1187 3562 2374 1187 3563 2377 1188 3564 2378 1188 3565 2376 1188 3566 2379 1189 3567 2380 1189 3568 2378 1189 3569 2381 1190 3570 2382 1190 3571 2380 1190 3572 2383 1191 3573 2384 1191 3574 2382 1191 3575 2385 1192 3576 2386 1192 3577 2384 1192 3578 2387 1193 3579 2388 1193 3580 2386 1193 3581 2389 1194 3582 2390 1194 3583 2388 1194 3584 2391 1195 3585 2392 1195 3586 2390 1195 3587 2393 1196 3588 2394 1196 3589 2392 1196 3590 2395 1197 3591 2396 1197 3592 2394 1197 3593 2397 1198 3594 2398 1198 3595 2396 1198 3596 2399 1199 3597 2400 1199 3598 2398 1199 3599 2401 1200 3600 2402 1200 3601 2400 1200 3602 2403 1201 3603 2404 1201 3604 2402 1201 3605 2405 1202 3606 2406 1202 3607 2404 1202 3608 2407 1203 3609 2408 1203 3610 2406 1203 3611 2409 1204 3612 2410 1204 3613 2408 1204 3614 2411 1205 3615 2412 1205 3616 2410 1205 3617 2413 1206 3618 2414 1206 3619 2412 1206 3620 2415 1207 3621 2416 1207 3622 2414 1207 3623 2417 1208 3624 2418 1208 3625 2416 1208 3626 2419 1209 3627 2420 1209 3628 2418 1209 3629 2421 1210 3630 2422 1210 3631 2420 1210 3632 2423 1211 3633 2424 1211 3634 2422 1211 3635 2425 1212 3636 2426 1212 3637 2424 1212 3638 2427 1213 3639 2428 1213 3640 2426 1213 3641 2429 1214 3642 2430 1214 3643 2428 1214 3644 2431 1215 3645 2432 1215 3646 2430 1215 3647 2433 1216 3648 2434 1216 3649 2432 1216 3650 2435 1217 3651 2436 1217 3652 2434 1217 3653 2437 1218 3654 2438 1218 3655 2436 1218 3656 2439 1219 3657 2440 1219 3658 2438 1219 3659 2441 1220 3660 2442 1220 3661 2440 1220 3662 2443 1221 3663 2444 1221 3664 2442 1221 3665 2445 1222 3666 2446 1222 3667 2444 1222 3668 2447 1223 3669 2448 1223 3670 2446 1223 3671 2449 1224 3672 2450 1224 3673 2448 1224 3674 2451 1225 3675 2452 1225 3676 2450 1225 3677 2453 1226 3678 2454 1226 3679 2452 1226 3680 2455 1227 3681 2456 1227 3682 2454 1227 3683 2457 1228 3684 2458 1228 3685 2456 1228 3686 2459 1229 3687 2460 1229 3688 2458 1229 3689 2461 1230 3690 2462 1230 3691 2460 1230 3692 2463 1231 3693 2464 1231 3694 2462 1231 3695 2465 1232 3696 2466 1232 3697 2464 1232 3698 2467 1233 3699 2468 1233 3700 2466 1233 3701 2469 1234 3702 2470 1234 3703 2468 1234 3704 2471 1235 3705 2472 1235 3706 2470 1235 3707 2473 1236 3708 2474 1236 3709 2472 1236 3710 2475 1237 3711 2476 1237 3712 2474 1237 3713 2477 1238 3714 2478 1238 3715 2476 1238 3716 2479 1239 3717 2480 1239 3718 2478 1239 3719 2481 1240 3720 2482 1240 3721 2480 1240 3722 2483 1241 3723 2484 1241 3724 2482 1241 3725 2485 1242 3726 2486 1242 3727 2484 1242 3728 2487 1243 3729 2488 1243 3730 2486 1243 3731 2489 1244 3732 2490 1244 3733 2488 1244 3734 2491 1245 3735 2492 1245 3736 2490 1245 3737 2493 1246 3738 2494 1246 3739 2492 1246 3740 2495 1247 3741 2496 1247 3742 2494 1247 3743 2497 1248 3744 2498 1248 3745 2496 1248 3746 2499 1249 3747 2500 1249 3748 2498 1249 3749 2501 1250 3750 2502 1250 3751 2500 1250 3752 2503 1251 3753 2504 1251 3754 2502 1251 3755 2505 1252 3756 2506 1252 3757 2504 1252 3758 2507 1253 3759 2508 1253 3760 2506 1253 3761 2509 1254 3762 2510 1254 3763 2508 1254 3764 2511 1255 3765 2512 1255 3766 2510 1255 3767 2513 1256 3768 2514 1256 3769 2512 1256 3770 2515 1257 3771 2516 1257 3772 2514 1257 3773 2517 1258 3774 2518 1258 3775 2516 1258 3776 2519 1259 3777 2520 1259 3778 2518 1259 3779 2521 1260 3780 2522 1260 3781 2520 1260 3782 2523 1261 3783 2524 1261 3784 2522 1261 3785 2525 1262 3786 2526 1262 3787 2524 1262 3788 2527 1263 3789 2528 1263 3790 2526 1263 3791 2529 1264 3792 2530 1264 3793 2528 1264 3794 2531 1265 3795 2532 1265 3796 2530 1265 3797 2533 1266 3798 2534 1266 3799 2532 1266 3800 2535 1267 3801 2536 1267 3802 2534 1267 3803 2537 1268 3804 2538 1268 3805 2536 1268 3806 2539 1269 3807 2540 1269 3808 2538 1269 3809 2541 1270 3810 2542 1270 3811 2540 1270 3812 2543 1271 3813 2544 1271 3814 2542 1271 3815 2545 1272 3816 2546 1272 3817 2544 1272 3818 2547 1273 3819 2548 1273 3820 2546 1273 3821 2549 1274 3822 2550 1274 3823 2548 1274 3824 2551 1275 3825 2552 1275 3826 2550 1275 3827 2553 1276 3828 2554 1276 3829 2552 1276 3830 2555 1277 3831 2556 1277 3832 2554 1277 3833 2557 1278 3834 2558 1278 3835 2556 1278 3836 2559 1279 3837 2560 1279 3838 2558 1279 3839 2561 1280 3840 2562 1280 3841 2560 1280 3842 2563 1281 3843 2564 1281 3844 2562 1281 3845 2565 1282 3846 2566 1282 3847 2564 1282 3848 2567 1283 3849 2568 1283 3850 2566 1283 3851 2569 1284 3852 2570 1284 3853 2568 1284 3854 2571 1285 3855 2572 1285 3856 2570 1285 3857 2573 1286 3858 2574 1286 3859 2572 1286 3860 2575 1287 3861 2576 1287 3862 2574 1287 3863 2577 1288 3864 2578 1288 3865 2576 1288 3866 2579 1289 3867 2580 1289 3868 2578 1289 3869 2581 1290 3870 2582 1290 3871 2580 1290 3872 2583 1291 3873 2584 1291 3874 2582 1291 3875 2585 1292 3876 2586 1292 3877 2584 1292 3878 2587 1293 3879 2588 1293 3880 2586 1293 3881 2589 1294 3882 2590 1294 3883 2588 1294 3884 2591 1295 3885 2592 1295 3886 2590 1295 3887 2593 1296 3888 2594 1296 3889 2592 1296 3890 2595 1297 3891 2596 1297 3892 2594 1297 3893 2597 1298 3894 2598 1298 3895 2596 1298 3896 2599 1299 3897 2600 1299 3898 2598 1299 3899 2601 1300 3900 2602 1300 3901 2600 1300 3902 2603 1301 3903 2604 1301 3904 2602 1301 3905 2605 1302 3906 2606 1302 3907 2604 1302 3908 2607 1303 3909 2608 1303 3910 2606 1303 3911 2609 1304 3912 2610 1304 3913 2608 1304 3914 2611 1305 3915 2612 1305 3916 2610 1305 3917 2613 1306 3918 2614 1306 3919 2612 1306 3920 2615 1307 3921 2616 1307 3922 2614 1307 3923 2617 1308 3924 2618 1308 3925 2616 1308 3926 2619 1309 3927 2620 1309 3928 2618 1309 3929 2621 1310 3930 2622 1310 3931 2620 1310 3932 2623 1311 3933 2624 1311 3934 2622 1311 3935 2625 1312 3936 2626 1312 3937 2624 1312 3938 2627 1313 3939 2628 1313 3940 2626 1313 3941 2629 1314 3942 2630 1314 3943 2628 1314 3944 2631 1315 3945 2632 1315 3946 2630 1315 3947 2633 1316 3948 2634 1316 3949 2632 1316 3950 2635 1317 3951 2636 1317 3952 2634 1317 3953 2637 1318 3954 2638 1318 3955 2636 1318 3956 2639 1319 3957 2640 1319 3958 2638 1319 3959 2641 1320 3960 2642 1320 3961 2640 1320 3962 2643 1321 3963 2644 1321 3964 2642 1321 3965 2645 1322 3966 2646 1322 3967 2644 1322 3968 2647 1323 3969 2648 1323 3970 2646 1323 3971 2649 1324 3972 2650 1324 3973 2648 1324 3974 2651 1325 3975 2652 1325 3976 2650 1325 3977 2653 1326 3978 2654 1326 3979 2652 1326 3980 2655 1327 3981 2656 1327 3982 2654 1327 3983 2657 1328 3984 2658 1328 3985 2656 1328 3986 2659 1329 3987 2660 1329 3988 2658 1329 3989 2661 1330 3990 2662 1330 3991 2660 1330 3992 2663 1331 3993 2664 1331 3994 2662 1331 3995 2665 1332 3996 2666 1332 3997 2664 1332 3998 2667 1333 3999 2668 1333 4000 2666 1333 4001 2669 1334 4002 2670 1334 4003 2668 1334 4004 2671 1335 4005 2672 1335 4006 2670 1335 4007 2673 1336 4008 2674 1336 4009 2672 1336 4010 2675 1337 4011 2676 1337 4012 2674 1337 4013 2677 1338 4014 2678 1338 4015 2676 1338 4016 2679 1339 4017 2680 1339 4018 2678 1339 4019 2681 1340 4020 2682 1340 4021 2680 1340 4022 2683 1341 4023 2684 1341 4024 2682 1341 4025 2685 1342 4026 2686 1342 4027 2684 1342 4028 2687 1343 4029 2688 1343 4030 2686 1343 4031 2689 1344 4032 2690 1344 4033 2688 1344 4034 2691 1345 4035 2692 1345 4036 2690 1345 4037 2693 1346 4038 2694 1346 4039 2692 1346 4040 2695 1347 4041 2696 1347 4042 2694 1347 4043 2697 1348 4044 2698 1348 4045 2696 1348 4046 2699 1349 4047 2700 1349 4048 2698 1349 4049 2701 1350 4050 2702 1350 4051 2700 1350 4052 2703 1351 4053 2704 1351 4054 2702 1351 4055 2705 1352 4056 2706 1352 4057 2704 1352 4058 2707 1353 4059 2708 1353 4060 2706 1353 4061 2709 1354 4062 2710 1354 4063 2708 1354 4064 2711 1355 4065 2712 1355 4066 2710 1355 4067 2713 1356 4068 2714 1356 4069 2712 1356 4070 2715 1357 4071 2716 1357 4072 2714 1357 4073 2717 1358 4074 2718 1358 4075 2716 1358 4076 2719 1359 4077 2720 1359 4078 2718 1359 4079 2721 1360 4080 2722 1360 4081 2720 1360 4082 2723 1361 4083 2724 1361 4084 2722 1361 4085 2725 1362 4086 2726 1362 4087 2724 1362 4088 2727 1363 4089 2728 1363 4090 2726 1363 4091 2729 1364 4092 2730 1364 4093 2728 1364 4094 2731 1365 4095 2732 1365 4096 2730 1365 4097 2733 1366 4098 2734 1366 4099 2732 1366 4100 2735 1367 4101 2736 1367 4102 2734 1367 4103 2737 1368 4104 2738 1368 4105 2736 1368 4106 2739 1369 4107 2740 1369 4108 2738 1369 4109 2741 1370 4110 2742 1370 4111 2740 1370 4112 2743 1371 4113 2744 1371 4114 2742 1371 4115 2745 1372 4116 2746 1372 4117 2744 1372 4118 2747 1373 4119 2748 1373 4120 2746 1373 4121 2749 1374 4122 2750 1374 4123 2748 1374 4124 2751 1375 4125 2752 1375 4126 2750 1375 4127 2753 1376 4128 2754 1376 4129 2752 1376 4130 2755 1377 4131 2756 1377 4132 2754 1377 4133 2757 1378 4134 2758 1378 4135 2756 1378 4136 2759 1379 4137 2760 1379 4138 2758 1379 4139 2761 1380 4140 2762 1380 4141 2760 1380 4142 2763 1381 4143 2764 1381 4144 2762 1381 4145 2765 1382 4146 2766 1382 4147 2764 1382 4148 2767 1383 4149 2768 1383 4150 2766 1383 4151 2769 1384 4152 2770 1384 4153 2768 1384 4154 2771 1385 4155 2772 1385 4156 2770 1385 4157 2773 1386 4158 2774 1386 4159 2772 1386 4160 2775 1387 4161 2776 1387 4162 2774 1387 4163 2777 1388 4164 2778 1388 4165 2776 1388 4166 2779 1389 4167 2780 1389 4168 2778 1389 4169 2781 1390 4170 2782 1390 4171 2780 1390 4172 2783 1391 4173 2784 1391 4174 2782 1391 4175 2785 1392 4176 2786 1392 4177 2784 1392 4178 2787 1393 4179 2788 1393 4180 2786 1393 4181 2789 1394 4182 2790 1394 4183 2788 1394 4184 2791 1395 4185 2792 1395 4186 2790 1395 4187 2793 1396 4188 2794 1396 4189 2792 1396 4190 2795 1397 4191 2796 1397 4192 2794 1397 4193 2797 1398 4194 2798 1398 4195 2796 1398 4196 2799 1399 4197 2800 1399 4198 2798 1399 4199 2801 1400 4200 2802 1400 4201 2800 1400 4202 2803 1401 4203 2804 1401 4204 2802 1401 4205 2805 1402 4206 2806 1402 4207 2804 1402 4208 2807 1403 4209 2808 1403 4210 2806 1403 4211 2809 1404 4212 2810 1404 4213 2808 1404 4214 2811 1405 4215 2812 1405 4216 2810 1405 4217 2813 1406 4218 2814 1406 4219 2812 1406 4220 2815 1407 4221 2816 1407 4222 2814 1407 4223 2817 1408 4224 2818 1408 4225 2816 1408 4226 2819 1409 4227 2820 1409 4228 2818 1409 4229 2821 1410 4230 2822 1410 4231 2820 1410 4232 2823 1411 4233 2824 1411 4234 2822 1411 4235 2825 1412 4236 2826 1412 4237 2824 1412 4238 2827 1413 4239 2828 1413 4240 2826 1413 4241 2829 1414 4242 2830 1414 4243 2828 1414 4244 2831 1415 4245 2832 1415 4246 2830 1415 4247 2833 1416 4248 2834 1416 4249 2832 1416 4250 2835 1417 4251 2836 1417 4252 2834 1417 4253 2837 1418 4254 2838 1418 4255 2836 1418 4256 2839 1419 4257 2840 1419 4258 2838 1419 4259 2841 1420 4260 2842 1420 4261 2840 1420 4262 2843 1421 4263 2844 1421 4264 2842 1421 4265 2845 1422 4266 2846 1422 4267 2844 1422 4268 2847 1423 4269 2848 1423 4270 2846 1423 4271 2849 1424 4272 2850 1424 4273 2848 1424 4274 2851 1425 4275 2852 1425 4276 2850 1425 4277 2853 1426 4278 2854 1426 4279 2852 1426 4280 2855 1427 4281 2856 1427 4282 2854 1427 4283 2857 1428 4284 2858 1428 4285 2856 1428 4286 2859 1429 4287 2860 1429 4288 2858 1429 4289 2861 1430 4290 2862 1430 4291 2860 1430 4292 2863 1431 4293 2864 1431 4294 2862 1431 4295 2865 1432 4296 2866 1432 4297 2864 1432 4298 2867 1433 4299 2868 1433 4300 2866 1433 4301 2869 1434 4302 2870 1434 4303 2868 1434 4304 2871 1435 4305 2872 1435 4306 2870 1435 4307 2873 1436 4308 2874 1436 4309 2872 1436 4310 2875 1437 4311 2876 1437 4312 2874 1437 4313 2877 1438 4314 2878 1438 4315 2876 1438 4316 2879 1439 4317 2880 1439 4318 2878 1439 4319 2881 1440 4320 2882 1440 4321 2880 1440 4322 2883 1441 4323 2884 1441 4324 2882 1441 4325 2885 1442 4326 2886 1442 4327 2884 1442 4328 2887 1443 4329 2888 1443 4330 2886 1443 4331 2889 1444 4332 2890 1444 4333 2888 1444 4334 2891 1445 4335 2892 1445 4336 2890 1445 4337 2893 1446 4338 2894 1446 4339 2892 1446 4340 2895 1447 4341 2896 1447 4342 2894 1447 4343 2897 1448 4344 2898 1448 4345 2896 1448 4346 2899 1449 4347 2900 1449 4348 2898 1449 4349 2901 1450 4350 2902 1450 4351 2900 1450 4352 2903 1451 4353 2904 1451 4354 2902 1451 4355 2905 1452 4356 2906 1452 4357 2904 1452 4358 2907 1453 4359 2908 1453 4360 2906 1453 4361 2909 1454 4362 2910 1454 4363 2908 1454 4364 2911 1455 4365 2912 1455 4366 2910 1455 4367 2913 1456 4368 2914 1456 4369 2912 1456 4370 2915 1457 4371 2916 1457 4372 2914 1457 4373 2917 1458 4374 2918 1458 4375 2916 1458 4376 2919 1459 4377 2920 1459 4378 2918 1459 4379 2921 1460 4380 2922 1460 4381 2920 1460 4382 2923 1461 4383 2924 1461 4384 2922 1461 4385 2925 1462 4386 2926 1462 4387 2924 1462 4388 2927 1463 4389 2928 1463 4390 2926 1463 4391 2929 1464 4392 2930 1464 4393 2928 1464 4394 2931 1465 4395 2932 1465 4396 2930 1465 4397 2933 1466 4398 2934 1466 4399 2932 1466 4400 2935 1467 4401 2936 1467 4402 2934 1467 4403 2937 1468 4404 2938 1468 4405 2936 1468 4406 2939 1469 4407 2940 1469 4408 2938 1469 4409 2941 1470 4410 2942 1470 4411 2940 1470 4412 2943 1471 4413 2944 1471 4414 2942 1471 4415 2945 1472 4416 2946 1472 4417 2944 1472 4418 2947 1473 4419 2948 1473 4420 2946 1473 4421 2949 1474 4422 2950 1474 4423 2948 1474 4424 2951 1475 4425 2952 1475 4426 2950 1475 4427 2953 1476 4428 2954 1476 4429 2952 1476 4430 2955 1477 4431 2956 1477 4432 2954 1477 4433 2957 1478 4434 2958 1478 4435 2956 1478 4436 2959 1479 4437 2960 1479 4438 2958 1479 4439 2961 1480 4440 2962 1480 4441 2960 1480 4442 2963 1481 4443 2964 1481 4444 2962 1481 4445 2965 1482 4446 2966 1482 4447 2964 1482 4448 2967 1483 4449 2968 1483 4450 2966 1483 4451 2969 1484 4452 2970 1484 4453 2968 1484 4454 2971 1485 4455 2972 1485 4456 2970 1485 4457 2973 1486 4458 2974 1486 4459 2972 1486 4460 2975 1487 4461 2976 1487 4462 2974 1487 4463 2977 1488 4464 2978 1488 4465 2976 1488 4466 2979 1489 4467 2980 1489 4468 2978 1489 4469 2981 1490 4470 2982 1490 4471 2980 1490 4472 2983 1491 4473 2984 1491 4474 2982 1491 4475 2985 1492 4476 2986 1492 4477 2984 1492 4478 2987 1493 4479 2988 1493 4480 2986 1493 4481 2989 1494 4482 2990 1494 4483 2988 1494 4484 2991 1495 4485 2992 1495 4486 2990 1495 4487 2993 1496 4488 2994 1496 4489 2992 1496 4490 2995 1497 4491 2996 1497 4492 2994 1497 4493 2997 1498 4494 2998 1498 4495 2996 1498 4496 2999 1499 4497 3000 1499 4498 2998 1499 4499 3001 1500 4500 3002 1500 4501 3000 1500 4502 3003 1501 4503 3004 1501 4504 3002 1501 4505 3005 1502 4506 3006 1502 4507 3004 1502 4508 3007 1503 4509 3008 1503 4510 3006 1503 4511 3009 1504 4512 3010 1504 4513 3008 1504 4514 3011 1505 4515 3012 1505 4516 3010 1505 4517 3013 1506 4518 3014 1506 4519 3012 1506 4520 3015 1507 4521 3016 1507 4522 3014 1507 4523 3017 1508 4524 3018 1508 4525 3016 1508 4526 3019 1509 4527 3020 1509 4528 3018 1509 4529 3021 1510 4530 3022 1510 4531 3020 1510 4532 3023 1511 4533 3024 1511 4534 3022 1511 4535 3025 1512 4536 3026 1512 4537 3024 1512 4538 3027 1513 4539 3028 1513 4540 3026 1513 4541 3029 1514 4542 3030 1514 4543 3028 1514 4544 3031 1515 4545 3032 1515 4546 3030 1515 4547 3033 1516 4548 3034 1516 4549 3032 1516 4550 3035 1517 4551 3036 1517 4552 3034 1517 4553 3037 1518 4554 3038 1518 4555 3036 1518 4556 3039 1519 4557 3040 1519 4558 3038 1519 4559 3041 1520 4560 3042 1520 4561 3040 1520 4562 3043 1521 4563 3044 1521 4564 3042 1521 4565 3045 1522 4566 3046 1522 4567 3044 1522 4568 3047 1523 4569 3048 1523 4570 3046 1523 4571 3049 1524 4572 3050 1524 4573 3048 1524 4574 3051 1525 4575 3052 1525 4576 3050 1525 4577 3053 1526 4578 3054 1526 4579 3052 1526 4580 3055 1527 4581 3056 1527 4582 3054 1527 4583 3057 1528 4584 3058 1528 4585 3056 1528 4586 3059 1529 4587 3060 1529 4588 3058 1529 4589 3061 1530 4590 3062 1530 4591 3060 1530 4592 3063 1531 4593 3064 1531 4594 3062 1531 4595 3065 1532 4596 3066 1532 4597 3064 1532 4598 3067 1533 4599 3068 1533 4600 3066 1533 4601 3069 1534 4602 3070 1534 4603 3068 1534 4604 3071 1535 4605 3072 1535 4606 3070 1535 4607 3073 1536 4608 3074 1536 4609 3072 1536 4610 3075 1537 4611 3076 1537 4612 3074 1537 4613 3077 1538 4614 3078 1538 4615 3076 1538 4616 3079 1539 4617 3080 1539 4618 3078 1539 4619 3081 1540 4620 3082 1540 4621 3080 1540 4622 3083 1541 4623 3084 1541 4624 3082 1541 4625 3085 1542 4626 3086 1542 4627 3084 1542 4628 3087 1543 4629 3088 1543 4630 3086 1543 4631 3089 1544 4632 3090 1544 4633 3088 1544 4634 3091 1545 4635 3092 1545 4636 3090 1545 4637 3093 1546 4638 3094 1546 4639 3092 1546 4640 3095 1547 4641 3096 1547 4642 3094 1547 4643 3097 1548 4644 3098 1548 4645 3096 1548 4646 3099 1549 4647 3100 1549 4648 3098 1549 4649 3101 1550 4650 3102 1550 4651 3100 1550 4652 3103 1551 4653 3104 1551 4654 3102 1551 4655 3105 1552 4656 3106 1552 4657 3104 1552 4658 3107 1553 4659 3108 1553 4660 3106 1553 4661 3109 1554 4662 3110 1554 4663 3108 1554 4664 3111 1555 4665 3112 1555 4666 3110 1555 4667 3113 1556 4668 3114 1556 4669 3112 1556 4670 3115 1557 4671 3116 1557 4672 3114 1557 4673 3117 1558 4674 3118 1558 4675 3116 1558 4676 3119 1559 4677 3120 1559 4678 3118 1559 4679 3121 1560 4680 3122 1560 4681 3120 1560 4682 3123 1561 4683 3124 1561 4684 3122 1561 4685 3125 1562 4686 3126 1562 4687 3124 1562 4688 3127 1563 4689 3128 1563 4690 3126 1563 4691 3129 1564 4692 3130 1564 4693 3128 1564 4694 3131 1565 4695 3132 1565 4696 3130 1565 4697 3133 1566 4698 3134 1566 4699 3132 1566 4700 3135 1567 4701 3136 1567 4702 3134 1567 4703 3137 1568 4704 3138 1568 4705 3136 1568 4706 3139 1569 4707 3140 1569 4708 3138 1569 4709 3141 1570 4710 3142 1570 4711 3140 1570 4712 3143 1571 4713 3144 1571 4714 3142 1571 4715 3145 1572 4716 3146 1572 4717 3144 1572 4718 3147 1573 4719 3148 1573 4720 3146 1573 4721 3149 1574 4722 3150 1574 4723 3148 1574 4724 3151 1575 4725 3152 1575 4726 3150 1575 4727 3153 1576 4728 3154 1576 4729 3152 1576 4730 3155 1577 4731 3156 1577 4732 3154 1577 4733 3157 1578 4734 3158 1578 4735 3156 1578 4736 3159 1579 4737 3160 1579 4738 3158 1579 4739 3161 1580 4740 3162 1580 4741 3160 1580 4742 3163 1581 4743 3164 1581 4744 3162 1581 4745 3165 1582 4746 3166 1582 4747 3164 1582 4748 3167 1583 4749 3168 1583 4750 3166 1583 4751 3169 1584 4752 3170 1584 4753 3168 1584 4754 3171 1585 4755 3172 1585 4756 3170 1585 4757 3173 1586 4758 3174 1586 4759 3172 1586 4760 3175 1587 4761 3176 1587 4762 3174 1587 4763 3177 1588 4764 3178 1588 4765 3176 1588 4766 3179 1589 4767 3180 1589 4768 3178 1589 4769 3181 1590 4770 3182 1590 4771 3180 1590 4772 3183 1591 4773 3184 1591 4774 3182 1591 4775 3185 1592 4776 3186 1592 4777 3184 1592 4778 3187 1593 4779 3188 1593 4780 3186 1593 4781 3189 1594 4782 3190 1594 4783 3188 1594 4784 3191 1595 4785 3192 1595 4786 3190 1595 4787 3193 1596 4788 3194 1596 4789 3192 1596 4790 3195 1597 4791 3196 1597 4792 3194 1597 4793 3197 1598 4794 3198 1598 4795 3196 1598 4796 3199 1599 4797 3200 1599 4798 3198 1599 4799 3201 1600 4800 3202 1600 4801 3200 1600 4802 3203 1601 4803 3204 1601 4804 3202 1601 4805 3205 1602 4806 3206 1602 4807 3204 1602 4808 3207 1603 4809 3208 1603 4810 3206 1603 4811 3209 1604 4812 3210 1604 4813 3208 1604 4814 3211 1605 4815 3212 1605 4816 3210 1605 4817 3213 1606 4818 3214 1606 4819 3212 1606 4820 3215 1607 4821 3216 1607 4822 3214 1607 4823 3217 1608 4824 3218 1608 4825 3216 1608 4826 3219 1609 4827 3220 1609 4828 3218 1609 4829 3221 1610 4830 3222 1610 4831 3220 1610 4832 3223 1611 4833 3224 1611 4834 3222 1611 4835 3225 1612 4836 3226 1612 4837 3224 1612 4838 3227 1613 4839 3228 1613 4840 3226 1613 4841 3229 1614 4842 3230 1614 4843 3228 1614 4844 3231 1615 4845 3232 1615 4846 3230 1615 4847 3233 1616 4848 3234 1616 4849 3232 1616 4850 3235 1617 4851 3236 1617 4852 3234 1617 4853 3237 1618 4854 3238 1618 4855 3236 1618 4856 3239 1619 4857 3240 1619 4858 3238 1619 4859 3241 1620 4860 3242 1620 4861 3240 1620 4862 3243 1621 4863 3244 1621 4864 3242 1621 4865 3245 1622 4866 3246 1622 4867 3244 1622 4868 3247 1623 4869 3248 1623 4870 3246 1623 4871 3249 1624 4872 3250 1624 4873 3248 1624 4874 3251 1625 4875 3252 1625 4876 3250 1625 4877 3253 1626 4878 3254 1626 4879 3252 1626 4880 3255 1627 4881 3256 1627 4882 3254 1627 4883 3257 1628 4884 3258 1628 4885 3256 1628 4886 3259 1629 4887 3260 1629 4888 3258 1629 4889 3261 1630 4890 3262 1630 4891 3260 1630 4892 3263 1631 4893 3264 1631 4894 3262 1631 4895 3265 1632 4896 3266 1632 4897 3264 1632 4898 3267 1633 4899 3268 1633 4900 3266 1633 4901 3269 1634 4902 3270 1634 4903 3268 1634 4904 3271 1635 4905 3272 1635 4906 3270 1635 4907 3273 1636 4908 3274 1636 4909 3272 1636 4910 3275 1637 4911 3276 1637 4912 3274 1637 4913 3277 1638 4914 3278 1638 4915 3276 1638 4916 3279 1639 4917 3280 1639 4918 3278 1639 4919 3281 1640 4920 3282 1640 4921 3280 1640 4922 3283 1641 4923 3284 1641 4924 3282 1641 4925 3285 1642 4926 3286 1642 4927 3284 1642 4928 3287 1643 4929 3288 1643 4930 3286 1643 4931 3289 1644 4932 3290 1644 4933 3288 1644 4934 3291 1645 4935 3292 1645 4936 3290 1645 4937 3293 1646 4938 3294 1646 4939 3292 1646 4940 3295 1647 4941 3296 1647 4942 3294 1647 4943 3297 1648 4944 3298 1648 4945 3296 1648 4946 3299 1649 4947 3300 1649 4948 3298 1649 4949 3301 1650 4950 3302 1650 4951 3300 1650 4952 3303 1651 4953 3304 1651 4954 3302 1651 4955 3305 1652 4956 3306 1652 4957 3304 1652 4958 3307 1653 4959 3308 1653 4960 3306 1653 4961 3309 1654 4962 3310 1654 4963 3308 1654 4964 3311 1655 4965 3312 1655 4966 3310 1655 4967 3313 1656 4968 3314 1656 4969 3312 1656 4970 3315 1657 4971 3316 1657 4972 3314 1657 4973 3317 1658 4974 3318 1658 4975 3316 1658 4976 3319 1659 4977 3320 1659 4978 3318 1659 4979 3321 1660 4980 3322 1660 4981 3320 1660 4982 3323 1661 4983 3324 1661 4984 3322 1661 4985 3325 1662 4986 3326 1662 4987 3324 1662 4988 3327 1663 4989 3328 1663 4990 3326 1663 4991 3329 1664 4992 3330 1664 4993 3328 1664 4994 3331 1665 4995 3332 1665 4996 3330 1665 4997 3333 1666 4998 3334 1666 4999 3332 1666 5000 3335 1667 5001 3336 1667 5002 3334 1667 5003 3337 1668 5004 3338 1668 5005 3336 1668 5006 3339 1669 5007 3340 1669 5008 3338 1669 5009 3341 1670 5010 3342 1670 5011 3340 1670 5012 3343 1671 5013 3344 1671 5014 3342 1671 5015 3345 1672 5016 3346 1672 5017 3344 1672 5018 3347 1673 5019 3348 1673 5020 3346 1673 5021 3349 1674 5022 3350 1674 5023 3348 1674 5024 3351 1675 5025 3352 1675 5026 3350 1675 5027 3353 1676 5028 3354 1676 5029 3352 1676 5030 3355 1677 5031 3356 1677 5032 3354 1677 5033 3357 1678 5034 3358 1678 5035 3356 1678 5036 3359 1679 5037 3360 1679 5038 3358 1679 5039 3361 1680 5040 3362 1680 5041 3360 1680 5042 3363 1681 5043 3364 1681 5044 3362 1681 5045 3365 1682 5046 3366 1682 5047 3364 1682 5048 3367 1683 5049 3368 1683 5050 3366 1683 5051 3369 1684 5052 3370 1684 5053 3368 1684 5054 3371 1685 5055 3372 1685 5056 3370 1685 5057 3373 1686 5058 3374 1686 5059 3372 1686 5060 3375 1687 5061 3376 1687 5062 3374 1687 5063 3377 1688 5064 3378 1688 5065 3376 1688 5066 3379 1689 5067 3380 1689 5068 3378 1689 5069 3381 1690 5070 3382 1690 5071 3380 1690 5072 3383 1691 5073 3384 1691 5074 3382 1691 5075 3385 1692 5076 3386 1692 5077 3384 1692 5078 3387 1693 5079 3388 1693 5080 3386 1693 5081 3389 1694 5082 3390 1694 5083 3388 1694 5084 3391 1695 5085 3392 1695 5086 3390 1695 5087 3393 1696 5088 3394 1696 5089 3392 1696 5090 3395 1697 5091 3396 1697 5092 3394 1697 5093 3397 1698 5094 3398 1698 5095 3396 1698 5096 3399 1699 5097 3400 1699 5098 3398 1699 5099 3401 1700 5100 3402 1700 5101 3400 1700 5102 3403 1701 5103 3404 1701 5104 3402 1701 5105 3405 1702 5106 3406 1702 5107 3404 1702 5108 3407 1703 5109 3408 1703 5110 3406 1703 5111 3409 1704 5112 3410 1704 5113 3408 1704 5114 3411 1705 5115 3412 1705 5116 3410 1705 5117 3413 1706 5118 3414 1706 5119 3412 1706 5120 3415 1707 5121 3416 1707 5122 3414 1707 5123 3417 1708 5124 3418 1708 5125 3416 1708 5126 3419 1709 5127 3420 1709 5128 3418 1709 5129 3421 1710 5130 3422 1710 5131 3420 1710 5132 3423 1711 5133 3424 1711 5134 3422 1711 5135 3425 1712 5136 3426 1712 5137 3424 1712 5138 3427 1713 5139 3428 1713 5140 3426 1713 5141 3429 1714 5142 3430 1714 5143 3428 1714 5144 3431 1715 5145 3432 1715 5146 3430 1715 5147 3433 1716 5148 3434 1716 5149 3432 1716 5150 3435 1717 5151 3436 1717 5152 3434 1717 5153 3437 1718 5154 3438 1718 5155 3436 1718 5156 3439 1719 5157 3440 1719 5158 3438 1719 5159 3441 1720 5160 3442 1720 5161 3440 1720 5162 3443 1721 5163 3444 1721 5164 3442 1721 5165 3445 1722 5166 3446 1722 5167 3444 1722 5168 3447 1723 5169 3448 1723 5170 3446 1723 5171 3449 1724 5172 3450 1724 5173 3448 1724 5174 3451 1725 5175 3452 1725 5176 3450 1725 5177 3453 1726 5178 3454 1726 5179 3452 1726 5180 3455 1727 5181 3456 1727 5182 3454 1727 5183 3457 1728 5184 3458 1728 5185 3456 1728 5186 3459 1729 5187 3460 1729 5188 3458 1729 5189 3461 1730 5190 3462 1730 5191 3460 1730 5192 3463 1731 5193 3464 1731 5194 3462 1731 5195 3465 1732 5196 3466 1732 5197 3464 1732 5198 3467 1733 5199 3468 1733 5200 3466 1733 5201 3469 1734 5202 3470 1734 5203 3468 1734 5204 3471 1735 5205 3472 1735 5206 3470 1735 5207 3473 1736 5208 3474 1736 5209 3472 1736 5210 3475 1737 5211 3476 1737 5212 3474 1737 5213 3477 1738 5214 3478 1738 5215 3476 1738 5216 3479 1739 5217 3480 1739 5218 3478 1739 5219 3481 1740 5220 3482 1740 5221 3480 1740 5222 3483 1741 5223 3484 1741 5224 3482 1741 5225 3485 1742 5226 3486 1742 5227 3484 1742 5228 3487 1743 5229 3488 1743 5230 3486 1743 5231 3489 1744 5232 3490 1744 5233 3488 1744 5234 3491 1745 5235 3492 1745 5236 3490 1745 5237 3493 1746 5238 3494 1746 5239 3492 1746 5240 3495 1747 5241 3496 1747 5242 3494 1747 5243 3497 1748 5244 3498 1748 5245 3496 1748 5246 3499 1749 5247 3500 1749 5248 3498 1749 5249 3501 1750 5250 3502 1750 5251 3500 1750 5252 3503 1751 5253 3504 1751 5254 3502 1751 5255 3505 1752 5256 3506 1752 5257 3504 1752 5258 3507 1753 5259 3508 1753 5260 3506 1753 5261 3509 1754 5262 3510 1754 5263 3508 1754 5264 3511 1755 5265 3512 1755 5266 3510 1755 5267 3513 1756 5268 3514 1756 5269 3512 1756 5270 3515 1757 5271 3516 1757 5272 3514 1757 5273 3517 1758 5274 3518 1758 5275 3516 1758 5276 3519 1759 5277 3520 1759 5278 3518 1759 5279 3521 1760 5280 3522 1760 5281 3520 1760 5282 3523 1761 5283 3524 1761 5284 3522 1761 5285 3525 1762 5286 3526 1762 5287 3524 1762 5288 3527 1763 5289 3528 1763 5290 3526 1763 5291 3529 1764 5292 3530 1764 5293 3528 1764 5294 3531 1765 5295 3532 1765 5296 3530 1765 5297 3533 1766 5298 3534 1766 5299 3532 1766 5300 3535 1767 5301 3536 1767 5302 3534 1767 5303 3537 1768 5304 3538 1768 5305 3536 1768 5306 3539 1769 5307 3540 1769 5308 3538 1769 5309 3541 1770 5310 3542 1770 5311 3540 1770 5312 3543 1771 5313 3544 1771 5314 3542 1771 5315 3545 1772 5316 3546 1772 5317 3544 1772 5318 3547 1773 5319 3548 1773 5320 3546 1773 5321 3549 1774 5322 3550 1774 5323 3548 1774 5324 3551 1775 5325 3552 1775 5326 3550 1775 5327 3553 1776 5328 3554 1776 5329 3552 1776 5330 3555 1777 5331 3556 1777 5332 3554 1777 5333 3557 1778 5334 3558 1778 5335 3556 1778 5336 3559 1779 5337 3560 1779 5338 3558 1779 5339 3561 1780 5340 3562 1780 5341 3560 1780 5342 3563 1781 5343 3564 1781 5344 3562 1781 5345 3565 1782 5346 3566 1782 5347 3564 1782 5348 3567 1783 5349 3568 1783 5350 3566 1783 5351 3569 1784 5352 3570 1784 5353 3568 1784 5354 3571 1785 5355 3572 1785 5356 3570 1785 5357 3573 1786 5358 3574 1786 5359 3572 1786 5360 3575 1787 5361 3576 1787 5362 3574 1787 5363 3577 1788 5364 3578 1788 5365 3576 1788 5366 3579 1789 5367 3580 1789 5368 3578 1789 5369 3581 1790 5370 3582 1790 5371 3580 1790 5372 3583 1791 5373 3584 1791 5374 3582 1791 5375 3585 1792 5376 3586 1792 5377 3584 1792 5378 3587 1793 5379 3588 1793 5380 3586 1793 5381 3589 1794 5382 3590 1794 5383 3588 1794 5384 3591 1795 5385 3592 1795 5386 3590 1795 5387 3593 1796 5388 3594 1796 5389 3592 1796 5390 3595 1797 5391 3596 1797 5392 3594 1797 5393 3597 1798 5394 3598 1798 5395 3596 1798 5396 3599 1799 5397 3600 1799 5398 3598 1799 5399 3601 1800 5400 3602 1800 5401 3600 1800 5402 3603 1801 5403 3604 1801 5404 3602 1801 5405 3605 1802 5406 3606 1802 5407 3604 1802 5408 3607 1803 5409 3608 1803 5410 3606 1803 5411 3609 1804 5412 3610 1804 5413 3608 1804 5414 3611 1805 5415 3612 1805 5416 3610 1805 5417 3613 1806 5418 3614 1806 5419 3612 1806 5420 3615 1807 5421 3616 1807 5422 3614 1807 5423 3617 1808 5424 3618 1808 5425 3616 1808 5426 3619 1809 5427 3620 1809 5428 3618 1809 5429 3621 1810 5430 3622 1810 5431 3620 1810 5432 3623 1811 5433 3624 1811 5434 3622 1811 5435 3625 1812 5436 3626 1812 5437 3624 1812 5438 3627 1813 5439 3628 1813 5440 3626 1813 5441 3629 1814 5442 3630 1814 5443 3628 1814 5444 3631 1815 5445 3632 1815 5446 3630 1815 5447 3633 1816 5448 3634 1816 5449 3632 1816 5450 3635 1817 5451 3636 1817 5452 3634 1817 5453 3637 1818 5454 3638 1818 5455 3636 1818 5456 3639 1819 5457 3640 1819 5458 3638 1819 5459 3641 1820 5460 3642 1820 5461 3640 1820 5462 3643 1821 5463 3644 1821 5464 3642 1821 5465 3645 1822 5466 3646 1822 5467 3644 1822 5468 3647 1823 5469 3648 1823 5470 3646 1823 5471 3649 1824 5472 3650 1824 5473 3648 1824 5474 3651 1825 5475 3652 1825 5476 3650 1825 5477 3653 1826 5478 3654 1826 5479 3652 1826 5480 3655 1827 5481 3656 1827 5482 3654 1827 5483 3657 1828 5484 3658 1828 5485 3656 1828 5486 3659 1829 5487 3660 1829 5488 3658 1829 5489 3661 1830 5490 3662 1830 5491 3660 1830 5492 3663 1831 5493 3664 1831 5494 3662 1831 5495 3665 1832 5496 3666 1832 5497 3664 1832 5498 3667 1833 5499 3668 1833 5500 3666 1833 5501 3669 1834 5502 3670 1834 5503 3668 1834 5504 3671 1835 5505 3672 1835 5506 3670 1835 5507 3673 1836 5508 3674 1836 5509 3672 1836 5510 3675 1837 5511 3676 1837 5512 3674 1837 5513 3677 1838 5514 3678 1838 5515 3676 1838 5516 3679 1839 5517 3680 1839 5518 3678 1839 5519 3681 1840 5520 3682 1840 5521 3680 1840 5522 3683 1841 5523 3684 1841 5524 3682 1841 5525 3685 1842 5526 3686 1842 5527 3684 1842 5528 3687 1843 5529 3688 1843 5530 3686 1843 5531 3689 1844 5532 3690 1844 5533 3688 1844 5534 3691 1845 5535 3692 1845 5536 3690 1845 5537 3693 1846 5538 3694 1846 5539 3692 1846 5540 3695 1847 5541 3696 1847 5542 3694 1847 5543 3697 1848 5544 3698 1848 5545 3696 1848 5546 3699 1849 5547 3700 1849 5548 3698 1849 5549 3701 1850 5550 3702 1850 5551 3700 1850 5552 3703 1851 5553 3704 1851 5554 3702 1851 5555 3705 1852 5556 3706 1852 5557 3704 1852 5558 3707 1853 5559 3708 1853 5560 3706 1853 5561 3709 1854 5562 3710 1854 5563 3708 1854 5564 3711 1855 5565 3712 1855 5566 3710 1855 5567 3713 1856 5568 3714 1856 5569 3712 1856 5570 3715 1857 5571 3716 1857 5572 3714 1857 5573 3717 1858 5574 3718 1858 5575 3716 1858 5576 3719 1859 5577 3720 1859 5578 3718 1859 5579 3721 1860 5580 3722 1860 5581 3720 1860 5582 3723 1861 5583 3724 1861 5584 3722 1861 5585 3725 1862 5586 3726 1862 5587 3724 1862 5588 3727 1863 5589 3728 1863 5590 3726 1863 5591 3729 1864 5592 3730 1864 5593 3728 1864 5594 3731 1865 5595 3732 1865 5596 3730 1865 5597 3733 1866 5598 3734 1866 5599 3732 1866 5600 3735 1867 5601 3736 1867 5602 3734 1867 5603 3737 1868 5604 3738 1868 5605 3736 1868 5606 3739 1869 5607 3740 1869 5608 3738 1869 5609 3741 1870 5610 3742 1870 5611 3740 1870 5612 3743 1871 5613 3744 1871 5614 3742 1871 5615 3745 1872 5616 3746 1872 5617 3744 1872 5618 3747 1873 5619 3748 1873 5620 3746 1873 5621 3749 1874 5622 3750 1874 5623 3748 1874 5624 3751 1875 5625 3752 1875 5626 3750 1875 5627 3753 1876 5628 3754 1876 5629 3752 1876 5630 3755 1877 5631 3756 1877 5632 3754 1877 5633 3757 1878 5634 3758 1878 5635 3756 1878 5636 3759 1879 5637 3760 1879 5638 3758 1879 5639 3761 1880 5640 3762 1880 5641 3760 1880 5642 3763 1881 5643 3764 1881 5644 3762 1881 5645 3765 1882 5646 3766 1882 5647 3764 1882 5648 3767 1883 5649 3768 1883 5650 3766 1883 5651 3769 1884 5652 3770 1884 5653 3768 1884 5654 3771 1885 5655 3772 1885 5656 3770 1885 5657 3773 1886 5658 3774 1886 5659 3772 1886 5660 3775 1887 5661 3776 1887 5662 3774 1887 5663 3777 1888 5664 3778 1888 5665 3776 1888 5666 3779 1889 5667 3780 1889 5668 3778 1889 5669 3781 1890 5670 3782 1890 5671 3780 1890 5672 3783 1891 5673 3784 1891 5674 3782 1891 5675 3785 1892 5676 3786 1892 5677 3784 1892 5678 3787 1893 5679 3788 1893 5680 3786 1893 5681 3789 1894 5682 3790 1894 5683 3788 1894 5684 3791 1895 5685 3792 1895 5686 3790 1895 5687 3793 1896 5688 3794 1896 5689 3792 1896 5690 3795 1897 5691 3796 1897 5692 3794 1897 5693 3797 1898 5694 3798 1898 5695 3796 1898 5696 3799 1899 5697 3800 1899 5698 3798 1899 5699 3801 1900 5700 3802 1900 5701 3800 1900 5702 3803 1901 5703 3804 1901 5704 3802 1901 5705 3805 1902 5706 3806 1902 5707 3804 1902 5708 3807 1903 5709 3808 1903 5710 3806 1903 5711 3809 1904 5712 3810 1904 5713 3808 1904 5714 3811 1905 5715 3812 1905 5716 3810 1905 5717 3813 1906 5718 3814 1906 5719 3812 1906 5720 3815 1907 5721 3816 1907 5722 3814 1907 5723 3817 1908 5724 3818 1908 5725 3816 1908 5726 3819 1909 5727 3820 1909 5728 3818 1909 5729 3821 1910 5730 3822 1910 5731 3820 1910 5732 3823 1911 5733 3824 1911 5734 3822 1911 5735 3825 1912 5736 3826 1912 5737 3824 1912 5738 3827 1913 5739 3828 1913 5740 3826 1913 5741 3829 1914 5742 3830 1914 5743 3828 1914 5744 3831 1915 5745 3832 1915 5746 3830 1915 5747 3833 1916 5748 3834 1916 5749 3832 1916 5750 3835 1917 5751 3836 1917 5752 3834 1917 5753 3837 1918 5754 3838 1918 5755 3836 1918 5756 3839 1919 5757 3840 1919 5758 3838 1919 5759 3841 1920 5760 3842 1920 5761 3840 1920 5762 3843 1921 5763 3844 1921 5764 3842 1921 5765 3845 1922 5766 3846 1922 5767 3844 1922 5768 3847 1923 5769 3848 1923 5770 3846 1923 5771 3849 1924 5772 3850 1924 5773 3848 1924 5774 3851 1925 5775 3852 1925 5776 3850 1925 5777 3853 1926 5778 3854 1926 5779 3852 1926 5780 3855 1927 5781 3856 1927 5782 3854 1927 5783 3857 1928 5784 3858 1928 5785 3856 1928 5786 3859 1929 5787 3860 1929 5788 3858 1929 5789 3861 1930 5790 3862 1930 5791 3860 1930 5792 3863 1931 5793 3864 1931 5794 3862 1931 5795 3865 1932 5796 3866 1932 5797 3864 1932 5798 3867 1933 5799 3868 1933 5800 3866 1933 5801 3869 1934 5802 3870 1934 5803 3868 1934 5804 3871 1935 5805 3872 1935 5806 3870 1935 5807 3873 1936 5808 3874 1936 5809 3872 1936 5810 3875 1937 5811 3876 1937 5812 3874 1937 5813 3877 1938 5814 3878 1938 5815 3876 1938 5816 3879 1939 5817 3880 1939 5818 3878 1939 5819 3881 1940 5820 3882 1940 5821 3880 1940 5822 3883 1941 5823 3884 1941 5824 3882 1941 5825 3885 1942 5826 3886 1942 5827 3884 1942 5828 3887 1943 5829 3888 1943 5830 3886 1943 5831 3889 1944 5832 3890 1944 5833 3888 1944 5834 3891 1945 5835 3892 1945 5836 3890 1945 5837 3893 1946 5838 3894 1946 5839 3892 1946 5840 3895 1947 5841 3896 1947 5842 3894 1947 5843 3897 1948 5844 3898 1948 5845 3896 1948 5846 3899 1949 5847 3900 1949 5848 3898 1949 5849 3901 1950 5850 3902 1950 5851 3900 1950 5852 3903 1951 5853 3904 1951 5854 3902 1951 5855 3905 1952 5856 3906 1952 5857 3904 1952 5858 3907 1953 5859 3908 1953 5860 3906 1953 5861 3909 1954 5862 3910 1954 5863 3908 1954 5864 3911 1955 5865 3912 1955 5866 3910 1955 5867 3913 1956 5868 3914 1956 5869 3912 1956 5870 3915 1957 5871 3916 1957 5872 3914 1957 5873 3917 1958 5874 3918 1958 5875 3916 1958 5876 3919 1959 5877 3920 1959 5878 3918 1959 5879 3921 1960 5880 3922 1960 5881 3920 1960 5882 3923 1961 5883 3924 1961 5884 3922 1961 5885 3925 1962 5886 3926 1962 5887 3924 1962 5888 3927 1963 5889 3928 1963 5890 3926 1963 5891 3929 1964 5892 3930 1964 5893 3928 1964 5894 3931 1965 5895 3932 1965 5896 3930 1965 5897 3933 1966 5898 3934 1966 5899 3932 1966 5900 3935 1967 5901 3936 1967 5902 3934 1967 5903 3937 1968 5904 3938 1968 5905 3936 1968 5906 3939 1969 5907 3940 1969 5908 3938 1969 5909 3941 1970 5910 3942 1970 5911 3940 1970 5912 3943 1971 5913 3944 1971 5914 3942 1971 5915 3945 1972 5916 3946 1972 5917 3944 1972 5918 3947 1973 5919 3948 1973 5920 3946 1973 5921 3949 1974 5922 3950 1974 5923 3948 1974 5924 3951 1975 5925 3952 1975 5926 3950 1975 5927 3953 1976 5928 3954 1976 5929 3952 1976 5930 3955 1977 5931 3956 1977 5932 3954 1977 5933 3957 1978 5934 3958 1978 5935 3956 1978 5936 3959 1979 5937 3960 1979 5938 3958 1979 5939 3961 1980 5940 3962 1980 5941 3960 1980 5942 3963 1981 5943 3964 1981 5944 3962 1981 5945 3965 1982 5946 3966 1982 5947 3964 1982 5948 3967 1983 5949 3968 1983 5950 3966 1983 5951 3969 1984 5952 3970 1984 5953 3968 1984 5954 3971 1985 5955 3972 1985 5956 3970 1985 5957 3973 1986 5958 3974 1986 5959 3972 1986 5960 3975 1987 5961 3976 1987 5962 3974 1987 5963 3977 1988 5964 3978 1988 5965 3976 1988 5966 3979 1989 5967 3980 1989 5968 3978 1989 5969 3981 1990 5970 3982 1990 5971 3980 1990 5972 3983 1991 5973 3984 1991 5974 3982 1991 5975 3985 1992 5976 3986 1992 5977 3984 1992 5978 3987 1993 5979 3988 1993 5980 3986 1993 5981 3989 1994 5982 3990 1994 5983 3988 1994 5984 3991 1995 5985 3992 1995 5986 3990 1995 5987 3993 1996 5988 3994 1996 5989 3992 1996 5990 3995 1997 5991 3996 1997 5992 3994 1997 5993 3997 1998 5994 3998 1998 5995 3996 1998 5996 3999 1999 5997 4000 1999 5998 3998 1999 5999 4001 2000 6000 4002 2000 6001 4000 2000 6002 4003 2001 6003 4004 2001 6004 4002 2001 6005 4005 2002 6006 4006 2002 6007 4004 2002 6008 4007 2003 6009 4008 2003 6010 4006 2003 6011 4009 2004 6012 4010 2004 6013 4008 2004 6014 4011 2005 6015 4012 2005 6016 4010 2005 6017 4013 2006 6018 4014 2006 6019 4012 2006 6020 4015 2007 6021 4016 2007 6022 4014 2007 6023 4017 2008 6024 4018 2008 6025 4016 2008 6026 4019 2009 6027 4020 2009 6028 4018 2009 6029 4021 2010 6030 4022 2010 6031 4020 2010 6032 4023 2011 6033 4024 2011 6034 4022 2011 6035 4025 2012 6036 4026 2012 6037 4024 2012 6038 4027 2013 6039 4028 2013 6040 4026 2013 6041 4029 2014 6042 4030 2014 6043 4028 2014 6044 4031 2015 6045 4032 2015 6046 4030 2015 6047 4033 2016 6048 4034 2016 6049 4032 2016 6050 4035 2017 6051 4036 2017 6052 4034 2017 6053 4037 2018 6054 4038 2018 6055 4036 2018 6056 4039 2019 6057 4040 2019 6058 4038 2019 6059 4041 2020 6060 4042 2020 6061 4040 2020 6062 4043 2021 6063 4044 2021 6064 4042 2021 6065 4045 2022 6066 4046 2022 6067 4044 2022 6068 4047 2023 6069 4048 2023 6070 4046 2023 6071 4049 2024 6072 4050 2024 6073 4048 2024 6074 4051 2025 6075 4052 2025 6076 4050 2025 6077 4053 2026 6078 4054 2026 6079 4052 2026 6080 4055 2027 6081 4056 2027 6082 4054 2027 6083 4057 2028 6084 4058 2028 6085 4056 2028 6086 4059 2029 6087 4060 2029 6088 4058 2029 6089 4061 2030 6090 4062 2030 6091 4060 2030 6092 4063 2031 6093 4064 2031 6094 4062 2031 6095 4065 2032 6096 4066 2032 6097 4064 2032 6098 4067 2033 6099 4068 2033 6100 4066 2033 6101 4069 2034 6102 4070 2034 6103 4068 2034 6104 4071 2035 6105 4072 2035 6106 4070 2035 6107 4073 2036 6108 4074 2036 6109 4072 2036 6110 4075 2037 6111 4076 2037 6112 4074 2037 6113 4077 2038 6114 4078 2038 6115 4076 2038 6116 4079 2039 6117 4080 2039 6118 4078 2039 6119 4081 2040 6120 4082 2040 6121 4080 2040 6122 4083 2041 6123 4084 2041 6124 4082 2041 6125 4085 2042 6126 4086 2042 6127 4084 2042 6128 4087 2043 6129 4088 2043 6130 4086 2043 6131 4089 2044 6132 4090 2044 6133 4088 2044 6134 4091 2045 6135 4092 2045 6136 4090 2045 6137 4093 2046 6138 4094 2046 6139 4092 2046 6140 4095 2047 6141 4096 2047 6142 4094 2047 6143 4097 2048 6144 4098 2048 6145 4096 2048 6146 4099 2049 6147 4100 2049 6148 4098 2049 6149 4101 2050 6150 4102 2050 6151 4100 2050 6152 4103 2051 6153 4104 2051 6154 4102 2051 6155 4105 2052 6156 4106 2052 6157 4104 2052 6158 4107 2053 6159 4108 2053 6160 4106 2053 6161 4109 2054 6162 4110 2054 6163 4108 2054 6164 4111 2055 6165 4112 2055 6166 4110 2055 6167 4113 2056 6168 4114 2056 6169 4112 2056 6170 4115 2057 6171 4116 2057 6172 4114 2057 6173 4117 2058 6174 4118 2058 6175 4116 2058 6176 4119 2059 6177 4120 2059 6178 4118 2059 6179 4121 2060 6180 4122 2060 6181 4120 2060 6182 4123 2061 6183 4124 2061 6184 4122 2061 6185 4125 2062 6186 4126 2062 6187 4124 2062 6188 4127 2063 6189 4128 2063 6190 4126 2063 6191 4129 2064 6192 4130 2064 6193 4128 2064 6194 4131 2065 6195 4132 2065 6196 4130 2065 6197 4133 2066 6198 4134 2066 6199 4132 2066 6200 4135 2067 6201 4136 2067 6202 4134 2067 6203 4137 2068 6204 4138 2068 6205 4136 2068 6206 4139 2069 6207 4140 2069 6208 4138 2069 6209 4141 2070 6210 4142 2070 6211 4140 2070 6212 4143 2071 6213 4144 2071 6214 4142 2071 6215 4145 2072 6216 4146 2072 6217 4144 2072 6218 4147 2073 6219 4148 2073 6220 4146 2073 6221 4149 2074 6222 4150 2074 6223 4148 2074 6224 4151 2075 6225 4152 2075 6226 4150 2075 6227 4153 2076 6228 4154 2076 6229 4152 2076 6230 4155 2077 6231 4156 2077 6232 4154 2077 6233 4157 2078 6234 4158 2078 6235 4156 2078 6236 4159 2079 6237 4160 2079 6238 4158 2079 6239 4161 2080 6240 4162 2080 6241 4160 2080 6242 4163 2081 6243 4164 2081 6244 4162 2081 6245 4165 2082 6246 4166 2082 6247 4164 2082 6248 4167 2083 6249 4168 2083 6250 4166 2083 6251 4169 2084 6252 4170 2084 6253 4168 2084 6254 4171 2085 6255 4172 2085 6256 4170 2085 6257 4173 2086 6258 4174 2086 6259 4172 2086 6260 4175 2087 6261 4176 2087 6262 4174 2087 6263 4177 2088 6264 4178 2088 6265 4176 2088 6266 4179 2089 6267 4180 2089 6268 4178 2089 6269 4181 2090 6270 4182 2090 6271 4180 2090 6272 4183 2091 6273 4184 2091 6274 4182 2091 6275 4185 2092 6276 4186 2092 6277 4184 2092 6278 4187 2093 6279 4188 2093 6280 4186 2093 6281 4189 2094 6282 4190 2094 6283 4188 2094 6284 4191 2095 6285 4192 2095 6286 4190 2095 6287 4193 2096 6288 4194 2096 6289 4192 2096 6290 4195 2097 6291 4196 2097 6292 4194 2097 6293 4197 2098 6294 4198 2098 6295 4196 2098 6296 4199 2099 6297 4200 2099 6298 4198 2099 6299 4201 2100 6300 4202 2100 6301 4200 2100 6302 4203 2101 6303 4204 2101 6304 4202 2101 6305 4205 2102 6306 4206 2102 6307 4204 2102 6308 4207 2103 6309 4208 2103 6310 4206 2103 6311 4209 2104 6312 4210 2104 6313 4208 2104 6314 4211 2105 6315 4212 2105 6316 4210 2105 6317 4213 2106 6318 4214 2106 6319 4212 2106 6320 4215 2107 6321 4216 2107 6322 4214 2107 6323 4217 2108 6324 4218 2108 6325 4216 2108 6326 4219 2109 6327 4220 2109 6328 4218 2109 6329 4221 2110 6330 4222 2110 6331 4220 2110 6332 4223 2111 6333 4224 2111 6334 4222 2111 6335 4225 2112 6336 4226 2112 6337 4224 2112 6338 4227 2113 6339 4228 2113 6340 4226 2113 6341 4229 2114 6342 4230 2114 6343 4228 2114 6344 4231 2115 6345 4232 2115 6346 4230 2115 6347 4233 2116 6348 4234 2116 6349 4232 2116 6350 4235 2117 6351 4236 2117 6352 4234 2117 6353 4237 2118 6354 4238 2118 6355 4236 2118 6356 4239 2119 6357 4240 2119 6358 4238 2119 6359 4241 2120 6360 4242 2120 6361 4240 2120 6362 4243 2121 6363 4244 2121 6364 4242 2121 6365 4245 2122 6366 4246 2122 6367 4244 2122 6368 4247 2123 6369 4248 2123 6370 4246 2123 6371 4249 2124 6372 4250 2124 6373 4248 2124 6374 4251 2125 6375 4252 2125 6376 4250 2125 6377 4253 2126 6378 4254 2126 6379 4252 2126 6380 4255 2127 6381 4256 2127 6382 4254 2127 6383 4257 2128 6384 4258 2128 6385 4256 2128 6386 4259 2129 6387 4260 2129 6388 4258 2129 6389 4261 2130 6390 4262 2130 6391 4260 2130 6392 4263 2131 6393 4264 2131 6394 4262 2131 6395 4265 2132 6396 4266 2132 6397 4264 2132 6398 4267 2133 6399 4268 2133 6400 4266 2133 6401 4269 2134 6402 4270 2134 6403 4268 2134 6404 4271 2135 6405 4272 2135 6406 4270 2135 6407 4273 2136 6408 4274 2136 6409 4272 2136 6410 4275 2137 6411 4276 2137 6412 4274 2137 6413 4277 2138 6414 4278 2138 6415 4276 2138 6416 4279 2139 6417 4280 2139 6418 4278 2139 6419 4281 2140 6420 4282 2140 6421 4280 2140 6422 4283 2141 6423 4284 2141 6424 4282 2141 6425 4285 2142 6426 4286 2142 6427 4284 2142 6428 4287 2143 6429 4288 2143 6430 4286 2143 6431 4289 2144 6432 4290 2144 6433 4288 2144 6434 4291 2145 6435 4292 2145 6436 4290 2145 6437 4293 2146 6438 4294 2146 6439 4292 2146 6440 4295 2147 6441 4296 2147 6442 4294 2147 6443 4297 2148 6444 4298 2148 6445 4296 2148 6446 4299 2149 6447 4300 2149 6448 4298 2149 6449 4301 2150 6450 4302 2150 6451 4300 2150 6452 4303 2151 6453 4304 2151 6454 4302 2151 6455 4305 2152 6456 4306 2152 6457 4304 2152 6458 4307 2153 6459 4308 2153 6460 4306 2153 6461 4309 2154 6462 4310 2154 6463 4308 2154 6464 4311 2155 6465 4312 2155 6466 4310 2155 6467 4313 2156 6468 4314 2156 6469 4312 2156 6470 4315 2157 6471 4316 2157 6472 4314 2157 6473 4317 2158 6474 4318 2158 6475 4316 2158 6476 4319 2159 6477 4320 2159 6478 4318 2159 6479 4321 2160 6480 4322 2160 6481 4320 2160 6482 4323 2161 6483 4324 2161 6484 4322 2161 6485 4325 2162 6486 4326 2162 6487 4324 2162 6488 4327 2163 6489 4328 2163 6490 4326 2163 6491 4329 2164 6492 4330 2164 6493 4328 2164 6494 4331 2165 6495 4332 2165 6496 4330 2165 6497 4333 2166 6498 4334 2166 6499 4332 2166 6500 4335 2167 6501 4336 2167 6502 4334 2167 6503 4337 2168 6504 4338 2168 6505 4336 2168 6506 4339 2169 6507 4340 2169 6508 4338 2169 6509 4341 2170 6510 4342 2170 6511 4340 2170 6512 4343 2171 6513 4344 2171 6514 4342 2171 6515 4345 2172 6516 4346 2172 6517 4344 2172 6518 4347 2173 6519 4348 2173 6520 4346 2173 6521 4349 2174 6522 4350 2174 6523 4348 2174 6524 4351 2175 6525 4352 2175 6526 4350 2175 6527 4353 2176 6528 4354 2176 6529 4352 2176 6530 4355 2177 6531 4356 2177 6532 4354 2177 6533 4357 2178 6534 4358 2178 6535 4356 2178 6536 4359 2179 6537 4360 2179 6538 4358 2179 6539 4361 2180 6540 4362 2180 6541 4360 2180 6542 4363 2181 6543 4364 2181 6544 4362 2181 6545 4365 2182 6546 4366 2182 6547 4364 2182 6548 4367 2183 6549 4368 2183 6550 4366 2183 6551 4369 2184 6552 4370 2184 6553 4368 2184 6554 4371 2185 6555 4372 2185 6556 4370 2185 6557 4373 2186 6558 4374 2186 6559 4372 2186 6560 4375 2187 6561 4376 2187 6562 4374 2187 6563 4377 2188 6564 4378 2188 6565 4376 2188 6566 4379 2189 6567 4380 2189 6568 4378 2189 6569 4381 2190 6570 4382 2190 6571 4380 2190 6572 4383 2191 6573 4384 2191 6574 4382 2191 6575 4385 2192 6576 4386 2192 6577 4384 2192 6578 4387 2193 6579 4388 2193 6580 4386 2193 6581 4389 2194 6582 4390 2194 6583 4388 2194 6584 4391 2195 6585 4392 2195 6586 4390 2195 6587 4393 2196 6588 4394 2196 6589 4392 2196 6590 4395 2197 6591 4396 2197 6592 4394 2197 6593 4397 2198 6594 4398 2198 6595 4396 2198 6596 4399 2199 6597 4400 2199 6598 4398 2199 6599 4401 2200 6600 4402 2200 6601 4400 2200 6602 4403 2201 6603 4404 2201 6604 4402 2201 6605 4405 2202 6606 4406 2202 6607 4404 2202 6608 4407 2203 6609 4408 2203 6610 4406 2203 6611 4409 2204 6612 4410 2204 6613 4408 2204 6614 4411 2205 6615 4412 2205 6616 4410 2205 6617 4413 2206 6618 4414 2206 6619 4412 2206 6620 4415 2207 6621 4416 2207 6622 4414 2207 6623 4417 2208 6624 4418 2208 6625 4416 2208 6626 4419 2209 6627 4420 2209 6628 4418 2209 6629 4421 2210 6630 4422 2210 6631 4420 2210 6632 4423 2211 6633 4424 2211 6634 4422 2211 6635 4425 2212 6636 4426 2212 6637 4424 2212 6638 4427 2213 6639 4428 2213 6640 4426 2213 6641 4429 2214 6642 4430 2214 6643 4428 2214 6644 4431 2215 6645 4432 2215 6646 4430 2215 6647 4433 2216 6648 4434 2216 6649 4432 2216 6650 4435 2217 6651 4436 2217 6652 4434 2217 6653 4437 2218 6654 4438 2218 6655 4436 2218 6656 4439 2219 6657 4440 2219 6658 4438 2219 6659 4441 2220 6660 4442 2220 6661 4440 2220 6662 4443 2221 6663 4444 2221 6664 4442 2221 6665 4445 2222 6666 4446 2222 6667 4444 2222 6668 4447 2223 6669 4448 2223 6670 4446 2223 6671 4449 2224 6672 4450 2224 6673 4448 2224 6674 4451 2225 6675 4452 2225 6676 4450 2225 6677 4453 2226 6678 4454 2226 6679 4452 2226 6680 4455 2227 6681 4456 2227 6682 4454 2227 6683 4457 2228 6684 4458 2228 6685 4456 2228 6686 4459 2229 6687 4460 2229 6688 4458 2229 6689 4461 2230 6690 4462 2230 6691 4460 2230 6692 4463 2231 6693 4464 2231 6694 4462 2231 6695 4465 2232 6696 4466 2232 6697 4464 2232 6698 4467 2233 6699 4468 2233 6700 4466 2233 6701 4469 2234 6702 4470 2234 6703 4468 2234 6704 4471 2235 6705 4472 2235 6706 4470 2235 6707 4473 2236 6708 4474 2236 6709 4472 2236 6710 4475 2237 6711 4476 2237 6712 4474 2237 6713 4477 2238 6714 4478 2238 6715 4476 2238 6716 4479 2239 6717 4480 2239 6718 4478 2239 6719 4481 2240 6720 4482 2240 6721 4480 2240 6722 4483 2241 6723 4484 2241 6724 4482 2241 6725 4485 2242 6726 4486 2242 6727 4484 2242 6728 4487 2243 6729 4488 2243 6730 4486 2243 6731 4489 2244 6732 4490 2244 6733 4488 2244 6734 4491 2245 6735 4492 2245 6736 4490 2245 6737 4493 2246 6738 4494 2246 6739 4492 2246 6740 4495 2247 6741 4496 2247 6742 4494 2247 6743 4497 2248 6744 4498 2248 6745 4496 2248 6746 4499 2249 6747 4500 2249 6748 4498 2249 6749 4501 2250 6750 4502 2250 6751 4500 2250 6752 4503 2251 6753 4504 2251 6754 4502 2251 6755 4505 2252 6756 4506 2252 6757 4504 2252 6758 4507 2253 6759 4508 2253 6760 4506 2253 6761 4509 2254 6762 4510 2254 6763 4508 2254 6764 4511 2255 6765 4512 2255 6766 4510 2255 6767 4513 2256 6768 4514 2256 6769 4512 2256 6770 4515 2257 6771 4516 2257 6772 4514 2257 6773 4517 2258 6774 4518 2258 6775 4516 2258 6776 4519 2259 6777 4520 2259 6778 4518 2259 6779 4521 2260 6780 4522 2260 6781 4520 2260 6782 4523 2261 6783 4524 2261 6784 4522 2261 6785 4525 2262 6786 4526 2262 6787 4524 2262 6788 4527 2263 6789 4528 2263 6790 4526 2263 6791 4529 2264 6792 4530 2264 6793 4528 2264 6794 4531 2265 6795 4532 2265 6796 4530 2265 6797 4533 2266 6798 4534 2266 6799 4532 2266 6800 4535 2267 6801 4536 2267 6802 4534 2267 6803 4537 2268 6804 4538 2268 6805 4536 2268 6806 4539 2269 6807 4540 2269 6808 4538 2269 6809 4541 2270 6810 4542 2270 6811 4540 2270 6812 4543 2271 6813 4544 2271 6814 4542 2271 6815 4545 2272 6816 4546 2272 6817 4544 2272 6818 4547 2273 6819 4548 2273 6820 4546 2273 6821 4549 2274 6822 4550 2274 6823 4548 2274 6824 4551 2275 6825 4552 2275 6826 4550 2275 6827 4553 2276 6828 4554 2276 6829 4552 2276 6830 4555 2277 6831 4556 2277 6832 4554 2277 6833 4557 2278 6834 4558 2278 6835 4556 2278 6836 4559 2279 6837 4560 2279 6838 4558 2279 6839 4561 2280 6840 4562 2280 6841 4560 2280 6842 4563 2281 6843 4564 2281 6844 4562 2281 6845 4565 2282 6846 4566 2282 6847 4564 2282 6848 4567 2283 6849 4568 2283 6850 4566 2283 6851 4569 2284 6852 4570 2284 6853 4568 2284 6854 4571 2285 6855 4572 2285 6856 4570 2285 6857 4573 2286 6858 4574 2286 6859 4572 2286 6860 4575 2287 6861 4576 2287 6862 4574 2287 6863 4577 2288 6864 4578 2288 6865 4576 2288 6866 4579 2289 6867 4580 2289 6868 4578 2289 6869 4581 2290 6870 4582 2290 6871 4580 2290 6872 4583 2291 6873 4584 2291 6874 4582 2291 6875 4585 2292 6876 4586 2292 6877 4584 2292 6878 4587 2293 6879 4588 2293 6880 4586 2293 6881 4589 2294 6882 4590 2294 6883 4588 2294 6884 4591 2295 6885 4592 2295 6886 4590 2295 6887 4593 2296 6888 4594 2296 6889 4592 2296 6890 4595 2297 6891 4596 2297 6892 4594 2297 6893 4597 2298 6894 4598 2298 6895 4596 2298 6896 4599 2299 6897 4600 2299 6898 4598 2299 6899 4601 2300 6900 4602 2300 6901 4600 2300 6902 4603 2301 6903 4604 2301 6904 4602 2301 6905 4605 2302 6906 4606 2302 6907 4604 2302 6908 4607 2303 6909 4608 2303 6910 4606 2303 6911 4609 2304 6912 4610 2304 6913 4608 2304 6914 4611 2305 6915 4612 2305 6916 4610 2305 6917 4613 2306 6918 4614 2306 6919 4612 2306 6920 4615 2307 6921 4616 2307 6922 4614 2307 6923 4617 2308 6924 4618 2308 6925 4616 2308 6926 4619 2309 6927 4620 2309 6928 4618 2309 6929 4621 2310 6930 4622 2310 6931 4620 2310 6932 4623 2311 6933 4624 2311 6934 4622 2311 6935 4625 2312 6936 4626 2312 6937 4624 2312 6938 4627 2313 6939 4628 2313 6940 4626 2313 6941 4629 2314 6942 4630 2314 6943 4628 2314 6944 4631 2315 6945 4632 2315 6946 4630 2315 6947 4633 2316 6948 4634 2316 6949 4632 2316 6950 4635 2317 6951 4636 2317 6952 4634 2317 6953 4637 2318 6954 4638 2318 6955 4636 2318 6956 4639 2319 6957 4640 2319 6958 4638 2319 6959 4641 2320 6960 4642 2320 6961 4640 2320 6962 4643 2321 6963 4644 2321 6964 4642 2321 6965 4645 2322 6966 4646 2322 6967 4644 2322 6968 4647 2323 6969 4648 2323 6970 4646 2323 6971 4649 2324 6972 4650 2324 6973 4648 2324 6974 4651 2325 6975 4652 2325 6976 4650 2325 6977 4653 2326 6978 4654 2326 6979 4652 2326 6980 4655 2327 6981 4656 2327 6982 4654 2327 6983 4657 2328 6984 4658 2328 6985 4656 2328 6986 4659 2329 6987 4660 2329 6988 4658 2329 6989 4661 2330 6990 4662 2330 6991 4660 2330 6992 4663 2331 6993 4664 2331 6994 4662 2331 6995 4665 2332 6996 4666 2332 6997 4664 2332 6998 4667 2333 6999 4668 2333 7000 4666 2333 7001 4669 2334 7002 4670 2334 7003 4668 2334 7004 4671 2335 7005 4672 2335 7006 4670 2335 7007 4673 2336 7008 4674 2336 7009 4672 2336 7010 4675 2337 7011 4676 2337 7012 4674 2337 7013 4677 2338 7014 4678 2338 7015 4676 2338 7016 4679 2339 7017 4680 2339 7018 4678 2339 7019 4681 2340 7020 4682 2340 7021 4680 2340 7022 4683 2341 7023 4684 2341 7024 4682 2341 7025 4685 2342 7026 4686 2342 7027 4684 2342 7028 4687 2343 7029 4688 2343 7030 4686 2343 7031 4689 2344 7032 4690 2344 7033 4688 2344 7034 4691 2345 7035 4692 2345 7036 4690 2345 7037 4693 2346 7038 4694 2346 7039 4692 2346 7040 4695 2347 7041 4696 2347 7042 4694 2347 7043 4697 2348 7044 4698 2348 7045 4696 2348 7046 4699 2349 7047 4700 2349 7048 4698 2349 7049 4701 2350 7050 4702 2350 7051 4700 2350 7052 4703 2351 7053 4704 2351 7054 4702 2351 7055 4705 2352 7056 4706 2352 7057 4704 2352 7058 4707 2353 7059 4708 2353 7060 4706 2353 7061 4709 2354 7062 4710 2354 7063 4708 2354 7064 4711 2355 7065 4712 2355 7066 4710 2355 7067 4713 2356 7068 4714 2356 7069 4712 2356 7070 4715 2357 7071 4716 2357 7072 4714 2357 7073 4717 2358 7074 4718 2358 7075 4716 2358 7076 4719 2359 7077 4720 2359 7078 4718 2359 7079 4721 2360 7080 4722 2360 7081 4720 2360 7082 4723 2361 7083 4724 2361 7084 4722 2361 7085 4725 2362 7086 4726 2362 7087 4724 2362 7088 4727 2363 7089 4728 2363 7090 4726 2363 7091 4729 2364 7092 4730 2364 7093 4728 2364 7094 4731 2365 7095 4732 2365 7096 4730 2365 7097 4733 2366 7098 4734 2366 7099 4732 2366 7100 4735 2367 7101 4736 2367 7102 4734 2367 7103 4737 2368 7104 4738 2368 7105 4736 2368 7106 4739 2369 7107 4740 2369 7108 4738 2369 7109 4741 2370 7110 4742 2370 7111 4740 2370 7112 4743 2371 7113 4744 2371 7114 4742 2371 7115 4745 2372 7116 4746 2372 7117 4744 2372 7118 4747 2373 7119 4748 2373 7120 4746 2373 7121 4749 2374 7122 4750 2374 7123 4748 2374 7124 4751 2375 7125 4752 2375 7126 4750 2375 7127 4753 2376 7128 4754 2376 7129 4752 2376 7130 4755 2377 7131 4756 2377 7132 4754 2377 7133 4757 2378 7134 4758 2378 7135 4756 2378 7136 4759 2379 7137 4760 2379 7138 4758 2379 7139 4761 2380 7140 4762 2380 7141 4760 2380 7142 4763 2381 7143 4764 2381 7144 4762 2381 7145 4765 2382 7146 4766 2382 7147 4764 2382 7148 4767 2383 7149 4768 2383 7150 4766 2383 7151 4769 2384 7152 4770 2384 7153 4768 2384 7154 4771 2385 7155 4772 2385 7156 4770 2385 7157 4773 2386 7158 4774 2386 7159 4772 2386 7160 4775 2387 7161 4776 2387 7162 4774 2387 7163 4777 2388 7164 4778 2388 7165 4776 2388 7166 4779 2389 7167 4780 2389 7168 4778 2389 7169 4781 2390 7170 4782 2390 7171 4780 2390 7172 4783 2391 7173 4784 2391 7174 4782 2391 7175 4785 2392 7176 4786 2392 7177 4784 2392 7178 4787 2393 7179 4788 2393 7180 4786 2393 7181 4789 2394 7182 4790 2394 7183 4788 2394 7184 4791 2395 7185 4792 2395 7186 4790 2395 7187 4793 2396 7188 4794 2396 7189 4792 2396 7190 4795 2397 7191 4796 2397 7192 4794 2397 7193 4797 2398 7194 4798 2398 7195 4796 2398 7196 4799 2399 7197 4800 2399 7198 4798 2399 7199 4801 2400 7200 4802 2400 7201 4800 2400 7202 4803 2401 7203 4804 2401 7204 4802 2401 7205 4805 2402 7206 4806 2402 7207 4804 2402 7208 4807 2403 7209 4808 2403 7210 4806 2403 7211 4809 2404 7212 4810 2404 7213 4808 2404 7214 4811 2405 7215 4812 2405 7216 4810 2405 7217 4813 2406 7218 4814 2406 7219 4812 2406 7220 4815 2407 7221 4816 2407 7222 4814 2407 7223 4817 2408 7224 4818 2408 7225 4816 2408 7226 4819 2409 7227 4820 2409 7228 4818 2409 7229 4821 2410 7230 4822 2410 7231 4820 2410 7232 4823 2411 7233 4824 2411 7234 4822 2411 7235 4825 2412 7236 4826 2412 7237 4824 2412 7238 4827 2413 7239 4828 2413 7240 4826 2413 7241 4829 2414 7242 4830 2414 7243 4828 2414 7244 4831 2415 7245 4832 2415 7246 4830 2415 7247 4833 2416 7248 4834 2416 7249 4832 2416 7250 4835 2417 7251 4836 2417 7252 4834 2417 7253 4837 2418 7254 4838 2418 7255 4836 2418 7256 4839 2419 7257 4840 2419 7258 4838 2419 7259 4841 2420 7260 4842 2420 7261 4840 2420 7262 4843 2421 7263 4844 2421 7264 4842 2421 7265 4845 2422 7266 4846 2422 7267 4844 2422 7268 4847 2423 7269 4848 2423 7270 4846 2423 7271 4849 2424 7272 4850 2424 7273 4848 2424 7274 4851 2425 7275 4852 2425 7276 4850 2425 7277 4853 2426 7278 4854 2426 7279 4852 2426 7280 4855 2427 7281 4856 2427 7282 4854 2427 7283 4857 2428 7284 4858 2428 7285 4856 2428 7286 4859 2429 7287 4860 2429 7288 4858 2429 7289 4861 2430 7290 4862 2430 7291 4860 2430 7292 4863 2431 7293 4864 2431 7294 4862 2431 7295 4865 2432 7296 4866 2432 7297 4864 2432 7298 4867 2433 7299 4868 2433 7300 4866 2433 7301 4869 2434 7302 4870 2434 7303 4868 2434 7304 4871 2435 7305 4872 2435 7306 4870 2435 7307 4873 2436 7308 4874 2436 7309 4872 2436 7310 4875 2437 7311 4876 2437 7312 4874 2437 7313 4877 2438 7314 4878 2438 7315 4876 2438 7316 4879 2439 7317 4880 2439 7318 4878 2439 7319 4881 2440 7320 4882 2440 7321 4880 2440 7322 4883 2441 7323 4884 2441 7324 4882 2441 7325 4885 2442 7326 4886 2442 7327 4884 2442 7328 4887 2443 7329 4888 2443 7330 4886 2443 7331 4889 2444 7332 4890 2444 7333 4888 2444 7334 4891 2445 7335 4892 2445 7336 4890 2445 7337 4893 2446 7338 4894 2446 7339 4892 2446 7340 4895 2447 7341 4896 2447 7342 4894 2447 7343 4897 2448 7344 4898 2448 7345 4896 2448 7346 4899 2449 7347 4900 2449 7348 4898 2449 7349 4901 2450 7350 4902 2450 7351 4900 2450 7352 4903 2451 7353 4904 2451 7354 4902 2451 7355 4905 2452 7356 4906 2452 7357 4904 2452 7358 4907 2453 7359 4908 2453 7360 4906 2453 7361 4909 2454 7362 4910 2454 7363 4908 2454 7364 4911 2455 7365 4912 2455 7366 4910 2455 7367 4913 2456 7368 4914 2456 7369 4912 2456 7370 4915 2457 7371 4916 2457 7372 4914 2457 7373 4917 2458 7374 4918 2458 7375 4916 2458 7376 4919 2459 7377 4920 2459 7378 4918 2459 7379 4921 2460 7380 4922 2460 7381 4920 2460 7382 4923 2461 7383 4924 2461 7384 4922 2461 7385 4925 2462 7386 4926 2462 7387 4924 2462 7388 4927 2463 7389 4928 2463 7390 4926 2463 7391 4929 2464 7392 4930 2464 7393 4928 2464 7394 4931 2465 7395 4932 2465 7396 4930 2465 7397 4933 2466 7398 4934 2466 7399 4932 2466 7400 4935 2467 7401 4936 2467 7402 4934 2467 7403 4937 2468 7404 4938 2468 7405 4936 2468 7406 4939 2469 7407 4940 2469 7408 4938 2469 7409 4941 2470 7410 4942 2470 7411 4940 2470 7412 4943 2471 7413 4944 2471 7414 4942 2471 7415 4945 2472 7416 4946 2472 7417 4944 2472 7418 4947 2473 7419 4948 2473 7420 4946 2473 7421 4949 2474 7422 4950 2474 7423 4948 2474 7424 4951 2475 7425 4952 2475 7426 4950 2475 7427 4953 2476 7428 4954 2476 7429 4952 2476 7430 4955 2477 7431 4956 2477 7432 4954 2477 7433 4957 2478 7434 4958 2478 7435 4956 2478 7436 4959 2479 7437 4960 2479 7438 4958 2479 7439 4961 2480 7440 4962 2480 7441 4960 2480 7442 4963 2481 7443 4964 2481 7444 4962 2481 7445 4965 2482 7446 4966 2482 7447 4964 2482 7448 4967 2483 7449 4968 2483 7450 4966 2483 7451 4969 2484 7452 4970 2484 7453 4968 2484 7454 4971 2485 7455 4972 2485 7456 4970 2485 7457 4973 2486 7458 4974 2486 7459 4972 2486 7460 4975 2487 7461 4976 2487 7462 4974 2487 7463 4977 2488 7464 4978 2488 7465 4976 2488 7466 4979 2489 7467 4980 2489 7468 4978 2489 7469 4981 2490 7470 4982 2490 7471 4980 2490 7472 4983 2491 7473 4984 2491 7474 4982 2491 7475 4985 2492 7476 4986 2492 7477 4984 2492 7478 4987 2493 7479 4988 2493 7480 4986 2493 7481 4989 2494 7482 4990 2494 7483 4988 2494 7484 4991 2495 7485 4992 2495 7486 4990 2495 7487 4993 2496 7488 4994 2496 7489 4992 2496 7490 4995 2497 7491 4996 2497 7492 4994 2497 7493 4997 2498 7494 4998 2498 7495 4996 2498 7496 4999 2499 7497 5000 2499 7498 4998 2499 7499 5001 2500 7500 5002 2500 7501 5000 2500 7502 5003 2501 7503 5004 2501 7504 5002 2501 7505 5005 2502 7506 5006 2502 7507 5004 2502 7508 5007 2503 7509 5008 2503 7510 5006 2503 7511 5009 2504 7512 5010 2504 7513 5008 2504 7514 5011 2505 7515 5012 2505 7516 5010 2505 7517 5013 2506 7518 5014 2506 7519 5012 2506 7520 5015 2507 7521 5016 2507 7522 5014 2507 7523 5017 2508 7524 5018 2508 7525 5016 2508 7526 5019 2509 7527 5020 2509 7528 5018 2509 7529 5021 2510 7530 5022 2510 7531 5020 2510 7532 5023 2511 7533 5024 2511 7534 5022 2511 7535 5025 2512 7536 5026 2512 7537 5024 2512 7538 5027 2513 7539 5028 2513 7540 5026 2513 7541 5029 2514 7542 5030 2514 7543 5028 2514 7544 5031 2515 7545 5032 2515 7546 5030 2515 7547 5033 2516 7548 5034 2516 7549 5032 2516 7550 5035 2517 7551 5036 2517 7552 5034 2517 7553 5037 2518 7554 5038 2518 7555 5036 2518 7556 5039 2519 7557 5040 2519 7558 5038 2519 7559 5041 2520 7560 5042 2520 7561 5040 2520 7562 5043 2521 7563 5044 2521 7564 5042 2521 7565 5045 2522 7566 5046 2522 7567 5044 2522 7568 5047 2523 7569 5048 2523 7570 5046 2523 7571 5049 2524 7572 5050 2524 7573 5048 2524 7574 5051 2525 7575 5052 2525 7576 5050 2525 7577 5053 2526 7578 5054 2526 7579 5052 2526 7580 5055 2527 7581 5056 2527 7582 5054 2527 7583 5057 2528 7584 5058 2528 7585 5056 2528 7586 5059 2529 7587 5060 2529 7588 5058 2529 7589 5061 2530 7590 5062 2530 7591 5060 2530 7592 5063 2531 7593 5064 2531 7594 5062 2531 7595 5065 2532 7596 5066 2532 7597 5064 2532 7598 5067 2533 7599 5068 2533 7600 5066 2533 7601 5069 2534 7602 5070 2534 7603 5068 2534 7604 5071 2535 7605 5072 2535 7606 5070 2535 7607 5073 2536 7608 5074 2536 7609 5072 2536 7610 5075 2537 7611 5076 2537 7612 5074 2537 7613 5077 2538 7614 5078 2538 7615 5076 2538 7616 5079 2539 7617 5080 2539 7618 5078 2539 7619 5081 2540 7620 5082 2540 7621 5080 2540 7622 5083 2541 7623 5084 2541 7624 5082 2541 7625 5085 2542 7626 5086 2542 7627 5084 2542 7628 5087 2543 7629 5088 2543 7630 5086 2543 7631 5089 2544 7632 5090 2544 7633 5088 2544 7634 5091 2545 7635 5092 2545 7636 5090 2545 7637 5093 2546 7638 5094 2546 7639 5092 2546 7640 5095 2547 7641 5096 2547 7642 5094 2547 7643 5097 2548 7644 5098 2548 7645 5096 2548 7646 5099 2549 7647 5100 2549 7648 5098 2549 7649 5101 2550 7650 5102 2550 7651 5100 2550 7652 5103 2551 7653 5104 2551 7654 5102 2551 7655 5105 2552 7656 5106 2552 7657 5104 2552 7658 5107 2553 7659 5108 2553 7660 5106 2553 7661 5109 2554 7662 5110 2554 7663 5108 2554 7664 5111 2555 7665 5112 2555 7666 5110 2555 7667 5113 2556 7668 5114 2556 7669 5112 2556 7670 5115 2557 7671 5116 2557 7672 5114 2557 7673 5117 2558 7674 5118 2558 7675 5116 2558 7676 5119 2559 7677 5120 2559 7678 5118 2559 7679 5121 2560 7680 5122 2560 7681 5120 2560 7682 5123 2561 7683 5124 2561 7684 5122 2561 7685 5125 2562 7686 5126 2562 7687 5124 2562 7688 5127 2563 7689 5128 2563 7690 5126 2563 7691 5129 2564 7692 5130 2564 7693 5128 2564 7694 5131 2565 7695 5132 2565 7696 5130 2565 7697 5133 2566 7698 5134 2566 7699 5132 2566 7700 5135 2567 7701 5136 2567 7702 5134 2567 7703 5137 2568 7704 5138 2568 7705 5136 2568 7706 5139 2569 7707 5140 2569 7708 5138 2569 7709 5141 2570 7710 5142 2570 7711 5140 2570 7712 5143 2571 7713 5144 2571 7714 5142 2571 7715 5145 2572 7716 5146 2572 7717 5144 2572 7718 5147 2573 7719 5148 2573 7720 5146 2573 7721 5149 2574 7722 5150 2574 7723 5148 2574 7724 5151 2575 7725 5152 2575 7726 5150 2575 7727 5153 2576 7728 5154 2576 7729 5152 2576 7730 5155 2577 7731 5156 2577 7732 5154 2577 7733 5157 2578 7734 5158 2578 7735 5156 2578 7736 5159 2579 7737 5160 2579 7738 5158 2579 7739 5161 2580 7740 5162 2580 7741 5160 2580 7742 5163 2581 7743 5164 2581 7744 5162 2581 7745 5165 2582 7746 5166 2582 7747 5164 2582 7748 5167 2583 7749 5168 2583 7750 5166 2583 7751 5169 2584 7752 5170 2584 7753 5168 2584 7754 5171 2585 7755 5172 2585 7756 5170 2585 7757 5173 2586 7758 5174 2586 7759 5172 2586 7760 5175 2587 7761 5176 2587 7762 5174 2587 7763 5177 2588 7764 5178 2588 7765 5176 2588 7766 5179 2589 7767 5180 2589 7768 5178 2589 7769 5181 2590 7770 5182 2590 7771 5180 2590 7772 5183 2591 7773 5184 2591 7774 5182 2591 7775 5185 2592 7776 5186 2592 7777 5184 2592 7778 5187 2593 7779 5188 2593 7780 5186 2593 7781 5189 2594 7782 5190 2594 7783 5188 2594 7784 5191 2595 7785 5192 2595 7786 5190 2595 7787 5193 2596 7788 5194 2596 7789 5192 2596 7790 5195 2597 7791 5196 2597 7792 5194 2597 7793 5197 2598 7794 5198 2598 7795 5196 2598 7796 5199 2599 7797 5200 2599 7798 5198 2599 7799 5201 2600 7800 5202 2600 7801 5200 2600 7802 5203 2601 7803 5204 2601 7804 5202 2601 7805 5205 2602 7806 5206 2602 7807 5204 2602 7808 5207 2603 7809 5208 2603 7810 5206 2603 7811 5209 2604 7812 5210 2604 7813 5208 2604 7814 5211 2605 7815 5212 2605 7816 5210 2605 7817 5213 2606 7818 5214 2606 7819 5212 2606 7820 5215 2607 7821 5216 2607 7822 5214 2607 7823 5217 2608 7824 5218 2608 7825 5216 2608 7826 5219 2609 7827 5220 2609 7828 5218 2609 7829 5221 2610 7830 5222 2610 7831 5220 2610 7832 5223 2611 7833 5224 2611 7834 5222 2611 7835 5225 2612 7836 5226 2612 7837 5224 2612 7838 5227 2613 7839 5228 2613 7840 5226 2613 7841 5229 2614 7842 5230 2614 7843 5228 2614 7844 5231 2615 7845 5232 2615 7846 5230 2615 7847 5233 2616 7848 5234 2616 7849 5232 2616 7850 5235 2617 7851 5236 2617 7852 5234 2617 7853 5237 2618 7854 5238 2618 7855 5236 2618 7856 5239 2619 7857 5240 2619 7858 5238 2619 7859 5241 2620 7860 5242 2620 7861 5240 2620 7862 5243 2621 7863 5244 2621 7864 5242 2621 7865 5245 2622 7866 5246 2622 7867 5244 2622 7868 5247 2623 7869 5248 2623 7870 5246 2623 7871 5249 2624 7872 5250 2624 7873 5248 2624 7874 5251 2625 7875 5252 2625 7876 5250 2625 7877 5253 2626 7878 5254 2626 7879 5252 2626 7880 5255 2627 7881 5256 2627 7882 5254 2627 7883 5257 2628 7884 5258 2628 7885 5256 2628 7886 5259 2629 7887 5260 2629 7888 5258 2629 7889 5261 2630 7890 5262 2630 7891 5260 2630 7892 5263 2631 7893 5264 2631 7894 5262 2631 7895 5265 2632 7896 5266 2632 7897 5264 2632 7898 5267 2633 7899 5268 2633 7900 5266 2633 7901 5269 2634 7902 5270 2634 7903 5268 2634 7904 5271 2635 7905 5272 2635 7906 5270 2635 7907 5273 2636 7908 5274 2636 7909 5272 2636 7910 5275 2637 7911 5276 2637 7912 5274 2637 7913 5277 2638 7914 5278 2638 7915 5276 2638 7916 5279 2639 7917 5280 2639 7918 5278 2639 7919 5281 2640 7920 5282 2640 7921 5280 2640 7922 5283 2641 7923 5284 2641 7924 5282 2641 7925 5285 2642 7926 5286 2642 7927 5284 2642 7928 5287 2643 7929 5288 2643 7930 5286 2643 7931 5289 2644 7932 5290 2644 7933 5288 2644 7934 5291 2645 7935 5292 2645 7936 5290 2645 7937 5293 2646 7938 5294 2646 7939 5292 2646 7940 5295 2647 7941 5296 2647 7942 5294 2647 7943 5297 2648 7944 5298 2648 7945 5296 2648 7946 5299 2649 7947 5300 2649 7948 5298 2649 7949 5301 2650 7950 5302 2650 7951 5300 2650 7952 5303 2651 7953 5304 2651 7954 5302 2651 7955 5305 2652 7956 5306 2652 7957 5304 2652 7958 5307 2653 7959 5308 2653 7960 5306 2653 7961 5309 2654 7962 5310 2654 7963 5308 2654 7964 5311 2655 7965 5312 2655 7966 5310 2655 7967 5313 2656 7968 5314 2656 7969 5312 2656 7970 5315 2657 7971 5316 2657 7972 5314 2657 7973 5317 2658 7974 5318 2658 7975 5316 2658 7976 5319 2659 7977 5320 2659 7978 5318 2659 7979 5321 2660 7980 5322 2660 7981 5320 2660 7982 5323 2661 7983 5324 2661 7984 5322 2661 7985 5325 2662 7986 5326 2662 7987 5324 2662 7988 5327 2663 7989 5328 2663 7990 5326 2663 7991 5329 2664 7992 5330 2664 7993 5328 2664 7994 5331 2665 7995 5332 2665 7996 5330 2665 7997 5333 2666 7998 5334 2666 7999 5332 2666 8000 5335 2667 8001 5336 2667 8002 5334 2667 8003 5337 2668 8004 5338 2668 8005 5336 2668 8006 5339 2669 8007 5340 2669 8008 5338 2669 8009 5341 2670 8010 5342 2670 8011 5340 2670 8012 5343 2671 8013 5344 2671 8014 5342 2671 8015 5345 2672 8016 5346 2672 8017 5344 2672 8018 5347 2673 8019 5348 2673 8020 5346 2673 8021 5349 2674 8022 5350 2674 8023 5348 2674 8024 5351 2675 8025 5352 2675 8026 5350 2675 8027 5353 2676 8028 5354 2676 8029 5352 2676 8030 5355 2677 8031 5356 2677 8032 5354 2677 8033 5357 2678 8034 5358 2678 8035 5356 2678 8036 5359 2679 8037 5360 2679 8038 5358 2679 8039 5361 2680 8040 5362 2680 8041 5360 2680 8042 5363 2681 8043 5364 2681 8044 5362 2681 8045 5365 2682 8046 5366 2682 8047 5364 2682 8048 5367 2683 8049 5368 2683 8050 5366 2683 8051 5369 2684 8052 5370 2684 8053 5368 2684 8054 5371 2685 8055 5372 2685 8056 5370 2685 8057 5373 2686 8058 5374 2686 8059 5372 2686 8060 5375 2687 8061 5376 2687 8062 5374 2687 8063 5377 2688 8064 5378 2688 8065 5376 2688 8066 5379 2689 8067 5380 2689 8068 5378 2689 8069 5381 2690 8070 5382 2690 8071 5380 2690 8072 5383 2691 8073 5384 2691 8074 5382 2691 8075 5385 2692 8076 5386 2692 8077 5384 2692 8078 5387 2693 8079 5388 2693 8080 5386 2693 8081 5389 2694 8082 5390 2694 8083 5388 2694 8084 5391 2695 8085 5392 2695 8086 5390 2695 8087 5393 2696 8088 5394 2696 8089 5392 2696 8090 5395 2697 8091 5396 2697 8092 5394 2697 8093 5397 2698 8094 5398 2698 8095 5396 2698 8096 5399 2699 8097 5400 2699 8098 5398 2699 8099 5401 2700 8100 5402 2700 8101 5400 2700 8102 5403 2701 8103 5404 2701 8104 5402 2701 8105 5405 2702 8106 5406 2702 8107 5404 2702 8108 5407 2703 8109 5408 2703 8110 5406 2703 8111 5409 2704 8112 5410 2704 8113 5408 2704 8114 5411 2705 8115 5412 2705 8116 5410 2705 8117 5413 2706 8118 5414 2706 8119 5412 2706 8120 5415 2707 8121 5416 2707 8122 5414 2707 8123 5417 2708 8124 5418 2708 8125 5416 2708 8126 5419 2709 8127 5420 2709 8128 5418 2709 8129 5421 2710 8130 5422 2710 8131 5420 2710 8132 5423 2711 8133 5424 2711 8134 5422 2711 8135 5425 2712 8136 5426 2712 8137 5424 2712 8138 5427 2713 8139 5428 2713 8140 5426 2713 8141 5429 2714 8142 5430 2714 8143 5428 2714 8144 5431 2715 8145 5432 2715 8146 5430 2715 8147 5433 2716 8148 5434 2716 8149 5432 2716 8150 5435 2717 8151 5436 2717 8152 5434 2717 8153 5437 2718 8154 5438 2718 8155 5436 2718 8156 5439 2719 8157 5440 2719 8158 5438 2719 8159 5441 2720 8160 5442 2720 8161 5440 2720 8162 5443 2721 8163 5444 2721 8164 5442 2721 8165 5445 2722 8166 5446 2722 8167 5444 2722 8168 5447 2723 8169 5448 2723 8170 5446 2723 8171 5449 2724 8172 5450 2724 8173 5448 2724 8174 5451 2725 8175 5452 2725 8176 5450 2725 8177 5453 2726 8178 5454 2726 8179 5452 2726 8180 5455 2727 8181 5456 2727 8182 5454 2727 8183 5457 2728 8184 5458 2728 8185 5456 2728 8186 5459 2729 8187 5460 2729 8188 5458 2729 8189 5461 2730 8190 5462 2730 8191 5460 2730 8192 5463 2731 8193 5464 2731 8194 5462 2731 8195 5465 2732 8196 5466 2732 8197 5464 2732 8198 5467 2733 8199 5468 2733 8200 5466 2733 8201 5469 2734 8202 5470 2734 8203 5468 2734 8204 5471 2735 8205 5472 2735 8206 5470 2735 8207 5473 2736 8208 5474 2736 8209 5472 2736 8210 5475 2737 8211 5476 2737 8212 5474 2737 8213 5477 2738 8214 5478 2738 8215 5476 2738 8216 5479 2739 8217 5480 2739 8218 5478 2739 8219 5481 2740 8220 5482 2740 8221 5480 2740 8222 5483 2741 8223 5484 2741 8224 5482 2741 8225 5485 2742 8226 5486 2742 8227 5484 2742 8228 5487 2743 8229 5488 2743 8230 5486 2743 8231 5489 2744 8232 5490 2744 8233 5488 2744 8234 5491 2745 8235 5492 2745 8236 5490 2745 8237 5493 2746 8238 5494 2746 8239 5492 2746 8240 5495 2747 8241 5496 2747 8242 5494 2747 8243 5497 2748 8244 5498 2748 8245 5496 2748 8246 5499 2749 8247 5500 2749 8248 5498 2749 8249 5501 2750 8250 5502 2750 8251 5500 2750 8252 5503 2751 8253 5504 2751 8254 5502 2751 8255 5505 2752 8256 5506 2752 8257 5504 2752 8258 5507 2753 8259 5508 2753 8260 5506 2753 8261 5509 2754 8262 5510 2754 8263 5508 2754 8264 5511 2755 8265 5512 2755 8266 5510 2755 8267 5513 2756 8268 5514 2756 8269 5512 2756 8270 5515 2757 8271 5516 2757 8272 5514 2757 8273 5517 2758 8274 5518 2758 8275 5516 2758 8276 5519 2759 8277 5520 2759 8278 5518 2759 8279 5521 2760 8280 5522 2760 8281 5520 2760 8282 5523 2761 8283 5524 2761 8284 5522 2761 8285 5525 2762 8286 5526 2762 8287 5524 2762 8288 5527 2763 8289 5528 2763 8290 5526 2763 8291 5529 2764 8292 5530 2764 8293 5528 2764 8294 5531 2765 8295 5532 2765 8296 5530 2765 8297 5533 2766 8298 5534 2766 8299 5532 2766 8300 5535 2767 8301 5536 2767 8302 5534 2767 8303 5537 2768 8304 5538 2768 8305 5536 2768 8306 5539 2769 8307 5540 2769 8308 5538 2769 8309 5541 2770 8310 5542 2770 8311 5540 2770 8312 5543 2771 8313 5544 2771 8314 5542 2771 8315 5545 2772 8316 5546 2772 8317 5544 2772 8318 5547 2773 8319 5548 2773 8320 5546 2773 8321 5549 2774 8322 5550 2774 8323 5548 2774 8324 5551 2775 8325 5552 2775 8326 5550 2775 8327 5553 2776 8328 5554 2776 8329 5552 2776 8330 5555 2777 8331 5556 2777 8332 5554 2777 8333 5557 2778 8334 5558 2778 8335 5556 2778 8336 5559 2779 8337 5560 2779 8338 5558 2779 8339 5561 2780 8340 5562 2780 8341 5560 2780 8342 5563 2781 8343 5564 2781 8344 5562 2781 8345 5565 2782 8346 5566 2782 8347 5564 2782 8348 5567 2783 8349 5568 2783 8350 5566 2783 8351 5569 2784 8352 5570 2784 8353 5568 2784 8354 5571 2785 8355 5572 2785 8356 5570 2785 8357 5573 2786 8358 5574 2786 8359 5572 2786 8360 5575 2787 8361 5576 2787 8362 5574 2787 8363 5577 2788 8364 5578 2788 8365 5576 2788 8366 5579 2789 8367 5580 2789 8368 5578 2789 8369 5581 2790 8370 5582 2790 8371 5580 2790 8372 5583 2791 8373 5584 2791 8374 5582 2791 8375 5585 2792 8376 5586 2792 8377 5584 2792 8378 5587 2793 8379 5588 2793 8380 5586 2793 8381 5589 2794 8382 5590 2794 8383 5588 2794 8384 5591 2795 8385 5592 2795 8386 5590 2795 8387 5593 2796 8388 5594 2796 8389 5592 2796 8390 5595 2797 8391 5596 2797 8392 5594 2797 8393 5597 2798 8394 5598 2798 8395 5596 2798 8396 5599 2799 8397 5600 2799 8398 5598 2799 8399 5601 2800 8400 5602 2800 8401 5600 2800 8402 5603 2801 8403 5604 2801 8404 5602 2801 8405 5605 2802 8406 5606 2802 8407 5604 2802 8408 5607 2803 8409 5608 2803 8410 5606 2803 8411 5609 2804 8412 5610 2804 8413 5608 2804 8414 5611 2805 8415 5612 2805 8416 5610 2805 8417 5613 2806 8418 5614 2806 8419 5612 2806 8420 5615 2807 8421 5616 2807 8422 5614 2807 8423 5617 2808 8424 5618 2808 8425 5616 2808 8426 5619 2809 8427 5620 2809 8428 5618 2809 8429 5621 2810 8430 5622 2810 8431 5620 2810 8432 5623 2811 8433 5624 2811 8434 5622 2811 8435 5625 2812 8436 5626 2812 8437 5624 2812 8438 5627 2813 8439 5628 2813 8440 5626 2813 8441 5629 2814 8442 5630 2814 8443 5628 2814 8444 5631 2815 8445 5632 2815 8446 5630 2815 8447 5633 2816 8448 5634 2816 8449 5632 2816 8450 5635 2817 8451 5636 2817 8452 5634 2817 8453 5637 2818 8454 5638 2818 8455 5636 2818 8456 5639 2819 8457 5640 2819 8458 5638 2819 8459 5641 2820 8460 5642 2820 8461 5640 2820 8462 5643 2821 8463 5644 2821 8464 5642 2821 8465 5645 2822 8466 5646 2822 8467 5644 2822 8468 5647 2823 8469 5648 2823 8470 5646 2823 8471 5649 2824 8472 5650 2824 8473 5648 2824 8474 5651 2825 8475 5652 2825 8476 5650 2825 8477 5653 2826 8478 5654 2826 8479 5652 2826 8480 5655 2827 8481 5656 2827 8482 5654 2827 8483 5657 2828 8484 5658 2828 8485 5656 2828 8486 5659 2829 8487 5660 2829 8488 5658 2829 8489 5661 2830 8490 5662 2830 8491 5660 2830 8492 5663 2831 8493 5664 2831 8494 5662 2831 8495 5665 2832 8496 5666 2832 8497 5664 2832 8498 5667 2833 8499 5668 2833 8500 5666 2833 8501 5669 2834 8502 5670 2834 8503 5668 2834 8504 5671 2835 8505 5672 2835 8506 5670 2835 8507 5673 2836 8508 5674 2836 8509 5672 2836 8510 5675 2837 8511 5676 2837 8512 5674 2837 8513 5677 2838 8514 5678 2838 8515 5676 2838 8516 5679 2839 8517 5680 2839 8518 5678 2839 8519 5681 2840 8520 5682 2840 8521 5680 2840 8522 5683 2841 8523 5684 2841 8524 5682 2841 8525 5685 2842 8526 5686 2842 8527 5684 2842 8528 5687 2843 8529 5688 2843 8530 5686 2843 8531 5689 2844 8532 5690 2844 8533 5688 2844 8534 5691 2845 8535 5692 2845 8536 5690 2845 8537 5693 2846 8538 5694 2846 8539 5692 2846 8540 5695 2847 8541 5696 2847 8542 5694 2847 8543 5697 2848 8544 5698 2848 8545 5696 2848 8546 5699 2849 8547 5700 2849 8548 5698 2849 8549 5701 2850 8550 5702 2850 8551 5700 2850 8552 5703 2851 8553 5704 2851 8554 5702 2851 8555 5705 2852 8556 5706 2852 8557 5704 2852 8558 5707 2853 8559 5708 2853 8560 5706 2853 8561 5709 2854 8562 5710 2854 8563 5708 2854 8564 5711 2855 8565 5712 2855 8566 5710 2855 8567 5713 2856 8568 5714 2856 8569 5712 2856 8570 5715 2857 8571 5716 2857 8572 5714 2857 8573 5717 2858 8574 5718 2858 8575 5716 2858 8576 5719 2859 8577 5720 2859 8578 5718 2859 8579 5721 2860 8580 5722 2860 8581 5720 2860 8582 5723 2861 8583 5724 2861 8584 5722 2861 8585 5725 2862 8586 5726 2862 8587 5724 2862 8588 5727 2863 8589 5728 2863 8590 5726 2863 8591 5729 2864 8592 5730 2864 8593 5728 2864 8594 5731 2865 8595 5732 2865 8596 5730 2865 8597 5733 2866 8598 5734 2866 8599 5732 2866 8600 5735 2867 8601 5736 2867 8602 5734 2867 8603 5737 2868 8604 5738 2868 8605 5736 2868 8606 5739 2869 8607 5740 2869 8608 5738 2869 8609 5741 2870 8610 5742 2870 8611 5740 2870 8612 5743 2871 8613 5744 2871 8614 5742 2871 8615 5745 2872 8616 5746 2872 8617 5744 2872 8618 5747 2873 8619 5748 2873 8620 5746 2873 8621 5749 2874 8622 5750 2874 8623 5748 2874 8624 5751 2875 8625 5752 2875 8626 5750 2875 8627 5753 2876 8628 5754 2876 8629 5752 2876 8630 5755 2877 8631 5756 2877 8632 5754 2877 8633 5757 2878 8634 5758 2878 8635 5756 2878 8636 5759 2879 8637 5760 2879 8638 5758 2879 8639 5761 2880 8640 5762 2880 8641 5760 2880 8642 5763 2881 8643 5764 2881 8644 5762 2881 8645 5765 2882 8646 5766 2882 8647 5764 2882 8648 5767 2883 8649 5768 2883 8650 5766 2883 8651 5769 2884 8652 5770 2884 8653 5768 2884 8654 5771 2885 8655 5772 2885 8656 5770 2885 8657 5773 2886 8658 5774 2886 8659 5772 2886 8660 5775 2887 8661 5776 2887 8662 5774 2887 8663 5777 2888 8664 5778 2888 8665 5776 2888 8666 5779 2889 8667 5780 2889 8668 5778 2889 8669 5781 2890 8670 5782 2890 8671 5780 2890 8672 5783 2891 8673 5784 2891 8674 5782 2891 8675 5785 2892 8676 5786 2892 8677 5784 2892 8678 5787 2893 8679 5788 2893 8680 5786 2893 8681 5789 2894 8682 5790 2894 8683 5788 2894 8684 5791 2895 8685 5792 2895 8686 5790 2895 8687 5793 2896 8688 5794 2896 8689 5792 2896 8690 5795 2897 8691 5796 2897 8692 5794 2897 8693 5797 2898 8694 5798 2898 8695 5796 2898 8696 5799 2899 8697 5800 2899 8698 5798 2899 8699 5801 2900 8700 5802 2900 8701 5800 2900 8702 5803 2901 8703 5804 2901 8704 5802 2901 8705 5805 2902 8706 5806 2902 8707 5804 2902 8708 5807 2903 8709 5808 2903 8710 5806 2903 8711 5809 2904 8712 5810 2904 8713 5808 2904 8714 5811 2905 8715 5812 2905 8716 5810 2905 8717 5813 2906 8718 5814 2906 8719 5812 2906 8720 5815 2907 8721 5816 2907 8722 5814 2907 8723 5817 2908 8724 5818 2908 8725 5816 2908 8726 5819 2909 8727 5820 2909 8728 5818 2909 8729 5821 2910 8730 5822 2910 8731 5820 2910 8732 5823 2911 8733 5824 2911 8734 5822 2911 8735 5825 2912 8736 5826 2912 8737 5824 2912 8738 5827 2913 8739 5828 2913 8740 5826 2913 8741 5829 2914 8742 5830 2914 8743 5828 2914 8744 5831 2915 8745 5832 2915 8746 5830 2915 8747 5833 2916 8748 5834 2916 8749 5832 2916 8750 5835 2917 8751 5836 2917 8752 5834 2917 8753 5837 2918 8754 5838 2918 8755 5836 2918 8756 5839 2919 8757 5840 2919 8758 5838 2919 8759 5841 2920 8760 5842 2920 8761 5840 2920 8762 5843 2921 8763 5844 2921 8764 5842 2921 8765 5845 2922 8766 5846 2922 8767 5844 2922 8768 5847 2923 8769 5848 2923 8770 5846 2923 8771 5849 2924 8772 5850 2924 8773 5848 2924 8774 5851 2925 8775 5852 2925 8776 5850 2925 8777 5853 2926 8778 5854 2926 8779 5852 2926 8780 5855 2927 8781 5856 2927 8782 5854 2927 8783 5857 2928 8784 5858 2928 8785 5856 2928 8786 5859 2929 8787 5860 2929 8788 5858 2929 8789 5861 2930 8790 5862 2930 8791 5860 2930 8792 5863 2931 8793 5864 2931 8794 5862 2931 8795 5865 2932 8796 5866 2932 8797 5864 2932 8798 5867 2933 8799 5868 2933 8800 5866 2933 8801 5869 2934 8802 5870 2934 8803 5868 2934 8804 5871 2935 8805 5872 2935 8806 5870 2935 8807 5873 2936 8808 5874 2936 8809 5872 2936 8810 5875 2937 8811 5876 2937 8812 5874 2937 8813 5877 2938 8814 5878 2938 8815 5876 2938 8816 5879 2939 8817 5880 2939 8818 5878 2939 8819 5881 2940 8820 5882 2940 8821 5880 2940 8822 5883 2941 8823 5884 2941 8824 5882 2941 8825 5885 2942 8826 5886 2942 8827 5884 2942 8828 5887 2943 8829 5888 2943 8830 5886 2943 8831 5889 2944 8832 5890 2944 8833 5888 2944 8834 5891 2945 8835 5892 2945 8836 5890 2945 8837 5893 2946 8838 5894 2946 8839 5892 2946 8840 5895 2947 8841 5896 2947 8842 5894 2947 8843 5897 2948 8844 5898 2948 8845 5896 2948 8846 5899 2949 8847 5900 2949 8848 5898 2949 8849 5901 2950 8850 5902 2950 8851 5900 2950 8852 5903 2951 8853 5904 2951 8854 5902 2951 8855 5905 2952 8856 5906 2952 8857 5904 2952 8858 5907 2953 8859 5908 2953 8860 5906 2953 8861 5909 2954 8862 5910 2954 8863 5908 2954 8864 5911 2955 8865 5912 2955 8866 5910 2955 8867 5913 2956 8868 5914 2956 8869 5912 2956 8870 5915 2957 8871 5916 2957 8872 5914 2957 8873 5917 2958 8874 5918 2958 8875 5916 2958 8876 5919 2959 8877 5920 2959 8878 5918 2959 8879 5921 2960 8880 5922 2960 8881 5920 2960 8882 5923 2961 8883 5924 2961 8884 5922 2961 8885 5925 2962 8886 5926 2962 8887 5924 2962 8888 5927 2963 8889 5928 2963 8890 5926 2963 8891 5929 2964 8892 5930 2964 8893 5928 2964 8894 5931 2965 8895 5932 2965 8896 5930 2965 8897 5933 2966 8898 5934 2966 8899 5932 2966 8900 5935 2967 8901 5936 2967 8902 5934 2967 8903 5937 2968 8904 5938 2968 8905 5936 2968 8906 5939 2969 8907 5940 2969 8908 5938 2969 8909 5941 2970 8910 5942 2970 8911 5940 2970 8912 5943 2971 8913 5944 2971 8914 5942 2971 8915 5945 2972 8916 5946 2972 8917 5944 2972 8918 5947 2973 8919 5948 2973 8920 5946 2973 8921 5949 2974 8922 5950 2974 8923 5948 2974 8924 5951 2975 8925 5952 2975 8926 5950 2975 8927 5953 2976 8928 5954 2976 8929 5952 2976 8930 5955 2977 8931 5956 2977 8932 5954 2977 8933 5957 2978 8934 5958 2978 8935 5956 2978 8936 5959 2979 8937 5960 2979 8938 5958 2979 8939 5961 2980 8940 5962 2980 8941 5960 2980 8942 5963 2981 8943 5964 2981 8944 5962 2981 8945 5965 2982 8946 5966 2982 8947 5964 2982 8948 5967 2983 8949 5968 2983 8950 5966 2983 8951 5969 2984 8952 5970 2984 8953 5968 2984 8954 5971 2985 8955 5972 2985 8956 5970 2985 8957 5973 2986 8958 5974 2986 8959 5972 2986 8960 5975 2987 8961 5976 2987 8962 5974 2987 8963 5977 2988 8964 5978 2988 8965 5976 2988 8966 5979 2989 8967 5980 2989 8968 5978 2989 8969 5981 2990 8970 5982 2990 8971 5980 2990 8972 5983 2991 8973 5984 2991 8974 5982 2991 8975 5985 2992 8976 5986 2992 8977 5984 2992 8978 5987 2993 8979 5988 2993 8980 5986 2993 8981 5989 2994 8982 5990 2994 8983 5988 2994 8984 5991 2995 8985 5992 2995 8986 5990 2995 8987 5993 2996 8988 5994 2996 8989 5992 2996 8990 5995 2997 8991 5996 2997 8992 5994 2997 8993 5997 2998 8994 5998 2998 8995 5996 2998 8996 5999 2999 8997 6000 2999 8998 5998 2999 8999 6001 3000 9000 6002 3000 9001 6000 3000 9002 6003 3001 9003 6004 3001 9004 6002 3001 9005 6005 3002 9006 6006 3002 9007 6004 3002 9008 6007 3003 9009 6008 3003 9010 6006 3003 9011 6009 3004 9012 6010 3004 9013 6008 3004 9014 6011 3005 9015 6012 3005 9016 6010 3005 9017 6013 3006 9018 6014 3006 9019 6012 3006 9020 6015 3007 9021 6016 3007 9022 6014 3007 9023 6017 3008 9024 6018 3008 9025 6016 3008 9026 6019 3009 9027 6020 3009 9028 6018 3009 9029 6021 3010 9030 6022 3010 9031 6020 3010 9032 6023 3011 9033 6024 3011 9034 6022 3011 9035 6025 3012 9036 6026 3012 9037 6024 3012 9038 6027 3013 9039 6028 3013 9040 6026 3013 9041 6029 3014 9042 6030 3014 9043 6028 3014 9044 6031 3015 9045 6032 3015 9046 6030 3015 9047 6033 3016 9048 6034 3016 9049 6032 3016 9050 6035 3017 9051 6036 3017 9052 6034 3017 9053 6037 3018 9054 6038 3018 9055 6036 3018 9056 6039 3019 9057 6040 3019 9058 6038 3019 9059 6041 3020 9060 6042 3020 9061 6040 3020 9062 6043 3021 9063 6044 3021 9064 6042 3021 9065 6045 3022 9066 6046 3022 9067 6044 3022 9068 6047 3023 9069 6048 3023 9070 6046 3023 9071 6049 3024 9072 6050 3024 9073 6048 3024 9074 6051 3025 9075 6052 3025 9076 6050 3025 9077 6053 3026 9078 6054 3026 9079 6052 3026 9080 6055 3027 9081 6056 3027 9082 6054 3027 9083 6057 3028 9084 6058 3028 9085 6056 3028 9086 6059 3029 9087 6060 3029 9088 6058 3029 9089 6061 3030 9090 6062 3030 9091 6060 3030 9092 6063 3031 9093 6064 3031 9094 6062 3031 9095 6065 3032 9096 6066 3032 9097 6064 3032 9098 6067 3033 9099 6068 3033 9100 6066 3033 9101 6069 3034 9102 6070 3034 9103 6068 3034 9104 6071 3035 9105 6072 3035 9106 6070 3035 9107 6073 3036 9108 6074 3036 9109 6072 3036 9110 6075 3037 9111 6076 3037 9112 6074 3037 9113 6077 3038 9114 6078 3038 9115 6076 3038 9116 6079 3039 9117 6080 3039 9118 6078 3039 9119 6081 3040 9120 6082 3040 9121 6080 3040 9122 6083 3041 9123 6084 3041 9124 6082 3041 9125 6085 3042 9126 6086 3042 9127 6084 3042 9128 6087 3043 9129 6088 3043 9130 6086 3043 9131 6089 3044 9132 6090 3044 9133 6088 3044 9134 6091 3045 9135 6092 3045 9136 6090 3045 9137 6093 3046 9138 6094 3046 9139 6092 3046 9140 6095 3047 9141 6096 3047 9142 6094 3047 9143 6097 3048 9144 6098 3048 9145 6096 3048 9146 6099 3049 9147 6100 3049 9148 6098 3049 9149 6101 3050 9150 6102 3050 9151 6100 3050 9152 6103 3051 9153 6104 3051 9154 6102 3051 9155 6105 3052 9156 6106 3052 9157 6104 3052 9158 6107 3053 9159 6108 3053 9160 6106 3053 9161 6109 3054 9162 6110 3054 9163 6108 3054 9164 6111 3055 9165 6112 3055 9166 6110 3055 9167 6113 3056 9168 6114 3056 9169 6112 3056 9170 6115 3057 9171 6116 3057 9172 6114 3057 9173 6117 3058 9174 6118 3058 9175 6116 3058 9176 6119 3059 9177 6120 3059 9178 6118 3059 9179 6121 3060 9180 6122 3060 9181 6120 3060 9182 6123 3061 9183 6124 3061 9184 6122 3061 9185 6125 3062 9186 6126 3062 9187 6124 3062 9188 6127 3063 9189 6128 3063 9190 6126 3063 9191 6129 3064 9192 6130 3064 9193 6128 3064 9194 6131 3065 9195 6132 3065 9196 6130 3065 9197 6133 3066 9198 6134 3066 9199 6132 3066 9200 6135 3067 9201 6136 3067 9202 6134 3067 9203 6137 3068 9204 6138 3068 9205 6136 3068 9206 6139 3069 9207 6140 3069 9208 6138 3069 9209 6141 3070 9210 6142 3070 9211 6140 3070 9212 6143 3071 9213 6144 3071 9214 6142 3071 9215 6145 3072 9216 6146 3072 9217 6144 3072 9218 6147 3073 9219 6148 3073 9220 6146 3073 9221 6149 3074 9222 6150 3074 9223 6148 3074 9224 6151 3075 9225 6152 3075 9226 6150 3075 9227 6153 3076 9228 6154 3076 9229 6152 3076 9230 6155 3077 9231 6156 3077 9232 6154 3077 9233 6157 3078 9234 6158 3078 9235 6156 3078 9236 6159 3079 9237 6160 3079 9238 6158 3079 9239 6161 3080 9240 6162 3080 9241 6160 3080 9242 6163 3081 9243 6164 3081 9244 6162 3081 9245 6165 3082 9246 6166 3082 9247 6164 3082 9248 6167 3083 9249 6168 3083 9250 6166 3083 9251 6169 3084 9252 6170 3084 9253 6168 3084 9254 6171 3085 9255 6172 3085 9256 6170 3085 9257 6173 3086 9258 6174 3086 9259 6172 3086 9260 6175 3087 9261 6176 3087 9262 6174 3087 9263 6177 3088 9264 6178 3088 9265 6176 3088 9266 6179 3089 9267 6180 3089 9268 6178 3089 9269 6181 3090 9270 6182 3090 9271 6180 3090 9272 6183 3091 9273 6184 3091 9274 6182 3091 9275 6185 3092 9276 6186 3092 9277 6184 3092 9278 6187 3093 9279 6188 3093 9280 6186 3093 9281 6189 3094 9282 6190 3094 9283 6188 3094 9284 6191 3095 9285 6192 3095 9286 6190 3095 9287 6193 3096 9288 6194 3096 9289 6192 3096 9290 6195 3097 9291 6196 3097 9292 6194 3097 9293 6197 3098 9294 6198 3098 9295 6196 3098 9296 6199 3099 9297 6200 3099 9298 6198 3099 9299 6201 3100 9300 6202 3100 9301 6200 3100 9302 6203 3101 9303 6204 3101 9304 6202 3101 9305 6205 3102 9306 6206 3102 9307 6204 3102 9308 6207 3103 9309 6208 3103 9310 6206 3103 9311 6209 3104 9312 6210 3104 9313 6208 3104 9314 6211 3105 9315 6212 3105 9316 6210 3105 9317 6213 3106 9318 6214 3106 9319 6212 3106 9320 6215 3107 9321 6216 3107 9322 6214 3107 9323 6217 3108 9324 6218 3108 9325 6216 3108 9326 6219 3109 9327 6220 3109 9328 6218 3109 9329 6221 3110 9330 6222 3110 9331 6220 3110 9332 6223 3111 9333 6224 3111 9334 6222 3111 9335 6225 3112 9336 6226 3112 9337 6224 3112 9338 6227 3113 9339 6228 3113 9340 6226 3113 9341 6229 3114 9342 6230 3114 9343 6228 3114 9344 6231 3115 9345 6232 3115 9346 6230 3115 9347 6233 3116 9348 6234 3116 9349 6232 3116 9350 6235 3117 9351 6236 3117 9352 6234 3117 9353 6237 3118 9354 6238 3118 9355 6236 3118 9356 6239 3119 9357 6240 3119 9358 6238 3119 9359 6241 3120 9360 6242 3120 9361 6240 3120 9362 6243 3121 9363 6244 3121 9364 6242 3121 9365 6245 3122 9366 6246 3122 9367 6244 3122 9368 6247 3123 9369 6248 3123 9370 6246 3123 9371 6249 3124 9372 6250 3124 9373 6248 3124 9374 6251 3125 9375 6252 3125 9376 6250 3125 9377 6253 3126 9378 6254 3126 9379 6252 3126 9380 6255 3127 9381 6256 3127 9382 6254 3127 9383 6257 3128 9384 6258 3128 9385 6256 3128 9386 6259 3129 9387 6260 3129 9388 6258 3129 9389 6261 3130 9390 6262 3130 9391 6260 3130 9392 6263 3131 9393 6264 3131 9394 6262 3131 9395 6265 3132 9396 6266 3132 9397 6264 3132 9398 6267 3133 9399 6268 3133 9400 6266 3133 9401 6269 3134 9402 6270 3134 9403 6268 3134 9404 6271 3135 9405 6272 3135 9406 6270 3135 9407 6273 3136 9408 6274 3136 9409 6272 3136 9410 6275 3137 9411 6276 3137 9412 6274 3137 9413 6277 3138 9414 6278 3138 9415 6276 3138 9416 6279 3139 9417 6280 3139 9418 6278 3139 9419 6281 3140 9420 6282 3140 9421 6280 3140 9422 6283 3141 9423 6284 3141 9424 6282 3141 9425 6285 3142 9426 6286 3142 9427 6284 3142 9428 6287 3143 9429 6288 3143 9430 6286 3143 9431 6289 3144 9432 6290 3144 9433 6288 3144 9434 6291 3145 9435 6292 3145 9436 6290 3145 9437 6293 3146 9438 6294 3146 9439 6292 3146 9440 6295 3147 9441 6296 3147 9442 6294 3147 9443 6297 3148 9444 6298 3148 9445 6296 3148 9446 6299 3149 9447 6300 3149 9448 6298 3149 9449 6301 3150 9450 6302 3150 9451 6300 3150 9452 6303 3151 9453 6304 3151 9454 6302 3151 9455 6305 3152 9456 6306 3152 9457 6304 3152 9458 6307 3153 9459 6308 3153 9460 6306 3153 9461 6309 3154 9462 6310 3154 9463 6308 3154 9464 6311 3155 9465 6312 3155 9466 6310 3155 9467 6313 3156 9468 6314 3156 9469 6312 3156 9470 6315 3157 9471 6316 3157 9472 6314 3157 9473 6317 3158 9474 6318 3158 9475 6316 3158 9476 6319 3159 9477 6320 3159 9478 6318 3159 9479 6321 3160 9480 6322 3160 9481 6320 3160 9482 6323 3161 9483 6324 3161 9484 6322 3161 9485 6325 3162 9486 6326 3162 9487 6324 3162 9488 6327 3163 9489 6328 3163 9490 6326 3163 9491 6329 3164 9492 6330 3164 9493 6328 3164 9494 6331 3165 9495 6332 3165 9496 6330 3165 9497 6333 3166 9498 6334 3166 9499 6332 3166 9500 6335 3167 9501 6336 3167 9502 6334 3167 9503 6337 3168 9504 6338 3168 9505 6336 3168 9506 6339 3169 9507 6340 3169 9508 6338 3169 9509 6341 3170 9510 6342 3170 9511 6340 3170 9512 6343 3171 9513 6344 3171 9514 6342 3171 9515 6345 3172 9516 6346 3172 9517 6344 3172 9518 6347 3173 9519 6348 3173 9520 6346 3173 9521 6349 3174 9522 6350 3174 9523 6348 3174 9524 6351 3175 9525 6352 3175 9526 6350 3175 9527 6353 3176 9528 6354 3176 9529 6352 3176 9530 6355 3177 9531 6356 3177 9532 6354 3177 9533 6357 3178 9534 6358 3178 9535 6356 3178 9536 6359 3179 9537 6360 3179 9538 6358 3179 9539 6361 3180 9540 6362 3180 9541 6360 3180 9542 6363 3181 9543 6364 3181 9544 6362 3181 9545 6365 3182 9546 6366 3182 9547 6364 3182 9548 6367 3183 9549 6368 3183 9550 6366 3183 9551 6369 3184 9552 6370 3184 9553 6368 3184 9554 6371 3185 9555 6372 3185 9556 6370 3185 9557 6373 3186 9558 6374 3186 9559 6372 3186 9560 6375 3187 9561 6376 3187 9562 6374 3187 9563 6377 3188 9564 6378 3188 9565 6376 3188 9566 6379 3189 9567 6380 3189 9568 6378 3189 9569 6381 3190 9570 6382 3190 9571 6380 3190 9572 6383 3191 9573 6384 3191 9574 6382 3191 9575 6385 3192 9576 6386 3192 9577 6384 3192 9578 6387 3193 9579 6388 3193 9580 6386 3193 9581 6389 3194 9582 6390 3194 9583 6388 3194 9584 6391 3195 9585 6392 3195 9586 6390 3195 9587 6393 3196 9588 6394 3196 9589 6392 3196 9590 6395 3197 9591 6396 3197 9592 6394 3197 9593 6397 3198 9594 6398 3198 9595 6396 3198 9596 6399 3199 9597 6400 3199 9598 6398 3199 9599 6401 3200 9600 6402 3200 9601 6400 3200 9602 6403 3201 9603 6404 3201 9604 6402 3201 9605 6405 3202 9606 6406 3202 9607 6404 3202 9608 6407 3203 9609 6408 3203 9610 6406 3203 9611 6409 3204 9612 6410 3204 9613 6408 3204 9614 6411 3205 9615 6412 3205 9616 6410 3205 9617 6413 3206 9618 6414 3206 9619 6412 3206 9620 6415 3207 9621 6416 3207 9622 6414 3207 9623 6417 3208 9624 6418 3208 9625 6416 3208 9626 6419 3209 9627 6420 3209 9628 6418 3209 9629 6421 3210 9630 6422 3210 9631 6420 3210 9632 6423 3211 9633 6424 3211 9634 6422 3211 9635 6425 3212 9636 6426 3212 9637 6424 3212 9638 6427 3213 9639 6428 3213 9640 6426 3213 9641 6429 3214 9642 6430 3214 9643 6428 3214 9644 6431 3215 9645 6432 3215 9646 6430 3215 9647 6433 3216 9648 6434 3216 9649 6432 3216 9650 6435 3217 9651 6436 3217 9652 6434 3217 9653 6437 3218 9654 6438 3218 9655 6436 3218 9656 6439 3219 9657 6440 3219 9658 6438 3219 9659 6441 3220 9660 6442 3220 9661 6440 3220 9662 6443 3221 9663 6444 3221 9664 6442 3221 9665 6445 3222 9666 6446 3222 9667 6444 3222 9668 6447 3223 9669 6448 3223 9670 6446 3223 9671 6449 3224 9672 6450 3224 9673 6448 3224 9674 6451 3225 9675 6452 3225 9676 6450 3225 9677 6453 3226 9678 6454 3226 9679 6452 3226 9680 6455 3227 9681 6456 3227 9682 6454 3227 9683 6457 3228 9684 6458 3228 9685 6456 3228 9686 6459 3229 9687 6460 3229 9688 6458 3229 9689 6461 3230 9690 6462 3230 9691 6460 3230 9692 6463 3231 9693 6464 3231 9694 6462 3231 9695 6465 3232 9696 6466 3232 9697 6464 3232 9698 6467 3233 9699 6468 3233 9700 6466 3233 9701 6469 3234 9702 6470 3234 9703 6468 3234 9704 6471 3235 9705 6472 3235 9706 6470 3235 9707 6473 3236 9708 6474 3236 9709 6472 3236 9710 6475 3237 9711 6476 3237 9712 6474 3237 9713 6477 3238 9714 6478 3238 9715 6476 3238 9716 6479 3239 9717 6480 3239 9718 6478 3239 9719 6481 3240 9720 6482 3240 9721 6480 3240 9722 6483 3241 9723 6484 3241 9724 6482 3241 9725 6485 3242 9726 6486 3242 9727 6484 3242 9728 6487 3243 9729 6488 3243 9730 6486 3243 9731 6489 3244 9732 6490 3244 9733 6488 3244 9734 6491 3245 9735 6492 3245 9736 6490 3245 9737 6493 3246 9738 6494 3246 9739 6492 3246 9740 6495 3247 9741 6496 3247 9742 6494 3247 9743 6497 3248 9744 6498 3248 9745 6496 3248 9746 6499 3249 9747 6500 3249 9748 6498 3249 9749 6501 3250 9750 6502 3250 9751 6500 3250 9752 6503 3251 9753 6504 3251 9754 6502 3251 9755 6505 3252 9756 6506 3252 9757 6504 3252 9758 6507 3253 9759 6508 3253 9760 6506 3253 9761 6509 3254 9762 6510 3254 9763 6508 3254 9764 6511 3255 9765 6512 3255 9766 6510 3255 9767 6513 3256 9768 6514 3256 9769 6512 3256 9770 6515 3257 9771 6516 3257 9772 6514 3257 9773 6517 3258 9774 6518 3258 9775 6516 3258 9776 6519 3259 9777 6520 3259 9778 6518 3259 9779 6521 3260 9780 6522 3260 9781 6520 3260 9782 6523 3261 9783 6524 3261 9784 6522 3261 9785 6525 3262 9786 6526 3262 9787 6524 3262 9788 6527 3263 9789 6528 3263 9790 6526 3263 9791 6529 3264 9792 6530 3264 9793 6528 3264 9794 6531 3265 9795 6532 3265 9796 6530 3265 9797 6533 3266 9798 6534 3266 9799 6532 3266 9800 6535 3267 9801 6536 3267 9802 6534 3267 9803 6537 3268 9804 6538 3268 9805 6536 3268 9806 6539 3269 9807 6540 3269 9808 6538 3269 9809 6541 3270 9810 6542 3270 9811 6540 3270 9812 6543 3271 9813 6544 3271 9814 6542 3271 9815 6545 3272 9816 6546 3272 9817 6544 3272 9818 6547 3273 9819 6548 3273 9820 6546 3273 9821 6549 3274 9822 6550 3274 9823 6548 3274 9824 6551 3275 9825 6552 3275 9826 6550 3275 9827 6553 3276 9828 6554 3276 9829 6552 3276 9830 6555 3277 9831 6556 3277 9832 6554 3277 9833 6557 3278 9834 6558 3278 9835 6556 3278 9836 6559 3279 9837 6560 3279 9838 6558 3279 9839 6561 3280 9840 6562 3280 9841 6560 3280 9842 6563 3281 9843 6564 3281 9844 6562 3281 9845 6565 3282 9846 6566 3282 9847 6564 3282 9848 6567 3283 9849 6568 3283 9850 6566 3283 9851 6569 3284 9852 6570 3284 9853 6568 3284 9854 6571 3285 9855 6572 3285 9856 6570 3285 9857 6573 3286 9858 6574 3286 9859 6572 3286 9860 6575 3287 9861 6576 3287 9862 6574 3287 9863 6577 3288 9864 6578 3288 9865 6576 3288 9866 6579 3289 9867 6580 3289 9868 6578 3289 9869 6581 3290 9870 6582 3290 9871 6580 3290 9872 6583 3291 9873 6584 3291 9874 6582 3291 9875 6585 3292 9876 6586 3292 9877 6584 3292 9878 6587 3293 9879 6588 3293 9880 6586 3293 9881 6589 3294 9882 6590 3294 9883 6588 3294 9884 6591 3295 9885 6592 3295 9886 6590 3295 9887 6593 3296 9888 6594 3296 9889 6592 3296 9890 6595 3297 9891 6596 3297 9892 6594 3297 9893 6597 3298 9894 6598 3298 9895 6596 3298 9896 6599 3299 9897 6600 3299 9898 6598 3299 9899 6601 3300 9900 6602 3300 9901 6600 3300 9902 6603 3301 9903 6604 3301 9904 6602 3301 9905 6605 3302 9906 6606 3302 9907 6604 3302 9908 6607 3303 9909 6608 3303 9910 6606 3303 9911 6609 3304 9912 6610 3304 9913 6608 3304 9914 6611 3305 9915 6612 3305 9916 6610 3305 9917 6613 3306 9918 6614 3306 9919 6612 3306 9920 6615 3307 9921 6616 3307 9922 6614 3307 9923 6617 3308 9924 6618 3308 9925 6616 3308 9926 6619 3309 9927 6620 3309 9928 6618 3309 9929 6621 3310 9930 6622 3310 9931 6620 3310 9932 6623 3311 9933 6624 3311 9934 6622 3311 9935 6625 3312 9936 6626 3312 9937 6624 3312 9938 6627 3313 9939 6628 3313 9940 6626 3313 9941 6629 3314 9942 6630 3314 9943 6628 3314 9944 6631 3315 9945 6632 3315 9946 6630 3315 9947 6633 3316 9948 6634 3316 9949 6632 3316 9950 6635 3317 9951 6636 3317 9952 6634 3317 9953 6637 3318 9954 6638 3318 9955 6636 3318 9956 6639 3319 9957 6640 3319 9958 6638 3319 9959 6641 3320 9960 6642 3320 9961 6640 3320 9962 6643 3321 9963 6644 3321 9964 6642 3321 9965 6645 3322 9966 6646 3322 9967 6644 3322 9968 6647 3323 9969 6648 3323 9970 6646 3323 9971 6649 3324 9972 6650 3324 9973 6648 3324 9974 6651 3325 9975 6652 3325 9976 6650 3325 9977 6653 3326 9978 6654 3326 9979 6652 3326 9980 6655 3327 9981 6656 3327 9982 6654 3327 9983 6657 3328 9984 6658 3328 9985 6656 3328 9986 6659 3329 9987 6660 3329 9988 6658 3329 9989 6661 3330 9990 6662 3330 9991 6660 3330 9992 6663 3331 9993 6664 3331 9994 6662 3331 9995 6665 3332 9996 6666 3332 9997 6664 3332 9998 6667 3333 9999 6668 3333 10000 6666 3333 10001 6669 3334 10002 6670 3334 10003 6668 3334 10004 6671 3335 10005 6672 3335 10006 6670 3335 10007 6673 3336 10008 6674 3336 10009 6672 3336 10010 6675 3337 10011 6676 3337 10012 6674 3337 10013 6677 3338 10014 6678 3338 10015 6676 3338 10016 6679 3339 10017 6680 3339 10018 6678 3339 10019 6681 3340 10020 6682 3340 10021 6680 3340 10022 6683 3341 10023 6684 3341 10024 6682 3341 10025 6685 3342 10026 6686 3342 10027 6684 3342 10028 6687 3343 10029 6688 3343 10030 6686 3343 10031 6689 3344 10032 6690 3344 10033 6688 3344 10034 6691 3345 10035 6692 3345 10036 6690 3345 10037 6693 3346 10038 6694 3346 10039 6692 3346 10040 6695 3347 10041 6696 3347 10042 6694 3347 10043 6697 3348 10044 6698 3348 10045 6696 3348 10046 6699 3349 10047 6700 3349 10048 6698 3349 10049 6701 3350 10050 6702 3350 10051 6700 3350 10052 6703 3351 10053 6704 3351 10054 6702 3351 10055 6705 3352 10056 6706 3352 10057 6704 3352 10058 6707 3353 10059 6708 3353 10060 6706 3353 10061 6709 3354 10062 6710 3354 10063 6708 3354 10064 6711 3355 10065 6712 3355 10066 6710 3355 10067 6713 3356 10068 6714 3356 10069 6712 3356 10070 6715 3357 10071 6716 3357 10072 6714 3357 10073 6717 3358 10074 6718 3358 10075 6716 3358 10076 6719 3359 10077 6720 3359 10078 6718 3359 10079 6721 3360 10080 6722 3360 10081 6720 3360 10082 6723 3361 10083 6724 3361 10084 6722 3361 10085 6725 3362 10086 6726 3362 10087 6724 3362 10088 6727 3363 10089 6728 3363 10090 6726 3363 10091 6729 3364 10092 6730 3364 10093 6728 3364 10094 6731 3365 10095 6732 3365 10096 6730 3365 10097 6733 3366 10098 6734 3366 10099 6732 3366 10100 6735 3367 10101 6736 3367 10102 6734 3367 10103 6737 3368 10104 6738 3368 10105 6736 3368 10106 6739 3369 10107 6740 3369 10108 6738 3369 10109 6741 3370 10110 6742 3370 10111 6740 3370 10112 6743 3371 10113 6744 3371 10114 6742 3371 10115 6745 3372 10116 6746 3372 10117 6744 3372 10118 6747 3373 10119 6748 3373 10120 6746 3373 10121 6749 3374 10122 6750 3374 10123 6748 3374 10124 6751 3375 10125 6752 3375 10126 6750 3375 10127 6753 3376 10128 6754 3376 10129 6752 3376 10130 6755 3377 10131 6756 3377 10132 6754 3377 10133 6757 3378 10134 6758 3378 10135 6756 3378 10136 6759 3379 10137 6760 3379 10138 6758 3379 10139 6761 3380 10140 6762 3380 10141 6760 3380 10142 6763 3381 10143 6764 3381 10144 6762 3381 10145 6765 3382 10146 6766 3382 10147 6764 3382 10148 6767 3383 10149 6768 3383 10150 6766 3383 10151 6769 3384 10152 6770 3384 10153 6768 3384 10154 6771 3385 10155 6772 3385 10156 6770 3385 10157 6773 3386 10158 6774 3386 10159 6772 3386 10160 6775 3387 10161 6776 3387 10162 6774 3387 10163 6777 3388 10164 6778 3388 10165 6776 3388 10166 6779 3389 10167 6780 3389 10168 6778 3389 10169 6781 3390 10170 6782 3390 10171 6780 3390 10172 6783 3391 10173 6784 3391 10174 6782 3391 10175 6785 3392 10176 6786 3392 10177 6784 3392 10178 6787 3393 10179 6788 3393 10180 6786 3393 10181 6789 3394 10182 6790 3394 10183 6788 3394 10184 6791 3395 10185 6792 3395 10186 6790 3395 10187 6793 3396 10188 6794 3396 10189 6792 3396 10190 6795 3397 10191 6796 3397 10192 6794 3397 10193 6797 3398 10194 6798 3398 10195 6796 3398 10196 6799 3399 10197 6800 3399 10198 6798 3399 10199 6801 3400 10200 6802 3400 10201 6800 3400 10202 6803 3401 10203 6804 3401 10204 6802 3401 10205 6805 3402 10206 6806 3402 10207 6804 3402 10208 6807 3403 10209 6808 3403 10210 6806 3403 10211 6809 3404 10212 6810 3404 10213 6808 3404 10214 6811 3405 10215 6812 3405 10216 6810 3405 10217 6813 3406 10218 6814 3406 10219 6812 3406 10220 6815 3407 10221 6816 3407 10222 6814 3407 10223 6817 3408 10224 6818 3408 10225 6816 3408 10226 6819 3409 10227 6820 3409 10228 6818 3409 10229 6821 3410 10230 6822 3410 10231 6820 3410 10232 6823 3411 10233 6824 3411 10234 6822 3411 10235 6825 3412 10236 6826 3412 10237 6824 3412 10238 6827 3413 10239 6828 3413 10240 6826 3413 10241 6829 3414 10242 6830 3414 10243 6828 3414 10244 6831 3415 10245 6832 3415 10246 6830 3415 10247 6833 3416 10248 6834 3416 10249 6832 3416 10250 6835 3417 10251 6836 3417 10252 6834 3417 10253 6837 3418 10254 6838 3418 10255 6836 3418 10256 6839 3419 10257 6840 3419 10258 6838 3419 10259 6841 3420 10260 6842 3420 10261 6840 3420 10262 6843 3421 10263 6844 3421 10264 6842 3421 10265 6845 3422 10266 6846 3422 10267 6844 3422 10268 6847 3423 10269 6848 3423 10270 6846 3423 10271 6849 3424 10272 6850 3424 10273 6848 3424 10274 6851 3425 10275 6852 3425 10276 6850 3425 10277 6853 3426 10278 6854 3426 10279 6852 3426 10280 6855 3427 10281 6856 3427 10282 6854 3427 10283 6857 3428 10284 6858 3428 10285 6856 3428 10286 6859 3429 10287 6860 3429 10288 6858 3429 10289 6861 3430 10290 6862 3430 10291 6860 3430 10292 6863 3431 10293 6864 3431 10294 6862 3431 10295 6865 3432 10296 6866 3432 10297 6864 3432 10298 6867 3433 10299 6868 3433 10300 6866 3433 10301 6869 3434 10302 6870 3434 10303 6868 3434 10304 6871 3435 10305 6872 3435 10306 6870 3435 10307 6873 3436 10308 6874 3436 10309 6872 3436 10310 6875 3437 10311 6876 3437 10312 6874 3437 10313 6877 3438 10314 6878 3438 10315 6876 3438 10316 6879 3439 10317 6880 3439 10318 6878 3439 10319 6881 3440 10320 6882 3440 10321 6880 3440 10322 6883 3441 10323 6884 3441 10324 6882 3441 10325 6885 3442 10326 6886 3442 10327 6884 3442 10328 6887 3443 10329 6888 3443 10330 6886 3443 10331 6889 3444 10332 6890 3444 10333 6888 3444 10334 6891 3445 10335 6892 3445 10336 6890 3445 10337 6893 3446 10338 6894 3446 10339 6892 3446 10340 6895 3447 10341 6896 3447 10342 6894 3447 10343 6897 3448 10344 6898 3448 10345 6896 3448 10346 6899 3449 10347 6900 3449 10348 6898 3449 10349 6901 3450 10350 6902 3450 10351 6900 3450 10352 6903 3451 10353 6904 3451 10354 6902 3451 10355 6905 3452 10356 6906 3452 10357 6904 3452 10358 6907 3453 10359 6908 3453 10360 6906 3453 10361 6909 3454 10362 6910 3454 10363 6908 3454 10364 6911 3455 10365 6912 3455 10366 6910 3455 10367 6913 3456 10368 6914 3456 10369 6912 3456 10370 6915 3457 10371 6916 3457 10372 6914 3457 10373 6917 3458 10374 6918 3458 10375 6916 3458 10376 6919 3459 10377 6920 3459 10378 6918 3459 10379 6921 3460 10380 6922 3460 10381 6920 3460 10382 6923 3461 10383 6924 3461 10384 6922 3461 10385 6925 3462 10386 6926 3462 10387 6924 3462 10388 6927 3463 10389 6928 3463 10390 6926 3463 10391 6929 3464 10392 6930 3464 10393 6928 3464 10394 6931 3465 10395 6932 3465 10396 6930 3465 10397 6933 3466 10398 6934 3466 10399 6932 3466 10400 6935 3467 10401 6936 3467 10402 6934 3467 10403 6937 3468 10404 6938 3468 10405 6936 3468 10406 6939 3469 10407 6940 3469 10408 6938 3469 10409 6941 3470 10410 6942 3470 10411 6940 3470 10412 6943 3471 10413 6944 3471 10414 6942 3471 10415 6945 3472 10416 6946 3472 10417 6944 3472 10418 6947 3473 10419 6948 3473 10420 6946 3473 10421 6949 3474 10422 6950 3474 10423 6948 3474 10424 6951 3475 10425 6952 3475 10426 6950 3475 10427 6953 3476 10428 6954 3476 10429 6952 3476 10430 6955 3477 10431 6956 3477 10432 6954 3477 10433 6957 3478 10434 6958 3478 10435 6956 3478 10436 6959 3479 10437 6960 3479 10438 6958 3479 10439 6961 3480 10440 6962 3480 10441 6960 3480 10442 6963 3481 10443 6964 3481 10444 6962 3481 10445 6965 3482 10446 6966 3482 10447 6964 3482 10448 6967 3483 10449 6968 3483 10450 6966 3483 10451 6969 3484 10452 6970 3484 10453 6968 3484 10454 6971 3485 10455 6972 3485 10456 6970 3485 10457 6973 3486 10458 6974 3486 10459 6972 3486 10460 6975 3487 10461 6976 3487 10462 6974 3487 10463 6977 3488 10464 6978 3488 10465 6976 3488 10466 6979 3489 10467 6980 3489 10468 6978 3489 10469 6981 3490 10470 6982 3490 10471 6980 3490 10472 6983 3491 10473 6984 3491 10474 6982 3491 10475 6985 3492 10476 6986 3492 10477 6984 3492 10478 6987 3493 10479 6988 3493 10480 6986 3493 10481 6989 3494 10482 6990 3494 10483 6988 3494 10484 6991 3495 10485 6992 3495 10486 6990 3495 10487 6993 3496 10488 6994 3496 10489 6992 3496 10490 6995 3497 10491 6996 3497 10492 6994 3497 10493 6997 3498 10494 6998 3498 10495 6996 3498 10496 6999 3499 10497 7000 3499 10498 6998 3499 10499 7001 3500 10500 7002 3500 10501 7000 3500 10502 7003 3501 10503 7004 3501 10504 7002 3501 10505 7005 3502 10506 7006 3502 10507 7004 3502 10508 7007 3503 10509 7008 3503 10510 7006 3503 10511 7009 3504 10512 7010 3504 10513 7008 3504 10514 7011 3505 10515 7012 3505 10516 7010 3505 10517 7013 3506 10518 7014 3506 10519 7012 3506 10520 7015 3507 10521 7016 3507 10522 7014 3507 10523 7017 3508 10524 7018 3508 10525 7016 3508 10526 7019 3509 10527 7020 3509 10528 7018 3509 10529 7021 3510 10530 7022 3510 10531 7020 3510 10532 7023 3511 10533 7024 3511 10534 7022 3511 10535 7025 3512 10536 7026 3512 10537 7024 3512 10538 7027 3513 10539 7028 3513 10540 7026 3513 10541 7029 3514 10542 7030 3514 10543 7028 3514 10544 7031 3515 10545 7032 3515 10546 7030 3515 10547 7033 3516 10548 7034 3516 10549 7032 3516 10550 7035 3517 10551 7036 3517 10552 7034 3517 10553 7037 3518 10554 7038 3518 10555 7036 3518 10556 7039 3519 10557 7040 3519 10558 7038 3519 10559 7041 3520 10560 7042 3520 10561 7040 3520 10562 7043 3521 10563 7044 3521 10564 7042 3521 10565 7045 3522 10566 7046 3522 10567 7044 3522 10568 7047 3523 10569 7048 3523 10570 7046 3523 10571 7049 3524 10572 7050 3524 10573 7048 3524 10574 7051 3525 10575 7052 3525 10576 7050 3525 10577 7053 3526 10578 7054 3526 10579 7052 3526 10580 7055 3527 10581 7056 3527 10582 7054 3527 10583 7057 3528 10584 7058 3528 10585 7056 3528 10586 7059 3529 10587 7060 3529 10588 7058 3529 10589 7061 3530 10590 7062 3530 10591 7060 3530 10592 7063 3531 10593 7064 3531 10594 7062 3531 10595 7065 3532 10596 7066 3532 10597 7064 3532 10598 7067 3533 10599 7068 3533 10600 7066 3533 10601 7069 3534 10602 7070 3534 10603 7068 3534 10604 7071 3535 10605 7072 3535 10606 7070 3535 10607 7073 3536 10608 7074 3536 10609 7072 3536 10610 7075 3537 10611 7076 3537 10612 7074 3537 10613 7077 3538 10614 7078 3538 10615 7076 3538 10616 7079 3539 10617 7080 3539 10618 7078 3539 10619 7081 3540 10620 7082 3540 10621 7080 3540 10622 7083 3541 10623 7084 3541 10624 7082 3541 10625 7085 3542 10626 7086 3542 10627 7084 3542 10628 7087 3543 10629 7088 3543 10630 7086 3543 10631 7089 3544 10632 7090 3544 10633 7088 3544 10634 7091 3545 10635 7092 3545 10636 7090 3545 10637 7093 3546 10638 7094 3546 10639 7092 3546 10640 7095 3547 10641 7096 3547 10642 7094 3547 10643 7097 3548 10644 7098 3548 10645 7096 3548 10646 7099 3549 10647 7100 3549 10648 7098 3549 10649 7101 3550 10650 7102 3550 10651 7100 3550 10652 7103 3551 10653 7104 3551 10654 7102 3551 10655 7105 3552 10656 7106 3552 10657 7104 3552 10658 7107 3553 10659 7108 3553 10660 7106 3553 10661 7109 3554 10662 7110 3554 10663 7108 3554 10664 7111 3555 10665 7112 3555 10666 7110 3555 10667 7113 3556 10668 7114 3556 10669 7112 3556 10670 7115 3557 10671 7116 3557 10672 7114 3557 10673 7117 3558 10674 7118 3558 10675 7116 3558 10676 7119 3559 10677 7120 3559 10678 7118 3559 10679 7121 3560 10680 7122 3560 10681 7120 3560 10682 7123 3561 10683 7124 3561 10684 7122 3561 10685 7125 3562 10686 7126 3562 10687 7124 3562 10688 7127 3563 10689 7128 3563 10690 7126 3563 10691 7129 3564 10692 7130 3564 10693 7128 3564 10694 7131 3565 10695 7132 3565 10696 7130 3565 10697 7133 3566 10698 7134 3566 10699 7132 3566 10700 7135 3567 10701 7136 3567 10702 7134 3567 10703 7137 3568 10704 7138 3568 10705 7136 3568 10706 7139 3569 10707 7140 3569 10708 7138 3569 10709 7141 3570 10710 7142 3570 10711 7140 3570 10712 7143 3571 10713 7144 3571 10714 7142 3571 10715 7145 3572 10716 7146 3572 10717 7144 3572 10718 7147 3573 10719 7148 3573 10720 7146 3573 10721 7149 3574 10722 7150 3574 10723 7148 3574 10724 7151 3575 10725 7152 3575 10726 7150 3575 10727 7153 3576 10728 7154 3576 10729 7152 3576 10730 7155 3577 10731 7156 3577 10732 7154 3577 10733 7157 3578 10734 7158 3578 10735 7156 3578 10736 7159 3579 10737 7160 3579 10738 7158 3579 10739 7161 3580 10740 7162 3580 10741 7160 3580 10742 7163 3581 10743 7164 3581 10744 7162 3581 10745 7165 3582 10746 7166 3582 10747 7164 3582 10748 7167 3583 10749 7168 3583 10750 7166 3583 10751 7169 3584 10752 7170 3584 10753 7168 3584 10754 7171 3585 10755 7172 3585 10756 7170 3585 10757 7173 3586 10758 7174 3586 10759 7172 3586 10760 7175 3587 10761 7176 3587 10762 7174 3587 10763 7177 3588 10764 7178 3588 10765 7176 3588 10766 7179 3589 10767 7180 3589 10768 7178 3589 10769 7181 3590 10770 7182 3590 10771 7180 3590 10772 7183 3591 10773 7184 3591 10774 7182 3591 10775 7185 3592 10776 7186 3592 10777 7184 3592 10778 7187 3593 10779 7188 3593 10780 7186 3593 10781 7189 3594 10782 7190 3594 10783 7188 3594 10784 7191 3595 10785 7192 3595 10786 7190 3595 10787 7193 3596 10788 7194 3596 10789 7192 3596 10790 7195 3597 10791 7196 3597 10792 7194 3597 10793 7197 3598 10794 7198 3598 10795 7196 3598 10796 7199 3599 10797 7200 3599 10798 7198 3599 10799 7201 3600 10800 7202 3600 10801 7200 3600 10802 7203 3601 10803 7204 3601 10804 7202 3601 10805 7205 3602 10806 7206 3602 10807 7204 3602 10808 7207 3603 10809 7208 3603 10810 7206 3603 10811 7209 3604 10812 7210 3604 10813 7208 3604 10814 7211 3605 10815 7212 3605 10816 7210 3605 10817 7213 3606 10818 7214 3606 10819 7212 3606 10820 7215 3607 10821 7216 3607 10822 7214 3607 10823 7217 3608 10824 7218 3608 10825 7216 3608 10826 7219 3609 10827 7220 3609 10828 7218 3609 10829 7221 3610 10830 7222 3610 10831 7220 3610 10832 7223 3611 10833 7224 3611 10834 7222 3611 10835 7225 3612 10836 7226 3612 10837 7224 3612 10838 7227 3613 10839 7228 3613 10840 7226 3613 10841 7229 3614 10842 7230 3614 10843 7228 3614 10844 7231 3615 10845 7232 3615 10846 7230 3615 10847 7233 3616 10848 7234 3616 10849 7232 3616 10850 7235 3617 10851 7236 3617 10852 7234 3617 10853 7237 3618 10854 7238 3618 10855 7236 3618 10856 7239 3619 10857 7240 3619 10858 7238 3619 10859 7241 3620 10860 7242 3620 10861 7240 3620 10862 7243 3621 10863 7244 3621 10864 7242 3621 10865 7245 3622 10866 7246 3622 10867 7244 3622 10868 7247 3623 10869 7248 3623 10870 7246 3623 10871 7249 3624 10872 7250 3624 10873 7248 3624 10874 7251 3625 10875 7252 3625 10876 7250 3625 10877 7253 3626 10878 7254 3626 10879 7252 3626 10880 7255 3627 10881 7256 3627 10882 7254 3627 10883 7257 3628 10884 7258 3628 10885 7256 3628 10886 7259 3629 10887 7260 3629 10888 7258 3629 10889 7261 3630 10890 7262 3630 10891 7260 3630 10892 7263 3631 10893 7264 3631 10894 7262 3631 10895 7265 3632 10896 7266 3632 10897 7264 3632 10898 7267 3633 10899 7268 3633 10900 7266 3633 10901 7269 3634 10902 7270 3634 10903 7268 3634 10904 7271 3635 10905 7272 3635 10906 7270 3635 10907 7273 3636 10908 7274 3636 10909 7272 3636 10910 7275 3637 10911 7276 3637 10912 7274 3637 10913 7277 3638 10914 7278 3638 10915 7276 3638 10916 7279 3639 10917 7280 3639 10918 7278 3639 10919 7281 3640 10920 7282 3640 10921 7280 3640 10922 7283 3641 10923 7284 3641 10924 7282 3641 10925 7285 3642 10926 7286 3642 10927 7284 3642 10928 7287 3643 10929 7288 3643 10930 7286 3643 10931 7289 3644 10932 7290 3644 10933 7288 3644 10934 7291 3645 10935 7292 3645 10936 7290 3645 10937 7293 3646 10938 7294 3646 10939 7292 3646 10940 7295 3647 10941 7296 3647 10942 7294 3647 10943 7297 3648 10944 7298 3648 10945 7296 3648 10946 7299 3649 10947 7300 3649 10948 7298 3649 10949 7301 3650 10950 7302 3650 10951 7300 3650 10952 7303 3651 10953 7304 3651 10954 7302 3651 10955 7305 3652 10956 7306 3652 10957 7304 3652 10958 7307 3653 10959 7308 3653 10960 7306 3653 10961 7309 3654 10962 7310 3654 10963 7308 3654 10964 7311 3655 10965 7312 3655 10966 7310 3655 10967 7313 3656 10968 7314 3656 10969 7312 3656 10970 7315 3657 10971 7316 3657 10972 7314 3657 10973 7317 3658 10974 7318 3658 10975 7316 3658 10976 7319 3659 10977 7320 3659 10978 7318 3659 10979 7321 3660 10980 7322 3660 10981 7320 3660 10982 7323 3661 10983 7324 3661 10984 7322 3661 10985 7325 3662 10986 7326 3662 10987 7324 3662 10988 7327 3663 10989 7328 3663 10990 7326 3663 10991 7329 3664 10992 7330 3664 10993 7328 3664 10994 7331 3665 10995 7332 3665 10996 7330 3665 10997 7333 3666 10998 7334 3666 10999 7332 3666 11000 7335 3667 11001 7336 3667 11002 7334 3667 11003 7337 3668 11004 7338 3668 11005 7336 3668 11006 7339 3669 11007 7340 3669 11008 7338 3669 11009 7341 3670 11010 7342 3670 11011 7340 3670 11012 7343 3671 11013 7344 3671 11014 7342 3671 11015 7345 3672 11016 7346 3672 11017 7344 3672 11018 7347 3673 11019 7348 3673 11020 7346 3673 11021 7349 3674 11022 7350 3674 11023 7348 3674 11024 7351 3675 11025 7352 3675 11026 7350 3675 11027 7353 3676 11028 7354 3676 11029 7352 3676 11030 7355 3677 11031 7356 3677 11032 7354 3677 11033 7357 3678 11034 7358 3678 11035 7356 3678 11036 7359 3679 11037 7360 3679 11038 7358 3679 11039 7361 3680 11040 7362 3680 11041 7360 3680 11042 7363 3681 11043 7364 3681 11044 7362 3681 11045 7365 3682 11046 7366 3682 11047 7364 3682 11048 7367 3683 11049 7368 3683 11050 7366 3683 11051 7369 3684 11052 7370 3684 11053 7368 3684 11054 7371 3685 11055 7372 3685 11056 7370 3685 11057 7373 3686 11058 7374 3686 11059 7372 3686 11060 7375 3687 11061 7376 3687 11062 7374 3687 11063 7377 3688 11064 7378 3688 11065 7376 3688 11066 7379 3689 11067 7380 3689 11068 7378 3689 11069 7381 3690 11070 7382 3690 11071 7380 3690 11072 7383 3691 11073 7384 3691 11074 7382 3691 11075 7385 3692 11076 7386 3692 11077 7384 3692 11078 7387 3693 11079 7388 3693 11080 7386 3693 11081 7389 3694 11082 7390 3694 11083 7388 3694 11084 7391 3695 11085 7392 3695 11086 7390 3695 11087 7393 3696 11088 7394 3696 11089 7392 3696 11090 7395 3697 11091 7396 3697 11092 7394 3697 11093 7397 3698 11094 7398 3698 11095 7396 3698 11096 7399 3699 11097 7400 3699 11098 7398 3699 11099 7401 3700 11100 7402 3700 11101 7400 3700 11102 7403 3701 11103 7404 3701 11104 7402 3701 11105 7405 3702 11106 7406 3702 11107 7404 3702 11108 7407 3703 11109 7408 3703 11110 7406 3703 11111 7409 3704 11112 7410 3704 11113 7408 3704 11114 7411 3705 11115 7412 3705 11116 7410 3705 11117 7413 3706 11118 7414 3706 11119 7412 3706 11120 7415 3707 11121 7416 3707 11122 7414 3707 11123 7417 3708 11124 7418 3708 11125 7416 3708 11126 7419 3709 11127 7420 3709 11128 7418 3709 11129 7421 3710 11130 7422 3710 11131 7420 3710 11132 7423 3711 11133 7424 3711 11134 7422 3711 11135 7425 3712 11136 7426 3712 11137 7424 3712 11138 7427 3713 11139 7428 3713 11140 7426 3713 11141 7429 3714 11142 7430 3714 11143 7428 3714 11144 7431 3715 11145 7432 3715 11146 7430 3715 11147 7433 3716 11148 7434 3716 11149 7432 3716 11150 7435 3717 11151 7436 3717 11152 7434 3717 11153 7437 3718 11154 7438 3718 11155 7436 3718 11156 7439 3719 11157 7440 3719 11158 7438 3719 11159 7441 3720 11160 7442 3720 11161 7440 3720 11162 7443 3721 11163 7444 3721 11164 7442 3721 11165 7445 3722 11166 7446 3722 11167 7444 3722 11168 7447 3723 11169 7448 3723 11170 7446 3723 11171 7449 3724 11172 7450 3724 11173 7448 3724 11174 7451 3725 11175 7452 3725 11176 7450 3725 11177 7453 3726 11178 7454 3726 11179 7452 3726 11180 7455 3727 11181 7456 3727 11182 7454 3727 11183 7457 3728 11184 7458 3728 11185 7456 3728 11186 7459 3729 11187 7460 3729 11188 7458 3729 11189 7461 3730 11190 7462 3730 11191 7460 3730 11192 7463 3731 11193 7464 3731 11194 7462 3731 11195 7465 3732 11196 7466 3732 11197 7464 3732 11198 7467 3733 11199 7468 3733 11200 7466 3733 11201 7469 3734 11202 7470 3734 11203 7468 3734 11204 7471 3735 11205 7472 3735 11206 7470 3735 11207 7473 3736 11208 7474 3736 11209 7472 3736 11210 7475 3737 11211 7476 3737 11212 7474 3737 11213 7477 3738 11214 7478 3738 11215 7476 3738 11216 7479 3739 11217 7480 3739 11218 7478 3739 11219 7481 3740 11220 7482 3740 11221 7480 3740 11222 7483 3741 11223 7484 3741 11224 7482 3741 11225 7485 3742 11226 7486 3742 11227 7484 3742 11228 7487 3743 11229 7488 3743 11230 7486 3743 11231 7489 3744 11232 7490 3744 11233 7488 3744 11234 7491 3745 11235 7492 3745 11236 7490 3745 11237 7493 3746 11238 7494 3746 11239 7492 3746 11240 7495 3747 11241 7496 3747 11242 7494 3747 11243 7497 3748 11244 7498 3748 11245 7496 3748 11246 7499 3749 11247 7500 3749 11248 7498 3749 11249 7501 3750 11250 7502 3750 11251 7500 3750 11252 7503 3751 11253 7504 3751 11254 7502 3751 11255 7505 3752 11256 7506 3752 11257 7504 3752 11258 7507 3753 11259 7508 3753 11260 7506 3753 11261 7509 3754 11262 7510 3754 11263 7508 3754 11264 7511 3755 11265 7512 3755 11266 7510 3755 11267 7513 3756 11268 7514 3756 11269 7512 3756 11270 7515 3757 11271 7516 3757 11272 7514 3757 11273 7517 3758 11274 7518 3758 11275 7516 3758 11276 7519 3759 11277 7520 3759 11278 7518 3759 11279 7521 3760 11280 7522 3760 11281 7520 3760 11282 7523 3761 11283 7524 3761 11284 7522 3761 11285 7525 3762 11286 7526 3762 11287 7524 3762 11288 7527 3763 11289 7528 3763 11290 7526 3763 11291 7529 3764 11292 7530 3764 11293 7528 3764 11294 7531 3765 11295 7532 3765 11296 7530 3765 11297 7533 3766 11298 7534 3766 11299 7532 3766 11300 7535 3767 11301 7536 3767 11302 7534 3767 11303 7537 3768 11304 7538 3768 11305 7536 3768 11306 7539 3769 11307 7540 3769 11308 7538 3769 11309 7541 3770 11310 7542 3770 11311 7540 3770 11312 7543 3771 11313 7544 3771 11314 7542 3771 11315 7545 3772 11316 7546 3772 11317 7544 3772 11318 7547 3773 11319 7548 3773 11320 7546 3773 11321 7549 3774 11322 7550 3774 11323 7548 3774 11324 7551 3775 11325 7552 3775 11326 7550 3775 11327 7553 3776 11328 7554 3776 11329 7552 3776 11330 7555 3777 11331 7556 3777 11332 7554 3777 11333 7557 3778 11334 7558 3778 11335 7556 3778 11336 7559 3779 11337 7560 3779 11338 7558 3779 11339 7561 3780 11340 7562 3780 11341 7560 3780 11342 7563 3781 11343 7564 3781 11344 7562 3781 11345 7565 3782 11346 7566 3782 11347 7564 3782 11348 7567 3783 11349 7568 3783 11350 7566 3783 11351 7569 3784 11352 7570 3784 11353 7568 3784 11354 7571 3785 11355 7572 3785 11356 7570 3785 11357 7573 3786 11358 7574 3786 11359 7572 3786 11360 7575 3787 11361 7576 3787 11362 7574 3787 11363 7577 3788 11364 7578 3788 11365 7576 3788 11366 7579 3789 11367 7580 3789 11368 7578 3789 11369 7581 3790 11370 7582 3790 11371 7580 3790 11372 7583 3791 11373 7584 3791 11374 7582 3791 11375 7585 3792 11376 7586 3792 11377 7584 3792 11378 7587 3793 11379 7588 3793 11380 7586 3793 11381 7589 3794 11382 7590 3794 11383 7588 3794 11384 7591 3795 11385 7592 3795 11386 7590 3795 11387 7593 3796 11388 7594 3796 11389 7592 3796 11390 7595 3797 11391 7596 3797 11392 7594 3797 11393 7597 3798 11394 7598 3798 11395 7596 3798 11396 7599 3799 11397 7600 3799 11398 7598 3799 11399 7601 3800 11400 7602 3800 11401 7600 3800 11402 7603 3801 11403 7604 3801 11404 7602 3801 11405 7605 3802 11406 7606 3802 11407 7604 3802 11408 7607 3803 11409 7608 3803 11410 7606 3803 11411 7609 3804 11412 7610 3804 11413 7608 3804 11414 7611 3805 11415 7612 3805 11416 7610 3805 11417 7613 3806 11418 7614 3806 11419 7612 3806 11420 7615 3807 11421 7616 3807 11422 7614 3807 11423 7617 3808 11424 7618 3808 11425 7616 3808 11426 7619 3809 11427 7620 3809 11428 7618 3809 11429 7621 3810 11430 7622 3810 11431 7620 3810 11432 7623 3811 11433 7624 3811 11434 7622 3811 11435 7625 3812 11436 7626 3812 11437 7624 3812 11438 7627 3813 11439 7628 3813 11440 7626 3813 11441 7629 3814 11442 7630 3814 11443 7628 3814 11444 7631 3815 11445 7632 3815 11446 7630 3815 11447 7633 3816 11448 7634 3816 11449 7632 3816 11450 7635 3817 11451 7636 3817 11452 7634 3817 11453 7637 3818 11454 7638 3818 11455 7636 3818 11456 7639 3819 11457 7640 3819 11458 7638 3819 11459 7641 3820 11460 7642 3820 11461 7640 3820 11462 7643 3821 11463 7644 3821 11464 7642 3821 11465 7645 3822 11466 7646 3822 11467 7644 3822 11468 7647 3823 11469 7648 3823 11470 7646 3823 11471 7649 3824 11472 7650 3824 11473 7648 3824 11474 7651 3825 11475 7652 3825 11476 7650 3825 11477 7653 3826 11478 7654 3826 11479 7652 3826 11480 7655 3827 11481 7656 3827 11482 7654 3827 11483 7657 3828 11484 7658 3828 11485 7656 3828 11486 7659 3829 11487 7660 3829 11488 7658 3829 11489 7661 3830 11490 7662 3830 11491 7660 3830 11492 7663 3831 11493 7664 3831 11494 7662 3831 11495 7665 3832 11496 7666 3832 11497 7664 3832 11498 7667 3833 11499 7668 3833 11500 7666 3833 11501 7669 3834 11502 7670 3834 11503 7668 3834 11504 7671 3835 11505 7672 3835 11506 7670 3835 11507 7673 3836 11508 7674 3836 11509 7672 3836 11510 7675 3837 11511 7676 3837 11512 7674 3837 11513 7677 3838 11514 7678 3838 11515 7676 3838 11516 7679 3839 11517 7680 3839 11518 7678 3839 11519 7681 3840 11520 7682 3840 11521 7680 3840 11522 7683 3841 11523 7684 3841 11524 7682 3841 11525 7685 3842 11526 7686 3842 11527 7684 3842 11528 7687 3843 11529 7688 3843 11530 7686 3843 11531 7689 3844 11532 7690 3844 11533 7688 3844 11534 7691 3845 11535 7692 3845 11536 7690 3845 11537 7693 3846 11538 7694 3846 11539 7692 3846 11540 7695 3847 11541 7696 3847 11542 7694 3847 11543 7697 3848 11544 7698 3848 11545 7696 3848 11546 7699 3849 11547 7700 3849 11548 7698 3849 11549 7701 3850 11550 7702 3850 11551 7700 3850 11552 7703 3851 11553 7704 3851 11554 7702 3851 11555 7705 3852 11556 7706 3852 11557 7704 3852 11558 7707 3853 11559 7708 3853 11560 7706 3853 11561 7709 3854 11562 7710 3854 11563 7708 3854 11564 7711 3855 11565 7712 3855 11566 7710 3855 11567 7713 3856 11568 7714 3856 11569 7712 3856 11570 7715 3857 11571 7716 3857 11572 7714 3857 11573 7717 3858 11574 7718 3858 11575 7716 3858 11576 7719 3859 11577 7720 3859 11578 7718 3859 11579 7721 3860 11580 7722 3860 11581 7720 3860 11582 7723 3861 11583 7724 3861 11584 7722 3861 11585 7725 3862 11586 7726 3862 11587 7724 3862 11588 7727 3863 11589 7728 3863 11590 7726 3863 11591 7729 3864 11592 7730 3864 11593 7728 3864 11594 7731 3865 11595 7732 3865 11596 7730 3865 11597 7733 3866 11598 7734 3866 11599 7732 3866 11600 7735 3867 11601 7736 3867 11602 7734 3867 11603 7737 3868 11604 7738 3868 11605 7736 3868 11606 7739 3869 11607 7740 3869 11608 7738 3869 11609 7741 3870 11610 7742 3870 11611 7740 3870 11612 7743 3871 11613 7744 3871 11614 7742 3871 11615 7745 3872 11616 7746 3872 11617 7744 3872 11618 7747 3873 11619 7748 3873 11620 7746 3873 11621 7749 3874 11622 7750 3874 11623 7748 3874 11624 7751 3875 11625 7752 3875 11626 7750 3875 11627 7753 3876 11628 7754 3876 11629 7752 3876 11630 7755 3877 11631 7756 3877 11632 7754 3877 11633 7757 3878 11634 7758 3878 11635 7756 3878 11636 7759 3879 11637 7760 3879 11638 7758 3879 11639 7761 3880 11640 7762 3880 11641 7760 3880 11642 7763 3881 11643 7764 3881 11644 7762 3881 11645 7765 3882 11646 7766 3882 11647 7764 3882 11648 7767 3883 11649 7768 3883 11650 7766 3883 11651 7769 3884 11652 7770 3884 11653 7768 3884 11654 7771 3885 11655 7772 3885 11656 7770 3885 11657 7773 3886 11658 7774 3886 11659 7772 3886 11660 7775 3887 11661 7776 3887 11662 7774 3887 11663 7777 3888 11664 7778 3888 11665 7776 3888 11666 7779 3889 11667 7780 3889 11668 7778 3889 11669 7781 3890 11670 7782 3890 11671 7780 3890 11672 7783 3891 11673 7784 3891 11674 7782 3891 11675 7785 3892 11676 7786 3892 11677 7784 3892 11678 7787 3893 11679 7788 3893 11680 7786 3893 11681 7789 3894 11682 7790 3894 11683 7788 3894 11684 7791 3895 11685 7792 3895 11686 7790 3895 11687 7793 3896 11688 7794 3896 11689 7792 3896 11690 7795 3897 11691 7796 3897 11692 7794 3897 11693 7797 3898 11694 7798 3898 11695 7796 3898 11696 7799 3899 11697 7800 3899 11698 7798 3899 11699 7801 3900 11700 7802 3900 11701 7800 3900 11702 7803 3901 11703 7804 3901 11704 7802 3901 11705 7805 3902 11706 7806 3902 11707 7804 3902 11708 7807 3903 11709 7808 3903 11710 7806 3903 11711 7809 3904 11712 7810 3904 11713 7808 3904 11714 7811 3905 11715 7812 3905 11716 7810 3905 11717 7813 3906 11718 7814 3906 11719 7812 3906 11720 7815 3907 11721 7816 3907 11722 7814 3907 11723 7817 3908 11724 7818 3908 11725 7816 3908 11726 7819 3909 11727 7820 3909 11728 7818 3909 11729 7821 3910 11730 7822 3910 11731 7820 3910 11732 7823 3911 11733 7824 3911 11734 7822 3911 11735 7825 3912 11736 7826 3912 11737 7824 3912 11738 7827 3913 11739 7828 3913 11740 7826 3913 11741 7829 3914 11742 7830 3914 11743 7828 3914 11744 7831 3915 11745 7832 3915 11746 7830 3915 11747 7833 3916 11748 7834 3916 11749 7832 3916 11750 7835 3917 11751 7836 3917 11752 7834 3917 11753 7837 3918 11754 7838 3918 11755 7836 3918 11756 7839 3919 11757 7840 3919 11758 7838 3919 11759 7841 3920 11760 7842 3920 11761 7840 3920 11762 7843 3921 11763 7844 3921 11764 7842 3921 11765 7845 3922 11766 7846 3922 11767 7844 3922 11768 7847 3923 11769 7848 3923 11770 7846 3923 11771 7849 3924 11772 7850 3924 11773 7848 3924 11774 7851 3925 11775 7852 3925 11776 7850 3925 11777 7853 3926 11778 7854 3926 11779 7852 3926 11780 7855 3927 11781 7856 3927 11782 7854 3927 11783 7857 3928 11784 7858 3928 11785 7856 3928 11786 7859 3929 11787 7860 3929 11788 7858 3929 11789 7861 3930 11790 7862 3930 11791 7860 3930 11792 7863 3931 11793 7864 3931 11794 7862 3931 11795 7865 3932 11796 7866 3932 11797 7864 3932 11798 7867 3933 11799 7868 3933 11800 7866 3933 11801 7869 3934 11802 7870 3934 11803 7868 3934 11804 7871 3935 11805 7872 3935 11806 7870 3935 11807 7873 3936 11808 7874 3936 11809 7872 3936 11810 7875 3937 11811 7876 3937 11812 7874 3937 11813 7877 3938 11814 7878 3938 11815 7876 3938 11816 7879 3939 11817 7880 3939 11818 7878 3939 11819 7881 3940 11820 7882 3940 11821 7880 3940 11822 7883 3941 11823 7884 3941 11824 7882 3941 11825 7885 3942 11826 7886 3942 11827 7884 3942 11828 7887 3943 11829 7888 3943 11830 7886 3943 11831 7889 3944 11832 7890 3944 11833 7888 3944 11834 7891 3945 11835 7892 3945 11836 7890 3945 11837 7893 3946 11838 7894 3946 11839 7892 3946 11840 7895 3947 11841 7896 3947 11842 7894 3947 11843 7897 3948 11844 7898 3948 11845 7896 3948 11846 7899 3949 11847 7900 3949 11848 7898 3949 11849 7901 3950 11850 7902 3950 11851 7900 3950 11852 7903 3951 11853 7904 3951 11854 7902 3951 11855 7905 3952 11856 7906 3952 11857 7904 3952 11858 7907 3953 11859 7908 3953 11860 7906 3953 11861 7909 3954 11862 7910 3954 11863 7908 3954 11864 7911 3955 11865 7912 3955 11866 7910 3955 11867 7913 3956 11868 7914 3956 11869 7912 3956 11870 7915 3957 11871 7916 3957 11872 7914 3957 11873 7917 3958 11874 7918 3958 11875 7916 3958 11876 7919 3959 11877 7920 3959 11878 7918 3959 11879 7921 3960 11880 7922 3960 11881 7920 3960 11882 7923 3961 11883 7924 3961 11884 7922 3961 11885 7925 3962 11886 7926 3962 11887 7924 3962 11888 7927 3963 11889 7928 3963 11890 7926 3963 11891 7929 3964 11892 7930 3964 11893 7928 3964 11894 7931 3965 11895 7932 3965 11896 7930 3965 11897 7933 3966 11898 7934 3966 11899 7932 3966 11900 7935 3967 11901 7936 3967 11902 7934 3967 11903 7937 3968 11904 7938 3968 11905 7936 3968 11906 7939 3969 11907 7940 3969 11908 7938 3969 11909 7941 3970 11910 7942 3970 11911 7940 3970 11912 7943 3971 11913 7944 3971 11914 7942 3971 11915 7945 3972 11916 7946 3972 11917 7944 3972 11918 7947 3973 11919 7948 3973 11920 7946 3973 11921 7949 3974 11922 7950 3974 11923 7948 3974 11924 7951 3975 11925 7952 3975 11926 7950 3975 11927 7953 3976 11928 7954 3976 11929 7952 3976 11930 7955 3977 11931 7956 3977 11932 7954 3977 11933 7957 3978 11934 7958 3978 11935 7956 3978 11936 7959 3979 11937 7960 3979 11938 7958 3979 11939 7961 3980 11940 7962 3980 11941 7960 3980 11942 7963 3981 11943 7964 3981 11944 7962 3981 11945 7965 3982 11946 7966 3982 11947 7964 3982 11948 7967 3983 11949 7968 3983 11950 7966 3983 11951 7969 3984 11952 7970 3984 11953 7968 3984 11954 7971 3985 11955 7972 3985 11956 7970 3985 11957 7973 3986 11958 7974 3986 11959 7972 3986 11960 7975 3987 11961 7976 3987 11962 7974 3987 11963 7977 3988 11964 7978 3988 11965 7976 3988 11966 7979 3989 11967 7980 3989 11968 7978 3989 11969 7981 3990 11970 7982 3990 11971 7980 3990 11972 7983 3991 11973 7984 3991 11974 7982 3991 11975 7985 3992 11976 7986 3992 11977 7984 3992 11978 7987 3993 11979 7988 3993 11980 7986 3993 11981 7989 3994 11982 7990 3994 11983 7988 3994 11984 7991 3995 11985 7992 3995 11986 7990 3995 11987 7993 3996 11988 7994 3996 11989 7992 3996 11990 7995 3997 11991 7996 3997 11992 7994 3997 11993 7997 3998 11994 7998 3998 11995 7996 3998 11996 7999 3999 11997 8000 3999 11998 7998 3999 11999 8001 4000 12000 8002 4000 12001 8000 4000 12002 8003 4001 12003 8004 4001 12004 8002 4001 12005 8005 4002 12006 8006 4002 12007 8004 4002 12008 8007 4003 12009 8008 4003 12010 8006 4003 12011 8009 4004 12012 8010 4004 12013 8008 4004 12014 8011 4005 12015 8012 4005 12016 8010 4005 12017 8013 4006 12018 8014 4006 12019 8012 4006 12020 8015 4007 12021 8016 4007 12022 8014 4007 12023 8017 4008 12024 8018 4008 12025 8016 4008 12026 8019 4009 12027 8020 4009 12028 8018 4009 12029 8021 4010 12030 8022 4010 12031 8020 4010 12032 8023 4011 12033 8024 4011 12034 8022 4011 12035 8025 4012 12036 8026 4012 12037 8024 4012 12038 8027 4013 12039 8028 4013 12040 8026 4013 12041 8029 4014 12042 8030 4014 12043 8028 4014 12044 8031 4015 12045 8032 4015 12046 8030 4015 12047 8033 4016 12048 8034 4016 12049 8032 4016 12050 8035 4017 12051 8036 4017 12052 8034 4017 12053 8037 4018 12054 8038 4018 12055 8036 4018 12056 8039 4019 12057 8040 4019 12058 8038 4019 12059 8041 4020 12060 8042 4020 12061 8040 4020 12062 8043 4021 12063 8044 4021 12064 8042 4021 12065 8045 4022 12066 8046 4022 12067 8044 4022 12068 8047 4023 12069 8048 4023 12070 8046 4023 12071 8049 4024 12072 8050 4024 12073 8048 4024 12074 8051 4025 12075 8052 4025 12076 8050 4025 12077 8053 4026 12078 8054 4026 12079 8052 4026 12080 8055 4027 12081 8056 4027 12082 8054 4027 12083 8057 4028 12084 8058 4028 12085 8056 4028 12086 8059 4029 12087 8060 4029 12088 8058 4029 12089 8061 4030 12090 8062 4030 12091 8060 4030 12092 8063 4031 12093 8064 4031 12094 8062 4031 12095 8065 4032 12096 8066 4032 12097 8064 4032 12098 8067 4033 12099 8068 4033 12100 8066 4033 12101 8069 4034 12102 8070 4034 12103 8068 4034 12104 8071 4035 12105 8072 4035 12106 8070 4035 12107 8073 4036 12108 8074 4036 12109 8072 4036 12110 8075 4037 12111 8076 4037 12112 8074 4037 12113 8077 4038 12114 8078 4038 12115 8076 4038 12116 8079 4039 12117 8080 4039 12118 8078 4039 12119 8081 4040 12120 8082 4040 12121 8080 4040 12122 8083 4041 12123 8084 4041 12124 8082 4041 12125 8085 4042 12126 8086 4042 12127 8084 4042 12128 8087 4043 12129 8088 4043 12130 8086 4043 12131 8089 4044 12132 8090 4044 12133 8088 4044 12134 8091 4045 12135 8092 4045 12136 8090 4045 12137 8093 4046 12138 8094 4046 12139 8092 4046 12140 8095 4047 12141 8096 4047 12142 8094 4047 12143 8097 4048 12144 8098 4048 12145 8096 4048 12146 8099 4049 12147 8100 4049 12148 8098 4049 12149 8101 4050 12150 8102 4050 12151 8100 4050 12152 8103 4051 12153 8104 4051 12154 8102 4051 12155 8105 4052 12156 8106 4052 12157 8104 4052 12158 8107 4053 12159 8108 4053 12160 8106 4053 12161 8109 4054 12162 8110 4054 12163 8108 4054 12164 8111 4055 12165 8112 4055 12166 8110 4055 12167 8113 4056 12168 8114 4056 12169 8112 4056 12170 8115 4057 12171 8116 4057 12172 8114 4057 12173 8117 4058 12174 8118 4058 12175 8116 4058 12176 8119 4059 12177 8120 4059 12178 8118 4059 12179 8121 4060 12180 8122 4060 12181 8120 4060 12182 8123 4061 12183 8124 4061 12184 8122 4061 12185 8125 4062 12186 8126 4062 12187 8124 4062 12188 8127 4063 12189 8128 4063 12190 8126 4063 12191 8129 4064 12192 8130 4064 12193 8128 4064 12194 8131 4065 12195 8132 4065 12196 8130 4065 12197 8133 4066 12198 8134 4066 12199 8132 4066 12200 8135 4067 12201 8136 4067 12202 8134 4067 12203 8137 4068 12204 8138 4068 12205 8136 4068 12206 8139 4069 12207 8140 4069 12208 8138 4069 12209 8141 4070 12210 8142 4070 12211 8140 4070 12212 8143 4071 12213 8144 4071 12214 8142 4071 12215 8145 4072 12216 8146 4072 12217 8144 4072 12218 8147 4073 12219 8148 4073 12220 8146 4073 12221 8149 4074 12222 8150 4074 12223 8148 4074 12224 8151 4075 12225 8152 4075 12226 8150 4075 12227 8153 4076 12228 8154 4076 12229 8152 4076 12230 8155 4077 12231 8156 4077 12232 8154 4077 12233 8157 4078 12234 8158 4078 12235 8156 4078 12236 8159 4079 12237 8160 4079 12238 8158 4079 12239 8161 4080 12240 8162 4080 12241 8160 4080 12242 8163 4081 12243 8164 4081 12244 8162 4081 12245 8165 4082 12246 8166 4082 12247 8164 4082 12248 8167 4083 12249 8168 4083 12250 8166 4083 12251 8169 4084 12252 8170 4084 12253 8168 4084 12254 8171 4085 12255 8172 4085 12256 8170 4085 12257 8173 4086 12258 8174 4086 12259 8172 4086 12260 8175 4087 12261 8176 4087 12262 8174 4087 12263 8177 4088 12264 8178 4088 12265 8176 4088 12266 8179 4089 12267 8180 4089 12268 8178 4089 12269 8181 4090 12270 8182 4090 12271 8180 4090 12272 8183 4091 12273 8184 4091 12274 8182 4091 12275 8185 4092 12276 8186 4092 12277 8184 4092 12278 8187 4093 12279 8188 4093 12280 8186 4093 12281 1029 4094 12282 5 4094 12283 4101 4094 12284 8189 4095 12285 8190 4095 12286 8188 4095 12287 8191 4096 12288 0 4096 12289 8190 4096 12290 4094 4097 12291 6142 4097 12292 8190 4097 12293 1 0 12294 3 0 12295 2 0 12296 3 4098 12297 5 4098 12298 4 4098 12299 5 2 12300 7 2 12301 6 2 12302 7 4099 12303 9 4099 12304 8 4099 12305 9 4100 12306 11 4100 12307 10 4100 12308 11 4101 12309 13 4101 12310 12 4101 12311 13 6 12312 15 6 12313 14 6 12314 15 7 12315 17 7 12316 16 7 12317 17 4102 12318 19 4102 12319 18 4102 12320 19 4103 12321 21 4103 12322 20 4103 12323 21 4104 12324 23 4104 12325 22 4104 12326 23 4105 12327 25 4105 12328 24 4105 12329 25 12 12330 27 12 12331 26 12 12332 27 13 12333 29 13 12334 28 13 12335 29 4106 12336 31 4106 12337 30 4106 12338 31 4107 12339 33 4107 12340 32 4107 12341 33 16 12342 35 16 12343 34 16 12344 35 17 12345 37 17 12346 36 17 12347 37 4108 12348 39 4108 12349 38 4108 12350 39 4109 12351 41 4109 12352 40 4109 12353 41 20 12354 43 20 12355 42 20 12356 43 4110 12357 45 4110 12358 44 4110 12359 45 22 12360 47 22 12361 46 22 12362 47 23 12363 49 23 12364 48 23 12365 49 24 12366 51 24 12367 50 24 12368 51 25 12369 53 25 12370 52 25 12371 53 4111 12372 55 4111 12373 54 4111 12374 55 27 12375 57 27 12376 56 27 12377 57 4112 12378 59 4112 12379 58 4112 12380 59 4113 12381 61 4113 12382 60 4113 12383 61 4114 12384 63 4114 12385 62 4114 12386 63 31 12387 65 31 12388 64 31 12389 65 4115 12390 67 4115 12391 66 4115 12392 67 33 12393 69 33 12394 68 33 12395 69 34 12396 71 34 12397 70 34 12398 71 35 12399 73 35 12400 72 35 12401 73 4116 12402 75 4116 12403 74 4116 12404 75 37 12405 77 37 12406 76 37 12407 77 4117 12408 79 4117 12409 78 4117 12410 79 39 12411 81 39 12412 80 39 12413 81 4118 12414 83 4118 12415 82 4118 12416 83 4119 12417 85 4119 12418 84 4119 12419 85 42 12420 87 42 12421 86 42 12422 87 4120 12423 89 4120 12424 88 4120 12425 89 44 12426 91 44 12427 90 44 12428 91 45 12429 93 45 12430 92 45 12431 93 46 12432 95 46 12433 94 46 12434 95 4121 12435 97 4121 12436 96 4121 12437 97 48 12438 99 48 12439 98 48 12440 99 49 12441 101 49 12442 100 49 12443 101 50 12444 103 50 12445 102 50 12446 103 4122 12447 105 4122 12448 104 4122 12449 105 52 12450 107 52 12451 106 52 12452 107 4123 12453 109 4123 12454 108 4123 12455 109 54 12456 111 54 12457 110 54 12458 111 55 12459 113 55 12460 112 55 12461 113 56 12462 115 56 12463 114 56 12464 115 4124 12465 117 4124 12466 116 4124 12467 117 4125 12468 119 4125 12469 118 4125 12470 119 59 12471 121 59 12472 120 59 12473 121 60 12474 123 60 12475 122 60 12476 123 61 12477 125 61 12478 124 61 12479 125 62 12480 127 62 12481 126 62 12482 127 4126 12483 129 4126 12484 128 4126 12485 129 64 12486 131 64 12487 130 64 12488 131 65 12489 133 65 12490 132 65 12491 133 4127 12492 135 4127 12493 134 4127 12494 135 4128 12495 137 4128 12496 136 4128 12497 137 4129 12498 139 4129 12499 138 4129 12500 139 4130 12501 141 4130 12502 140 4130 12503 141 70 12504 143 70 12505 142 70 12506 143 71 12507 145 71 12508 144 71 12509 145 72 12510 147 72 12511 146 72 12512 147 73 12513 149 73 12514 148 73 12515 149 4131 12516 151 4131 12517 150 4131 12518 151 75 12519 153 75 12520 152 75 12521 153 4132 12522 155 4132 12523 154 4132 12524 155 77 12525 157 77 12526 156 77 12527 157 4133 12528 159 4133 12529 158 4133 12530 159 79 12531 161 79 12532 160 79 12533 161 80 12534 163 80 12535 162 80 12536 163 4134 12537 165 4134 12538 164 4134 12539 165 4135 12540 167 4135 12541 166 4135 12542 167 4136 12543 169 4136 12544 168 4136 12545 169 4137 12546 171 4137 12547 170 4137 12548 171 85 12549 173 85 12550 172 85 12551 173 4138 12552 175 4138 12553 174 4138 12554 175 87 12555 177 87 12556 176 87 12557 177 88 12558 179 88 12559 178 88 12560 179 4139 12561 181 4139 12562 180 4139 12563 181 90 12564 183 90 12565 182 90 12566 183 4140 12567 185 4140 12568 184 4140 12569 185 4141 12570 187 4141 12571 186 4141 12572 187 4142 12573 189 4142 12574 188 4142 12575 189 94 12576 191 94 12577 190 94 12578 191 95 12579 193 95 12580 192 95 12581 193 4143 12582 195 4143 12583 194 4143 12584 195 97 12585 197 97 12586 196 97 12587 197 4144 12588 199 4144 12589 198 4144 12590 199 4145 12591 201 4145 12592 200 4145 12593 201 4146 12594 203 4146 12595 202 4146 12596 203 4147 12597 205 4147 12598 204 4147 12599 205 4148 12600 207 4148 12601 206 4148 12602 207 4149 12603 209 4149 12604 208 4149 12605 209 104 12606 211 104 12607 210 104 12608 211 105 12609 213 105 12610 212 105 12611 213 4150 12612 215 4150 12613 214 4150 12614 215 107 12615 217 107 12616 216 107 12617 217 108 12618 219 108 12619 218 108 12620 219 4151 12621 221 4151 12622 220 4151 12623 221 4152 12624 223 4152 12625 222 4152 12626 223 111 12627 225 111 12628 224 111 12629 225 112 12630 227 112 12631 226 112 12632 227 4153 12633 229 4153 12634 228 4153 12635 229 4154 12636 231 4154 12637 230 4154 12638 231 4155 12639 233 4155 12640 232 4155 12641 233 4156 12642 235 4156 12643 234 4156 12644 235 117 12645 237 117 12646 236 117 12647 237 118 12648 239 118 12649 238 118 12650 239 119 12651 241 119 12652 240 119 12653 241 120 12654 243 120 12655 242 120 12656 243 121 12657 245 121 12658 244 121 12659 245 122 12660 247 122 12661 246 122 12662 247 4157 12663 249 4157 12664 248 4157 12665 249 124 12666 251 124 12667 250 124 12668 251 125 12669 253 125 12670 252 125 12671 253 4158 12672 255 4158 12673 254 4158 12674 255 4159 12675 257 4159 12676 256 4159 12677 257 4160 12678 259 4160 12679 258 4160 12680 259 129 12681 261 129 12682 260 129 12683 261 130 12684 263 130 12685 262 130 12686 263 4161 12687 265 4161 12688 264 4161 12689 265 4162 12690 267 4162 12691 266 4162 12692 267 133 12693 269 133 12694 268 133 12695 269 4163 12696 271 4163 12697 270 4163 12698 271 135 12699 273 135 12700 272 135 12701 273 136 12702 275 136 12703 274 136 12704 275 4164 12705 277 4164 12706 276 4164 12707 277 4165 12708 279 4165 12709 278 4165 12710 279 139 12711 281 139 12712 280 139 12713 281 140 12714 283 140 12715 282 140 12716 283 141 12717 285 141 12718 284 141 12719 285 142 12720 287 142 12721 286 142 12722 287 4166 12723 289 4166 12724 288 4166 12725 289 144 12726 291 144 12727 290 144 12728 291 145 12729 293 145 12730 292 145 12731 293 146 12732 295 146 12733 294 146 12734 295 4167 12735 297 4167 12736 296 4167 12737 297 148 12738 299 148 12739 298 148 12740 299 4168 12741 301 4168 12742 300 4168 12743 301 150 12744 303 150 12745 302 150 12746 303 4169 12747 305 4169 12748 304 4169 12749 305 152 12750 307 152 12751 306 152 12752 307 153 12753 309 153 12754 308 153 12755 309 154 12756 311 154 12757 310 154 12758 311 155 12759 313 155 12760 312 155 12761 313 4170 12762 315 4170 12763 314 4170 12764 315 4171 12765 317 4171 12766 316 4171 12767 317 4172 12768 319 4172 12769 318 4172 12770 319 159 12771 321 159 12772 320 159 12773 321 160 12774 323 160 12775 322 160 12776 323 4173 12777 325 4173 12778 324 4173 12779 325 162 12780 327 162 12781 326 162 12782 327 4174 12783 329 4174 12784 328 4174 12785 329 4175 12786 331 4175 12787 330 4175 12788 331 165 12789 333 165 12790 332 165 12791 333 4176 12792 335 4176 12793 334 4176 12794 335 167 12795 337 167 12796 336 167 12797 337 168 12798 339 168 12799 338 168 12800 339 4177 12801 341 4177 12802 340 4177 12803 341 170 12804 343 170 12805 342 170 12806 343 4178 12807 345 4178 12808 344 4178 12809 345 172 12810 347 172 12811 346 172 12812 347 173 12813 349 173 12814 348 173 12815 349 4179 12816 351 4179 12817 350 4179 12818 351 175 12819 353 175 12820 352 175 12821 353 176 12822 355 176 12823 354 176 12824 355 177 12825 357 177 12826 356 177 12827 357 178 12828 359 178 12829 358 178 12830 359 4180 12831 361 4180 12832 360 4180 12833 361 180 12834 363 180 12835 362 180 12836 363 4181 12837 365 4181 12838 364 4181 12839 365 4182 12840 367 4182 12841 366 4182 12842 367 4183 12843 369 4183 12844 368 4183 12845 369 184 12846 371 184 12847 370 184 12848 371 185 12849 373 185 12850 372 185 12851 373 186 12852 375 186 12853 374 186 12854 375 187 12855 377 187 12856 376 187 12857 377 4184 12858 379 4184 12859 378 4184 12860 379 4185 12861 381 4185 12862 380 4185 12863 381 190 12864 383 190 12865 382 190 12866 383 191 12867 385 191 12868 384 191 12869 385 192 12870 387 192 12871 386 192 12872 387 4186 12873 389 4186 12874 388 4186 12875 389 194 12876 391 194 12877 390 194 12878 391 195 12879 393 195 12880 392 195 12881 393 196 12882 395 196 12883 394 196 12884 395 4187 12885 397 4187 12886 396 4187 12887 397 198 12888 399 198 12889 398 198 12890 399 199 12891 401 199 12892 400 199 12893 401 4188 12894 403 4188 12895 402 4188 12896 403 4189 12897 405 4189 12898 404 4189 12899 405 202 12900 407 202 12901 406 202 12902 407 4190 12903 409 4190 12904 408 4190 12905 409 4191 12906 411 4191 12907 410 4191 12908 411 4192 12909 413 4192 12910 412 4192 12911 413 206 12912 415 206 12913 414 206 12914 415 207 12915 417 207 12916 416 207 12917 417 208 12918 419 208 12919 418 208 12920 419 4193 12921 421 4193 12922 420 4193 12923 421 4194 12924 423 4194 12925 422 4194 12926 423 211 12927 425 211 12928 424 211 12929 425 212 12930 427 212 12931 426 212 12932 427 213 12933 429 213 12934 428 213 12935 429 214 12936 431 214 12937 430 214 12938 431 215 12939 433 215 12940 432 215 12941 433 4195 12942 435 4195 12943 434 4195 12944 435 4196 12945 437 4196 12946 436 4196 12947 437 4197 12948 439 4197 12949 438 4197 12950 439 219 12951 441 219 12952 440 219 12953 441 220 12954 443 220 12955 442 220 12956 443 4198 12957 445 4198 12958 444 4198 12959 445 4199 12960 447 4199 12961 446 4199 12962 447 223 12963 449 223 12964 448 223 12965 449 4200 12966 451 4200 12967 450 4200 12968 451 4201 12969 453 4201 12970 452 4201 12971 453 4202 12972 455 4202 12973 454 4202 12974 455 4203 12975 457 4203 12976 456 4203 12977 457 228 12978 459 228 12979 458 228 12980 459 4204 12981 461 4204 12982 460 4204 12983 461 230 12984 463 230 12985 462 230 12986 463 231 12987 465 231 12988 464 231 12989 465 4205 12990 467 4205 12991 466 4205 12992 467 4206 12993 469 4206 12994 468 4206 12995 469 234 12996 471 234 12997 470 234 12998 471 4207 12999 473 4207 13000 472 4207 13001 473 236 13002 475 236 13003 474 236 13004 475 237 13005 477 237 13006 476 237 13007 477 238 13008 479 238 13009 478 238 13010 479 239 13011 481 239 13012 480 239 13013 481 240 13014 483 240 13015 482 240 13016 483 4208 13017 485 4208 13018 484 4208 13019 485 4209 13020 487 4209 13021 486 4209 13022 487 4210 13023 489 4210 13024 488 4210 13025 489 244 13026 491 244 13027 490 244 13028 491 245 13029 493 245 13030 492 245 13031 493 246 13032 495 246 13033 494 246 13034 495 4211 13035 497 4211 13036 496 4211 13037 497 4212 13038 499 4212 13039 498 4212 13040 499 249 13041 501 249 13042 500 249 13043 501 250 13044 503 250 13045 502 250 13046 503 4213 13047 505 4213 13048 504 4213 13049 505 252 13050 507 252 13051 506 252 13052 507 4214 13053 509 4214 13054 508 4214 13055 509 254 13056 511 254 13057 510 254 13058 511 4215 13059 513 4215 13060 512 4215 13061 513 256 13062 515 256 13063 514 256 13064 515 4216 13065 517 4216 13066 516 4216 13067 517 258 13068 519 258 13069 518 258 13070 519 259 13071 521 259 13072 520 259 13073 521 4217 13074 523 4217 13075 522 4217 13076 523 261 13077 525 261 13078 524 261 13079 525 4218 13080 527 4218 13081 526 4218 13082 527 4219 13083 529 4219 13084 528 4219 13085 529 4220 13086 531 4220 13087 530 4220 13088 531 265 13089 533 265 13090 532 265 13091 533 4221 13092 535 4221 13093 534 4221 13094 535 4222 13095 537 4222 13096 536 4222 13097 537 268 13098 539 268 13099 538 268 13100 539 269 13101 541 269 13102 540 269 13103 541 270 13104 543 270 13105 542 270 13106 543 271 13107 545 271 13108 544 271 13109 545 272 13110 547 272 13111 546 272 13112 547 4223 13113 549 4223 13114 548 4223 13115 549 274 13116 551 274 13117 550 274 13118 551 275 13119 553 275 13120 552 275 13121 553 4224 13122 555 4224 13123 554 4224 13124 555 277 13125 557 277 13126 556 277 13127 557 278 13128 559 278 13129 558 278 13130 559 4225 13131 561 4225 13132 560 4225 13133 561 4226 13134 563 4226 13135 562 4226 13136 563 281 13137 565 281 13138 564 281 13139 565 282 13140 567 282 13141 566 282 13142 567 4227 13143 569 4227 13144 568 4227 13145 569 4228 13146 571 4228 13147 570 4228 13148 571 4229 13149 573 4229 13150 572 4229 13151 573 286 13152 575 286 13153 574 286 13154 575 287 13155 577 287 13156 576 287 13157 577 288 13158 579 288 13159 578 288 13160 579 4230 13161 581 4230 13162 580 4230 13163 581 4231 13164 583 4231 13165 582 4231 13166 583 291 13167 585 291 13168 584 291 13169 585 4232 13170 587 4232 13171 586 4232 13172 587 4233 13173 589 4233 13174 588 4233 13175 589 4234 13176 591 4234 13177 590 4234 13178 591 295 13179 593 295 13180 592 295 13181 593 4235 13182 595 4235 13183 594 4235 13184 595 4236 13185 597 4236 13186 596 4236 13187 597 4237 13188 599 4237 13189 598 4237 13190 599 4238 13191 601 4238 13192 600 4238 13193 601 4239 13194 603 4239 13195 602 4239 13196 603 301 13197 605 301 13198 604 301 13199 605 4240 13200 607 4240 13201 606 4240 13202 607 303 13203 609 303 13204 608 303 13205 609 304 13206 611 304 13207 610 304 13208 611 4241 13209 613 4241 13210 612 4241 13211 613 4242 13212 615 4242 13213 614 4242 13214 615 307 13215 617 307 13216 616 307 13217 617 4243 13218 619 4243 13219 618 4243 13220 619 309 13221 621 309 13222 620 309 13223 621 4244 13224 623 4244 13225 622 4244 13226 623 311 13227 625 311 13228 624 311 13229 625 4245 13230 627 4245 13231 626 4245 13232 627 313 13233 629 313 13234 628 313 13235 629 314 13236 631 314 13237 630 314 13238 631 4246 13239 633 4246 13240 632 4246 13241 633 316 13242 635 316 13243 634 316 13244 635 4247 13245 637 4247 13246 636 4247 13247 637 4248 13248 639 4248 13249 638 4248 13250 639 4249 13251 641 4249 13252 640 4249 13253 641 320 13254 643 320 13255 642 320 13256 643 4250 13257 645 4250 13258 644 4250 13259 645 4251 13260 647 4251 13261 646 4251 13262 647 323 13263 649 323 13264 648 323 13265 649 4252 13266 651 4252 13267 650 4252 13268 651 4253 13269 653 4253 13270 652 4253 13271 653 326 13272 655 326 13273 654 326 13274 655 327 13275 657 327 13276 656 327 13277 657 328 13278 659 328 13279 658 328 13280 659 329 13281 661 329 13282 660 329 13283 661 330 13284 663 330 13285 662 330 13286 663 4254 13287 665 4254 13288 664 4254 13289 665 4255 13290 667 4255 13291 666 4255 13292 667 333 13293 669 333 13294 668 333 13295 669 4256 13296 671 4256 13297 670 4256 13298 671 4257 13299 673 4257 13300 672 4257 13301 673 4258 13302 675 4258 13303 674 4258 13304 675 4259 13305 677 4259 13306 676 4259 13307 677 4260 13308 679 4260 13309 678 4260 13310 679 4261 13311 681 4261 13312 680 4261 13313 681 4262 13314 683 4262 13315 682 4262 13316 683 4263 13317 685 4263 13318 684 4263 13319 685 4264 13320 687 4264 13321 686 4264 13322 687 4265 13323 689 4265 13324 688 4265 13325 689 344 13326 691 344 13327 690 344 13328 691 4266 13329 693 4266 13330 692 4266 13331 693 4267 13332 695 4267 13333 694 4267 13334 695 347 13335 697 347 13336 696 347 13337 697 4268 13338 699 4268 13339 698 4268 13340 699 4269 13341 701 4269 13342 700 4269 13343 701 4270 13344 703 4270 13345 702 4270 13346 703 351 13347 705 351 13348 704 351 13349 705 352 13350 707 352 13351 706 352 13352 707 353 13353 709 353 13354 708 353 13355 709 4271 13356 711 4271 13357 710 4271 13358 711 355 13359 713 355 13360 712 355 13361 713 356 13362 715 356 13363 714 356 13364 715 357 13365 717 357 13366 716 357 13367 717 358 13368 719 358 13369 718 358 13370 719 4272 13371 721 4272 13372 720 4272 13373 721 360 13374 723 360 13375 722 360 13376 723 4273 13377 725 4273 13378 724 4273 13379 725 4274 13380 727 4274 13381 726 4274 13382 727 4275 13383 729 4275 13384 728 4275 13385 729 4276 13386 731 4276 13387 730 4276 13388 731 365 13389 733 365 13390 732 365 13391 733 366 13392 735 366 13393 734 366 13394 735 4277 13395 737 4277 13396 736 4277 13397 737 4278 13398 739 4278 13399 738 4278 13400 739 4279 13401 741 4279 13402 740 4279 13403 741 4280 13404 743 4280 13405 742 4280 13406 743 4281 13407 745 4281 13408 744 4281 13409 745 4282 13410 747 4282 13411 746 4282 13412 747 373 13413 749 373 13414 748 373 13415 749 4283 13416 751 4283 13417 750 4283 13418 751 4284 13419 753 4284 13420 752 4284 13421 753 376 13422 755 376 13423 754 376 13424 755 377 13425 757 377 13426 756 377 13427 757 4285 13428 759 4285 13429 758 4285 13430 759 4286 13431 761 4286 13432 760 4286 13433 761 380 13434 763 380 13435 762 380 13436 763 381 13437 765 381 13438 764 381 13439 765 4287 13440 767 4287 13441 766 4287 13442 767 383 13443 769 383 13444 768 383 13445 769 384 13446 771 384 13447 770 384 13448 771 4288 13449 773 4288 13450 772 4288 13451 773 386 13452 775 386 13453 774 386 13454 775 387 13455 777 387 13456 776 387 13457 777 4289 13458 779 4289 13459 778 4289 13460 779 4290 13461 781 4290 13462 780 4290 13463 781 4291 13464 783 4291 13465 782 4291 13466 783 4292 13467 785 4292 13468 784 4292 13469 785 4293 13470 787 4293 13471 786 4293 13472 787 393 13473 789 393 13474 788 393 13475 789 4294 13476 791 4294 13477 790 4294 13478 791 4295 13479 793 4295 13480 792 4295 13481 793 396 13482 795 396 13483 794 396 13484 795 397 13485 797 397 13486 796 397 13487 797 398 13488 799 398 13489 798 398 13490 799 4296 13491 801 4296 13492 800 4296 13493 801 400 13494 803 400 13495 802 400 13496 803 4297 13497 805 4297 13498 804 4297 13499 805 402 13500 807 402 13501 806 402 13502 807 403 13503 809 403 13504 808 403 13505 809 404 13506 811 404 13507 810 404 13508 811 405 13509 813 405 13510 812 405 13511 813 406 13512 815 406 13513 814 406 13514 815 407 13515 817 407 13516 816 407 13517 817 4298 13518 819 4298 13519 818 4298 13520 819 409 13521 821 409 13522 820 409 13523 821 4299 13524 823 4299 13525 822 4299 13526 823 4300 13527 825 4300 13528 824 4300 13529 825 412 13530 827 412 13531 826 412 13532 827 413 13533 829 413 13534 828 413 13535 829 414 13536 831 414 13537 830 414 13538 831 4301 13539 833 4301 13540 832 4301 13541 833 416 13542 835 416 13543 834 416 13544 835 417 13545 837 417 13546 836 417 13547 837 418 13548 839 418 13549 838 418 13550 839 4302 13551 841 4302 13552 840 4302 13553 841 4303 13554 843 4303 13555 842 4303 13556 843 4304 13557 845 4304 13558 844 4304 13559 845 4305 13560 847 4305 13561 846 4305 13562 847 4306 13563 849 4306 13564 848 4306 13565 849 424 13566 851 424 13567 850 424 13568 851 425 13569 853 425 13570 852 425 13571 853 426 13572 855 426 13573 854 426 13574 855 4307 13575 857 4307 13576 856 4307 13577 857 428 13578 859 428 13579 858 428 13580 859 4308 13581 861 4308 13582 860 4308 13583 861 430 13584 863 430 13585 862 430 13586 863 4309 13587 865 4309 13588 864 4309 13589 865 432 13590 867 432 13591 866 432 13592 867 4310 13593 869 4310 13594 868 4310 13595 869 434 13596 871 434 13597 870 434 13598 871 4311 13599 873 4311 13600 872 4311 13601 873 4312 13602 875 4312 13603 874 4312 13604 875 437 13605 877 437 13606 876 437 13607 877 438 13608 879 438 13609 878 438 13610 879 439 13611 881 439 13612 880 439 13613 881 440 13614 883 440 13615 882 440 13616 883 441 13617 885 441 13618 884 441 13619 885 442 13620 887 442 13621 886 442 13622 887 443 13623 889 443 13624 888 443 13625 889 444 13626 891 444 13627 890 444 13628 891 445 13629 893 445 13630 892 445 13631 893 446 13632 895 446 13633 894 446 13634 895 4313 13635 897 4313 13636 896 4313 13637 897 4314 13638 899 4314 13639 898 4314 13640 899 449 13641 901 449 13642 900 449 13643 901 450 13644 903 450 13645 902 450 13646 903 451 13647 905 451 13648 904 451 13649 905 4315 13650 907 4315 13651 906 4315 13652 907 453 13653 909 453 13654 908 453 13655 909 454 13656 911 454 13657 910 454 13658 911 4316 13659 913 4316 13660 912 4316 13661 913 456 13662 915 456 13663 914 456 13664 915 457 13665 917 457 13666 916 457 13667 917 4317 13668 919 4317 13669 918 4317 13670 919 4318 13671 921 4318 13672 920 4318 13673 921 4319 13674 923 4319 13675 922 4319 13676 923 461 13677 925 461 13678 924 461 13679 925 462 13680 927 462 13681 926 462 13682 927 463 13683 929 463 13684 928 463 13685 929 464 13686 931 464 13687 930 464 13688 931 4320 13689 933 4320 13690 932 4320 13691 933 4321 13692 935 4321 13693 934 4321 13694 935 4322 13695 937 4322 13696 936 4322 13697 937 4323 13698 939 4323 13699 938 4323 13700 939 4324 13701 941 4324 13702 940 4324 13703 941 4325 13704 943 4325 13705 942 4325 13706 943 4326 13707 945 4326 13708 944 4326 13709 945 4327 13710 947 4327 13711 946 4327 13712 947 473 13713 949 473 13714 948 473 13715 949 474 13716 951 474 13717 950 474 13718 951 475 13719 953 475 13720 952 475 13721 953 476 13722 955 476 13723 954 476 13724 955 4328 13725 957 4328 13726 956 4328 13727 957 478 13728 959 478 13729 958 478 13730 959 4329 13731 961 4329 13732 960 4329 13733 961 480 13734 963 480 13735 962 480 13736 963 4330 13737 965 4330 13738 964 4330 13739 965 4331 13740 967 4331 13741 966 4331 13742 967 483 13743 969 483 13744 968 483 13745 969 4332 13746 971 4332 13747 970 4332 13748 971 4333 13749 973 4333 13750 972 4333 13751 973 4334 13752 975 4334 13753 974 4334 13754 975 4335 13755 977 4335 13756 976 4335 13757 977 4336 13758 979 4336 13759 978 4336 13760 979 4337 13761 981 4337 13762 980 4337 13763 981 490 13764 983 490 13765 982 490 13766 983 4338 13767 985 4338 13768 984 4338 13769 985 492 13770 987 492 13771 986 492 13772 987 4339 13773 989 4339 13774 988 4339 13775 989 494 13776 991 494 13777 990 494 13778 991 4340 13779 993 4340 13780 992 4340 13781 993 4341 13782 995 4341 13783 994 4341 13784 995 4342 13785 997 4342 13786 996 4342 13787 997 4343 13788 999 4343 13789 998 4343 13790 999 4344 13791 1001 4344 13792 1000 4344 13793 1001 4345 13794 1003 4345 13795 1002 4345 13796 1003 4346 13797 1005 4346 13798 1004 4346 13799 1005 4347 13800 1007 4347 13801 1006 4347 13802 1007 503 13803 1009 503 13804 1008 503 13805 1009 504 13806 1011 504 13807 1010 504 13808 1011 505 13809 1013 505 13810 1012 505 13811 1013 4348 13812 1015 4348 13813 1014 4348 13814 1015 4349 13815 1017 4349 13816 1016 4349 13817 1017 508 13818 1019 508 13819 1018 508 13820 1019 4350 13821 1021 4350 13822 1020 4350 13823 1021 510 13824 1023 510 13825 1022 510 13826 1023 511 13827 1025 511 13828 1024 511 13829 1025 512 13830 1027 512 13831 1026 512 13832 1027 513 13833 1029 513 13834 1028 513 13835 1029 514 13836 1031 514 13837 1030 514 13838 1031 4351 13839 1033 4351 13840 1032 4351 13841 1033 516 13842 1035 516 13843 1034 516 13844 1035 517 13845 1037 517 13846 1036 517 13847 1037 4352 13848 1039 4352 13849 1038 4352 13850 1039 4353 13851 1041 4353 13852 1040 4353 13853 1041 4354 13854 1043 4354 13855 1042 4354 13856 1043 4355 13857 1045 4355 13858 1044 4355 13859 1045 4356 13860 1047 4356 13861 1046 4356 13862 1047 523 13863 1049 523 13864 1048 523 13865 1049 524 13866 1051 524 13867 1050 524 13868 1051 4357 13869 1053 4357 13870 1052 4357 13871 1053 4358 13872 1055 4358 13873 1054 4358 13874 1055 4359 13875 1057 4359 13876 1056 4359 13877 1057 4360 13878 1059 4360 13879 1058 4360 13880 1059 4361 13881 1061 4361 13882 1060 4361 13883 1061 4362 13884 1063 4362 13885 1062 4362 13886 1063 4363 13887 1065 4363 13888 1064 4363 13889 1065 4364 13890 1067 4364 13891 1066 4364 13892 1067 533 13893 1069 533 13894 1068 533 13895 1069 4365 13896 1071 4365 13897 1070 4365 13898 1071 4366 13899 1073 4366 13900 1072 4366 13901 1073 4367 13902 1075 4367 13903 1074 4367 13904 1075 4368 13905 1077 4368 13906 1076 4368 13907 1077 4369 13908 1079 4369 13909 1078 4369 13910 1079 4370 13911 1081 4370 13912 1080 4370 13913 1081 4371 13914 1083 4371 13915 1082 4371 13916 1083 541 13917 1085 541 13918 1084 541 13919 1085 4372 13920 1087 4372 13921 1086 4372 13922 1087 543 13923 1089 543 13924 1088 543 13925 1089 4373 13926 1091 4373 13927 1090 4373 13928 1091 4374 13929 1093 4374 13930 1092 4374 13931 1093 4375 13932 1095 4375 13933 1094 4375 13934 1095 4376 13935 1097 4376 13936 1096 4376 13937 1097 4377 13938 1099 4377 13939 1098 4377 13940 1099 549 13941 1101 549 13942 1100 549 13943 1101 550 13944 1103 550 13945 1102 550 13946 1103 4378 13947 1105 4378 13948 1104 4378 13949 1105 4379 13950 1107 4379 13951 1106 4379 13952 1107 4380 13953 1109 4380 13954 1108 4380 13955 1109 554 13956 1111 554 13957 1110 554 13958 1111 4381 13959 1113 4381 13960 1112 4381 13961 1113 556 13962 1115 556 13963 1114 556 13964 1115 4382 13965 1117 4382 13966 1116 4382 13967 1117 558 13968 1119 558 13969 1118 558 13970 1119 4383 13971 1121 4383 13972 1120 4383 13973 1121 4384 13974 1123 4384 13975 1122 4384 13976 1123 4385 13977 1125 4385 13978 1124 4385 13979 1125 4386 13980 1127 4386 13981 1126 4386 13982 1127 4387 13983 1129 4387 13984 1128 4387 13985 1129 564 13986 1131 564 13987 1130 564 13988 1131 4388 13989 1133 4388 13990 1132 4388 13991 1133 4389 13992 1135 4389 13993 1134 4389 13994 1135 567 13995 1137 567 13996 1136 567 13997 1137 4390 13998 1139 4390 13999 1138 4390 14000 1139 569 14001 1141 569 14002 1140 569 14003 1141 570 14004 1143 570 14005 1142 570 14006 1143 571 14007 1145 571 14008 1144 571 14009 1145 4391 14010 1147 4391 14011 1146 4391 14012 1147 4392 14013 1149 4392 14014 1148 4392 14015 1149 574 14016 1151 574 14017 1150 574 14018 1151 575 14019 1153 575 14020 1152 575 14021 1153 4393 14022 1155 4393 14023 1154 4393 14024 1155 4394 14025 1157 4394 14026 1156 4394 14027 1157 4395 14028 1159 4395 14029 1158 4395 14030 1159 4396 14031 1161 4396 14032 1160 4396 14033 1161 4397 14034 1163 4397 14035 1162 4397 14036 1163 4398 14037 1165 4398 14038 1164 4398 14039 1165 4399 14040 1167 4399 14041 1166 4399 14042 1167 4400 14043 1169 4400 14044 1168 4400 14045 1169 584 14046 1171 584 14047 1170 584 14048 1171 4401 14049 1173 4401 14050 1172 4401 14051 1173 586 14052 1175 586 14053 1174 586 14054 1175 587 14055 1177 587 14056 1176 587 14057 1177 4402 14058 1179 4402 14059 1178 4402 14060 1179 589 14061 1181 589 14062 1180 589 14063 1181 590 14064 1183 590 14065 1182 590 14066 1183 4403 14067 1185 4403 14068 1184 4403 14069 1185 592 14070 1187 592 14071 1186 592 14072 1187 4404 14073 1189 4404 14074 1188 4404 14075 1189 594 14076 1191 594 14077 1190 594 14078 1191 595 14079 1193 595 14080 1192 595 14081 1193 4405 14082 1195 4405 14083 1194 4405 14084 1195 597 14085 1197 597 14086 1196 597 14087 1197 4406 14088 1199 4406 14089 1198 4406 14090 1199 4407 14091 1201 4407 14092 1200 4407 14093 1201 4408 14094 1203 4408 14095 1202 4408 14096 1203 601 14097 1205 601 14098 1204 601 14099 1205 4409 14100 1207 4409 14101 1206 4409 14102 1207 4410 14103 1209 4410 14104 1208 4410 14105 1209 604 14106 1211 604 14107 1210 604 14108 1211 605 14109 1213 605 14110 1212 605 14111 1213 606 14112 1215 606 14113 1214 606 14114 1215 4411 14115 1217 4411 14116 1216 4411 14117 1217 4412 14118 1219 4412 14119 1218 4412 14120 1219 4413 14121 1221 4413 14122 1220 4413 14123 1221 610 14124 1223 610 14125 1222 610 14126 1223 611 14127 1225 611 14128 1224 611 14129 1225 612 14130 1227 612 14131 1226 612 14132 1227 4414 14133 1229 4414 14134 1228 4414 14135 1229 4415 14136 1231 4415 14137 1230 4415 14138 1231 4416 14139 1233 4416 14140 1232 4416 14141 1233 616 14142 1235 616 14143 1234 616 14144 1235 617 14145 1237 617 14146 1236 617 14147 1237 618 14148 1239 618 14149 1238 618 14150 1239 619 14151 1241 619 14152 1240 619 14153 1241 620 14154 1243 620 14155 1242 620 14156 1243 4417 14157 1245 4417 14158 1244 4417 14159 1245 622 14160 1247 622 14161 1246 622 14162 1247 4418 14163 1249 4418 14164 1248 4418 14165 1249 4419 14166 1251 4419 14167 1250 4419 14168 1251 625 14169 1253 625 14170 1252 625 14171 1253 626 14172 1255 626 14173 1254 626 14174 1255 627 14175 1257 627 14176 1256 627 14177 1257 628 14178 1259 628 14179 1258 628 14180 1259 629 14181 1261 629 14182 1260 629 14183 1261 4420 14184 1263 4420 14185 1262 4420 14186 1263 631 14187 1265 631 14188 1264 631 14189 1265 4421 14190 1267 4421 14191 1266 4421 14192 1267 4422 14193 1269 4422 14194 1268 4422 14195 1269 634 14196 1271 634 14197 1270 634 14198 1271 4423 14199 1273 4423 14200 1272 4423 14201 1273 4424 14202 1275 4424 14203 1274 4424 14204 1275 637 14205 1277 637 14206 1276 637 14207 1277 638 14208 1279 638 14209 1278 638 14210 1279 639 14211 1281 639 14212 1280 639 14213 1281 640 14214 1283 640 14215 1282 640 14216 1283 4425 14217 1285 4425 14218 1284 4425 14219 1285 642 14220 1287 642 14221 1286 642 14222 1287 643 14223 1289 643 14224 1288 643 14225 1289 644 14226 1291 644 14227 1290 644 14228 1291 645 14229 1293 645 14230 1292 645 14231 1293 646 14232 1295 646 14233 1294 646 14234 1295 4426 14235 1297 4426 14236 1296 4426 14237 1297 648 14238 1299 648 14239 1298 648 14240 1299 649 14241 1301 649 14242 1300 649 14243 1301 650 14244 1303 650 14245 1302 650 14246 1303 4427 14247 1305 4427 14248 1304 4427 14249 1305 4428 14250 1307 4428 14251 1306 4428 14252 1307 653 14253 1309 653 14254 1308 653 14255 1309 654 14256 1311 654 14257 1310 654 14258 1311 655 14259 1313 655 14260 1312 655 14261 1313 656 14262 1315 656 14263 1314 656 14264 1315 657 14265 1317 657 14266 1316 657 14267 1317 4429 14268 1319 4429 14269 1318 4429 14270 1319 659 14271 1321 659 14272 1320 659 14273 1321 660 14274 1323 660 14275 1322 660 14276 1323 4430 14277 1325 4430 14278 1324 4430 14279 1325 4431 14280 1327 4431 14281 1326 4431 14282 1327 663 14283 1329 663 14284 1328 663 14285 1329 664 14286 1331 664 14287 1330 664 14288 1331 665 14289 1333 665 14290 1332 665 14291 1333 4432 14292 1335 4432 14293 1334 4432 14294 1335 4433 14295 1337 4433 14296 1336 4433 14297 1337 4434 14298 1339 4434 14299 1338 4434 14300 1339 669 14301 1341 669 14302 1340 669 14303 1341 4435 14304 1343 4435 14305 1342 4435 14306 1343 671 14307 1345 671 14308 1344 671 14309 1345 672 14310 1347 672 14311 1346 672 14312 1347 673 14313 1349 673 14314 1348 673 14315 1349 674 14316 1351 674 14317 1350 674 14318 1351 675 14319 1353 675 14320 1352 675 14321 1353 4436 14322 1355 4436 14323 1354 4436 14324 1355 677 14325 1357 677 14326 1356 677 14327 1357 678 14328 1359 678 14329 1358 678 14330 1359 679 14331 1361 679 14332 1360 679 14333 1361 680 14334 1363 680 14335 1362 680 14336 1363 681 14337 1365 681 14338 1364 681 14339 1365 682 14340 1367 682 14341 1366 682 14342 1367 4437 14343 1369 4437 14344 1368 4437 14345 1369 4438 14346 1371 4438 14347 1370 4438 14348 1371 4439 14349 1373 4439 14350 1372 4439 14351 1373 4440 14352 1375 4440 14353 1374 4440 14354 1375 687 14355 1377 687 14356 1376 687 14357 1377 688 14358 1379 688 14359 1378 688 14360 1379 689 14361 1381 689 14362 1380 689 14363 1381 4441 14364 1383 4441 14365 1382 4441 14366 1383 4442 14367 1385 4442 14368 1384 4442 14369 1385 692 14370 1387 692 14371 1386 692 14372 1387 693 14373 1389 693 14374 1388 693 14375 1389 4443 14376 1391 4443 14377 1390 4443 14378 1391 4444 14379 1393 4444 14380 1392 4444 14381 1393 696 14382 1395 696 14383 1394 696 14384 1395 697 14385 1397 697 14386 1396 697 14387 1397 4445 14388 1399 4445 14389 1398 4445 14390 1399 699 14391 1401 699 14392 1400 699 14393 1401 4446 14394 1403 4446 14395 1402 4446 14396 1403 4447 14397 1405 4447 14398 1404 4447 14399 1405 702 14400 1407 702 14401 1406 702 14402 1407 4448 14403 1409 4448 14404 1408 4448 14405 1409 4449 14406 1411 4449 14407 1410 4449 14408 1411 4450 14409 1413 4450 14410 1412 4450 14411 1413 4451 14412 1415 4451 14413 1414 4451 14414 1415 707 14415 1417 707 14416 1416 707 14417 1417 4452 14418 1419 4452 14419 1418 4452 14420 1419 709 14421 1421 709 14422 1420 709 14423 1421 4453 14424 1423 4453 14425 1422 4453 14426 1423 711 14427 1425 711 14428 1424 711 14429 1425 712 14430 1427 712 14431 1426 712 14432 1427 713 14433 1429 713 14434 1428 713 14435 1429 4454 14436 1431 4454 14437 1430 4454 14438 1431 715 14439 1433 715 14440 1432 715 14441 1433 716 14442 1435 716 14443 1434 716 14444 1435 4455 14445 1437 4455 14446 1436 4455 14447 1437 718 14448 1439 718 14449 1438 718 14450 1439 4456 14451 1441 4456 14452 1440 4456 14453 1441 720 14454 1443 720 14455 1442 720 14456 1443 721 14457 1445 721 14458 1444 721 14459 1445 4457 14460 1447 4457 14461 1446 4457 14462 1447 4458 14463 1449 4458 14464 1448 4458 14465 1449 724 14466 1451 724 14467 1450 724 14468 1451 4459 14469 1453 4459 14470 1452 4459 14471 1453 726 14472 1455 726 14473 1454 726 14474 1455 727 14475 1457 727 14476 1456 727 14477 1457 728 14478 1459 728 14479 1458 728 14480 1459 4460 14481 1461 4460 14482 1460 4460 14483 1461 4461 14484 1463 4461 14485 1462 4461 14486 1463 731 14487 1465 731 14488 1464 731 14489 1465 732 14490 1467 732 14491 1466 732 14492 1467 4462 14493 1469 4462 14494 1468 4462 14495 1469 4463 14496 1471 4463 14497 1470 4463 14498 1471 735 14499 1473 735 14500 1472 735 14501 1473 4464 14502 1475 4464 14503 1474 4464 14504 1475 737 14505 1477 737 14506 1476 737 14507 1477 738 14508 1479 738 14509 1478 738 14510 1479 4465 14511 1481 4465 14512 1480 4465 14513 1481 4466 14514 1483 4466 14515 1482 4466 14516 1483 741 14517 1485 741 14518 1484 741 14519 1485 4467 14520 1487 4467 14521 1486 4467 14522 1487 4468 14523 1489 4468 14524 1488 4468 14525 1489 744 14526 1491 744 14527 1490 744 14528 1491 4469 14529 1493 4469 14530 1492 4469 14531 1493 746 14532 1495 746 14533 1494 746 14534 1495 4470 14535 1497 4470 14536 1496 4470 14537 1497 4471 14538 1499 4471 14539 1498 4471 14540 1499 749 14541 1501 749 14542 1500 749 14543 1501 4472 14544 1503 4472 14545 1502 4472 14546 1503 4473 14547 1505 4473 14548 1504 4473 14549 1505 752 14550 1507 752 14551 1506 752 14552 1507 4474 14553 1509 4474 14554 1508 4474 14555 1509 4475 14556 1511 4475 14557 1510 4475 14558 1511 4476 14559 1513 4476 14560 1512 4476 14561 1513 756 14562 1515 756 14563 1514 756 14564 1515 757 14565 1517 757 14566 1516 757 14567 1517 4477 14568 1519 4477 14569 1518 4477 14570 1519 759 14571 1521 759 14572 1520 759 14573 1521 4478 14574 1523 4478 14575 1522 4478 14576 1523 4479 14577 1525 4479 14578 1524 4479 14579 1525 4480 14580 1527 4480 14581 1526 4480 14582 1527 4481 14583 1529 4481 14584 1528 4481 14585 1529 764 14586 1531 764 14587 1530 764 14588 1531 765 14589 1533 765 14590 1532 765 14591 1533 4482 14592 1535 4482 14593 1534 4482 14594 1535 4483 14595 1537 4483 14596 1536 4483 14597 1537 4484 14598 1539 4484 14599 1538 4484 14600 1539 769 14601 1541 769 14602 1540 769 14603 1541 4485 14604 1543 4485 14605 1542 4485 14606 1543 4486 14607 1545 4486 14608 1544 4486 14609 1545 4487 14610 1547 4487 14611 1546 4487 14612 1547 4488 14613 1549 4488 14614 1548 4488 14615 1549 4489 14616 1551 4489 14617 1550 4489 14618 1551 4490 14619 1553 4490 14620 1552 4490 14621 1553 776 14622 1555 776 14623 1554 776 14624 1555 4491 14625 1557 4491 14626 1556 4491 14627 1557 778 14628 1559 778 14629 1558 778 14630 1559 779 14631 1561 779 14632 1560 779 14633 1561 4492 14634 1563 4492 14635 1562 4492 14636 1563 4493 14637 1565 4493 14638 1564 4493 14639 1565 4494 14640 1567 4494 14641 1566 4494 14642 1567 4495 14643 1569 4495 14644 1568 4495 14645 1569 784 14646 1571 784 14647 1570 784 14648 1571 785 14649 1573 785 14650 1572 785 14651 1573 786 14652 1575 786 14653 1574 786 14654 1575 787 14655 1577 787 14656 1576 787 14657 1577 788 14658 1579 788 14659 1578 788 14660 1579 4496 14661 1581 4496 14662 1580 4496 14663 1581 4497 14664 1583 4497 14665 1582 4497 14666 1583 4498 14667 1585 4498 14668 1584 4498 14669 1585 792 14670 1587 792 14671 1586 792 14672 1587 793 14673 1589 793 14674 1588 793 14675 1589 794 14676 1591 794 14677 1590 794 14678 1591 4499 14679 1593 4499 14680 1592 4499 14681 1593 796 14682 1595 796 14683 1594 796 14684 1595 4500 14685 1597 4500 14686 1596 4500 14687 1597 798 14688 1599 798 14689 1598 798 14690 1599 4501 14691 1601 4501 14692 1600 4501 14693 1601 800 14694 1603 800 14695 1602 800 14696 1603 801 14697 1605 801 14698 1604 801 14699 1605 4502 14700 1607 4502 14701 1606 4502 14702 1607 803 14703 1609 803 14704 1608 803 14705 1609 4503 14706 1611 4503 14707 1610 4503 14708 1611 4504 14709 1613 4504 14710 1612 4504 14711 1613 806 14712 1615 806 14713 1614 806 14714 1615 4505 14715 1617 4505 14716 1616 4505 14717 1617 808 14718 1619 808 14719 1618 808 14720 1619 809 14721 1621 809 14722 1620 809 14723 1621 4506 14724 1623 4506 14725 1622 4506 14726 1623 4507 14727 1625 4507 14728 1624 4507 14729 1625 812 14730 1627 812 14731 1626 812 14732 1627 4508 14733 1629 4508 14734 1628 4508 14735 1629 4509 14736 1631 4509 14737 1630 4509 14738 1631 4510 14739 1633 4510 14740 1632 4510 14741 1633 816 14742 1635 816 14743 1634 816 14744 1635 4511 14745 1637 4511 14746 1636 4511 14747 1637 4512 14748 1639 4512 14749 1638 4512 14750 1639 819 14751 1641 819 14752 1640 819 14753 1641 820 14754 1643 820 14755 1642 820 14756 1643 821 14757 1645 821 14758 1644 821 14759 1645 4513 14760 1647 4513 14761 1646 4513 14762 1647 4514 14763 1649 4514 14764 1648 4514 14765 1649 824 14766 1651 824 14767 1650 824 14768 1651 825 14769 1653 825 14770 1652 825 14771 1653 826 14772 1655 826 14773 1654 826 14774 1655 4515 14775 1657 4515 14776 1656 4515 14777 1657 828 14778 1659 828 14779 1658 828 14780 1659 829 14781 1661 829 14782 1660 829 14783 1661 4516 14784 1663 4516 14785 1662 4516 14786 1663 831 14787 1665 831 14788 1664 831 14789 1665 832 14790 1667 832 14791 1666 832 14792 1667 833 14793 1669 833 14794 1668 833 14795 1669 834 14796 1671 834 14797 1670 834 14798 1671 835 14799 1673 835 14800 1672 835 14801 1673 4517 14802 1675 4517 14803 1674 4517 14804 1675 4518 14805 1677 4518 14806 1676 4518 14807 1677 838 14808 1679 838 14809 1678 838 14810 1679 4519 14811 1681 4519 14812 1680 4519 14813 1681 4520 14814 1683 4520 14815 1682 4520 14816 1683 4521 14817 1685 4521 14818 1684 4521 14819 1685 4522 14820 1687 4522 14821 1686 4522 14822 1687 843 14823 1689 843 14824 1688 843 14825 1689 4523 14826 1691 4523 14827 1690 4523 14828 1691 4524 14829 1693 4524 14830 1692 4524 14831 1693 4525 14832 1695 4525 14833 1694 4525 14834 1695 4526 14835 1697 4526 14836 1696 4526 14837 1697 4527 14838 1699 4527 14839 1698 4527 14840 1699 4528 14841 1701 4528 14842 1700 4528 14843 1701 4529 14844 1703 4529 14845 1702 4529 14846 1703 4530 14847 1705 4530 14848 1704 4530 14849 1705 4531 14850 1707 4531 14851 1706 4531 14852 1707 853 14853 1709 853 14854 1708 853 14855 1709 4532 14856 1711 4532 14857 1710 4532 14858 1711 855 14859 1713 855 14860 1712 855 14861 1713 856 14862 1715 856 14863 1714 856 14864 1715 857 14865 1717 857 14866 1716 857 14867 1717 858 14868 1719 858 14869 1718 858 14870 1719 4533 14871 1721 4533 14872 1720 4533 14873 1721 860 14874 1723 860 14875 1722 860 14876 1723 4534 14877 1725 4534 14878 1724 4534 14879 1725 862 14880 1727 862 14881 1726 862 14882 1727 4535 14883 1729 4535 14884 1728 4535 14885 1729 864 14886 1731 864 14887 1730 864 14888 1731 865 14889 1733 865 14890 1732 865 14891 1733 4536 14892 1735 4536 14893 1734 4536 14894 1735 867 14895 1737 867 14896 1736 867 14897 1737 868 14898 1739 868 14899 1738 868 14900 1739 4537 14901 1741 4537 14902 1740 4537 14903 1741 870 14904 1743 870 14905 1742 870 14906 1743 871 14907 1745 871 14908 1744 871 14909 1745 4538 14910 1747 4538 14911 1746 4538 14912 1747 4539 14913 1749 4539 14914 1748 4539 14915 1749 874 14916 1751 874 14917 1750 874 14918 1751 875 14919 1753 875 14920 1752 875 14921 1753 876 14922 1755 876 14923 1754 876 14924 1755 4540 14925 1757 4540 14926 1756 4540 14927 1757 878 14928 1759 878 14929 1758 878 14930 1759 879 14931 1761 879 14932 1760 879 14933 1761 880 14934 1763 880 14935 1762 880 14936 1763 4541 14937 1765 4541 14938 1764 4541 14939 1765 882 14940 1767 882 14941 1766 882 14942 1767 883 14943 1769 883 14944 1768 883 14945 1769 4542 14946 1771 4542 14947 1770 4542 14948 1771 4543 14949 1773 4543 14950 1772 4543 14951 1773 886 14952 1775 886 14953 1774 886 14954 1775 887 14955 1777 887 14956 1776 887 14957 1777 4544 14958 1779 4544 14959 1778 4544 14960 1779 889 14961 1781 889 14962 1780 889 14963 1781 890 14964 1783 890 14965 1782 890 14966 1783 4545 14967 1785 4545 14968 1784 4545 14969 1785 892 14970 1787 892 14971 1786 892 14972 1787 4546 14973 1789 4546 14974 1788 4546 14975 1789 4547 14976 1791 4547 14977 1790 4547 14978 1791 895 14979 1793 895 14980 1792 895 14981 1793 896 14982 1795 896 14983 1794 896 14984 1795 4548 14985 1797 4548 14986 1796 4548 14987 1797 898 14988 1799 898 14989 1798 898 14990 1799 4549 14991 1801 4549 14992 1800 4549 14993 1801 900 14994 1803 900 14995 1802 900 14996 1803 901 14997 1805 901 14998 1804 901 14999 1805 4550 15000 1807 4550 15001 1806 4550 15002 1807 903 15003 1809 903 15004 1808 903 15005 1809 4551 15006 1811 4551 15007 1810 4551 15008 1811 4552 15009 1813 4552 15010 1812 4552 15011 1813 906 15012 1815 906 15013 1814 906 15014 1815 907 15015 1817 907 15016 1816 907 15017 1817 908 15018 1819 908 15019 1818 908 15020 1819 4553 15021 1821 4553 15022 1820 4553 15023 1821 4554 15024 1823 4554 15025 1822 4554 15026 1823 4555 15027 1825 4555 15028 1824 4555 15029 1825 912 15030 1827 912 15031 1826 912 15032 1827 913 15033 1829 913 15034 1828 913 15035 1829 914 15036 1831 914 15037 1830 914 15038 1831 915 15039 1833 915 15040 1832 915 15041 1833 4556 15042 1835 4556 15043 1834 4556 15044 1835 4557 15045 1837 4557 15046 1836 4557 15047 1837 4558 15048 1839 4558 15049 1838 4558 15050 1839 919 15051 1841 919 15052 1840 919 15053 1841 4559 15054 1843 4559 15055 1842 4559 15056 1843 921 15057 1845 921 15058 1844 921 15059 1845 4560 15060 1847 4560 15061 1846 4560 15062 1847 923 15063 1849 923 15064 1848 923 15065 1849 4561 15066 1851 4561 15067 1850 4561 15068 1851 4562 15069 1853 4562 15070 1852 4562 15071 1853 4563 15072 1855 4563 15073 1854 4563 15074 1855 927 15075 1857 927 15076 1856 927 15077 1857 4564 15078 1859 4564 15079 1858 4564 15080 1859 4565 15081 1861 4565 15082 1860 4565 15083 1861 4566 15084 1863 4566 15085 1862 4566 15086 1863 4567 15087 1865 4567 15088 1864 4567 15089 1865 4568 15090 1867 4568 15091 1866 4568 15092 1867 4569 15093 1869 4569 15094 1868 4569 15095 1869 934 15096 1871 934 15097 1870 934 15098 1871 935 15099 1873 935 15100 1872 935 15101 1873 936 15102 1875 936 15103 1874 936 15104 1875 937 15105 1877 937 15106 1876 937 15107 1877 938 15108 1879 938 15109 1878 938 15110 1879 4570 15111 1881 4570 15112 1880 4570 15113 1881 4571 15114 1883 4571 15115 1882 4571 15116 1883 941 15117 1885 941 15118 1884 941 15119 1885 942 15120 1887 942 15121 1886 942 15122 1887 943 15123 1889 943 15124 1888 943 15125 1889 944 15126 1891 944 15127 1890 944 15128 1891 945 15129 1893 945 15130 1892 945 15131 1893 946 15132 1895 946 15133 1894 946 15134 1895 4572 15135 1897 4572 15136 1896 4572 15137 1897 948 15138 1899 948 15139 1898 948 15140 1899 4573 15141 1901 4573 15142 1900 4573 15143 1901 950 15144 1903 950 15145 1902 950 15146 1903 951 15147 1905 951 15148 1904 951 15149 1905 4574 15150 1907 4574 15151 1906 4574 15152 1907 953 15153 1909 953 15154 1908 953 15155 1909 954 15156 1911 954 15157 1910 954 15158 1911 955 15159 1913 955 15160 1912 955 15161 1913 956 15162 1915 956 15163 1914 956 15164 1915 957 15165 1917 957 15166 1916 957 15167 1917 958 15168 1919 958 15169 1918 958 15170 1919 959 15171 1921 959 15172 1920 959 15173 1921 4575 15174 1923 4575 15175 1922 4575 15176 1923 961 15177 1925 961 15178 1924 961 15179 1925 962 15180 1927 962 15181 1926 962 15182 1927 4576 15183 1929 4576 15184 1928 4576 15185 1929 964 15186 1931 964 15187 1930 964 15188 1931 965 15189 1933 965 15190 1932 965 15191 1933 4577 15192 1935 4577 15193 1934 4577 15194 1935 967 15195 1937 967 15196 1936 967 15197 1937 968 15198 1939 968 15199 1938 968 15200 1939 4578 15201 1941 4578 15202 1940 4578 15203 1941 970 15204 1943 970 15205 1942 970 15206 1943 971 15207 1945 971 15208 1944 971 15209 1945 4579 15210 1947 4579 15211 1946 4579 15212 1947 973 15213 1949 973 15214 1948 973 15215 1949 974 15216 1951 974 15217 1950 974 15218 1951 4580 15219 1953 4580 15220 1952 4580 15221 1953 976 15222 1955 976 15223 1954 976 15224 1955 977 15225 1957 977 15226 1956 977 15227 1957 4581 15228 1959 4581 15229 1958 4581 15230 1959 4582 15231 1961 4582 15232 1960 4582 15233 1961 980 15234 1963 980 15235 1962 980 15236 1963 4583 15237 1965 4583 15238 1964 4583 15239 1965 4584 15240 1967 4584 15241 1966 4584 15242 1967 983 15243 1969 983 15244 1968 983 15245 1969 4585 15246 1971 4585 15247 1970 4585 15248 1971 4586 15249 1973 4586 15250 1972 4586 15251 1973 4587 15252 1975 4587 15253 1974 4587 15254 1975 987 15255 1977 987 15256 1976 987 15257 1977 4588 15258 1979 4588 15259 1978 4588 15260 1979 989 15261 1981 989 15262 1980 989 15263 1981 990 15264 1983 990 15265 1982 990 15266 1983 991 15267 1985 991 15268 1984 991 15269 1985 4589 15270 1987 4589 15271 1986 4589 15272 1987 993 15273 1989 993 15274 1988 993 15275 1989 994 15276 1991 994 15277 1990 994 15278 1991 4590 15279 1993 4590 15280 1992 4590 15281 1993 4591 15282 1995 4591 15283 1994 4591 15284 1995 997 15285 1997 997 15286 1996 997 15287 1997 4592 15288 1999 4592 15289 1998 4592 15290 1999 999 15291 2001 999 15292 2000 999 15293 2001 1000 15294 2003 1000 15295 2002 1000 15296 2003 1001 15297 2005 1001 15298 2004 1001 15299 2005 4593 15300 2007 4593 15301 2006 4593 15302 2007 4594 15303 2009 4594 15304 2008 4594 15305 2009 1004 15306 2011 1004 15307 2010 1004 15308 2011 1005 15309 2013 1005 15310 2012 1005 15311 2013 4595 15312 2015 4595 15313 2014 4595 15314 2015 4596 15315 2017 4596 15316 2016 4596 15317 2017 1008 15318 2019 1008 15319 2018 1008 15320 2019 1009 15321 2021 1009 15322 2020 1009 15323 2021 4597 15324 2023 4597 15325 2022 4597 15326 2023 1011 15327 2025 1011 15328 2024 1011 15329 2025 1012 15330 2027 1012 15331 2026 1012 15332 2027 1013 15333 2029 1013 15334 2028 1013 15335 2029 4598 15336 2031 4598 15337 2030 4598 15338 2031 1015 15339 2033 1015 15340 2032 1015 15341 2033 1016 15342 2035 1016 15343 2034 1016 15344 2035 1017 15345 2037 1017 15346 2036 1017 15347 2037 1018 15348 2039 1018 15349 2038 1018 15350 2039 4599 15351 2041 4599 15352 2040 4599 15353 2041 1020 15354 2043 1020 15355 2042 1020 15356 2043 4600 15357 2045 4600 15358 2044 4600 15359 2045 4601 15360 2047 4601 15361 2046 4601 15362 2047 1023 15363 2049 1023 15364 2048 1023 15365 2049 1024 15366 2051 1024 15367 2050 1024 15368 2051 4602 15369 2053 4602 15370 2052 4602 15371 2053 4603 15372 2055 4603 15373 2054 4603 15374 2055 1027 15375 2057 1027 15376 2056 1027 15377 2057 4604 15378 2059 4604 15379 2058 4604 15380 2059 1029 15381 2061 1029 15382 2060 1029 15383 2061 1030 15384 2063 1030 15385 2062 1030 15386 2063 1031 15387 2065 1031 15388 2064 1031 15389 2065 1032 15390 2067 1032 15391 2066 1032 15392 2067 4605 15393 2069 4605 15394 2068 4605 15395 2069 1034 15396 2071 1034 15397 2070 1034 15398 2071 1035 15399 2073 1035 15400 2072 1035 15401 2073 1036 15402 2075 1036 15403 2074 1036 15404 2075 4606 15405 2077 4606 15406 2076 4606 15407 2077 1038 15408 2079 1038 15409 2078 1038 15410 2079 1039 15411 2081 1039 15412 2080 1039 15413 2081 4607 15414 2083 4607 15415 2082 4607 15416 2083 4608 15417 2085 4608 15418 2084 4608 15419 2085 1042 15420 2087 1042 15421 2086 1042 15422 2087 1043 15423 2089 1043 15424 2088 1043 15425 2089 4609 15426 2091 4609 15427 2090 4609 15428 2091 4610 15429 2093 4610 15430 2092 4610 15431 2093 1046 15432 2095 1046 15433 2094 1046 15434 2095 1047 15435 2097 1047 15436 2096 1047 15437 2097 1048 15438 2099 1048 15439 2098 1048 15440 2099 4611 15441 2101 4611 15442 2100 4611 15443 2101 1050 15444 2103 1050 15445 2102 1050 15446 2103 4612 15447 2105 4612 15448 2104 4612 15449 2105 4613 15450 2107 4613 15451 2106 4613 15452 2107 1053 15453 2109 1053 15454 2108 1053 15455 2109 1054 15456 2111 1054 15457 2110 1054 15458 2111 4614 15459 2113 4614 15460 2112 4614 15461 2113 1056 15462 2115 1056 15463 2114 1056 15464 2115 1057 15465 2117 1057 15466 2116 1057 15467 2117 1058 15468 2119 1058 15469 2118 1058 15470 2119 4615 15471 2121 4615 15472 2120 4615 15473 2121 1060 15474 2123 1060 15475 2122 1060 15476 2123 4616 15477 2125 4616 15478 2124 4616 15479 2125 4617 15480 2127 4617 15481 2126 4617 15482 2127 4618 15483 2129 4618 15484 2128 4618 15485 2129 1064 15486 2131 1064 15487 2130 1064 15488 2131 4619 15489 2133 4619 15490 2132 4619 15491 2133 4620 15492 2135 4620 15493 2134 4620 15494 2135 1067 15495 2137 1067 15496 2136 1067 15497 2137 4621 15498 2139 4621 15499 2138 4621 15500 2139 4622 15501 2141 4622 15502 2140 4622 15503 2141 1070 15504 2143 1070 15505 2142 1070 15506 2143 1071 15507 2145 1071 15508 2144 1071 15509 2145 4623 15510 2147 4623 15511 2146 4623 15512 2147 1073 15513 2149 1073 15514 2148 1073 15515 2149 1074 15516 2151 1074 15517 2150 1074 15518 2151 4624 15519 2153 4624 15520 2152 4624 15521 2153 1076 15522 2155 1076 15523 2154 1076 15524 2155 1077 15525 2157 1077 15526 2156 1077 15527 2157 4625 15528 2159 4625 15529 2158 4625 15530 2159 1079 15531 2161 1079 15532 2160 1079 15533 2161 1080 15534 2163 1080 15535 2162 1080 15536 2163 4626 15537 2165 4626 15538 2164 4626 15539 2165 1082 15540 2167 1082 15541 2166 1082 15542 2167 1083 15543 2169 1083 15544 2168 1083 15545 2169 4627 15546 2171 4627 15547 2170 4627 15548 2171 1085 15549 2173 1085 15550 2172 1085 15551 2173 1086 15552 2175 1086 15553 2174 1086 15554 2175 4628 15555 2177 4628 15556 2176 4628 15557 2177 1088 15558 2179 1088 15559 2178 1088 15560 2179 1089 15561 2181 1089 15562 2180 1089 15563 2181 1090 15564 2183 1090 15565 2182 1090 15566 2183 1091 15567 2185 1091 15568 2184 1091 15569 2185 1092 15570 2187 1092 15571 2186 1092 15572 2187 1093 15573 2189 1093 15574 2188 1093 15575 2189 1094 15576 2191 1094 15577 2190 1094 15578 2191 4629 15579 2193 4629 15580 2192 4629 15581 2193 1096 15582 2195 1096 15583 2194 1096 15584 2195 1097 15585 2197 1097 15586 2196 1097 15587 2197 4630 15588 2199 4630 15589 2198 4630 15590 2199 1099 15591 2201 1099 15592 2200 1099 15593 2201 4631 15594 2203 4631 15595 2202 4631 15596 2203 1101 15597 2205 1101 15598 2204 1101 15599 2205 1102 15600 2207 1102 15601 2206 1102 15602 2207 1103 15603 2209 1103 15604 2208 1103 15605 2209 1104 15606 2211 1104 15607 2210 1104 15608 2211 1105 15609 2213 1105 15610 2212 1105 15611 2213 1106 15612 2215 1106 15613 2214 1106 15614 2215 4632 15615 2217 4632 15616 2216 4632 15617 2217 4633 15618 2219 4633 15619 2218 4633 15620 2219 1109 15621 2221 1109 15622 2220 1109 15623 2221 1110 15624 2223 1110 15625 2222 1110 15626 2223 1111 15627 2225 1111 15628 2224 1111 15629 2225 1112 15630 2227 1112 15631 2226 1112 15632 2227 1113 15633 2229 1113 15634 2228 1113 15635 2229 4634 15636 2231 4634 15637 2230 4634 15638 2231 4635 15639 2233 4635 15640 2232 4635 15641 2233 4636 15642 2235 4636 15643 2234 4636 15644 2235 4637 15645 2237 4637 15646 2236 4637 15647 2237 4638 15648 2239 4638 15649 2238 4638 15650 2239 4639 15651 2241 4639 15652 2240 4639 15653 2241 1120 15654 2243 1120 15655 2242 1120 15656 2243 4640 15657 2245 4640 15658 2244 4640 15659 2245 4641 15660 2247 4641 15661 2246 4641 15662 2247 4642 15663 2249 4642 15664 2248 4642 15665 2249 1124 15666 2251 1124 15667 2250 1124 15668 2251 4643 15669 2253 4643 15670 2252 4643 15671 2253 1126 15672 2255 1126 15673 2254 1126 15674 2255 4644 15675 2257 4644 15676 2256 4644 15677 2257 1128 15678 2259 1128 15679 2258 1128 15680 2259 4645 15681 2261 4645 15682 2260 4645 15683 2261 4646 15684 2263 4646 15685 2262 4646 15686 2263 4647 15687 2265 4647 15688 2264 4647 15689 2265 1132 15690 2267 1132 15691 2266 1132 15692 2267 1133 15693 2269 1133 15694 2268 1133 15695 2269 1134 15696 2271 1134 15697 2270 1134 15698 2271 1135 15699 2273 1135 15700 2272 1135 15701 2273 4648 15702 2275 4648 15703 2274 4648 15704 2275 4649 15705 2277 4649 15706 2276 4649 15707 2277 4650 15708 2279 4650 15709 2278 4650 15710 2279 1139 15711 2281 1139 15712 2280 1139 15713 2281 1140 15714 2283 1140 15715 2282 1140 15716 2283 1141 15717 2285 1141 15718 2284 1141 15719 2285 4651 15720 2287 4651 15721 2286 4651 15722 2287 4652 15723 2289 4652 15724 2288 4652 15725 2289 1144 15726 2291 1144 15727 2290 1144 15728 2291 4653 15729 2293 4653 15730 2292 4653 15731 2293 1146 15732 2295 1146 15733 2294 1146 15734 2295 1147 15735 2297 1147 15736 2296 1147 15737 2297 4654 15738 2299 4654 15739 2298 4654 15740 2299 1149 15741 2301 1149 15742 2300 1149 15743 2301 4655 15744 2303 4655 15745 2302 4655 15746 2303 1151 15747 2305 1151 15748 2304 1151 15749 2305 1152 15750 2307 1152 15751 2306 1152 15752 2307 4656 15753 2309 4656 15754 2308 4656 15755 2309 4657 15756 2311 4657 15757 2310 4657 15758 2311 1155 15759 2313 1155 15760 2312 1155 15761 2313 4658 15762 2315 4658 15763 2314 4658 15764 2315 1157 15765 2317 1157 15766 2316 1157 15767 2317 1158 15768 2319 1158 15769 2318 1158 15770 2319 4659 15771 2321 4659 15772 2320 4659 15773 2321 1160 15774 2323 1160 15775 2322 1160 15776 2323 1161 15777 2325 1161 15778 2324 1161 15779 2325 4660 15780 2327 4660 15781 2326 4660 15782 2327 4661 15783 2329 4661 15784 2328 4661 15785 2329 1164 15786 2331 1164 15787 2330 1164 15788 2331 1165 15789 2333 1165 15790 2332 1165 15791 2333 4662 15792 2335 4662 15793 2334 4662 15794 2335 1167 15795 2337 1167 15796 2336 1167 15797 2337 1168 15798 2339 1168 15799 2338 1168 15800 2339 1169 15801 2341 1169 15802 2340 1169 15803 2341 4663 15804 2343 4663 15805 2342 4663 15806 2343 1171 15807 2345 1171 15808 2344 1171 15809 2345 1172 15810 2347 1172 15811 2346 1172 15812 2347 1173 15813 2349 1173 15814 2348 1173 15815 2349 4664 15816 2351 4664 15817 2350 4664 15818 2351 4665 15819 2353 4665 15820 2352 4665 15821 2353 1176 15822 2355 1176 15823 2354 1176 15824 2355 1177 15825 2357 1177 15826 2356 1177 15827 2357 4666 15828 2359 4666 15829 2358 4666 15830 2359 1179 15831 2361 1179 15832 2360 1179 15833 2361 1180 15834 2363 1180 15835 2362 1180 15836 2363 4667 15837 2365 4667 15838 2364 4667 15839 2365 1182 15840 2367 1182 15841 2366 1182 15842 2367 1183 15843 2369 1183 15844 2368 1183 15845 2369 4668 15846 2371 4668 15847 2370 4668 15848 2371 1185 15849 2373 1185 15850 2372 1185 15851 2373 4669 15852 2375 4669 15853 2374 4669 15854 2375 1187 15855 2377 1187 15856 2376 1187 15857 2377 4670 15858 2379 4670 15859 2378 4670 15860 2379 1189 15861 2381 1189 15862 2380 1189 15863 2381 1190 15864 2383 1190 15865 2382 1190 15866 2383 1191 15867 2385 1191 15868 2384 1191 15869 2385 1192 15870 2387 1192 15871 2386 1192 15872 2387 4671 15873 2389 4671 15874 2388 4671 15875 2389 1194 15876 2391 1194 15877 2390 1194 15878 2391 4672 15879 2393 4672 15880 2392 4672 15881 2393 4673 15882 2395 4673 15883 2394 4673 15884 2395 4674 15885 2397 4674 15886 2396 4674 15887 2397 4675 15888 2399 4675 15889 2398 4675 15890 2399 4676 15891 2401 4676 15892 2400 4676 15893 2401 4677 15894 2403 4677 15895 2402 4677 15896 2403 4678 15897 2405 4678 15898 2404 4678 15899 2405 4679 15900 2407 4679 15901 2406 4679 15902 2407 4680 15903 2409 4680 15904 2408 4680 15905 2409 1204 15906 2411 1204 15907 2410 1204 15908 2411 4681 15909 2413 4681 15910 2412 4681 15911 2413 4682 15912 2415 4682 15913 2414 4682 15914 2415 4683 15915 2417 4683 15916 2416 4683 15917 2417 4684 15918 2419 4684 15919 2418 4684 15920 2419 1209 15921 2421 1209 15922 2420 1209 15923 2421 4685 15924 2423 4685 15925 2422 4685 15926 2423 4686 15927 2425 4686 15928 2424 4686 15929 2425 1212 15930 2427 1212 15931 2426 1212 15932 2427 1213 15933 2429 1213 15934 2428 1213 15935 2429 1214 15936 2431 1214 15937 2430 1214 15938 2431 1215 15939 2433 1215 15940 2432 1215 15941 2433 1216 15942 2435 1216 15943 2434 1216 15944 2435 4687 15945 2437 4687 15946 2436 4687 15947 2437 1218 15948 2439 1218 15949 2438 1218 15950 2439 1219 15951 2441 1219 15952 2440 1219 15953 2441 4688 15954 2443 4688 15955 2442 4688 15956 2443 1221 15957 2445 1221 15958 2444 1221 15959 2445 1222 15960 2447 1222 15961 2446 1222 15962 2447 1223 15963 2449 1223 15964 2448 1223 15965 2449 4689 15966 2451 4689 15967 2450 4689 15968 2451 4690 15969 2453 4690 15970 2452 4690 15971 2453 1226 15972 2455 1226 15973 2454 1226 15974 2455 1227 15975 2457 1227 15976 2456 1227 15977 2457 1228 15978 2459 1228 15979 2458 1228 15980 2459 4691 15981 2461 4691 15982 2460 4691 15983 2461 4692 15984 2463 4692 15985 2462 4692 15986 2463 1231 15987 2465 1231 15988 2464 1231 15989 2465 4693 15990 2467 4693 15991 2466 4693 15992 2467 4694 15993 2469 4694 15994 2468 4694 15995 2469 4695 15996 2471 4695 15997 2470 4695 15998 2471 1235 15999 2473 1235 16000 2472 1235 16001 2473 4696 16002 2475 4696 16003 2474 4696 16004 2475 4697 16005 2477 4697 16006 2476 4697 16007 2477 1238 16008 2479 1238 16009 2478 1238 16010 2479 1239 16011 2481 1239 16012 2480 1239 16013 2481 4698 16014 2483 4698 16015 2482 4698 16016 2483 1241 16017 2485 1241 16018 2484 1241 16019 2485 4699 16020 2487 4699 16021 2486 4699 16022 2487 4700 16023 2489 4700 16024 2488 4700 16025 2489 1244 16026 2491 1244 16027 2490 1244 16028 2491 4701 16029 2493 4701 16030 2492 4701 16031 2493 1246 16032 2495 1246 16033 2494 1246 16034 2495 1247 16035 2497 1247 16036 2496 1247 16037 2497 4702 16038 2499 4702 16039 2498 4702 16040 2499 1249 16041 2501 1249 16042 2500 1249 16043 2501 4703 16044 2503 4703 16045 2502 4703 16046 2503 1251 16047 2505 1251 16048 2504 1251 16049 2505 4704 16050 2507 4704 16051 2506 4704 16052 2507 1253 16053 2509 1253 16054 2508 1253 16055 2509 1254 16056 2511 1254 16057 2510 1254 16058 2511 1255 16059 2513 1255 16060 2512 1255 16061 2513 4705 16062 2515 4705 16063 2514 4705 16064 2515 4706 16065 2517 4706 16066 2516 4706 16067 2517 4707 16068 2519 4707 16069 2518 4707 16070 2519 1259 16071 2521 1259 16072 2520 1259 16073 2521 1260 16074 2523 1260 16075 2522 1260 16076 2523 1261 16077 2525 1261 16078 2524 1261 16079 2525 1262 16080 2527 1262 16081 2526 1262 16082 2527 1263 16083 2529 1263 16084 2528 1263 16085 2529 4708 16086 2531 4708 16087 2530 4708 16088 2531 4709 16089 2533 4709 16090 2532 4709 16091 2533 4710 16092 2535 4710 16093 2534 4710 16094 2535 4711 16095 2537 4711 16096 2536 4711 16097 2537 1268 16098 2539 1268 16099 2538 1268 16100 2539 1269 16101 2541 1269 16102 2540 1269 16103 2541 4712 16104 2543 4712 16105 2542 4712 16106 2543 1271 16107 2545 1271 16108 2544 1271 16109 2545 4713 16110 2547 4713 16111 2546 4713 16112 2547 4714 16113 2549 4714 16114 2548 4714 16115 2549 4715 16116 2551 4715 16117 2550 4715 16118 2551 4716 16119 2553 4716 16120 2552 4716 16121 2553 4717 16122 2555 4717 16123 2554 4717 16124 2555 4718 16125 2557 4718 16126 2556 4718 16127 2557 1278 16128 2559 1278 16129 2558 1278 16130 2559 4719 16131 2561 4719 16132 2560 4719 16133 2561 4720 16134 2563 4720 16135 2562 4720 16136 2563 4721 16137 2565 4721 16138 2564 4721 16139 2565 1282 16140 2567 1282 16141 2566 1282 16142 2567 1283 16143 2569 1283 16144 2568 1283 16145 2569 4722 16146 2571 4722 16147 2570 4722 16148 2571 4723 16149 2573 4723 16150 2572 4723 16151 2573 4724 16152 2575 4724 16153 2574 4724 16154 2575 4725 16155 2577 4725 16156 2576 4725 16157 2577 1288 16158 2579 1288 16159 2578 1288 16160 2579 4726 16161 2581 4726 16162 2580 4726 16163 2581 1290 16164 2583 1290 16165 2582 1290 16166 2583 1291 16167 2585 1291 16168 2584 1291 16169 2585 4727 16170 2587 4727 16171 2586 4727 16172 2587 4728 16173 2589 4728 16174 2588 4728 16175 2589 4729 16176 2591 4729 16177 2590 4729 16178 2591 1295 16179 2593 1295 16180 2592 1295 16181 2593 4730 16182 2595 4730 16183 2594 4730 16184 2595 4731 16185 2597 4731 16186 2596 4731 16187 2597 1298 16188 2599 1298 16189 2598 1298 16190 2599 4732 16191 2601 4732 16192 2600 4732 16193 2601 4733 16194 2603 4733 16195 2602 4733 16196 2603 1301 16197 2605 1301 16198 2604 1301 16199 2605 4734 16200 2607 4734 16201 2606 4734 16202 2607 1303 16203 2609 1303 16204 2608 1303 16205 2609 4735 16206 2611 4735 16207 2610 4735 16208 2611 4736 16209 2613 4736 16210 2612 4736 16211 2613 1306 16212 2615 1306 16213 2614 1306 16214 2615 4737 16215 2617 4737 16216 2616 4737 16217 2617 4738 16218 2619 4738 16219 2618 4738 16220 2619 1309 16221 2621 1309 16222 2620 1309 16223 2621 1310 16224 2623 1310 16225 2622 1310 16226 2623 4739 16227 2625 4739 16228 2624 4739 16229 2625 1312 16230 2627 1312 16231 2626 1312 16232 2627 4740 16233 2629 4740 16234 2628 4740 16235 2629 4741 16236 2631 4741 16237 2630 4741 16238 2631 1315 16239 2633 1315 16240 2632 1315 16241 2633 1316 16242 2635 1316 16243 2634 1316 16244 2635 4742 16245 2637 4742 16246 2636 4742 16247 2637 4743 16248 2639 4743 16249 2638 4743 16250 2639 1319 16251 2641 1319 16252 2640 1319 16253 2641 1320 16254 2643 1320 16255 2642 1320 16256 2643 1321 16257 2645 1321 16258 2644 1321 16259 2645 4744 16260 2647 4744 16261 2646 4744 16262 2647 1323 16263 2649 1323 16264 2648 1323 16265 2649 4745 16266 2651 4745 16267 2650 4745 16268 2651 4746 16269 2653 4746 16270 2652 4746 16271 2653 1326 16272 2655 1326 16273 2654 1326 16274 2655 1327 16275 2657 1327 16276 2656 1327 16277 2657 4747 16278 2659 4747 16279 2658 4747 16280 2659 1329 16281 2661 1329 16282 2660 1329 16283 2661 4748 16284 2663 4748 16285 2662 4748 16286 2663 1331 16287 2665 1331 16288 2664 1331 16289 2665 1332 16290 2667 1332 16291 2666 1332 16292 2667 4749 16293 2669 4749 16294 2668 4749 16295 2669 1334 16296 2671 1334 16297 2670 1334 16298 2671 1335 16299 2673 1335 16300 2672 1335 16301 2673 1336 16302 2675 1336 16303 2674 1336 16304 2675 4750 16305 2677 4750 16306 2676 4750 16307 2677 1338 16308 2679 1338 16309 2678 1338 16310 2679 4751 16311 2681 4751 16312 2680 4751 16313 2681 1340 16314 2683 1340 16315 2682 1340 16316 2683 4752 16317 2685 4752 16318 2684 4752 16319 2685 4753 16320 2687 4753 16321 2686 4753 16322 2687 4754 16323 2689 4754 16324 2688 4754 16325 2689 4755 16326 2691 4755 16327 2690 4755 16328 2691 1345 16329 2693 1345 16330 2692 1345 16331 2693 4756 16332 2695 4756 16333 2694 4756 16334 2695 4757 16335 2697 4757 16336 2696 4757 16337 2697 1348 16338 2699 1348 16339 2698 1348 16340 2699 4758 16341 2701 4758 16342 2700 4758 16343 2701 1350 16344 2703 1350 16345 2702 1350 16346 2703 1351 16347 2705 1351 16348 2704 1351 16349 2705 4759 16350 2707 4759 16351 2706 4759 16352 2707 4760 16353 2709 4760 16354 2708 4760 16355 2709 1354 16356 2711 1354 16357 2710 1354 16358 2711 1355 16359 2713 1355 16360 2712 1355 16361 2713 4761 16362 2715 4761 16363 2714 4761 16364 2715 4762 16365 2717 4762 16366 2716 4762 16367 2717 1358 16368 2719 1358 16369 2718 1358 16370 2719 1359 16371 2721 1359 16372 2720 1359 16373 2721 1360 16374 2723 1360 16375 2722 1360 16376 2723 4763 16377 2725 4763 16378 2724 4763 16379 2725 4764 16380 2727 4764 16381 2726 4764 16382 2727 4765 16383 2729 4765 16384 2728 4765 16385 2729 4766 16386 2731 4766 16387 2730 4766 16388 2731 1365 16389 2733 1365 16390 2732 1365 16391 2733 1366 16392 2735 1366 16393 2734 1366 16394 2735 1367 16395 2737 1367 16396 2736 1367 16397 2737 1368 16398 2739 1368 16399 2738 1368 16400 2739 1369 16401 2741 1369 16402 2740 1369 16403 2741 1370 16404 2743 1370 16405 2742 1370 16406 2743 4767 16407 2745 4767 16408 2744 4767 16409 2745 1372 16410 2747 1372 16411 2746 1372 16412 2747 1373 16413 2749 1373 16414 2748 1373 16415 2749 1374 16416 2751 1374 16417 2750 1374 16418 2751 1375 16419 2753 1375 16420 2752 1375 16421 2753 1376 16422 2755 1376 16423 2754 1376 16424 2755 4768 16425 2757 4768 16426 2756 4768 16427 2757 1378 16428 2759 1378 16429 2758 1378 16430 2759 4769 16431 2761 4769 16432 2760 4769 16433 2761 4770 16434 2763 4770 16435 2762 4770 16436 2763 4771 16437 2765 4771 16438 2764 4771 16439 2765 1382 16440 2767 1382 16441 2766 1382 16442 2767 1383 16443 2769 1383 16444 2768 1383 16445 2769 1384 16446 2771 1384 16447 2770 1384 16448 2771 4772 16449 2773 4772 16450 2772 4772 16451 2773 4773 16452 2775 4773 16453 2774 4773 16454 2775 1387 16455 2777 1387 16456 2776 1387 16457 2777 1388 16458 2779 1388 16459 2778 1388 16460 2779 4774 16461 2781 4774 16462 2780 4774 16463 2781 1390 16464 2783 1390 16465 2782 1390 16466 2783 1391 16467 2785 1391 16468 2784 1391 16469 2785 1392 16470 2787 1392 16471 2786 1392 16472 2787 1393 16473 2789 1393 16474 2788 1393 16475 2789 1394 16476 2791 1394 16477 2790 1394 16478 2791 4775 16479 2793 4775 16480 2792 4775 16481 2793 4776 16482 2795 4776 16483 2794 4776 16484 2795 1397 16485 2797 1397 16486 2796 1397 16487 2797 1398 16488 2799 1398 16489 2798 1398 16490 2799 1399 16491 2801 1399 16492 2800 1399 16493 2801 4777 16494 2803 4777 16495 2802 4777 16496 2803 1401 16497 2805 1401 16498 2804 1401 16499 2805 1402 16500 2807 1402 16501 2806 1402 16502 2807 1403 16503 2809 1403 16504 2808 1403 16505 2809 1404 16506 2811 1404 16507 2810 1404 16508 2811 1405 16509 2813 1405 16510 2812 1405 16511 2813 4778 16512 2815 4778 16513 2814 4778 16514 2815 1407 16515 2817 1407 16516 2816 1407 16517 2817 1408 16518 2819 1408 16519 2818 1408 16520 2819 1409 16521 2821 1409 16522 2820 1409 16523 2821 1410 16524 2823 1410 16525 2822 1410 16526 2823 4779 16527 2825 4779 16528 2824 4779 16529 2825 4780 16530 2827 4780 16531 2826 4780 16532 2827 1413 16533 2829 1413 16534 2828 1413 16535 2829 4781 16536 2831 4781 16537 2830 4781 16538 2831 4782 16539 2833 4782 16540 2832 4782 16541 2833 1416 16542 2835 1416 16543 2834 1416 16544 2835 4783 16545 2837 4783 16546 2836 4783 16547 2837 1418 16548 2839 1418 16549 2838 1418 16550 2839 1419 16551 2841 1419 16552 2840 1419 16553 2841 1420 16554 2843 1420 16555 2842 1420 16556 2843 1421 16557 2845 1421 16558 2844 1421 16559 2845 1422 16560 2847 1422 16561 2846 1422 16562 2847 4784 16563 2849 4784 16564 2848 4784 16565 2849 4785 16566 2851 4785 16567 2850 4785 16568 2851 1425 16569 2853 1425 16570 2852 1425 16571 2853 4786 16572 2855 4786 16573 2854 4786 16574 2855 1427 16575 2857 1427 16576 2856 1427 16577 2857 1428 16578 2859 1428 16579 2858 1428 16580 2859 1429 16581 2861 1429 16582 2860 1429 16583 2861 1430 16584 2863 1430 16585 2862 1430 16586 2863 1431 16587 2865 1431 16588 2864 1431 16589 2865 4787 16590 2867 4787 16591 2866 4787 16592 2867 4788 16593 2869 4788 16594 2868 4788 16595 2869 4789 16596 2871 4789 16597 2870 4789 16598 2871 1435 16599 2873 1435 16600 2872 1435 16601 2873 1436 16602 2875 1436 16603 2874 1436 16604 2875 1437 16605 2877 1437 16606 2876 1437 16607 2877 4790 16608 2879 4790 16609 2878 4790 16610 2879 4791 16611 2881 4791 16612 2880 4791 16613 2881 4792 16614 2883 4792 16615 2882 4792 16616 2883 1441 16617 2885 1441 16618 2884 1441 16619 2885 1442 16620 2887 1442 16621 2886 1442 16622 2887 1443 16623 2889 1443 16624 2888 1443 16625 2889 4793 16626 2891 4793 16627 2890 4793 16628 2891 4794 16629 2893 4794 16630 2892 4794 16631 2893 1446 16632 2895 1446 16633 2894 1446 16634 2895 4795 16635 2897 4795 16636 2896 4795 16637 2897 4796 16638 2899 4796 16639 2898 4796 16640 2899 4797 16641 2901 4797 16642 2900 4797 16643 2901 1450 16644 2903 1450 16645 2902 1450 16646 2903 4798 16647 2905 4798 16648 2904 4798 16649 2905 1452 16650 2907 1452 16651 2906 1452 16652 2907 1453 16653 2909 1453 16654 2908 1453 16655 2909 4799 16656 2911 4799 16657 2910 4799 16658 2911 1455 16659 2913 1455 16660 2912 1455 16661 2913 4800 16662 2915 4800 16663 2914 4800 16664 2915 1457 16665 2917 1457 16666 2916 1457 16667 2917 1458 16668 2919 1458 16669 2918 1458 16670 2919 4801 16671 2921 4801 16672 2920 4801 16673 2921 1460 16674 2923 1460 16675 2922 1460 16676 2923 1461 16677 2925 1461 16678 2924 1461 16679 2925 4802 16680 2927 4802 16681 2926 4802 16682 2927 1463 16683 2929 1463 16684 2928 1463 16685 2929 4803 16686 2931 4803 16687 2930 4803 16688 2931 4804 16689 2933 4804 16690 2932 4804 16691 2933 4805 16692 2935 4805 16693 2934 4805 16694 2935 4806 16695 2937 4806 16696 2936 4806 16697 2937 4807 16698 2939 4807 16699 2938 4807 16700 2939 4808 16701 2941 4808 16702 2940 4808 16703 2941 4809 16704 2943 4809 16705 2942 4809 16706 2943 4810 16707 2945 4810 16708 2944 4810 16709 2945 1472 16710 2947 1472 16711 2946 1472 16712 2947 1473 16713 2949 1473 16714 2948 1473 16715 2949 4811 16716 2951 4811 16717 2950 4811 16718 2951 4812 16719 2953 4812 16720 2952 4812 16721 2953 1476 16722 2955 1476 16723 2954 1476 16724 2955 1477 16725 2957 1477 16726 2956 1477 16727 2957 1478 16728 2959 1478 16729 2958 1478 16730 2959 4813 16731 2961 4813 16732 2960 4813 16733 2961 1480 16734 2963 1480 16735 2962 1480 16736 2963 4814 16737 2965 4814 16738 2964 4814 16739 2965 4815 16740 2967 4815 16741 2966 4815 16742 2967 1483 16743 2969 1483 16744 2968 1483 16745 2969 4816 16746 2971 4816 16747 2970 4816 16748 2971 4817 16749 2973 4817 16750 2972 4817 16751 2973 4818 16752 2975 4818 16753 2974 4818 16754 2975 4819 16755 2977 4819 16756 2976 4819 16757 2977 4820 16758 2979 4820 16759 2978 4820 16760 2979 1489 16761 2981 1489 16762 2980 1489 16763 2981 4821 16764 2983 4821 16765 2982 4821 16766 2983 1491 16767 2985 1491 16768 2984 1491 16769 2985 4822 16770 2987 4822 16771 2986 4822 16772 2987 1493 16773 2989 1493 16774 2988 1493 16775 2989 4823 16776 2991 4823 16777 2990 4823 16778 2991 4824 16779 2993 4824 16780 2992 4824 16781 2993 4825 16782 2995 4825 16783 2994 4825 16784 2995 1497 16785 2997 1497 16786 2996 1497 16787 2997 1498 16788 2999 1498 16789 2998 1498 16790 2999 4826 16791 3001 4826 16792 3000 4826 16793 3001 4827 16794 3003 4827 16795 3002 4827 16796 3003 4828 16797 3005 4828 16798 3004 4828 16799 3005 4829 16800 3007 4829 16801 3006 4829 16802 3007 4830 16803 3009 4830 16804 3008 4830 16805 3009 1504 16806 3011 1504 16807 3010 1504 16808 3011 4831 16809 3013 4831 16810 3012 4831 16811 3013 1506 16812 3015 1506 16813 3014 1506 16814 3015 4832 16815 3017 4832 16816 3016 4832 16817 3017 4833 16818 3019 4833 16819 3018 4833 16820 3019 4834 16821 3021 4834 16822 3020 4834 16823 3021 4835 16824 3023 4835 16825 3022 4835 16826 3023 4836 16827 3025 4836 16828 3024 4836 16829 3025 4837 16830 3027 4837 16831 3026 4837 16832 3027 4838 16833 3029 4838 16834 3028 4838 16835 3029 1514 16836 3031 1514 16837 3030 1514 16838 3031 4839 16839 3033 4839 16840 3032 4839 16841 3033 4840 16842 3035 4840 16843 3034 4840 16844 3035 4841 16845 3037 4841 16846 3036 4841 16847 3037 4842 16848 3039 4842 16849 3038 4842 16850 3039 4843 16851 3041 4843 16852 3040 4843 16853 3041 4844 16854 3043 4844 16855 3042 4844 16856 3043 4845 16857 3045 4845 16858 3044 4845 16859 3045 4846 16860 3047 4846 16861 3046 4846 16862 3047 1523 16863 3049 1523 16864 3048 1523 16865 3049 1524 16866 3051 1524 16867 3050 1524 16868 3051 4847 16869 3053 4847 16870 3052 4847 16871 3053 4848 16872 3055 4848 16873 3054 4848 16874 3055 4849 16875 3057 4849 16876 3056 4849 16877 3057 4850 16878 3059 4850 16879 3058 4850 16880 3059 4851 16881 3061 4851 16882 3060 4851 16883 3061 1530 16884 3063 1530 16885 3062 1530 16886 3063 1531 16887 3065 1531 16888 3064 1531 16889 3065 4852 16890 3067 4852 16891 3066 4852 16892 3067 1533 16893 3069 1533 16894 3068 1533 16895 3069 1534 16896 3071 1534 16897 3070 1534 16898 3071 1535 16899 3073 1535 16900 3072 1535 16901 3073 1536 16902 3075 1536 16903 3074 1536 16904 3075 1537 16905 3077 1537 16906 3076 1537 16907 3077 4853 16908 3079 4853 16909 3078 4853 16910 3079 1539 16911 3081 1539 16912 3080 1539 16913 3081 4854 16914 3083 4854 16915 3082 4854 16916 3083 4855 16917 3085 4855 16918 3084 4855 16919 3085 1542 16920 3087 1542 16921 3086 1542 16922 3087 1543 16923 3089 1543 16924 3088 1543 16925 3089 1544 16926 3091 1544 16927 3090 1544 16928 3091 4856 16929 3093 4856 16930 3092 4856 16931 3093 4857 16932 3095 4857 16933 3094 4857 16934 3095 4858 16935 3097 4858 16936 3096 4858 16937 3097 4859 16938 3099 4859 16939 3098 4859 16940 3099 4860 16941 3101 4860 16942 3100 4860 16943 3101 4861 16944 3103 4861 16945 3102 4861 16946 3103 4862 16947 3105 4862 16948 3104 4862 16949 3105 4863 16950 3107 4863 16951 3106 4863 16952 3107 1553 16953 3109 1553 16954 3108 1553 16955 3109 4864 16956 3111 4864 16957 3110 4864 16958 3111 1555 16959 3113 1555 16960 3112 1555 16961 3113 4865 16962 3115 4865 16963 3114 4865 16964 3115 1557 16965 3117 1557 16966 3116 1557 16967 3117 4866 16968 3119 4866 16969 3118 4866 16970 3119 4867 16971 3121 4867 16972 3120 4867 16973 3121 4868 16974 3123 4868 16975 3122 4868 16976 3123 4869 16977 3125 4869 16978 3124 4869 16979 3125 4870 16980 3127 4870 16981 3126 4870 16982 3127 4871 16983 3129 4871 16984 3128 4871 16985 3129 1564 16986 3131 1564 16987 3130 1564 16988 3131 4872 16989 3133 4872 16990 3132 4872 16991 3133 4873 16992 3135 4873 16993 3134 4873 16994 3135 1567 16995 3137 1567 16996 3136 1567 16997 3137 4874 16998 3139 4874 16999 3138 4874 17000 3139 1569 17001 3141 1569 17002 3140 1569 17003 3141 4875 17004 3143 4875 17005 3142 4875 17006 3143 1571 17007 3145 1571 17008 3144 1571 17009 3145 1572 17010 3147 1572 17011 3146 1572 17012 3147 1573 17013 3149 1573 17014 3148 1573 17015 3149 1574 17016 3151 1574 17017 3150 1574 17018 3151 4876 17019 3153 4876 17020 3152 4876 17021 3153 4877 17022 3155 4877 17023 3154 4877 17024 3155 4878 17025 3157 4878 17026 3156 4878 17027 3157 4879 17028 3159 4879 17029 3158 4879 17030 3159 4880 17031 3161 4880 17032 3160 4880 17033 3161 4881 17034 3163 4881 17035 3162 4881 17036 3163 4882 17037 3165 4882 17038 3164 4882 17039 3165 4883 17040 3167 4883 17041 3166 4883 17042 3167 1583 17043 3169 1583 17044 3168 1583 17045 3169 1584 17046 3171 1584 17047 3170 1584 17048 3171 1585 17049 3173 1585 17050 3172 1585 17051 3173 1586 17052 3175 1586 17053 3174 1586 17054 3175 4884 17055 3177 4884 17056 3176 4884 17057 3177 4885 17058 3179 4885 17059 3178 4885 17060 3179 4886 17061 3181 4886 17062 3180 4886 17063 3181 1590 17064 3183 1590 17065 3182 1590 17066 3183 1591 17067 3185 1591 17068 3184 1591 17069 3185 4887 17070 3187 4887 17071 3186 4887 17072 3187 1593 17073 3189 1593 17074 3188 1593 17075 3189 1594 17076 3191 1594 17077 3190 1594 17078 3191 4888 17079 3193 4888 17080 3192 4888 17081 3193 1596 17082 3195 1596 17083 3194 1596 17084 3195 1597 17085 3197 1597 17086 3196 1597 17087 3197 1598 17088 3199 1598 17089 3198 1598 17090 3199 4889 17091 3201 4889 17092 3200 4889 17093 3201 4890 17094 3203 4890 17095 3202 4890 17096 3203 1601 17097 3205 1601 17098 3204 1601 17099 3205 1602 17100 3207 1602 17101 3206 1602 17102 3207 1603 17103 3209 1603 17104 3208 1603 17105 3209 1604 17106 3211 1604 17107 3210 1604 17108 3211 1605 17109 3213 1605 17110 3212 1605 17111 3213 1606 17112 3215 1606 17113 3214 1606 17114 3215 1607 17115 3217 1607 17116 3216 1607 17117 3217 1608 17118 3219 1608 17119 3218 1608 17120 3219 1609 17121 3221 1609 17122 3220 1609 17123 3221 1610 17124 3223 1610 17125 3222 1610 17126 3223 4891 17127 3225 4891 17128 3224 4891 17129 3225 4892 17130 3227 4892 17131 3226 4892 17132 3227 1613 17133 3229 1613 17134 3228 1613 17135 3229 4893 17136 3231 4893 17137 3230 4893 17138 3231 1615 17139 3233 1615 17140 3232 1615 17141 3233 4894 17142 3235 4894 17143 3234 4894 17144 3235 1617 17145 3237 1617 17146 3236 1617 17147 3237 4895 17148 3239 4895 17149 3238 4895 17150 3239 1619 17151 3241 1619 17152 3240 1619 17153 3241 4896 17154 3243 4896 17155 3242 4896 17156 3243 1621 17157 3245 1621 17158 3244 1621 17159 3245 1622 17160 3247 1622 17161 3246 1622 17162 3247 1623 17163 3249 1623 17164 3248 1623 17165 3249 4897 17166 3251 4897 17167 3250 4897 17168 3251 4898 17169 3253 4898 17170 3252 4898 17171 3253 4899 17172 3255 4899 17173 3254 4899 17174 3255 4900 17175 3257 4900 17176 3256 4900 17177 3257 4901 17178 3259 4901 17179 3258 4901 17180 3259 1629 17181 3261 1629 17182 3260 1629 17183 3261 1630 17184 3263 1630 17185 3262 1630 17186 3263 1631 17187 3265 1631 17188 3264 1631 17189 3265 4902 17190 3267 4902 17191 3266 4902 17192 3267 1633 17193 3269 1633 17194 3268 1633 17195 3269 1634 17196 3271 1634 17197 3270 1634 17198 3271 1635 17199 3273 1635 17200 3272 1635 17201 3273 4903 17202 3275 4903 17203 3274 4903 17204 3275 4904 17205 3277 4904 17206 3276 4904 17207 3277 1638 17208 3279 1638 17209 3278 1638 17210 3279 4905 17211 3281 4905 17212 3280 4905 17213 3281 1640 17214 3283 1640 17215 3282 1640 17216 3283 1641 17217 3285 1641 17218 3284 1641 17219 3285 1642 17220 3287 1642 17221 3286 1642 17222 3287 1643 17223 3289 1643 17224 3288 1643 17225 3289 1644 17226 3291 1644 17227 3290 1644 17228 3291 1645 17229 3293 1645 17230 3292 1645 17231 3293 4906 17232 3295 4906 17233 3294 4906 17234 3295 1647 17235 3297 1647 17236 3296 1647 17237 3297 4907 17238 3299 4907 17239 3298 4907 17240 3299 1649 17241 3301 1649 17242 3300 1649 17243 3301 1650 17244 3303 1650 17245 3302 1650 17246 3303 1651 17247 3305 1651 17248 3304 1651 17249 3305 4908 17250 3307 4908 17251 3306 4908 17252 3307 4909 17253 3309 4909 17254 3308 4909 17255 3309 1654 17256 3311 1654 17257 3310 1654 17258 3311 4910 17259 3313 4910 17260 3312 4910 17261 3313 4911 17262 3315 4911 17263 3314 4911 17264 3315 4912 17265 3317 4912 17266 3316 4912 17267 3317 4913 17268 3319 4913 17269 3318 4913 17270 3319 4914 17271 3321 4914 17272 3320 4914 17273 3321 1660 17274 3323 1660 17275 3322 1660 17276 3323 1661 17277 3325 1661 17278 3324 1661 17279 3325 4915 17280 3327 4915 17281 3326 4915 17282 3327 1663 17283 3329 1663 17284 3328 1663 17285 3329 1664 17286 3331 1664 17287 3330 1664 17288 3331 4916 17289 3333 4916 17290 3332 4916 17291 3333 1666 17292 3335 1666 17293 3334 1666 17294 3335 1667 17295 3337 1667 17296 3336 1667 17297 3337 4917 17298 3339 4917 17299 3338 4917 17300 3339 4918 17301 3341 4918 17302 3340 4918 17303 3341 1670 17304 3343 1670 17305 3342 1670 17306 3343 1671 17307 3345 1671 17308 3344 1671 17309 3345 4919 17310 3347 4919 17311 3346 4919 17312 3347 4920 17313 3349 4920 17314 3348 4920 17315 3349 1674 17316 3351 1674 17317 3350 1674 17318 3351 4921 17319 3353 4921 17320 3352 4921 17321 3353 4922 17322 3355 4922 17323 3354 4922 17324 3355 4923 17325 3357 4923 17326 3356 4923 17327 3357 4924 17328 3359 4924 17329 3358 4924 17330 3359 4925 17331 3361 4925 17332 3360 4925 17333 3361 4926 17334 3363 4926 17335 3362 4926 17336 3363 1681 17337 3365 1681 17338 3364 1681 17339 3365 1682 17340 3367 1682 17341 3366 1682 17342 3367 4927 17343 3369 4927 17344 3368 4927 17345 3369 4928 17346 3371 4928 17347 3370 4928 17348 3371 4929 17349 3373 4929 17350 3372 4929 17351 3373 4930 17352 3375 4930 17353 3374 4930 17354 3375 1687 17355 3377 1687 17356 3376 1687 17357 3377 4931 17358 3379 4931 17359 3378 4931 17360 3379 1689 17361 3381 1689 17362 3380 1689 17363 3381 1690 17364 3383 1690 17365 3382 1690 17366 3383 1691 17367 3385 1691 17368 3384 1691 17369 3385 1692 17370 3387 1692 17371 3386 1692 17372 3387 4932 17373 3389 4932 17374 3388 4932 17375 3389 1694 17376 3391 1694 17377 3390 1694 17378 3391 1695 17379 3393 1695 17380 3392 1695 17381 3393 1696 17382 3395 1696 17383 3394 1696 17384 3395 4933 17385 3397 4933 17386 3396 4933 17387 3397 4934 17388 3399 4934 17389 3398 4934 17390 3399 4935 17391 3401 4935 17392 3400 4935 17393 3401 1700 17394 3403 1700 17395 3402 1700 17396 3403 4936 17397 3405 4936 17398 3404 4936 17399 3405 4937 17400 3407 4937 17401 3406 4937 17402 3407 1703 17403 3409 1703 17404 3408 1703 17405 3409 4938 17406 3411 4938 17407 3410 4938 17408 3411 4939 17409 3413 4939 17410 3412 4939 17411 3413 4940 17412 3415 4940 17413 3414 4940 17414 3415 4941 17415 3417 4941 17416 3416 4941 17417 3417 4942 17418 3419 4942 17419 3418 4942 17420 3419 4943 17421 3421 4943 17422 3420 4943 17423 3421 4944 17424 3423 4944 17425 3422 4944 17426 3423 4945 17427 3425 4945 17428 3424 4945 17429 3425 4946 17430 3427 4946 17431 3426 4946 17432 3427 4947 17433 3429 4947 17434 3428 4947 17435 3429 1714 17436 3431 1714 17437 3430 1714 17438 3431 4948 17439 3433 4948 17440 3432 4948 17441 3433 4949 17442 3435 4949 17443 3434 4949 17444 3435 1717 17445 3437 1717 17446 3436 1717 17447 3437 1718 17448 3439 1718 17449 3438 1718 17450 3439 1719 17451 3441 1719 17452 3440 1719 17453 3441 1720 17454 3443 1720 17455 3442 1720 17456 3443 1721 17457 3445 1721 17458 3444 1721 17459 3445 4950 17460 3447 4950 17461 3446 4950 17462 3447 4951 17463 3449 4951 17464 3448 4951 17465 3449 1724 17466 3451 1724 17467 3450 1724 17468 3451 4952 17469 3453 4952 17470 3452 4952 17471 3453 4953 17472 3455 4953 17473 3454 4953 17474 3455 1727 17475 3457 1727 17476 3456 1727 17477 3457 4954 17478 3459 4954 17479 3458 4954 17480 3459 4955 17481 3461 4955 17482 3460 4955 17483 3461 4956 17484 3463 4956 17485 3462 4956 17486 3463 1731 17487 3465 1731 17488 3464 1731 17489 3465 4957 17490 3467 4957 17491 3466 4957 17492 3467 1733 17493 3469 1733 17494 3468 1733 17495 3469 1734 17496 3471 1734 17497 3470 1734 17498 3471 4958 17499 3473 4958 17500 3472 4958 17501 3473 1736 17502 3475 1736 17503 3474 1736 17504 3475 4959 17505 3477 4959 17506 3476 4959 17507 3477 1738 17508 3479 1738 17509 3478 1738 17510 3479 4960 17511 3481 4960 17512 3480 4960 17513 3481 1740 17514 3483 1740 17515 3482 1740 17516 3483 4961 17517 3485 4961 17518 3484 4961 17519 3485 4962 17520 3487 4962 17521 3486 4962 17522 3487 1743 17523 3489 1743 17524 3488 1743 17525 3489 1744 17526 3491 1744 17527 3490 1744 17528 3491 4963 17529 3493 4963 17530 3492 4963 17531 3493 1746 17532 3495 1746 17533 3494 1746 17534 3495 4964 17535 3497 4964 17536 3496 4964 17537 3497 4965 17538 3499 4965 17539 3498 4965 17540 3499 4966 17541 3501 4966 17542 3500 4966 17543 3501 4967 17544 3503 4967 17545 3502 4967 17546 3503 4968 17547 3505 4968 17548 3504 4968 17549 3505 1752 17550 3507 1752 17551 3506 1752 17552 3507 4969 17553 3509 4969 17554 3508 4969 17555 3509 4970 17556 3511 4970 17557 3510 4970 17558 3511 4971 17559 3513 4971 17560 3512 4971 17561 3513 1756 17562 3515 1756 17563 3514 1756 17564 3515 4972 17565 3517 4972 17566 3516 4972 17567 3517 4973 17568 3519 4973 17569 3518 4973 17570 3519 1759 17571 3521 1759 17572 3520 1759 17573 3521 1760 17574 3523 1760 17575 3522 1760 17576 3523 1761 17577 3525 1761 17578 3524 1761 17579 3525 4974 17580 3527 4974 17581 3526 4974 17582 3527 4975 17583 3529 4975 17584 3528 4975 17585 3529 4976 17586 3531 4976 17587 3530 4976 17588 3531 1765 17589 3533 1765 17590 3532 1765 17591 3533 1766 17592 3535 1766 17593 3534 1766 17594 3535 4977 17595 3537 4977 17596 3536 4977 17597 3537 4978 17598 3539 4978 17599 3538 4978 17600 3539 1769 17601 3541 1769 17602 3540 1769 17603 3541 1770 17604 3543 1770 17605 3542 1770 17606 3543 4979 17607 3545 4979 17608 3544 4979 17609 3545 1772 17610 3547 1772 17611 3546 1772 17612 3547 1773 17613 3549 1773 17614 3548 1773 17615 3549 4980 17616 3551 4980 17617 3550 4980 17618 3551 1775 17619 3553 1775 17620 3552 1775 17621 3553 1776 17622 3555 1776 17623 3554 1776 17624 3555 1777 17625 3557 1777 17626 3556 1777 17627 3557 1778 17628 3559 1778 17629 3558 1778 17630 3559 1779 17631 3561 1779 17632 3560 1779 17633 3561 4981 17634 3563 4981 17635 3562 4981 17636 3563 4982 17637 3565 4982 17638 3564 4982 17639 3565 1782 17640 3567 1782 17641 3566 1782 17642 3567 4983 17643 3569 4983 17644 3568 4983 17645 3569 4984 17646 3571 4984 17647 3570 4984 17648 3571 4985 17649 3573 4985 17650 3572 4985 17651 3573 1786 17652 3575 1786 17653 3574 1786 17654 3575 4986 17655 3577 4986 17656 3576 4986 17657 3577 1788 17658 3579 1788 17659 3578 1788 17660 3579 1789 17661 3581 1789 17662 3580 1789 17663 3581 4987 17664 3583 4987 17665 3582 4987 17666 3583 1791 17667 3585 1791 17668 3584 1791 17669 3585 4988 17670 3587 4988 17671 3586 4988 17672 3587 1793 17673 3589 1793 17674 3588 1793 17675 3589 4989 17676 3591 4989 17677 3590 4989 17678 3591 1795 17679 3593 1795 17680 3592 1795 17681 3593 4990 17682 3595 4990 17683 3594 4990 17684 3595 1797 17685 3597 1797 17686 3596 1797 17687 3597 1798 17688 3599 1798 17689 3598 1798 17690 3599 4991 17691 3601 4991 17692 3600 4991 17693 3601 4992 17694 3603 4992 17695 3602 4992 17696 3603 1801 17697 3605 1801 17698 3604 1801 17699 3605 1802 17700 3607 1802 17701 3606 1802 17702 3607 1803 17703 3609 1803 17704 3608 1803 17705 3609 4993 17706 3611 4993 17707 3610 4993 17708 3611 4994 17709 3613 4994 17710 3612 4994 17711 3613 4995 17712 3615 4995 17713 3614 4995 17714 3615 1807 17715 3617 1807 17716 3616 1807 17717 3617 1808 17718 3619 1808 17719 3618 1808 17720 3619 1809 17721 3621 1809 17722 3620 1809 17723 3621 1810 17724 3623 1810 17725 3622 1810 17726 3623 1811 17727 3625 1811 17728 3624 1811 17729 3625 4996 17730 3627 4996 17731 3626 4996 17732 3627 1813 17733 3629 1813 17734 3628 1813 17735 3629 4997 17736 3631 4997 17737 3630 4997 17738 3631 4998 17739 3633 4998 17740 3632 4998 17741 3633 1816 17742 3635 1816 17743 3634 1816 17744 3635 1817 17745 3637 1817 17746 3636 1817 17747 3637 4999 17748 3639 4999 17749 3638 4999 17750 3639 1819 17751 3641 1819 17752 3640 1819 17753 3641 5000 17754 3643 5000 17755 3642 5000 17756 3643 5001 17757 3645 5001 17758 3644 5001 17759 3645 5002 17760 3647 5002 17761 3646 5002 17762 3647 5003 17763 3649 5003 17764 3648 5003 17765 3649 1824 17766 3651 1824 17767 3650 1824 17768 3651 5004 17769 3653 5004 17770 3652 5004 17771 3653 5005 17772 3655 5005 17773 3654 5005 17774 3655 1827 17775 3657 1827 17776 3656 1827 17777 3657 1828 17778 3659 1828 17779 3658 1828 17780 3659 5006 17781 3661 5006 17782 3660 5006 17783 3661 5007 17784 3663 5007 17785 3662 5007 17786 3663 5008 17787 3665 5008 17788 3664 5008 17789 3665 1832 17790 3667 1832 17791 3666 1832 17792 3667 1833 17793 3669 1833 17794 3668 1833 17795 3669 1834 17796 3671 1834 17797 3670 1834 17798 3671 1835 17799 3673 1835 17800 3672 1835 17801 3673 1836 17802 3675 1836 17803 3674 1836 17804 3675 5009 17805 3677 5009 17806 3676 5009 17807 3677 5010 17808 3679 5010 17809 3678 5010 17810 3679 1839 17811 3681 1839 17812 3680 1839 17813 3681 1840 17814 3683 1840 17815 3682 1840 17816 3683 1841 17817 3685 1841 17818 3684 1841 17819 3685 5011 17820 3687 5011 17821 3686 5011 17822 3687 5012 17823 3689 5012 17824 3688 5012 17825 3689 5013 17826 3691 5013 17827 3690 5013 17828 3691 1845 17829 3693 1845 17830 3692 1845 17831 3693 5014 17832 3695 5014 17833 3694 5014 17834 3695 5015 17835 3697 5015 17836 3696 5015 17837 3697 1848 17838 3699 1848 17839 3698 1848 17840 3699 1849 17841 3701 1849 17842 3700 1849 17843 3701 5016 17844 3703 5016 17845 3702 5016 17846 3703 1851 17847 3705 1851 17848 3704 1851 17849 3705 1852 17850 3707 1852 17851 3706 1852 17852 3707 1853 17853 3709 1853 17854 3708 1853 17855 3709 5017 17856 3711 5017 17857 3710 5017 17858 3711 1855 17859 3713 1855 17860 3712 1855 17861 3713 1856 17862 3715 1856 17863 3714 1856 17864 3715 1857 17865 3717 1857 17866 3716 1857 17867 3717 5018 17868 3719 5018 17869 3718 5018 17870 3719 5019 17871 3721 5019 17872 3720 5019 17873 3721 1860 17874 3723 1860 17875 3722 1860 17876 3723 1861 17877 3725 1861 17878 3724 1861 17879 3725 1862 17880 3727 1862 17881 3726 1862 17882 3727 1863 17883 3729 1863 17884 3728 1863 17885 3729 5020 17886 3731 5020 17887 3730 5020 17888 3731 5021 17889 3733 5021 17890 3732 5021 17891 3733 5022 17892 3735 5022 17893 3734 5022 17894 3735 1867 17895 3737 1867 17896 3736 1867 17897 3737 5023 17898 3739 5023 17899 3738 5023 17900 3739 1869 17901 3741 1869 17902 3740 1869 17903 3741 1870 17904 3743 1870 17905 3742 1870 17906 3743 1871 17907 3745 1871 17908 3744 1871 17909 3745 1872 17910 3747 1872 17911 3746 1872 17912 3747 5024 17913 3749 5024 17914 3748 5024 17915 3749 1874 17916 3751 1874 17917 3750 1874 17918 3751 1875 17919 3753 1875 17920 3752 1875 17921 3753 5025 17922 3755 5025 17923 3754 5025 17924 3755 1877 17925 3757 1877 17926 3756 1877 17927 3757 5026 17928 3759 5026 17929 3758 5026 17930 3759 1879 17931 3761 1879 17932 3760 1879 17933 3761 1880 17934 3763 1880 17935 3762 1880 17936 3763 5027 17937 3765 5027 17938 3764 5027 17939 3765 1882 17940 3767 1882 17941 3766 1882 17942 3767 5028 17943 3769 5028 17944 3768 5028 17945 3769 5029 17946 3771 5029 17947 3770 5029 17948 3771 1885 17949 3773 1885 17950 3772 1885 17951 3773 5030 17952 3775 5030 17953 3774 5030 17954 3775 1887 17955 3777 1887 17956 3776 1887 17957 3777 1888 17958 3779 1888 17959 3778 1888 17960 3779 5031 17961 3781 5031 17962 3780 5031 17963 3781 5032 17964 3783 5032 17965 3782 5032 17966 3783 5033 17967 3785 5033 17968 3784 5033 17969 3785 1892 17970 3787 1892 17971 3786 1892 17972 3787 1893 17973 3789 1893 17974 3788 1893 17975 3789 1894 17976 3791 1894 17977 3790 1894 17978 3791 1895 17979 3793 1895 17980 3792 1895 17981 3793 5034 17982 3795 5034 17983 3794 5034 17984 3795 1897 17985 3797 1897 17986 3796 1897 17987 3797 5035 17988 3799 5035 17989 3798 5035 17990 3799 1899 17991 3801 1899 17992 3800 1899 17993 3801 5036 17994 3803 5036 17995 3802 5036 17996 3803 1901 17997 3805 1901 17998 3804 1901 17999 3805 1902 18000 3807 1902 18001 3806 1902 18002 3807 1903 18003 3809 1903 18004 3808 1903 18005 3809 5037 18006 3811 5037 18007 3810 5037 18008 3811 1905 18009 3813 1905 18010 3812 1905 18011 3813 1906 18012 3815 1906 18013 3814 1906 18014 3815 1907 18015 3817 1907 18016 3816 1907 18017 3817 1908 18018 3819 1908 18019 3818 1908 18020 3819 5038 18021 3821 5038 18022 3820 5038 18023 3821 5039 18024 3823 5039 18025 3822 5039 18026 3823 1911 18027 3825 1911 18028 3824 1911 18029 3825 1912 18030 3827 1912 18031 3826 1912 18032 3827 5040 18033 3829 5040 18034 3828 5040 18035 3829 1914 18036 3831 1914 18037 3830 1914 18038 3831 5041 18039 3833 5041 18040 3832 5041 18041 3833 5042 18042 3835 5042 18043 3834 5042 18044 3835 1917 18045 3837 1917 18046 3836 1917 18047 3837 1918 18048 3839 1918 18049 3838 1918 18050 3839 5043 18051 3841 5043 18052 3840 5043 18053 3841 5044 18054 3843 5044 18055 3842 5044 18056 3843 5045 18057 3845 5045 18058 3844 5045 18059 3845 1922 18060 3847 1922 18061 3846 1922 18062 3847 1923 18063 3849 1923 18064 3848 1923 18065 3849 5046 18066 3851 5046 18067 3850 5046 18068 3851 1925 18069 3853 1925 18070 3852 1925 18071 3853 1926 18072 3855 1926 18073 3854 1926 18074 3855 1927 18075 3857 1927 18076 3856 1927 18077 3857 1928 18078 3859 1928 18079 3858 1928 18080 3859 1929 18081 3861 1929 18082 3860 1929 18083 3861 1930 18084 3863 1930 18085 3862 1930 18086 3863 5047 18087 3865 5047 18088 3864 5047 18089 3865 5048 18090 3867 5048 18091 3866 5048 18092 3867 5049 18093 3869 5049 18094 3868 5049 18095 3869 5050 18096 3871 5050 18097 3870 5050 18098 3871 1935 18099 3873 1935 18100 3872 1935 18101 3873 1936 18102 3875 1936 18103 3874 1936 18104 3875 5051 18105 3877 5051 18106 3876 5051 18107 3877 5052 18108 3879 5052 18109 3878 5052 18110 3879 1939 18111 3881 1939 18112 3880 1939 18113 3881 1940 18114 3883 1940 18115 3882 1940 18116 3883 5053 18117 3885 5053 18118 3884 5053 18119 3885 1942 18120 3887 1942 18121 3886 1942 18122 3887 1943 18123 3889 1943 18124 3888 1943 18125 3889 5054 18126 3891 5054 18127 3890 5054 18128 3891 5055 18129 3893 5055 18130 3892 5055 18131 3893 5056 18132 3895 5056 18133 3894 5056 18134 3895 5057 18135 3897 5057 18136 3896 5057 18137 3897 5058 18138 3899 5058 18139 3898 5058 18140 3899 5059 18141 3901 5059 18142 3900 5059 18143 3901 1950 18144 3903 1950 18145 3902 1950 18146 3903 5060 18147 3905 5060 18148 3904 5060 18149 3905 1952 18150 3907 1952 18151 3906 1952 18152 3907 1953 18153 3909 1953 18154 3908 1953 18155 3909 5061 18156 3911 5061 18157 3910 5061 18158 3911 5062 18159 3913 5062 18160 3912 5062 18161 3913 5063 18162 3915 5063 18163 3914 5063 18164 3915 1957 18165 3917 1957 18166 3916 1957 18167 3917 5064 18168 3919 5064 18169 3918 5064 18170 3919 1959 18171 3921 1959 18172 3920 1959 18173 3921 1960 18174 3923 1960 18175 3922 1960 18176 3923 5065 18177 3925 5065 18178 3924 5065 18179 3925 1962 18180 3927 1962 18181 3926 1962 18182 3927 5066 18183 3929 5066 18184 3928 5066 18185 3929 5067 18186 3931 5067 18187 3930 5067 18188 3931 5068 18189 3933 5068 18190 3932 5068 18191 3933 5069 18192 3935 5069 18193 3934 5069 18194 3935 1967 18195 3937 1967 18196 3936 1967 18197 3937 1968 18198 3939 1968 18199 3938 1968 18200 3939 5070 18201 3941 5070 18202 3940 5070 18203 3941 1970 18204 3943 1970 18205 3942 1970 18206 3943 5071 18207 3945 5071 18208 3944 5071 18209 3945 1972 18210 3947 1972 18211 3946 1972 18212 3947 5072 18213 3949 5072 18214 3948 5072 18215 3949 1974 18216 3951 1974 18217 3950 1974 18218 3951 1975 18219 3953 1975 18220 3952 1975 18221 3953 1976 18222 3955 1976 18223 3954 1976 18224 3955 1977 18225 3957 1977 18226 3956 1977 18227 3957 5073 18228 3959 5073 18229 3958 5073 18230 3959 5074 18231 3961 5074 18232 3960 5074 18233 3961 5075 18234 3963 5075 18235 3962 5075 18236 3963 5076 18237 3965 5076 18238 3964 5076 18239 3965 1982 18240 3967 1982 18241 3966 1982 18242 3967 1983 18243 3969 1983 18244 3968 1983 18245 3969 5077 18246 3971 5077 18247 3970 5077 18248 3971 1985 18249 3973 1985 18250 3972 1985 18251 3973 1986 18252 3975 1986 18253 3974 1986 18254 3975 1987 18255 3977 1987 18256 3976 1987 18257 3977 1988 18258 3979 1988 18259 3978 1988 18260 3979 5078 18261 3981 5078 18262 3980 5078 18263 3981 5079 18264 3983 5079 18265 3982 5079 18266 3983 1991 18267 3985 1991 18268 3984 1991 18269 3985 1992 18270 3987 1992 18271 3986 1992 18272 3987 1993 18273 3989 1993 18274 3988 1993 18275 3989 5080 18276 3991 5080 18277 3990 5080 18278 3991 1995 18279 3993 1995 18280 3992 1995 18281 3993 5081 18282 3995 5081 18283 3994 5081 18284 3995 1997 18285 3997 1997 18286 3996 1997 18287 3997 1998 18288 3999 1998 18289 3998 1998 18290 3999 1999 18291 4001 1999 18292 4000 1999 18293 4001 5082 18294 4003 5082 18295 4002 5082 18296 4003 2001 18297 4005 2001 18298 4004 2001 18299 4005 2002 18300 4007 2002 18301 4006 2002 18302 4007 2003 18303 4009 2003 18304 4008 2003 18305 4009 5083 18306 4011 5083 18307 4010 5083 18308 4011 2005 18309 4013 2005 18310 4012 2005 18311 4013 5084 18312 4015 5084 18313 4014 5084 18314 4015 5085 18315 4017 5085 18316 4016 5085 18317 4017 2008 18318 4019 2008 18319 4018 2008 18320 4019 5086 18321 4021 5086 18322 4020 5086 18323 4021 2010 18324 4023 2010 18325 4022 2010 18326 4023 5087 18327 4025 5087 18328 4024 5087 18329 4025 2012 18330 4027 2012 18331 4026 2012 18332 4027 2013 18333 4029 2013 18334 4028 2013 18335 4029 2014 18336 4031 2014 18337 4030 2014 18338 4031 5088 18339 4033 5088 18340 4032 5088 18341 4033 2016 18342 4035 2016 18343 4034 2016 18344 4035 5089 18345 4037 5089 18346 4036 5089 18347 4037 5090 18348 4039 5090 18349 4038 5090 18350 4039 5091 18351 4041 5091 18352 4040 5091 18353 4041 2020 18354 4043 2020 18355 4042 2020 18356 4043 5092 18357 4045 5092 18358 4044 5092 18359 4045 2022 18360 4047 2022 18361 4046 2022 18362 4047 2023 18363 4049 2023 18364 4048 2023 18365 4049 2024 18366 4051 2024 18367 4050 2024 18368 4051 2025 18369 4053 2025 18370 4052 2025 18371 4053 5093 18372 4055 5093 18373 4054 5093 18374 4055 2027 18375 4057 2027 18376 4056 2027 18377 4057 5094 18378 4059 5094 18379 4058 5094 18380 4059 5095 18381 4061 5095 18382 4060 5095 18383 4061 2030 18384 4063 2030 18385 4062 2030 18386 4063 2031 18387 4065 2031 18388 4064 2031 18389 4065 5096 18390 4067 5096 18391 4066 5096 18392 4067 5097 18393 4069 5097 18394 4068 5097 18395 4069 2034 18396 4071 2034 18397 4070 2034 18398 4071 2035 18399 4073 2035 18400 4072 2035 18401 4073 5098 18402 4075 5098 18403 4074 5098 18404 4075 5099 18405 4077 5099 18406 4076 5099 18407 4077 5100 18408 4079 5100 18409 4078 5100 18410 4079 5101 18411 4081 5101 18412 4080 5101 18413 4081 2040 18414 4083 2040 18415 4082 2040 18416 4083 2041 18417 4085 2041 18418 4084 2041 18419 4085 5102 18420 4087 5102 18421 4086 5102 18422 4087 5103 18423 4089 5103 18424 4088 5103 18425 4089 5104 18426 4091 5104 18427 4090 5104 18428 4091 2045 18429 4093 2045 18430 4092 2045 18431 4093 5105 18432 4095 5105 18433 4094 5105 18434 4095 2047 18435 4097 2047 18436 4096 2047 18437 4097 2048 18438 4099 2048 18439 4098 2048 18440 4099 5106 18441 4101 5106 18442 4100 5106 18443 4101 2050 18444 4103 2050 18445 4102 2050 18446 4103 5107 18447 4105 5107 18448 4104 5107 18449 4105 5108 18450 4107 5108 18451 4106 5108 18452 4107 5109 18453 4109 5109 18454 4108 5109 18455 4109 2054 18456 4111 2054 18457 4110 2054 18458 4111 2055 18459 4113 2055 18460 4112 2055 18461 4113 5110 18462 4115 5110 18463 4114 5110 18464 4115 5111 18465 4117 5111 18466 4116 5111 18467 4117 5112 18468 4119 5112 18469 4118 5112 18470 4119 5113 18471 4121 5113 18472 4120 5113 18473 4121 2060 18474 4123 2060 18475 4122 2060 18476 4123 2061 18477 4125 2061 18478 4124 2061 18479 4125 5114 18480 4127 5114 18481 4126 5114 18482 4127 5115 18483 4129 5115 18484 4128 5115 18485 4129 2064 18486 4131 2064 18487 4130 2064 18488 4131 2065 18489 4133 2065 18490 4132 2065 18491 4133 5116 18492 4135 5116 18493 4134 5116 18494 4135 5117 18495 4137 5117 18496 4136 5117 18497 4137 2068 18498 4139 2068 18499 4138 2068 18500 4139 5118 18501 4141 5118 18502 4140 5118 18503 4141 2070 18504 4143 2070 18505 4142 2070 18506 4143 2071 18507 4145 2071 18508 4144 2071 18509 4145 2072 18510 4147 2072 18511 4146 2072 18512 4147 2073 18513 4149 2073 18514 4148 2073 18515 4149 5119 18516 4151 5119 18517 4150 5119 18518 4151 2075 18519 4153 2075 18520 4152 2075 18521 4153 5120 18522 4155 5120 18523 4154 5120 18524 4155 5121 18525 4157 5121 18526 4156 5121 18527 4157 5122 18528 4159 5122 18529 4158 5122 18530 4159 2079 18531 4161 2079 18532 4160 2079 18533 4161 5123 18534 4163 5123 18535 4162 5123 18536 4163 2081 18537 4165 2081 18538 4164 2081 18539 4165 2082 18540 4167 2082 18541 4166 2082 18542 4167 2083 18543 4169 2083 18544 4168 2083 18545 4169 5124 18546 4171 5124 18547 4170 5124 18548 4171 2085 18549 4173 2085 18550 4172 2085 18551 4173 5125 18552 4175 5125 18553 4174 5125 18554 4175 2087 18555 4177 2087 18556 4176 2087 18557 4177 5126 18558 4179 5126 18559 4178 5126 18560 4179 5127 18561 4181 5127 18562 4180 5127 18563 4181 2090 18564 4183 2090 18565 4182 2090 18566 4183 5128 18567 4185 5128 18568 4184 5128 18569 4185 2092 18570 4187 2092 18571 4186 2092 18572 4187 2093 18573 4189 2093 18574 4188 2093 18575 4189 2094 18576 4191 2094 18577 4190 2094 18578 4191 5129 18579 4193 5129 18580 4192 5129 18581 4193 2096 18582 4195 2096 18583 4194 2096 18584 4195 2097 18585 4197 2097 18586 4196 2097 18587 4197 2098 18588 4199 2098 18589 4198 2098 18590 4199 5130 18591 4201 5130 18592 4200 5130 18593 4201 2100 18594 4203 2100 18595 4202 2100 18596 4203 5131 18597 4205 5131 18598 4204 5131 18599 4205 2102 18600 4207 2102 18601 4206 2102 18602 4207 2103 18603 4209 2103 18604 4208 2103 18605 4209 2104 18606 4211 2104 18607 4210 2104 18608 4211 5132 18609 4213 5132 18610 4212 5132 18611 4213 5133 18612 4215 5133 18613 4214 5133 18614 4215 2107 18615 4217 2107 18616 4216 2107 18617 4217 2108 18618 4219 2108 18619 4218 2108 18620 4219 2109 18621 4221 2109 18622 4220 2109 18623 4221 2110 18624 4223 2110 18625 4222 2110 18626 4223 5134 18627 4225 5134 18628 4224 5134 18629 4225 2112 18630 4227 2112 18631 4226 2112 18632 4227 2113 18633 4229 2113 18634 4228 2113 18635 4229 5135 18636 4231 5135 18637 4230 5135 18638 4231 5136 18639 4233 5136 18640 4232 5136 18641 4233 5137 18642 4235 5137 18643 4234 5137 18644 4235 5138 18645 4237 5138 18646 4236 5138 18647 4237 2118 18648 4239 2118 18649 4238 2118 18650 4239 2119 18651 4241 2119 18652 4240 2119 18653 4241 2120 18654 4243 2120 18655 4242 2120 18656 4243 2121 18657 4245 2121 18658 4244 2121 18659 4245 5139 18660 4247 5139 18661 4246 5139 18662 4247 2123 18663 4249 2123 18664 4248 2123 18665 4249 5140 18666 4251 5140 18667 4250 5140 18668 4251 2125 18669 4253 2125 18670 4252 2125 18671 4253 5141 18672 4255 5141 18673 4254 5141 18674 4255 2127 18675 4257 2127 18676 4256 2127 18677 4257 2128 18678 4259 2128 18679 4258 2128 18680 4259 5142 18681 4261 5142 18682 4260 5142 18683 4261 5143 18684 4263 5143 18685 4262 5143 18686 4263 5144 18687 4265 5144 18688 4264 5144 18689 4265 5145 18690 4267 5145 18691 4266 5145 18692 4267 2133 18693 4269 2133 18694 4268 2133 18695 4269 5146 18696 4271 5146 18697 4270 5146 18698 4271 2135 18699 4273 2135 18700 4272 2135 18701 4273 2136 18702 4275 2136 18703 4274 2136 18704 4275 5147 18705 4277 5147 18706 4276 5147 18707 4277 2138 18708 4279 2138 18709 4278 2138 18710 4279 5148 18711 4281 5148 18712 4280 5148 18713 4281 5149 18714 4283 5149 18715 4282 5149 18716 4283 5150 18717 4285 5150 18718 4284 5150 18719 4285 2142 18720 4287 2142 18721 4286 2142 18722 4287 2143 18723 4289 2143 18724 4288 2143 18725 4289 5151 18726 4291 5151 18727 4290 5151 18728 4291 2145 18729 4293 2145 18730 4292 2145 18731 4293 5152 18732 4295 5152 18733 4294 5152 18734 4295 5153 18735 4297 5153 18736 4296 5153 18737 4297 5154 18738 4299 5154 18739 4298 5154 18740 4299 5155 18741 4301 5155 18742 4300 5155 18743 4301 5156 18744 4303 5156 18745 4302 5156 18746 4303 5157 18747 4305 5157 18748 4304 5157 18749 4305 2152 18750 4307 2152 18751 4306 2152 18752 4307 2153 18753 4309 2153 18754 4308 2153 18755 4309 5158 18756 4311 5158 18757 4310 5158 18758 4311 2155 18759 4313 2155 18760 4312 2155 18761 4313 2156 18762 4315 2156 18763 4314 2156 18764 4315 5159 18765 4317 5159 18766 4316 5159 18767 4317 5160 18768 4319 5160 18769 4318 5160 18770 4319 2159 18771 4321 2159 18772 4320 2159 18773 4321 2160 18774 4323 2160 18775 4322 2160 18776 4323 5161 18777 4325 5161 18778 4324 5161 18779 4325 5162 18780 4327 5162 18781 4326 5162 18782 4327 5163 18783 4329 5163 18784 4328 5163 18785 4329 5164 18786 4331 5164 18787 4330 5164 18788 4331 2165 18789 4333 2165 18790 4332 2165 18791 4333 2166 18792 4335 2166 18793 4334 2166 18794 4335 2167 18795 4337 2167 18796 4336 2167 18797 4337 2168 18798 4339 2168 18799 4338 2168 18800 4339 2169 18801 4341 2169 18802 4340 2169 18803 4341 2170 18804 4343 2170 18805 4342 2170 18806 4343 5165 18807 4345 5165 18808 4344 5165 18809 4345 2172 18810 4347 2172 18811 4346 2172 18812 4347 2173 18813 4349 2173 18814 4348 2173 18815 4349 5166 18816 4351 5166 18817 4350 5166 18818 4351 5167 18819 4353 5167 18820 4352 5167 18821 4353 5168 18822 4355 5168 18823 4354 5168 18824 4355 2177 18825 4357 2177 18826 4356 2177 18827 4357 2178 18828 4359 2178 18829 4358 2178 18830 4359 5169 18831 4361 5169 18832 4360 5169 18833 4361 5170 18834 4363 5170 18835 4362 5170 18836 4363 2181 18837 4365 2181 18838 4364 2181 18839 4365 5171 18840 4367 5171 18841 4366 5171 18842 4367 2183 18843 4369 2183 18844 4368 2183 18845 4369 2184 18846 4371 2184 18847 4370 2184 18848 4371 5172 18849 4373 5172 18850 4372 5172 18851 4373 5173 18852 4375 5173 18853 4374 5173 18854 4375 2187 18855 4377 2187 18856 4376 2187 18857 4377 2188 18858 4379 2188 18859 4378 2188 18860 4379 2189 18861 4381 2189 18862 4380 2189 18863 4381 2190 18864 4383 2190 18865 4382 2190 18866 4383 5174 18867 4385 5174 18868 4384 5174 18869 4385 2192 18870 4387 2192 18871 4386 2192 18872 4387 2193 18873 4389 2193 18874 4388 2193 18875 4389 2194 18876 4391 2194 18877 4390 2194 18878 4391 5175 18879 4393 5175 18880 4392 5175 18881 4393 2196 18882 4395 2196 18883 4394 2196 18884 4395 5176 18885 4397 5176 18886 4396 5176 18887 4397 2198 18888 4399 2198 18889 4398 2198 18890 4399 5177 18891 4401 5177 18892 4400 5177 18893 4401 2200 18894 4403 2200 18895 4402 2200 18896 4403 2201 18897 4405 2201 18898 4404 2201 18899 4405 2202 18900 4407 2202 18901 4406 2202 18902 4407 2203 18903 4409 2203 18904 4408 2203 18905 4409 5178 18906 4411 5178 18907 4410 5178 18908 4411 5179 18909 4413 5179 18910 4412 5179 18911 4413 5180 18912 4415 5180 18913 4414 5180 18914 4415 2207 18915 4417 2207 18916 4416 2207 18917 4417 2208 18918 4419 2208 18919 4418 2208 18920 4419 5181 18921 4421 5181 18922 4420 5181 18923 4421 2210 18924 4423 2210 18925 4422 2210 18926 4423 5182 18927 4425 5182 18928 4424 5182 18929 4425 5183 18930 4427 5183 18931 4426 5183 18932 4427 2213 18933 4429 2213 18934 4428 2213 18935 4429 5184 18936 4431 5184 18937 4430 5184 18938 4431 2215 18939 4433 2215 18940 4432 2215 18941 4433 2216 18942 4435 2216 18943 4434 2216 18944 4435 5185 18945 4437 5185 18946 4436 5185 18947 4437 2218 18948 4439 2218 18949 4438 2218 18950 4439 5186 18951 4441 5186 18952 4440 5186 18953 4441 2220 18954 4443 2220 18955 4442 2220 18956 4443 2221 18957 4445 2221 18958 4444 2221 18959 4445 5187 18960 4447 5187 18961 4446 5187 18962 4447 2223 18963 4449 2223 18964 4448 2223 18965 4449 2224 18966 4451 2224 18967 4450 2224 18968 4451 2225 18969 4453 2225 18970 4452 2225 18971 4453 2226 18972 4455 2226 18973 4454 2226 18974 4455 5188 18975 4457 5188 18976 4456 5188 18977 4457 2228 18978 4459 2228 18979 4458 2228 18980 4459 5189 18981 4461 5189 18982 4460 5189 18983 4461 5190 18984 4463 5190 18985 4462 5190 18986 4463 5191 18987 4465 5191 18988 4464 5191 18989 4465 2232 18990 4467 2232 18991 4466 2232 18992 4467 2233 18993 4469 2233 18994 4468 2233 18995 4469 2234 18996 4471 2234 18997 4470 2234 18998 4471 2235 18999 4473 2235 19000 4472 2235 19001 4473 5192 19002 4475 5192 19003 4474 5192 19004 4475 5193 19005 4477 5193 19006 4476 5193 19007 4477 2238 19008 4479 2238 19009 4478 2238 19010 4479 2239 19011 4481 2239 19012 4480 2239 19013 4481 2240 19014 4483 2240 19015 4482 2240 19016 4483 5194 19017 4485 5194 19018 4484 5194 19019 4485 2242 19020 4487 2242 19021 4486 2242 19022 4487 2243 19023 4489 2243 19024 4488 2243 19025 4489 2244 19026 4491 2244 19027 4490 2244 19028 4491 5195 19029 4493 5195 19030 4492 5195 19031 4493 2246 19032 4495 2246 19033 4494 2246 19034 4495 2247 19035 4497 2247 19036 4496 2247 19037 4497 5196 19038 4499 5196 19039 4498 5196 19040 4499 5197 19041 4501 5197 19042 4500 5197 19043 4501 2250 19044 4503 2250 19045 4502 2250 19046 4503 5198 19047 4505 5198 19048 4504 5198 19049 4505 5199 19050 4507 5199 19051 4506 5199 19052 4507 5200 19053 4509 5200 19054 4508 5200 19055 4509 2254 19056 4511 2254 19057 4510 2254 19058 4511 2255 19059 4513 2255 19060 4512 2255 19061 4513 2256 19062 4515 2256 19063 4514 2256 19064 4515 5201 19065 4517 5201 19066 4516 5201 19067 4517 5202 19068 4519 5202 19069 4518 5202 19070 4519 2259 19071 4521 2259 19072 4520 2259 19073 4521 2260 19074 4523 2260 19075 4522 2260 19076 4523 2261 19077 4525 2261 19078 4524 2261 19079 4525 2262 19080 4527 2262 19081 4526 2262 19082 4527 2263 19083 4529 2263 19084 4528 2263 19085 4529 5203 19086 4531 5203 19087 4530 5203 19088 4531 5204 19089 4533 5204 19090 4532 5204 19091 4533 5205 19092 4535 5205 19093 4534 5205 19094 4535 2267 19095 4537 2267 19096 4536 2267 19097 4537 2268 19098 4539 2268 19099 4538 2268 19100 4539 5206 19101 4541 5206 19102 4540 5206 19103 4541 5207 19104 4543 5207 19105 4542 5207 19106 4543 2271 19107 4545 2271 19108 4544 2271 19109 4545 5208 19110 4547 5208 19111 4546 5208 19112 4547 5209 19113 4549 5209 19114 4548 5209 19115 4549 5210 19116 4551 5210 19117 4550 5210 19118 4551 5211 19119 4553 5211 19120 4552 5211 19121 4553 2276 19122 4555 2276 19123 4554 2276 19124 4555 5212 19125 4557 5212 19126 4556 5212 19127 4557 2278 19128 4559 2278 19129 4558 2278 19130 4559 2279 19131 4561 2279 19132 4560 2279 19133 4561 5213 19134 4563 5213 19135 4562 5213 19136 4563 5214 19137 4565 5214 19138 4564 5214 19139 4565 2282 19140 4567 2282 19141 4566 2282 19142 4567 5215 19143 4569 5215 19144 4568 5215 19145 4569 2284 19146 4571 2284 19147 4570 2284 19148 4571 2285 19149 4573 2285 19150 4572 2285 19151 4573 2286 19152 4575 2286 19153 4574 2286 19154 4575 2287 19155 4577 2287 19156 4576 2287 19157 4577 2288 19158 4579 2288 19159 4578 2288 19160 4579 5216 19161 4581 5216 19162 4580 5216 19163 4581 5217 19164 4583 5217 19165 4582 5217 19166 4583 5218 19167 4585 5218 19168 4584 5218 19169 4585 2292 19170 4587 2292 19171 4586 2292 19172 4587 2293 19173 4589 2293 19174 4588 2293 19175 4589 2294 19176 4591 2294 19177 4590 2294 19178 4591 5219 19179 4593 5219 19180 4592 5219 19181 4593 5220 19182 4595 5220 19183 4594 5220 19184 4595 2297 19185 4597 2297 19186 4596 2297 19187 4597 2298 19188 4599 2298 19189 4598 2298 19190 4599 5221 19191 4601 5221 19192 4600 5221 19193 4601 2300 19194 4603 2300 19195 4602 2300 19196 4603 5222 19197 4605 5222 19198 4604 5222 19199 4605 2302 19200 4607 2302 19201 4606 2302 19202 4607 5223 19203 4609 5223 19204 4608 5223 19205 4609 2304 19206 4611 2304 19207 4610 2304 19208 4611 5224 19209 4613 5224 19210 4612 5224 19211 4613 2306 19212 4615 2306 19213 4614 2306 19214 4615 2307 19215 4617 2307 19216 4616 2307 19217 4617 5225 19218 4619 5225 19219 4618 5225 19220 4619 2309 19221 4621 2309 19222 4620 2309 19223 4621 5226 19224 4623 5226 19225 4622 5226 19226 4623 5227 19227 4625 5227 19228 4624 5227 19229 4625 5228 19230 4627 5228 19231 4626 5228 19232 4627 2313 19233 4629 2313 19234 4628 2313 19235 4629 5229 19236 4631 5229 19237 4630 5229 19238 4631 5230 19239 4633 5230 19240 4632 5230 19241 4633 2316 19242 4635 2316 19243 4634 2316 19244 4635 2317 19245 4637 2317 19246 4636 2317 19247 4637 2318 19248 4639 2318 19249 4638 2318 19250 4639 2319 19251 4641 2319 19252 4640 2319 19253 4641 2320 19254 4643 2320 19255 4642 2320 19256 4643 5231 19257 4645 5231 19258 4644 5231 19259 4645 2322 19260 4647 2322 19261 4646 2322 19262 4647 2323 19263 4649 2323 19264 4648 2323 19265 4649 5232 19266 4651 5232 19267 4650 5232 19268 4651 2325 19269 4653 2325 19270 4652 2325 19271 4653 2326 19272 4655 2326 19273 4654 2326 19274 4655 5233 19275 4657 5233 19276 4656 5233 19277 4657 5234 19278 4659 5234 19279 4658 5234 19280 4659 2329 19281 4661 2329 19282 4660 2329 19283 4661 2330 19284 4663 2330 19285 4662 2330 19286 4663 5235 19287 4665 5235 19288 4664 5235 19289 4665 5236 19290 4667 5236 19291 4666 5236 19292 4667 5237 19293 4669 5237 19294 4668 5237 19295 4669 2334 19296 4671 2334 19297 4670 2334 19298 4671 2335 19299 4673 2335 19300 4672 2335 19301 4673 2336 19302 4675 2336 19303 4674 2336 19304 4675 5238 19305 4677 5238 19306 4676 5238 19307 4677 5239 19308 4679 5239 19309 4678 5239 19310 4679 2339 19311 4681 2339 19312 4680 2339 19313 4681 5240 19314 4683 5240 19315 4682 5240 19316 4683 5241 19317 4685 5241 19318 4684 5241 19319 4685 5242 19320 4687 5242 19321 4686 5242 19322 4687 2343 19323 4689 2343 19324 4688 2343 19325 4689 5243 19326 4691 5243 19327 4690 5243 19328 4691 5244 19329 4693 5244 19330 4692 5244 19331 4693 5245 19332 4695 5245 19333 4694 5245 19334 4695 5246 19335 4697 5246 19336 4696 5246 19337 4697 5247 19338 4699 5247 19339 4698 5247 19340 4699 2349 19341 4701 2349 19342 4700 2349 19343 4701 5248 19344 4703 5248 19345 4702 5248 19346 4703 2351 19347 4705 2351 19348 4704 2351 19349 4705 2352 19350 4707 2352 19351 4706 2352 19352 4707 5249 19353 4709 5249 19354 4708 5249 19355 4709 5250 19356 4711 5250 19357 4710 5250 19358 4711 2355 19359 4713 2355 19360 4712 2355 19361 4713 5251 19362 4715 5251 19363 4714 5251 19364 4715 2357 19365 4717 2357 19366 4716 2357 19367 4717 5252 19368 4719 5252 19369 4718 5252 19370 4719 2359 19371 4721 2359 19372 4720 2359 19373 4721 5253 19374 4723 5253 19375 4722 5253 19376 4723 2361 19377 4725 2361 19378 4724 2361 19379 4725 2362 19380 4727 2362 19381 4726 2362 19382 4727 5254 19383 4729 5254 19384 4728 5254 19385 4729 2364 19386 4731 2364 19387 4730 2364 19388 4731 5255 19389 4733 5255 19390 4732 5255 19391 4733 5256 19392 4735 5256 19393 4734 5256 19394 4735 5257 19395 4737 5257 19396 4736 5257 19397 4737 2368 19398 4739 2368 19399 4738 2368 19400 4739 5258 19401 4741 5258 19402 4740 5258 19403 4741 5259 19404 4743 5259 19405 4742 5259 19406 4743 2371 19407 4745 2371 19408 4744 2371 19409 4745 5260 19410 4747 5260 19411 4746 5260 19412 4747 5261 19413 4749 5261 19414 4748 5261 19415 4749 2374 19416 4751 2374 19417 4750 2374 19418 4751 2375 19419 4753 2375 19420 4752 2375 19421 4753 2376 19422 4755 2376 19423 4754 2376 19424 4755 2377 19425 4757 2377 19426 4756 2377 19427 4757 2378 19428 4759 2378 19429 4758 2378 19430 4759 5262 19431 4761 5262 19432 4760 5262 19433 4761 5263 19434 4763 5263 19435 4762 5263 19436 4763 2381 19437 4765 2381 19438 4764 2381 19439 4765 5264 19440 4767 5264 19441 4766 5264 19442 4767 5265 19443 4769 5265 19444 4768 5265 19445 4769 5266 19446 4771 5266 19447 4770 5266 19448 4771 5267 19449 4773 5267 19450 4772 5267 19451 4773 5268 19452 4775 5268 19453 4774 5268 19454 4775 5269 19455 4777 5269 19456 4776 5269 19457 4777 5270 19458 4779 5270 19459 4778 5270 19460 4779 5271 19461 4781 5271 19462 4780 5271 19463 4781 5272 19464 4783 5272 19465 4782 5272 19466 4783 5273 19467 4785 5273 19468 4784 5273 19469 4785 2392 19470 4787 2392 19471 4786 2392 19472 4787 5274 19473 4789 5274 19474 4788 5274 19475 4789 5275 19476 4791 5275 19477 4790 5275 19478 4791 2395 19479 4793 2395 19480 4792 2395 19481 4793 5276 19482 4795 5276 19483 4794 5276 19484 4795 5277 19485 4797 5277 19486 4796 5277 19487 4797 5278 19488 4799 5278 19489 4798 5278 19490 4799 2399 19491 4801 2399 19492 4800 2399 19493 4801 2400 19494 4803 2400 19495 4802 2400 19496 4803 2401 19497 4805 2401 19498 4804 2401 19499 4805 5279 19500 4807 5279 19501 4806 5279 19502 4807 2403 19503 4809 2403 19504 4808 2403 19505 4809 2404 19506 4811 2404 19507 4810 2404 19508 4811 2405 19509 4813 2405 19510 4812 2405 19511 4813 2406 19512 4815 2406 19513 4814 2406 19514 4815 5280 19515 4817 5280 19516 4816 5280 19517 4817 2408 19518 4819 2408 19519 4818 2408 19520 4819 5281 19521 4821 5281 19522 4820 5281 19523 4821 5282 19524 4823 5282 19525 4822 5282 19526 4823 5283 19527 4825 5283 19528 4824 5283 19529 4825 5284 19530 4827 5284 19531 4826 5284 19532 4827 2413 19533 4829 2413 19534 4828 2413 19535 4829 2414 19536 4831 2414 19537 4830 2414 19538 4831 5285 19539 4833 5285 19540 4832 5285 19541 4833 5286 19542 4835 5286 19543 4834 5286 19544 4835 5287 19545 4837 5287 19546 4836 5287 19547 4837 5288 19548 4839 5288 19549 4838 5288 19550 4839 5289 19551 4841 5289 19552 4840 5289 19553 4841 5290 19554 4843 5290 19555 4842 5290 19556 4843 2421 19557 4845 2421 19558 4844 2421 19559 4845 5291 19560 4847 5291 19561 4846 5291 19562 4847 5292 19563 4849 5292 19564 4848 5292 19565 4849 2424 19566 4851 2424 19567 4850 2424 19568 4851 2425 19569 4853 2425 19570 4852 2425 19571 4853 5293 19572 4855 5293 19573 4854 5293 19574 4855 5294 19575 4857 5294 19576 4856 5294 19577 4857 2428 19578 4859 2428 19579 4858 2428 19580 4859 2429 19581 4861 2429 19582 4860 2429 19583 4861 5295 19584 4863 5295 19585 4862 5295 19586 4863 2431 19587 4865 2431 19588 4864 2431 19589 4865 2432 19590 4867 2432 19591 4866 2432 19592 4867 5296 19593 4869 5296 19594 4868 5296 19595 4869 2434 19596 4871 2434 19597 4870 2434 19598 4871 2435 19599 4873 2435 19600 4872 2435 19601 4873 5297 19602 4875 5297 19603 4874 5297 19604 4875 5298 19605 4877 5298 19606 4876 5298 19607 4877 5299 19608 4879 5299 19609 4878 5299 19610 4879 5300 19611 4881 5300 19612 4880 5300 19613 4881 5301 19614 4883 5301 19615 4882 5301 19616 4883 2441 19617 4885 2441 19618 4884 2441 19619 4885 5302 19620 4887 5302 19621 4886 5302 19622 4887 5303 19623 4889 5303 19624 4888 5303 19625 4889 2444 19626 4891 2444 19627 4890 2444 19628 4891 2445 19629 4893 2445 19630 4892 2445 19631 4893 2446 19632 4895 2446 19633 4894 2446 19634 4895 5304 19635 4897 5304 19636 4896 5304 19637 4897 2448 19638 4899 2448 19639 4898 2448 19640 4899 5305 19641 4901 5305 19642 4900 5305 19643 4901 2450 19644 4903 2450 19645 4902 2450 19646 4903 2451 19647 4905 2451 19648 4904 2451 19649 4905 2452 19650 4907 2452 19651 4906 2452 19652 4907 2453 19653 4909 2453 19654 4908 2453 19655 4909 2454 19656 4911 2454 19657 4910 2454 19658 4911 2455 19659 4913 2455 19660 4912 2455 19661 4913 5306 19662 4915 5306 19663 4914 5306 19664 4915 2457 19665 4917 2457 19666 4916 2457 19667 4917 5307 19668 4919 5307 19669 4918 5307 19670 4919 5308 19671 4921 5308 19672 4920 5308 19673 4921 2460 19674 4923 2460 19675 4922 2460 19676 4923 2461 19677 4925 2461 19678 4924 2461 19679 4925 2462 19680 4927 2462 19681 4926 2462 19682 4927 5309 19683 4929 5309 19684 4928 5309 19685 4929 2464 19686 4931 2464 19687 4930 2464 19688 4931 2465 19689 4933 2465 19690 4932 2465 19691 4933 2466 19692 4935 2466 19693 4934 2466 19694 4935 5310 19695 4937 5310 19696 4936 5310 19697 4937 5311 19698 4939 5311 19699 4938 5311 19700 4939 5312 19701 4941 5312 19702 4940 5312 19703 4941 5313 19704 4943 5313 19705 4942 5313 19706 4943 5314 19707 4945 5314 19708 4944 5314 19709 4945 2472 19710 4947 2472 19711 4946 2472 19712 4947 2473 19713 4949 2473 19714 4948 2473 19715 4949 2474 19716 4951 2474 19717 4950 2474 19718 4951 5315 19719 4953 5315 19720 4952 5315 19721 4953 2476 19722 4955 2476 19723 4954 2476 19724 4955 5316 19725 4957 5316 19726 4956 5316 19727 4957 2478 19728 4959 2478 19729 4958 2478 19730 4959 5317 19731 4961 5317 19732 4960 5317 19733 4961 2480 19734 4963 2480 19735 4962 2480 19736 4963 5318 19737 4965 5318 19738 4964 5318 19739 4965 2482 19740 4967 2482 19741 4966 2482 19742 4967 5319 19743 4969 5319 19744 4968 5319 19745 4969 5320 19746 4971 5320 19747 4970 5320 19748 4971 2485 19749 4973 2485 19750 4972 2485 19751 4973 2486 19752 4975 2486 19753 4974 2486 19754 4975 2487 19755 4977 2487 19756 4976 2487 19757 4977 2488 19758 4979 2488 19759 4978 2488 19760 4979 2489 19761 4981 2489 19762 4980 2489 19763 4981 2490 19764 4983 2490 19765 4982 2490 19766 4983 2491 19767 4985 2491 19768 4984 2491 19769 4985 2492 19770 4987 2492 19771 4986 2492 19772 4987 2493 19773 4989 2493 19774 4988 2493 19775 4989 2494 19776 4991 2494 19777 4990 2494 19778 4991 5321 19779 4993 5321 19780 4992 5321 19781 4993 5322 19782 4995 5322 19783 4994 5322 19784 4995 2497 19785 4997 2497 19786 4996 2497 19787 4997 2498 19788 4999 2498 19789 4998 2498 19790 4999 2499 19791 5001 2499 19792 5000 2499 19793 5001 5323 19794 5003 5323 19795 5002 5323 19796 5003 2501 19797 5005 2501 19798 5004 2501 19799 5005 2502 19800 5007 2502 19801 5006 2502 19802 5007 5324 19803 5009 5324 19804 5008 5324 19805 5009 2504 19806 5011 2504 19807 5010 2504 19808 5011 2505 19809 5013 2505 19810 5012 2505 19811 5013 5325 19812 5015 5325 19813 5014 5325 19814 5015 5326 19815 5017 5326 19816 5016 5326 19817 5017 5327 19818 5019 5327 19819 5018 5327 19820 5019 2509 19821 5021 2509 19822 5020 2509 19823 5021 2510 19824 5023 2510 19825 5022 2510 19826 5023 2511 19827 5025 2511 19828 5024 2511 19829 5025 2512 19830 5027 2512 19831 5026 2512 19832 5027 5328 19833 5029 5328 19834 5028 5328 19835 5029 5329 19836 5031 5329 19837 5030 5329 19838 5031 5330 19839 5033 5330 19840 5032 5330 19841 5033 5331 19842 5035 5331 19843 5034 5331 19844 5035 5332 19845 5037 5332 19846 5036 5332 19847 5037 5333 19848 5039 5333 19849 5038 5333 19850 5039 5334 19851 5041 5334 19852 5040 5334 19853 5041 5335 19854 5043 5335 19855 5042 5335 19856 5043 2521 19857 5045 2521 19858 5044 2521 19859 5045 2522 19860 5047 2522 19861 5046 2522 19862 5047 2523 19863 5049 2523 19864 5048 2523 19865 5049 2524 19866 5051 2524 19867 5050 2524 19868 5051 5336 19869 5053 5336 19870 5052 5336 19871 5053 2526 19872 5055 2526 19873 5054 2526 19874 5055 5337 19875 5057 5337 19876 5056 5337 19877 5057 2528 19878 5059 2528 19879 5058 2528 19880 5059 5338 19881 5061 5338 19882 5060 5338 19883 5061 5339 19884 5063 5339 19885 5062 5339 19886 5063 2531 19887 5065 2531 19888 5064 2531 19889 5065 5340 19890 5067 5340 19891 5066 5340 19892 5067 5341 19893 5069 5341 19894 5068 5341 19895 5069 5342 19896 5071 5342 19897 5070 5342 19898 5071 5343 19899 5073 5343 19900 5072 5343 19901 5073 5344 19902 5075 5344 19903 5074 5344 19904 5075 5345 19905 5077 5345 19906 5076 5345 19907 5077 2538 19908 5079 2538 19909 5078 2538 19910 5079 5346 19911 5081 5346 19912 5080 5346 19913 5081 2540 19914 5083 2540 19915 5082 2540 19916 5083 5347 19917 5085 5347 19918 5084 5347 19919 5085 2542 19920 5087 2542 19921 5086 2542 19922 5087 5348 19923 5089 5348 19924 5088 5348 19925 5089 5349 19926 5091 5349 19927 5090 5349 19928 5091 5350 19929 5093 5350 19930 5092 5350 19931 5093 5351 19932 5095 5351 19933 5094 5351 19934 5095 5352 19935 5097 5352 19936 5096 5352 19937 5097 5353 19938 5099 5353 19939 5098 5353 19940 5099 5354 19941 5101 5354 19942 5100 5354 19943 5101 5355 19944 5103 5355 19945 5102 5355 19946 5103 2551 19947 5105 2551 19948 5104 2551 19949 5105 2552 19950 5107 2552 19951 5106 2552 19952 5107 2553 19953 5109 2553 19954 5108 2553 19955 5109 5356 19956 5111 5356 19957 5110 5356 19958 5111 5357 19959 5113 5357 19960 5112 5357 19961 5113 2556 19962 5115 2556 19963 5114 2556 19964 5115 5358 19965 5117 5358 19966 5116 5358 19967 5117 2558 19968 5119 2558 19969 5118 2558 19970 5119 2559 19971 5121 2559 19972 5120 2559 19973 5121 2560 19974 5123 2560 19975 5122 2560 19976 5123 2561 19977 5125 2561 19978 5124 2561 19979 5125 2562 19980 5127 2562 19981 5126 2562 19982 5127 5359 19983 5129 5359 19984 5128 5359 19985 5129 2564 19986 5131 2564 19987 5130 2564 19988 5131 2565 19989 5133 2565 19990 5132 2565 19991 5133 5360 19992 5135 5360 19993 5134 5360 19994 5135 5361 19995 5137 5361 19996 5136 5361 19997 5137 5362 19998 5139 5362 19999 5138 5362 20000 5139 5363 20001 5141 5363 20002 5140 5363 20003 5141 5364 20004 5143 5364 20005 5142 5364 20006 5143 2571 20007 5145 2571 20008 5144 2571 20009 5145 2572 20010 5147 2572 20011 5146 2572 20012 5147 5365 20013 5149 5365 20014 5148 5365 20015 5149 5366 20016 5151 5366 20017 5150 5366 20018 5151 5367 20019 5153 5367 20020 5152 5367 20021 5153 5368 20022 5155 5368 20023 5154 5368 20024 5155 5369 20025 5157 5369 20026 5156 5369 20027 5157 5370 20028 5159 5370 20029 5158 5370 20030 5159 5371 20031 5161 5371 20032 5160 5371 20033 5161 5372 20034 5163 5372 20035 5162 5372 20036 5163 2581 20037 5165 2581 20038 5164 2581 20039 5165 5373 20040 5167 5373 20041 5166 5373 20042 5167 5374 20043 5169 5374 20044 5168 5374 20045 5169 5375 20046 5171 5375 20047 5170 5375 20048 5171 5376 20049 5173 5376 20050 5172 5376 20051 5173 5377 20052 5175 5377 20053 5174 5377 20054 5175 5378 20055 5177 5378 20056 5176 5378 20057 5177 5379 20058 5179 5379 20059 5178 5379 20060 5179 2589 20061 5181 2589 20062 5180 2589 20063 5181 5380 20064 5183 5380 20065 5182 5380 20066 5183 2591 20067 5185 2591 20068 5184 2591 20069 5185 5381 20070 5187 5381 20071 5186 5381 20072 5187 5382 20073 5189 5382 20074 5188 5382 20075 5189 5383 20076 5191 5383 20077 5190 5383 20078 5191 5384 20079 5193 5384 20080 5192 5384 20081 5193 5385 20082 5195 5385 20083 5194 5385 20084 5195 2597 20085 5197 2597 20086 5196 2597 20087 5197 2598 20088 5199 2598 20089 5198 2598 20090 5199 5386 20091 5201 5386 20092 5200 5386 20093 5201 5387 20094 5203 5387 20095 5202 5387 20096 5203 5388 20097 5205 5388 20098 5204 5388 20099 5205 2602 20100 5207 2602 20101 5206 2602 20102 5207 5389 20103 5209 5389 20104 5208 5389 20105 5209 2604 20106 5211 2604 20107 5210 2604 20108 5211 5390 20109 5213 5390 20110 5212 5390 20111 5213 2606 20112 5215 2606 20113 5214 2606 20114 5215 5391 20115 5217 5391 20116 5216 5391 20117 5217 5392 20118 5219 5392 20119 5218 5392 20120 5219 5393 20121 5221 5393 20122 5220 5393 20123 5221 5394 20124 5223 5394 20125 5222 5394 20126 5223 5395 20127 5225 5395 20128 5224 5395 20129 5225 2612 20130 5227 2612 20131 5226 2612 20132 5227 5396 20133 5229 5396 20134 5228 5396 20135 5229 5397 20136 5231 5397 20137 5230 5397 20138 5231 2615 20139 5233 2615 20140 5232 2615 20141 5233 5398 20142 5235 5398 20143 5234 5398 20144 5235 2617 20145 5237 2617 20146 5236 2617 20147 5237 2618 20148 5239 2618 20149 5238 2618 20150 5239 2619 20151 5241 2619 20152 5240 2619 20153 5241 5399 20154 5243 5399 20155 5242 5399 20156 5243 5400 20157 5245 5400 20158 5244 5400 20159 5245 2622 20160 5247 2622 20161 5246 2622 20162 5247 2623 20163 5249 2623 20164 5248 2623 20165 5249 5401 20166 5251 5401 20167 5250 5401 20168 5251 5402 20169 5253 5402 20170 5252 5402 20171 5253 5403 20172 5255 5403 20173 5254 5403 20174 5255 5404 20175 5257 5404 20176 5256 5404 20177 5257 5405 20178 5259 5405 20179 5258 5405 20180 5259 5406 20181 5261 5406 20182 5260 5406 20183 5261 5407 20184 5263 5407 20185 5262 5407 20186 5263 5408 20187 5265 5408 20188 5264 5408 20189 5265 2632 20190 5267 2632 20191 5266 2632 20192 5267 5409 20193 5269 5409 20194 5268 5409 20195 5269 2634 20196 5271 2634 20197 5270 2634 20198 5271 2635 20199 5273 2635 20200 5272 2635 20201 5273 5410 20202 5275 5410 20203 5274 5410 20204 5275 2637 20205 5277 2637 20206 5276 2637 20207 5277 2638 20208 5279 2638 20209 5278 2638 20210 5279 5411 20211 5281 5411 20212 5280 5411 20213 5281 2640 20214 5283 2640 20215 5282 2640 20216 5283 5412 20217 5285 5412 20218 5284 5412 20219 5285 2642 20220 5287 2642 20221 5286 2642 20222 5287 2643 20223 5289 2643 20224 5288 2643 20225 5289 5413 20226 5291 5413 20227 5290 5413 20228 5291 2645 20229 5293 2645 20230 5292 2645 20231 5293 5414 20232 5295 5414 20233 5294 5414 20234 5295 5415 20235 5297 5415 20236 5296 5415 20237 5297 5416 20238 5299 5416 20239 5298 5416 20240 5299 2649 20241 5301 2649 20242 5300 2649 20243 5301 5417 20244 5303 5417 20245 5302 5417 20246 5303 5418 20247 5305 5418 20248 5304 5418 20249 5305 2652 20250 5307 2652 20251 5306 2652 20252 5307 2653 20253 5309 2653 20254 5308 2653 20255 5309 2654 20256 5311 2654 20257 5310 2654 20258 5311 5419 20259 5313 5419 20260 5312 5419 20261 5313 5420 20262 5315 5420 20263 5314 5420 20264 5315 5421 20265 5317 5421 20266 5316 5421 20267 5317 2658 20268 5319 2658 20269 5318 2658 20270 5319 2659 20271 5321 2659 20272 5320 2659 20273 5321 2660 20274 5323 2660 20275 5322 2660 20276 5323 5422 20277 5325 5422 20278 5324 5422 20279 5325 5423 20280 5327 5423 20281 5326 5423 20282 5327 5424 20283 5329 5424 20284 5328 5424 20285 5329 2664 20286 5331 2664 20287 5330 2664 20288 5331 2665 20289 5333 2665 20290 5332 2665 20291 5333 2666 20292 5335 2666 20293 5334 2666 20294 5335 2667 20295 5337 2667 20296 5336 2667 20297 5337 2668 20298 5339 2668 20299 5338 2668 20300 5339 5425 20301 5341 5425 20302 5340 5425 20303 5341 2670 20304 5343 2670 20305 5342 2670 20306 5343 5426 20307 5345 5426 20308 5344 5426 20309 5345 5427 20310 5347 5427 20311 5346 5427 20312 5347 2673 20313 5349 2673 20314 5348 2673 20315 5349 2674 20316 5351 2674 20317 5350 2674 20318 5351 2675 20319 5353 2675 20320 5352 2675 20321 5353 2676 20322 5355 2676 20323 5354 2676 20324 5355 2677 20325 5357 2677 20326 5356 2677 20327 5357 5428 20328 5359 5428 20329 5358 5428 20330 5359 2679 20331 5361 2679 20332 5360 2679 20333 5361 5429 20334 5363 5429 20335 5362 5429 20336 5363 5430 20337 5365 5430 20338 5364 5430 20339 5365 2682 20340 5367 2682 20341 5366 2682 20342 5367 5431 20343 5369 5431 20344 5368 5431 20345 5369 5432 20346 5371 5432 20347 5370 5432 20348 5371 2685 20349 5373 2685 20350 5372 2685 20351 5373 2686 20352 5375 2686 20353 5374 2686 20354 5375 2687 20355 5377 2687 20356 5376 2687 20357 5377 2688 20358 5379 2688 20359 5378 2688 20360 5379 5433 20361 5381 5433 20362 5380 5433 20363 5381 2690 20364 5383 2690 20365 5382 2690 20366 5383 2691 20367 5385 2691 20368 5384 2691 20369 5385 2692 20370 5387 2692 20371 5386 2692 20372 5387 2693 20373 5389 2693 20374 5388 2693 20375 5389 2694 20376 5391 2694 20377 5390 2694 20378 5391 5434 20379 5393 5434 20380 5392 5434 20381 5393 2696 20382 5395 2696 20383 5394 2696 20384 5395 2697 20385 5397 2697 20386 5396 2697 20387 5397 2698 20388 5399 2698 20389 5398 2698 20390 5399 5435 20391 5401 5435 20392 5400 5435 20393 5401 5436 20394 5403 5436 20395 5402 5436 20396 5403 2701 20397 5405 2701 20398 5404 2701 20399 5405 2702 20400 5407 2702 20401 5406 2702 20402 5407 2703 20403 5409 2703 20404 5408 2703 20405 5409 2704 20406 5411 2704 20407 5410 2704 20408 5411 2705 20409 5413 2705 20410 5412 2705 20411 5413 5437 20412 5415 5437 20413 5414 5437 20414 5415 2707 20415 5417 2707 20416 5416 2707 20417 5417 2708 20418 5419 2708 20419 5418 2708 20420 5419 5438 20421 5421 5438 20422 5420 5438 20423 5421 5439 20424 5423 5439 20425 5422 5439 20426 5423 2711 20427 5425 2711 20428 5424 2711 20429 5425 2712 20430 5427 2712 20431 5426 2712 20432 5427 2713 20433 5429 2713 20434 5428 2713 20435 5429 5440 20436 5431 5440 20437 5430 5440 20438 5431 5441 20439 5433 5441 20440 5432 5441 20441 5433 5442 20442 5435 5442 20443 5434 5442 20444 5435 2717 20445 5437 2717 20446 5436 2717 20447 5437 5443 20448 5439 5443 20449 5438 5443 20450 5439 2719 20451 5441 2719 20452 5440 2719 20453 5441 2720 20454 5443 2720 20455 5442 2720 20456 5443 2721 20457 5445 2721 20458 5444 2721 20459 5445 2722 20460 5447 2722 20461 5446 2722 20462 5447 2723 20463 5449 2723 20464 5448 2723 20465 5449 5444 20466 5451 5444 20467 5450 5444 20468 5451 2725 20469 5453 2725 20470 5452 2725 20471 5453 2726 20472 5455 2726 20473 5454 2726 20474 5455 2727 20475 5457 2727 20476 5456 2727 20477 5457 2728 20478 5459 2728 20479 5458 2728 20480 5459 2729 20481 5461 2729 20482 5460 2729 20483 5461 2730 20484 5463 2730 20485 5462 2730 20486 5463 5445 20487 5465 5445 20488 5464 5445 20489 5465 5446 20490 5467 5446 20491 5466 5446 20492 5467 5447 20493 5469 5447 20494 5468 5447 20495 5469 5448 20496 5471 5448 20497 5470 5448 20498 5471 2735 20499 5473 2735 20500 5472 2735 20501 5473 2736 20502 5475 2736 20503 5474 2736 20504 5475 2737 20505 5477 2737 20506 5476 2737 20507 5477 5449 20508 5479 5449 20509 5478 5449 20510 5479 5450 20511 5481 5450 20512 5480 5450 20513 5481 2740 20514 5483 2740 20515 5482 2740 20516 5483 2741 20517 5485 2741 20518 5484 2741 20519 5485 5451 20520 5487 5451 20521 5486 5451 20522 5487 5452 20523 5489 5452 20524 5488 5452 20525 5489 2744 20526 5491 2744 20527 5490 2744 20528 5491 2745 20529 5493 2745 20530 5492 2745 20531 5493 5453 20532 5495 5453 20533 5494 5453 20534 5495 2747 20535 5497 2747 20536 5496 2747 20537 5497 5454 20538 5499 5454 20539 5498 5454 20540 5499 5455 20541 5501 5455 20542 5500 5455 20543 5501 2750 20544 5503 2750 20545 5502 2750 20546 5503 5456 20547 5505 5456 20548 5504 5456 20549 5505 5457 20550 5507 5457 20551 5506 5457 20552 5507 5458 20553 5509 5458 20554 5508 5458 20555 5509 5459 20556 5511 5459 20557 5510 5459 20558 5511 2755 20559 5513 2755 20560 5512 2755 20561 5513 5460 20562 5515 5460 20563 5514 5460 20564 5515 2757 20565 5517 2757 20566 5516 2757 20567 5517 5461 20568 5519 5461 20569 5518 5461 20570 5519 2759 20571 5521 2759 20572 5520 2759 20573 5521 2760 20574 5523 2760 20575 5522 2760 20576 5523 2761 20577 5525 2761 20578 5524 2761 20579 5525 5462 20580 5527 5462 20581 5526 5462 20582 5527 2763 20583 5529 2763 20584 5528 2763 20585 5529 2764 20586 5531 2764 20587 5530 2764 20588 5531 5463 20589 5533 5463 20590 5532 5463 20591 5533 2766 20592 5535 2766 20593 5534 2766 20594 5535 5464 20595 5537 5464 20596 5536 5464 20597 5537 2768 20598 5539 2768 20599 5538 2768 20600 5539 2769 20601 5541 2769 20602 5540 2769 20603 5541 5465 20604 5543 5465 20605 5542 5465 20606 5543 5466 20607 5545 5466 20608 5544 5466 20609 5545 2772 20610 5547 2772 20611 5546 2772 20612 5547 5467 20613 5549 5467 20614 5548 5467 20615 5549 2774 20616 5551 2774 20617 5550 2774 20618 5551 2775 20619 5553 2775 20620 5552 2775 20621 5553 2776 20622 5555 2776 20623 5554 2776 20624 5555 5468 20625 5557 5468 20626 5556 5468 20627 5557 5469 20628 5559 5469 20629 5558 5469 20630 5559 2779 20631 5561 2779 20632 5560 2779 20633 5561 2780 20634 5563 2780 20635 5562 2780 20636 5563 5470 20637 5565 5470 20638 5564 5470 20639 5565 5471 20640 5567 5471 20641 5566 5471 20642 5567 2783 20643 5569 2783 20644 5568 2783 20645 5569 5472 20646 5571 5472 20647 5570 5472 20648 5571 2785 20649 5573 2785 20650 5572 2785 20651 5573 2786 20652 5575 2786 20653 5574 2786 20654 5575 5473 20655 5577 5473 20656 5576 5473 20657 5577 5474 20658 5579 5474 20659 5578 5474 20660 5579 2789 20661 5581 2789 20662 5580 2789 20663 5581 5475 20664 5583 5475 20665 5582 5475 20666 5583 5476 20667 5585 5476 20668 5584 5476 20669 5585 2792 20670 5587 2792 20671 5586 2792 20672 5587 5477 20673 5589 5477 20674 5588 5477 20675 5589 2794 20676 5591 2794 20677 5590 2794 20678 5591 5478 20679 5593 5478 20680 5592 5478 20681 5593 5479 20682 5595 5479 20683 5594 5479 20684 5595 2797 20685 5597 2797 20686 5596 2797 20687 5597 5480 20688 5599 5480 20689 5598 5480 20690 5599 5481 20691 5601 5481 20692 5600 5481 20693 5601 2800 20694 5603 2800 20695 5602 2800 20696 5603 5482 20697 5605 5482 20698 5604 5482 20699 5605 5483 20700 5607 5483 20701 5606 5483 20702 5607 5484 20703 5609 5484 20704 5608 5484 20705 5609 2804 20706 5611 2804 20707 5610 2804 20708 5611 2805 20709 5613 2805 20710 5612 2805 20711 5613 5485 20712 5615 5485 20713 5614 5485 20714 5615 2807 20715 5617 2807 20716 5616 2807 20717 5617 5486 20718 5619 5486 20719 5618 5486 20720 5619 5487 20721 5621 5487 20722 5620 5487 20723 5621 5488 20724 5623 5488 20725 5622 5488 20726 5623 5489 20727 5625 5489 20728 5624 5489 20729 5625 2812 20730 5627 2812 20731 5626 2812 20732 5627 2813 20733 5629 2813 20734 5628 2813 20735 5629 5490 20736 5631 5490 20737 5630 5490 20738 5631 5491 20739 5633 5491 20740 5632 5491 20741 5633 5492 20742 5635 5492 20743 5634 5492 20744 5635 2817 20745 5637 2817 20746 5636 2817 20747 5637 5493 20748 5639 5493 20749 5638 5493 20750 5639 5494 20751 5641 5494 20752 5640 5494 20753 5641 5495 20754 5643 5495 20755 5642 5495 20756 5643 5496 20757 5645 5496 20758 5644 5496 20759 5645 5497 20760 5647 5497 20761 5646 5497 20762 5647 5498 20763 5649 5498 20764 5648 5498 20765 5649 2824 20766 5651 2824 20767 5650 2824 20768 5651 5499 20769 5653 5499 20770 5652 5499 20771 5653 2826 20772 5655 2826 20773 5654 2826 20774 5655 2827 20775 5657 2827 20776 5656 2827 20777 5657 5500 20778 5659 5500 20779 5658 5500 20780 5659 5501 20781 5661 5501 20782 5660 5501 20783 5661 5502 20784 5663 5502 20785 5662 5502 20786 5663 5503 20787 5665 5503 20788 5664 5503 20789 5665 2832 20790 5667 2832 20791 5666 2832 20792 5667 2833 20793 5669 2833 20794 5668 2833 20795 5669 2834 20796 5671 2834 20797 5670 2834 20798 5671 2835 20799 5673 2835 20800 5672 2835 20801 5673 2836 20802 5675 2836 20803 5674 2836 20804 5675 5504 20805 5677 5504 20806 5676 5504 20807 5677 5505 20808 5679 5505 20809 5678 5505 20810 5679 5506 20811 5681 5506 20812 5680 5506 20813 5681 2840 20814 5683 2840 20815 5682 2840 20816 5683 2841 20817 5685 2841 20818 5684 2841 20819 5685 2842 20820 5687 2842 20821 5686 2842 20822 5687 5507 20823 5689 5507 20824 5688 5507 20825 5689 2844 20826 5691 2844 20827 5690 2844 20828 5691 5508 20829 5693 5508 20830 5692 5508 20831 5693 2846 20832 5695 2846 20833 5694 2846 20834 5695 5509 20835 5697 5509 20836 5696 5509 20837 5697 2848 20838 5699 2848 20839 5698 2848 20840 5699 2849 20841 5701 2849 20842 5700 2849 20843 5701 5510 20844 5703 5510 20845 5702 5510 20846 5703 2851 20847 5705 2851 20848 5704 2851 20849 5705 5511 20850 5707 5511 20851 5706 5511 20852 5707 5512 20853 5709 5512 20854 5708 5512 20855 5709 2854 20856 5711 2854 20857 5710 2854 20858 5711 5513 20859 5713 5513 20860 5712 5513 20861 5713 2856 20862 5715 2856 20863 5714 2856 20864 5715 2857 20865 5717 2857 20866 5716 2857 20867 5717 5514 20868 5719 5514 20869 5718 5514 20870 5719 5515 20871 5721 5515 20872 5720 5515 20873 5721 2860 20874 5723 2860 20875 5722 2860 20876 5723 5516 20877 5725 5516 20878 5724 5516 20879 5725 5517 20880 5727 5517 20881 5726 5517 20882 5727 5518 20883 5729 5518 20884 5728 5518 20885 5729 2864 20886 5731 2864 20887 5730 2864 20888 5731 5519 20889 5733 5519 20890 5732 5519 20891 5733 5520 20892 5735 5520 20893 5734 5520 20894 5735 2867 20895 5737 2867 20896 5736 2867 20897 5737 2868 20898 5739 2868 20899 5738 2868 20900 5739 2869 20901 5741 2869 20902 5740 2869 20903 5741 5521 20904 5743 5521 20905 5742 5521 20906 5743 5522 20907 5745 5522 20908 5744 5522 20909 5745 2872 20910 5747 2872 20911 5746 2872 20912 5747 2873 20913 5749 2873 20914 5748 2873 20915 5749 2874 20916 5751 2874 20917 5750 2874 20918 5751 5523 20919 5753 5523 20920 5752 5523 20921 5753 2876 20922 5755 2876 20923 5754 2876 20924 5755 2877 20925 5757 2877 20926 5756 2877 20927 5757 5524 20928 5759 5524 20929 5758 5524 20930 5759 2879 20931 5761 2879 20932 5760 2879 20933 5761 2880 20934 5763 2880 20935 5762 2880 20936 5763 2881 20937 5765 2881 20938 5764 2881 20939 5765 2882 20940 5767 2882 20941 5766 2882 20942 5767 2883 20943 5769 2883 20944 5768 2883 20945 5769 5525 20946 5771 5525 20947 5770 5525 20948 5771 5526 20949 5773 5526 20950 5772 5526 20951 5773 2886 20952 5775 2886 20953 5774 2886 20954 5775 5527 20955 5777 5527 20956 5776 5527 20957 5777 5528 20958 5779 5528 20959 5778 5528 20960 5779 5529 20961 5781 5529 20962 5780 5529 20963 5781 5530 20964 5783 5530 20965 5782 5530 20966 5783 2891 20967 5785 2891 20968 5784 2891 20969 5785 5531 20970 5787 5531 20971 5786 5531 20972 5787 5532 20973 5789 5532 20974 5788 5532 20975 5789 5533 20976 5791 5533 20977 5790 5533 20978 5791 5534 20979 5793 5534 20980 5792 5534 20981 5793 5535 20982 5795 5535 20983 5794 5535 20984 5795 5536 20985 5797 5536 20986 5796 5536 20987 5797 5537 20988 5799 5537 20989 5798 5537 20990 5799 5538 20991 5801 5538 20992 5800 5538 20993 5801 5539 20994 5803 5539 20995 5802 5539 20996 5803 2901 20997 5805 2901 20998 5804 2901 20999 5805 5540 21000 5807 5540 21001 5806 5540 21002 5807 2903 21003 5809 2903 21004 5808 2903 21005 5809 2904 21006 5811 2904 21007 5810 2904 21008 5811 2905 21009 5813 2905 21010 5812 2905 21011 5813 2906 21012 5815 2906 21013 5814 2906 21014 5815 5541 21015 5817 5541 21016 5816 5541 21017 5817 2908 21018 5819 2908 21019 5818 2908 21020 5819 5542 21021 5821 5542 21022 5820 5542 21023 5821 2910 21024 5823 2910 21025 5822 2910 21026 5823 5543 21027 5825 5543 21028 5824 5543 21029 5825 2912 21030 5827 2912 21031 5826 2912 21032 5827 2913 21033 5829 2913 21034 5828 2913 21035 5829 5544 21036 5831 5544 21037 5830 5544 21038 5831 2915 21039 5833 2915 21040 5832 2915 21041 5833 2916 21042 5835 2916 21043 5834 2916 21044 5835 5545 21045 5837 5545 21046 5836 5545 21047 5837 2918 21048 5839 2918 21049 5838 2918 21050 5839 2919 21051 5841 2919 21052 5840 2919 21053 5841 5546 21054 5843 5546 21055 5842 5546 21056 5843 5547 21057 5845 5547 21058 5844 5547 21059 5845 2922 21060 5847 2922 21061 5846 2922 21062 5847 2923 21063 5849 2923 21064 5848 2923 21065 5849 2924 21066 5851 2924 21067 5850 2924 21068 5851 5548 21069 5853 5548 21070 5852 5548 21071 5853 2926 21072 5855 2926 21073 5854 2926 21074 5855 2927 21075 5857 2927 21076 5856 2927 21077 5857 2928 21078 5859 2928 21079 5858 2928 21080 5859 5549 21081 5861 5549 21082 5860 5549 21083 5861 2930 21084 5863 2930 21085 5862 2930 21086 5863 2931 21087 5865 2931 21088 5864 2931 21089 5865 5550 21090 5867 5550 21091 5866 5550 21092 5867 5551 21093 5869 5551 21094 5868 5551 21095 5869 2934 21096 5871 2934 21097 5870 2934 21098 5871 2935 21099 5873 2935 21100 5872 2935 21101 5873 5552 21102 5875 5552 21103 5874 5552 21104 5875 2937 21105 5877 2937 21106 5876 2937 21107 5877 2938 21108 5879 2938 21109 5878 2938 21110 5879 5553 21111 5881 5553 21112 5880 5553 21113 5881 2940 21114 5883 2940 21115 5882 2940 21116 5883 5554 21117 5885 5554 21118 5884 5554 21119 5885 5555 21120 5887 5555 21121 5886 5555 21122 5887 2943 21123 5889 2943 21124 5888 2943 21125 5889 2944 21126 5891 2944 21127 5890 2944 21128 5891 5556 21129 5893 5556 21130 5892 5556 21131 5893 2946 21132 5895 2946 21133 5894 2946 21134 5895 5557 21135 5897 5557 21136 5896 5557 21137 5897 2948 21138 5899 2948 21139 5898 2948 21140 5899 2949 21141 5901 2949 21142 5900 2949 21143 5901 5558 21144 5903 5558 21145 5902 5558 21146 5903 2951 21147 5905 2951 21148 5904 2951 21149 5905 5559 21150 5907 5559 21151 5906 5559 21152 5907 5560 21153 5909 5560 21154 5908 5560 21155 5909 2954 21156 5911 2954 21157 5910 2954 21158 5911 2955 21159 5913 2955 21160 5912 2955 21161 5913 2956 21162 5915 2956 21163 5914 2956 21164 5915 5561 21165 5917 5561 21166 5916 5561 21167 5917 5562 21168 5919 5562 21169 5918 5562 21170 5919 5563 21171 5921 5563 21172 5920 5563 21173 5921 2960 21174 5923 2960 21175 5922 2960 21176 5923 2961 21177 5925 2961 21178 5924 2961 21179 5925 2962 21180 5927 2962 21181 5926 2962 21182 5927 2963 21183 5929 2963 21184 5928 2963 21185 5929 5564 21186 5931 5564 21187 5930 5564 21188 5931 5565 21189 5933 5565 21190 5932 5565 21191 5933 5566 21192 5935 5566 21193 5934 5566 21194 5935 2967 21195 5937 2967 21196 5936 2967 21197 5937 5567 21198 5939 5567 21199 5938 5567 21200 5939 2969 21201 5941 2969 21202 5940 2969 21203 5941 5568 21204 5943 5568 21205 5942 5568 21206 5943 2971 21207 5945 2971 21208 5944 2971 21209 5945 5569 21210 5947 5569 21211 5946 5569 21212 5947 5570 21213 5949 5570 21214 5948 5570 21215 5949 5571 21216 5951 5571 21217 5950 5571 21218 5951 2975 21219 5953 2975 21220 5952 2975 21221 5953 5572 21222 5955 5572 21223 5954 5572 21224 5955 5573 21225 5957 5573 21226 5956 5573 21227 5957 5574 21228 5959 5574 21229 5958 5574 21230 5959 5575 21231 5961 5575 21232 5960 5575 21233 5961 5576 21234 5963 5576 21235 5962 5576 21236 5963 5577 21237 5965 5577 21238 5964 5577 21239 5965 2982 21240 5967 2982 21241 5966 2982 21242 5967 2983 21243 5969 2983 21244 5968 2983 21245 5969 2984 21246 5971 2984 21247 5970 2984 21248 5971 2985 21249 5973 2985 21250 5972 2985 21251 5973 2986 21252 5975 2986 21253 5974 2986 21254 5975 5578 21255 5977 5578 21256 5976 5578 21257 5977 5579 21258 5979 5579 21259 5978 5579 21260 5979 2989 21261 5981 2989 21262 5980 2989 21263 5981 2990 21264 5983 2990 21265 5982 2990 21266 5983 2991 21267 5985 2991 21268 5984 2991 21269 5985 2992 21270 5987 2992 21271 5986 2992 21272 5987 2993 21273 5989 2993 21274 5988 2993 21275 5989 2994 21276 5991 2994 21277 5990 2994 21278 5991 5580 21279 5993 5580 21280 5992 5580 21281 5993 2996 21282 5995 2996 21283 5994 2996 21284 5995 5581 21285 5997 5581 21286 5996 5581 21287 5997 2998 21288 5999 2998 21289 5998 2998 21290 5999 2999 21291 6001 2999 21292 6000 2999 21293 6001 5582 21294 6003 5582 21295 6002 5582 21296 6003 3001 21297 6005 3001 21298 6004 3001 21299 6005 3002 21300 6007 3002 21301 6006 3002 21302 6007 3003 21303 6009 3003 21304 6008 3003 21305 6009 3004 21306 6011 3004 21307 6010 3004 21308 6011 3005 21309 6013 3005 21310 6012 3005 21311 6013 3006 21312 6015 3006 21313 6014 3006 21314 6015 3007 21315 6017 3007 21316 6016 3007 21317 6017 5583 21318 6019 5583 21319 6018 5583 21320 6019 3009 21321 6021 3009 21322 6020 3009 21323 6021 3010 21324 6023 3010 21325 6022 3010 21326 6023 5584 21327 6025 5584 21328 6024 5584 21329 6025 3012 21330 6027 3012 21331 6026 3012 21332 6027 3013 21333 6029 3013 21334 6028 3013 21335 6029 5585 21336 6031 5585 21337 6030 5585 21338 6031 3015 21339 6033 3015 21340 6032 3015 21341 6033 3016 21342 6035 3016 21343 6034 3016 21344 6035 5586 21345 6037 5586 21346 6036 5586 21347 6037 3018 21348 6039 3018 21349 6038 3018 21350 6039 3019 21351 6041 3019 21352 6040 3019 21353 6041 5587 21354 6043 5587 21355 6042 5587 21356 6043 3021 21357 6045 3021 21358 6044 3021 21359 6045 3022 21360 6047 3022 21361 6046 3022 21362 6047 5588 21363 6049 5588 21364 6048 5588 21365 6049 3024 21366 6051 3024 21367 6050 3024 21368 6051 3025 21369 6053 3025 21370 6052 3025 21371 6053 5589 21372 6055 5589 21373 6054 5589 21374 6055 5590 21375 6057 5590 21376 6056 5590 21377 6057 3028 21378 6059 3028 21379 6058 3028 21380 6059 5591 21381 6061 5591 21382 6060 5591 21383 6061 5592 21384 6063 5592 21385 6062 5592 21386 6063 3031 21387 6065 3031 21388 6064 3031 21389 6065 5593 21390 6067 5593 21391 6066 5593 21392 6067 5594 21393 6069 5594 21394 6068 5594 21395 6069 5595 21396 6071 5595 21397 6070 5595 21398 6071 3035 21399 6073 3035 21400 6072 3035 21401 6073 5596 21402 6075 5596 21403 6074 5596 21404 6075 3037 21405 6077 3037 21406 6076 3037 21407 6077 3038 21408 6079 3038 21409 6078 3038 21410 6079 3039 21411 6081 3039 21412 6080 3039 21413 6081 5597 21414 6083 5597 21415 6082 5597 21416 6083 3041 21417 6085 3041 21418 6084 3041 21419 6085 3042 21420 6087 3042 21421 6086 3042 21422 6087 5598 21423 6089 5598 21424 6088 5598 21425 6089 5599 21426 6091 5599 21427 6090 5599 21428 6091 3045 21429 6093 3045 21430 6092 3045 21431 6093 5600 21432 6095 5600 21433 6094 5600 21434 6095 3047 21435 6097 3047 21436 6096 3047 21437 6097 3048 21438 6099 3048 21439 6098 3048 21440 6099 3049 21441 6101 3049 21442 6100 3049 21443 6101 5601 21444 6103 5601 21445 6102 5601 21446 6103 5602 21447 6105 5602 21448 6104 5602 21449 6105 3052 21450 6107 3052 21451 6106 3052 21452 6107 3053 21453 6109 3053 21454 6108 3053 21455 6109 5603 21456 6111 5603 21457 6110 5603 21458 6111 5604 21459 6113 5604 21460 6112 5604 21461 6113 3056 21462 6115 3056 21463 6114 3056 21464 6115 3057 21465 6117 3057 21466 6116 3057 21467 6117 5605 21468 6119 5605 21469 6118 5605 21470 6119 3059 21471 6121 3059 21472 6120 3059 21473 6121 3060 21474 6123 3060 21475 6122 3060 21476 6123 3061 21477 6125 3061 21478 6124 3061 21479 6125 5606 21480 6127 5606 21481 6126 5606 21482 6127 3063 21483 6129 3063 21484 6128 3063 21485 6129 3064 21486 6131 3064 21487 6130 3064 21488 6131 3065 21489 6133 3065 21490 6132 3065 21491 6133 3066 21492 6135 3066 21493 6134 3066 21494 6135 5607 21495 6137 5607 21496 6136 5607 21497 6137 3068 21498 6139 3068 21499 6138 3068 21500 6139 5608 21501 6141 5608 21502 6140 5608 21503 6141 5609 21504 6143 5609 21505 6142 5609 21506 6143 3071 21507 6145 3071 21508 6144 3071 21509 6145 3072 21510 6147 3072 21511 6146 3072 21512 6147 5610 21513 6149 5610 21514 6148 5610 21515 6149 5611 21516 6151 5611 21517 6150 5611 21518 6151 3075 21519 6153 3075 21520 6152 3075 21521 6153 5612 21522 6155 5612 21523 6154 5612 21524 6155 3077 21525 6157 3077 21526 6156 3077 21527 6157 3078 21528 6159 3078 21529 6158 3078 21530 6159 3079 21531 6161 3079 21532 6160 3079 21533 6161 3080 21534 6163 3080 21535 6162 3080 21536 6163 5613 21537 6165 5613 21538 6164 5613 21539 6165 3082 21540 6167 3082 21541 6166 3082 21542 6167 3083 21543 6169 3083 21544 6168 3083 21545 6169 3084 21546 6171 3084 21547 6170 3084 21548 6171 5614 21549 6173 5614 21550 6172 5614 21551 6173 3086 21552 6175 3086 21553 6174 3086 21554 6175 3087 21555 6177 3087 21556 6176 3087 21557 6177 5615 21558 6179 5615 21559 6178 5615 21560 6179 5616 21561 6181 5616 21562 6180 5616 21563 6181 3090 21564 6183 3090 21565 6182 3090 21566 6183 3091 21567 6185 3091 21568 6184 3091 21569 6185 5617 21570 6187 5617 21571 6186 5617 21572 6187 5618 21573 6189 5618 21574 6188 5618 21575 6189 3094 21576 6191 3094 21577 6190 3094 21578 6191 3095 21579 6193 3095 21580 6192 3095 21581 6193 3096 21582 6195 3096 21583 6194 3096 21584 6195 5619 21585 6197 5619 21586 6196 5619 21587 6197 3098 21588 6199 3098 21589 6198 3098 21590 6199 5620 21591 6201 5620 21592 6200 5620 21593 6201 5621 21594 6203 5621 21595 6202 5621 21596 6203 3101 21597 6205 3101 21598 6204 3101 21599 6205 3102 21600 6207 3102 21601 6206 3102 21602 6207 5622 21603 6209 5622 21604 6208 5622 21605 6209 3104 21606 6211 3104 21607 6210 3104 21608 6211 3105 21609 6213 3105 21610 6212 3105 21611 6213 3106 21612 6215 3106 21613 6214 3106 21614 6215 5623 21615 6217 5623 21616 6216 5623 21617 6217 3108 21618 6219 3108 21619 6218 3108 21620 6219 5624 21621 6221 5624 21622 6220 5624 21623 6221 5625 21624 6223 5625 21625 6222 5625 21626 6223 5626 21627 6225 5626 21628 6224 5626 21629 6225 3112 21630 6227 3112 21631 6226 3112 21632 6227 5627 21633 6229 5627 21634 6228 5627 21635 6229 5628 21636 6231 5628 21637 6230 5628 21638 6231 3115 21639 6233 3115 21640 6232 3115 21641 6233 5629 21642 6235 5629 21643 6234 5629 21644 6235 5630 21645 6237 5630 21646 6236 5630 21647 6237 3118 21648 6239 3118 21649 6238 3118 21650 6239 3119 21651 6241 3119 21652 6240 3119 21653 6241 5631 21654 6243 5631 21655 6242 5631 21656 6243 3121 21657 6245 3121 21658 6244 3121 21659 6245 3122 21660 6247 3122 21661 6246 3122 21662 6247 5632 21663 6249 5632 21664 6248 5632 21665 6249 3124 21666 6251 3124 21667 6250 3124 21668 6251 3125 21669 6253 3125 21670 6252 3125 21671 6253 5633 21672 6255 5633 21673 6254 5633 21674 6255 3127 21675 6257 3127 21676 6256 3127 21677 6257 3128 21678 6259 3128 21679 6258 3128 21680 6259 5634 21681 6261 5634 21682 6260 5634 21683 6261 3130 21684 6263 3130 21685 6262 3130 21686 6263 3131 21687 6265 3131 21688 6264 3131 21689 6265 5635 21690 6267 5635 21691 6266 5635 21692 6267 3133 21693 6269 3133 21694 6268 3133 21695 6269 3134 21696 6271 3134 21697 6270 3134 21698 6271 5636 21699 6273 5636 21700 6272 5636 21701 6273 3136 21702 6275 3136 21703 6274 3136 21704 6275 3137 21705 6277 3137 21706 6276 3137 21707 6277 3138 21708 6279 3138 21709 6278 3138 21710 6279 3139 21711 6281 3139 21712 6280 3139 21713 6281 3140 21714 6283 3140 21715 6282 3140 21716 6283 3141 21717 6285 3141 21718 6284 3141 21719 6285 3142 21720 6287 3142 21721 6286 3142 21722 6287 5637 21723 6289 5637 21724 6288 5637 21725 6289 3144 21726 6291 3144 21727 6290 3144 21728 6291 3145 21729 6293 3145 21730 6292 3145 21731 6293 5638 21732 6295 5638 21733 6294 5638 21734 6295 3147 21735 6297 3147 21736 6296 3147 21737 6297 5639 21738 6299 5639 21739 6298 5639 21740 6299 3149 21741 6301 3149 21742 6300 3149 21743 6301 3150 21744 6303 3150 21745 6302 3150 21746 6303 3151 21747 6305 3151 21748 6304 3151 21749 6305 3152 21750 6307 3152 21751 6306 3152 21752 6307 3153 21753 6309 3153 21754 6308 3153 21755 6309 3154 21756 6311 3154 21757 6310 3154 21758 6311 5640 21759 6313 5640 21760 6312 5640 21761 6313 5641 21762 6315 5641 21763 6314 5641 21764 6315 3157 21765 6317 3157 21766 6316 3157 21767 6317 3158 21768 6319 3158 21769 6318 3158 21770 6319 3159 21771 6321 3159 21772 6320 3159 21773 6321 3160 21774 6323 3160 21775 6322 3160 21776 6323 3161 21777 6325 3161 21778 6324 3161 21779 6325 5642 21780 6327 5642 21781 6326 5642 21782 6327 5643 21783 6329 5643 21784 6328 5643 21785 6329 5644 21786 6331 5644 21787 6330 5644 21788 6331 5645 21789 6333 5645 21790 6332 5645 21791 6333 5646 21792 6335 5646 21793 6334 5646 21794 6335 5647 21795 6337 5647 21796 6336 5647 21797 6337 3168 21798 6339 3168 21799 6338 3168 21800 6339 5648 21801 6341 5648 21802 6340 5648 21803 6341 5649 21804 6343 5649 21805 6342 5649 21806 6343 5650 21807 6345 5650 21808 6344 5650 21809 6345 3172 21810 6347 3172 21811 6346 3172 21812 6347 5651 21813 6349 5651 21814 6348 5651 21815 6349 3174 21816 6351 3174 21817 6350 3174 21818 6351 5652 21819 6353 5652 21820 6352 5652 21821 6353 3176 21822 6355 3176 21823 6354 3176 21824 6355 5653 21825 6357 5653 21826 6356 5653 21827 6357 5654 21828 6359 5654 21829 6358 5654 21830 6359 5655 21831 6361 5655 21832 6360 5655 21833 6361 3180 21834 6363 3180 21835 6362 3180 21836 6363 3181 21837 6365 3181 21838 6364 3181 21839 6365 3182 21840 6367 3182 21841 6366 3182 21842 6367 3183 21843 6369 3183 21844 6368 3183 21845 6369 5656 21846 6371 5656 21847 6370 5656 21848 6371 5657 21849 6373 5657 21850 6372 5657 21851 6373 5658 21852 6375 5658 21853 6374 5658 21854 6375 3187 21855 6377 3187 21856 6376 3187 21857 6377 3188 21858 6379 3188 21859 6378 3188 21860 6379 3189 21861 6381 3189 21862 6380 3189 21863 6381 5659 21864 6383 5659 21865 6382 5659 21866 6383 5660 21867 6385 5660 21868 6384 5660 21869 6385 3192 21870 6387 3192 21871 6386 3192 21872 6387 5661 21873 6389 5661 21874 6388 5661 21875 6389 3194 21876 6391 3194 21877 6390 3194 21878 6391 3195 21879 6393 3195 21880 6392 3195 21881 6393 5662 21882 6395 5662 21883 6394 5662 21884 6395 3197 21885 6397 3197 21886 6396 3197 21887 6397 5663 21888 6399 5663 21889 6398 5663 21890 6399 3199 21891 6401 3199 21892 6400 3199 21893 6401 3200 21894 6403 3200 21895 6402 3200 21896 6403 5664 21897 6405 5664 21898 6404 5664 21899 6405 5665 21900 6407 5665 21901 6406 5665 21902 6407 3203 21903 6409 3203 21904 6408 3203 21905 6409 5666 21906 6411 5666 21907 6410 5666 21908 6411 3205 21909 6413 3205 21910 6412 3205 21911 6413 3206 21912 6415 3206 21913 6414 3206 21914 6415 5667 21915 6417 5667 21916 6416 5667 21917 6417 3208 21918 6419 3208 21919 6418 3208 21920 6419 3209 21921 6421 3209 21922 6420 3209 21923 6421 5668 21924 6423 5668 21925 6422 5668 21926 6423 5669 21927 6425 5669 21928 6424 5669 21929 6425 3212 21930 6427 3212 21931 6426 3212 21932 6427 3213 21933 6429 3213 21934 6428 3213 21935 6429 5670 21936 6431 5670 21937 6430 5670 21938 6431 3215 21939 6433 3215 21940 6432 3215 21941 6433 3216 21942 6435 3216 21943 6434 3216 21944 6435 3217 21945 6437 3217 21946 6436 3217 21947 6437 5671 21948 6439 5671 21949 6438 5671 21950 6439 3219 21951 6441 3219 21952 6440 3219 21953 6441 3220 21954 6443 3220 21955 6442 3220 21956 6443 3221 21957 6445 3221 21958 6444 3221 21959 6445 5672 21960 6447 5672 21961 6446 5672 21962 6447 5673 21963 6449 5673 21964 6448 5673 21965 6449 3224 21966 6451 3224 21967 6450 3224 21968 6451 3225 21969 6453 3225 21970 6452 3225 21971 6453 5674 21972 6455 5674 21973 6454 5674 21974 6455 3227 21975 6457 3227 21976 6456 3227 21977 6457 3228 21978 6459 3228 21979 6458 3228 21980 6459 5675 21981 6461 5675 21982 6460 5675 21983 6461 3230 21984 6463 3230 21985 6462 3230 21986 6463 3231 21987 6465 3231 21988 6464 3231 21989 6465 5676 21990 6467 5676 21991 6466 5676 21992 6467 3233 21993 6469 3233 21994 6468 3233 21995 6469 5677 21996 6471 5677 21997 6470 5677 21998 6471 3235 21999 6473 3235 22000 6472 3235 22001 6473 5678 22002 6475 5678 22003 6474 5678 22004 6475 3237 22005 6477 3237 22006 6476 3237 22007 6477 3238 22008 6479 3238 22009 6478 3238 22010 6479 3239 22011 6481 3239 22012 6480 3239 22013 6481 3240 22014 6483 3240 22015 6482 3240 22016 6483 5679 22017 6485 5679 22018 6484 5679 22019 6485 3242 22020 6487 3242 22021 6486 3242 22022 6487 5680 22023 6489 5680 22024 6488 5680 22025 6489 5681 22026 6491 5681 22027 6490 5681 22028 6491 5682 22029 6493 5682 22030 6492 5682 22031 6493 5683 22032 6495 5683 22033 6494 5683 22034 6495 5684 22035 6497 5684 22036 6496 5684 22037 6497 5685 22038 6499 5685 22039 6498 5685 22040 6499 5686 22041 6501 5686 22042 6500 5686 22043 6501 5687 22044 6503 5687 22045 6502 5687 22046 6503 5688 22047 6505 5688 22048 6504 5688 22049 6505 3252 22050 6507 3252 22051 6506 3252 22052 6507 5689 22053 6509 5689 22054 6508 5689 22055 6509 5690 22056 6511 5690 22057 6510 5690 22058 6511 5691 22059 6513 5691 22060 6512 5691 22061 6513 5692 22062 6515 5692 22063 6514 5692 22064 6515 3257 22065 6517 3257 22066 6516 3257 22067 6517 5693 22068 6519 5693 22069 6518 5693 22070 6519 5694 22071 6521 5694 22072 6520 5694 22073 6521 3260 22074 6523 3260 22075 6522 3260 22076 6523 3261 22077 6525 3261 22078 6524 3261 22079 6525 3262 22080 6527 3262 22081 6526 3262 22082 6527 3263 22083 6529 3263 22084 6528 3263 22085 6529 3264 22086 6531 3264 22087 6530 3264 22088 6531 5695 22089 6533 5695 22090 6532 5695 22091 6533 3266 22092 6535 3266 22093 6534 3266 22094 6535 3267 22095 6537 3267 22096 6536 3267 22097 6537 5696 22098 6539 5696 22099 6538 5696 22100 6539 3269 22101 6541 3269 22102 6540 3269 22103 6541 3270 22104 6543 3270 22105 6542 3270 22106 6543 3271 22107 6545 3271 22108 6544 3271 22109 6545 5697 22110 6547 5697 22111 6546 5697 22112 6547 5698 22113 6549 5698 22114 6548 5698 22115 6549 3274 22116 6551 3274 22117 6550 3274 22118 6551 3275 22119 6553 3275 22120 6552 3275 22121 6553 3276 22122 6555 3276 22123 6554 3276 22124 6555 5699 22125 6557 5699 22126 6556 5699 22127 6557 5700 22128 6559 5700 22129 6558 5700 22130 6559 3279 22131 6561 3279 22132 6560 3279 22133 6561 5701 22134 6563 5701 22135 6562 5701 22136 6563 5702 22137 6565 5702 22138 6564 5702 22139 6565 5703 22140 6567 5703 22141 6566 5703 22142 6567 3283 22143 6569 3283 22144 6568 3283 22145 6569 5704 22146 6571 5704 22147 6570 5704 22148 6571 5705 22149 6573 5705 22150 6572 5705 22151 6573 3286 22152 6575 3286 22153 6574 3286 22154 6575 3287 22155 6577 3287 22156 6576 3287 22157 6577 5706 22158 6579 5706 22159 6578 5706 22160 6579 3289 22161 6581 3289 22162 6580 3289 22163 6581 5707 22164 6583 5707 22165 6582 5707 22166 6583 5708 22167 6585 5708 22168 6584 5708 22169 6585 3292 22170 6587 3292 22171 6586 3292 22172 6587 5709 22173 6589 5709 22174 6588 5709 22175 6589 3294 22176 6591 3294 22177 6590 3294 22178 6591 3295 22179 6593 3295 22180 6592 3295 22181 6593 5710 22182 6595 5710 22183 6594 5710 22184 6595 3297 22185 6597 3297 22186 6596 3297 22187 6597 5711 22188 6599 5711 22189 6598 5711 22190 6599 3299 22191 6601 3299 22192 6600 3299 22193 6601 5712 22194 6603 5712 22195 6602 5712 22196 6603 3301 22197 6605 3301 22198 6604 3301 22199 6605 3302 22200 6607 3302 22201 6606 3302 22202 6607 3303 22203 6609 3303 22204 6608 3303 22205 6609 5713 22206 6611 5713 22207 6610 5713 22208 6611 5714 22209 6613 5714 22210 6612 5714 22211 6613 5715 22212 6615 5715 22213 6614 5715 22214 6615 3307 22215 6617 3307 22216 6616 3307 22217 6617 3308 22218 6619 3308 22219 6618 3308 22220 6619 3309 22221 6621 3309 22222 6620 3309 22223 6621 3310 22224 6623 3310 22225 6622 3310 22226 6623 3311 22227 6625 3311 22228 6624 3311 22229 6625 5716 22230 6627 5716 22231 6626 5716 22232 6627 5717 22233 6629 5717 22234 6628 5717 22235 6629 5718 22236 6631 5718 22237 6630 5718 22238 6631 5719 22239 6633 5719 22240 6632 5719 22241 6633 3316 22242 6635 3316 22243 6634 3316 22244 6635 3317 22245 6637 3317 22246 6636 3317 22247 6637 5720 22248 6639 5720 22249 6638 5720 22250 6639 3319 22251 6641 3319 22252 6640 3319 22253 6641 5721 22254 6643 5721 22255 6642 5721 22256 6643 5722 22257 6645 5722 22258 6644 5722 22259 6645 5723 22260 6647 5723 22261 6646 5723 22262 6647 5724 22263 6649 5724 22264 6648 5724 22265 6649 5725 22266 6651 5725 22267 6650 5725 22268 6651 5726 22269 6653 5726 22270 6652 5726 22271 6653 3326 22272 6655 3326 22273 6654 3326 22274 6655 5727 22275 6657 5727 22276 6656 5727 22277 6657 5728 22278 6659 5728 22279 6658 5728 22280 6659 5729 22281 6661 5729 22282 6660 5729 22283 6661 3330 22284 6663 3330 22285 6662 3330 22286 6663 3331 22287 6665 3331 22288 6664 3331 22289 6665 5730 22290 6667 5730 22291 6666 5730 22292 6667 5731 22293 6669 5731 22294 6668 5731 22295 6669 5732 22296 6671 5732 22297 6670 5732 22298 6671 5733 22299 6673 5733 22300 6672 5733 22301 6673 3336 22302 6675 3336 22303 6674 3336 22304 6675 5734 22305 6677 5734 22306 6676 5734 22307 6677 3338 22308 6679 3338 22309 6678 3338 22310 6679 3339 22311 6681 3339 22312 6680 3339 22313 6681 5735 22314 6683 5735 22315 6682 5735 22316 6683 5736 22317 6685 5736 22318 6684 5736 22319 6685 5737 22320 6687 5737 22321 6686 5737 22322 6687 3343 22323 6689 3343 22324 6688 3343 22325 6689 5738 22326 6691 5738 22327 6690 5738 22328 6691 5739 22329 6693 5739 22330 6692 5739 22331 6693 3346 22332 6695 3346 22333 6694 3346 22334 6695 5740 22335 6697 5740 22336 6696 5740 22337 6697 5741 22338 6699 5741 22339 6698 5741 22340 6699 3349 22341 6701 3349 22342 6700 3349 22343 6701 5742 22344 6703 5742 22345 6702 5742 22346 6703 3351 22347 6705 3351 22348 6704 3351 22349 6705 5743 22350 6707 5743 22351 6706 5743 22352 6707 5744 22353 6709 5744 22354 6708 5744 22355 6709 3354 22356 6711 3354 22357 6710 3354 22358 6711 5745 22359 6713 5745 22360 6712 5745 22361 6713 5746 22362 6715 5746 22363 6714 5746 22364 6715 3357 22365 6717 3357 22366 6716 3357 22367 6717 3358 22368 6719 3358 22369 6718 3358 22370 6719 5747 22371 6721 5747 22372 6720 5747 22373 6721 3360 22374 6723 3360 22375 6722 3360 22376 6723 5748 22377 6725 5748 22378 6724 5748 22379 6725 5749 22380 6727 5749 22381 6726 5749 22382 6727 3363 22383 6729 3363 22384 6728 3363 22385 6729 3364 22386 6731 3364 22387 6730 3364 22388 6731 5750 22389 6733 5750 22390 6732 5750 22391 6733 5751 22392 6735 5751 22393 6734 5751 22394 6735 3367 22395 6737 3367 22396 6736 3367 22397 6737 3368 22398 6739 3368 22399 6738 3368 22400 6739 3369 22401 6741 3369 22402 6740 3369 22403 6741 5752 22404 6743 5752 22405 6742 5752 22406 6743 3371 22407 6745 3371 22408 6744 3371 22409 6745 5753 22410 6747 5753 22411 6746 5753 22412 6747 5754 22413 6749 5754 22414 6748 5754 22415 6749 3374 22416 6751 3374 22417 6750 3374 22418 6751 3375 22419 6753 3375 22420 6752 3375 22421 6753 5755 22422 6755 5755 22423 6754 5755 22424 6755 3377 22425 6757 3377 22426 6756 3377 22427 6757 5756 22428 6759 5756 22429 6758 5756 22430 6759 3379 22431 6761 3379 22432 6760 3379 22433 6761 3380 22434 6763 3380 22435 6762 3380 22436 6763 5757 22437 6765 5757 22438 6764 5757 22439 6765 3382 22440 6767 3382 22441 6766 3382 22442 6767 3383 22443 6769 3383 22444 6768 3383 22445 6769 3384 22446 6771 3384 22447 6770 3384 22448 6771 5758 22449 6773 5758 22450 6772 5758 22451 6773 3386 22452 6775 3386 22453 6774 3386 22454 6775 5759 22455 6777 5759 22456 6776 5759 22457 6777 3388 22458 6779 3388 22459 6778 3388 22460 6779 5760 22461 6781 5760 22462 6780 5760 22463 6781 5761 22464 6783 5761 22465 6782 5761 22466 6783 5762 22467 6785 5762 22468 6784 5762 22469 6785 5763 22470 6787 5763 22471 6786 5763 22472 6787 3393 22473 6789 3393 22474 6788 3393 22475 6789 5764 22476 6791 5764 22477 6790 5764 22478 6791 5765 22479 6793 5765 22480 6792 5765 22481 6793 3396 22482 6795 3396 22483 6794 3396 22484 6795 5766 22485 6797 5766 22486 6796 5766 22487 6797 3398 22488 6799 3398 22489 6798 3398 22490 6799 3399 22491 6801 3399 22492 6800 3399 22493 6801 5767 22494 6803 5767 22495 6802 5767 22496 6803 5768 22497 6805 5768 22498 6804 5768 22499 6805 3402 22500 6807 3402 22501 6806 3402 22502 6807 3403 22503 6809 3403 22504 6808 3403 22505 6809 5769 22506 6811 5769 22507 6810 5769 22508 6811 5770 22509 6813 5770 22510 6812 5770 22511 6813 3406 22512 6815 3406 22513 6814 3406 22514 6815 3407 22515 6817 3407 22516 6816 3407 22517 6817 3408 22518 6819 3408 22519 6818 3408 22520 6819 5771 22521 6821 5771 22522 6820 5771 22523 6821 5772 22524 6823 5772 22525 6822 5772 22526 6823 5773 22527 6825 5773 22528 6824 5773 22529 6825 5774 22530 6827 5774 22531 6826 5774 22532 6827 3413 22533 6829 3413 22534 6828 3413 22535 6829 3414 22536 6831 3414 22537 6830 3414 22538 6831 3415 22539 6833 3415 22540 6832 3415 22541 6833 3416 22542 6835 3416 22543 6834 3416 22544 6835 3417 22545 6837 3417 22546 6836 3417 22547 6837 3418 22548 6839 3418 22549 6838 3418 22550 6839 5775 22551 6841 5775 22552 6840 5775 22553 6841 3420 22554 6843 3420 22555 6842 3420 22556 6843 3421 22557 6845 3421 22558 6844 3421 22559 6845 3422 22560 6847 3422 22561 6846 3422 22562 6847 3423 22563 6849 3423 22564 6848 3423 22565 6849 3424 22566 6851 3424 22567 6850 3424 22568 6851 5776 22569 6853 5776 22570 6852 5776 22571 6853 3426 22572 6855 3426 22573 6854 3426 22574 6855 5777 22575 6857 5777 22576 6856 5777 22577 6857 5778 22578 6859 5778 22579 6858 5778 22580 6859 5779 22581 6861 5779 22582 6860 5779 22583 6861 3430 22584 6863 3430 22585 6862 3430 22586 6863 3431 22587 6865 3431 22588 6864 3431 22589 6865 3432 22590 6867 3432 22591 6866 3432 22592 6867 5780 22593 6869 5780 22594 6868 5780 22595 6869 5781 22596 6871 5781 22597 6870 5781 22598 6871 3435 22599 6873 3435 22600 6872 3435 22601 6873 3436 22602 6875 3436 22603 6874 3436 22604 6875 5782 22605 6877 5782 22606 6876 5782 22607 6877 3438 22608 6879 3438 22609 6878 3438 22610 6879 3439 22611 6881 3439 22612 6880 3439 22613 6881 3440 22614 6883 3440 22615 6882 3440 22616 6883 3441 22617 6885 3441 22618 6884 3441 22619 6885 3442 22620 6887 3442 22621 6886 3442 22622 6887 5783 22623 6889 5783 22624 6888 5783 22625 6889 5784 22626 6891 5784 22627 6890 5784 22628 6891 3445 22629 6893 3445 22630 6892 3445 22631 6893 3446 22632 6895 3446 22633 6894 3446 22634 6895 3447 22635 6897 3447 22636 6896 3447 22637 6897 5785 22638 6899 5785 22639 6898 5785 22640 6899 3449 22641 6901 3449 22642 6900 3449 22643 6901 3450 22644 6903 3450 22645 6902 3450 22646 6903 3451 22647 6905 3451 22648 6904 3451 22649 6905 3452 22650 6907 3452 22651 6906 3452 22652 6907 3453 22653 6909 3453 22654 6908 3453 22655 6909 5786 22656 6911 5786 22657 6910 5786 22658 6911 3455 22659 6913 3455 22660 6912 3455 22661 6913 3456 22662 6915 3456 22663 6914 3456 22664 6915 3457 22665 6917 3457 22666 6916 3457 22667 6917 3458 22668 6919 3458 22669 6918 3458 22670 6919 5787 22671 6921 5787 22672 6920 5787 22673 6921 5788 22674 6923 5788 22675 6922 5788 22676 6923 3461 22677 6925 3461 22678 6924 3461 22679 6925 5789 22680 6927 5789 22681 6926 5789 22682 6927 5790 22683 6929 5790 22684 6928 5790 22685 6929 3464 22686 6931 3464 22687 6930 3464 22688 6931 5791 22689 6933 5791 22690 6932 5791 22691 6933 3466 22692 6935 3466 22693 6934 3466 22694 6935 3467 22695 6937 3467 22696 6936 3467 22697 6937 3468 22698 6939 3468 22699 6938 3468 22700 6939 3469 22701 6941 3469 22702 6940 3469 22703 6941 3470 22704 6943 3470 22705 6942 3470 22706 6943 5792 22707 6945 5792 22708 6944 5792 22709 6945 5793 22710 6947 5793 22711 6946 5793 22712 6947 3473 22713 6949 3473 22714 6948 3473 22715 6949 5794 22716 6951 5794 22717 6950 5794 22718 6951 3475 22719 6953 3475 22720 6952 3475 22721 6953 3476 22722 6955 3476 22723 6954 3476 22724 6955 3477 22725 6957 3477 22726 6956 3477 22727 6957 3478 22728 6959 3478 22729 6958 3478 22730 6959 3479 22731 6961 3479 22732 6960 3479 22733 6961 5795 22734 6963 5795 22735 6962 5795 22736 6963 5796 22737 6965 5796 22738 6964 5796 22739 6965 5797 22740 6967 5797 22741 6966 5797 22742 6967 3483 22743 6969 3483 22744 6968 3483 22745 6969 3484 22746 6971 3484 22747 6970 3484 22748 6971 3485 22749 6973 3485 22750 6972 3485 22751 6973 5798 22752 6975 5798 22753 6974 5798 22754 6975 5799 22755 6977 5799 22756 6976 5799 22757 6977 5800 22758 6979 5800 22759 6978 5800 22760 6979 3489 22761 6981 3489 22762 6980 3489 22763 6981 3490 22764 6983 3490 22765 6982 3490 22766 6983 3491 22767 6985 3491 22768 6984 3491 22769 6985 5801 22770 6987 5801 22771 6986 5801 22772 6987 5802 22773 6989 5802 22774 6988 5802 22775 6989 3494 22776 6991 3494 22777 6990 3494 22778 6991 5803 22779 6993 5803 22780 6992 5803 22781 6993 5804 22782 6995 5804 22783 6994 5804 22784 6995 5805 22785 6997 5805 22786 6996 5805 22787 6997 3498 22788 6999 3498 22789 6998 3498 22790 6999 5806 22791 7001 5806 22792 7000 5806 22793 7001 3500 22794 7003 3500 22795 7002 3500 22796 7003 3501 22797 7005 3501 22798 7004 3501 22799 7005 5807 22800 7007 5807 22801 7006 5807 22802 7007 3503 22803 7009 3503 22804 7008 3503 22805 7009 5808 22806 7011 5808 22807 7010 5808 22808 7011 3505 22809 7013 3505 22810 7012 3505 22811 7013 3506 22812 7015 3506 22813 7014 3506 22814 7015 5809 22815 7017 5809 22816 7016 5809 22817 7017 3508 22818 7019 3508 22819 7018 3508 22820 7019 3509 22821 7021 3509 22822 7020 3509 22823 7021 5810 22824 7023 5810 22825 7022 5810 22826 7023 3511 22827 7025 3511 22828 7024 3511 22829 7025 5811 22830 7027 5811 22831 7026 5811 22832 7027 5812 22833 7029 5812 22834 7028 5812 22835 7029 5813 22836 7031 5813 22837 7030 5813 22838 7031 5814 22839 7033 5814 22840 7032 5814 22841 7033 5815 22842 7035 5815 22843 7034 5815 22844 7035 5816 22845 7037 5816 22846 7036 5816 22847 7037 5817 22848 7039 5817 22849 7038 5817 22850 7039 5818 22851 7041 5818 22852 7040 5818 22853 7041 3520 22854 7043 3520 22855 7042 3520 22856 7043 3521 22857 7045 3521 22858 7044 3521 22859 7045 5819 22860 7047 5819 22861 7046 5819 22862 7047 5820 22863 7049 5820 22864 7048 5820 22865 7049 3524 22866 7051 3524 22867 7050 3524 22868 7051 3525 22869 7053 3525 22870 7052 3525 22871 7053 3526 22872 7055 3526 22873 7054 3526 22874 7055 5821 22875 7057 5821 22876 7056 5821 22877 7057 3528 22878 7059 3528 22879 7058 3528 22880 7059 5822 22881 7061 5822 22882 7060 5822 22883 7061 5823 22884 7063 5823 22885 7062 5823 22886 7063 3531 22887 7065 3531 22888 7064 3531 22889 7065 5824 22890 7067 5824 22891 7066 5824 22892 7067 5825 22893 7069 5825 22894 7068 5825 22895 7069 5826 22896 7071 5826 22897 7070 5826 22898 7071 5827 22899 7073 5827 22900 7072 5827 22901 7073 5828 22902 7075 5828 22903 7074 5828 22904 7075 3537 22905 7077 3537 22906 7076 3537 22907 7077 5829 22908 7079 5829 22909 7078 5829 22910 7079 3539 22911 7081 3539 22912 7080 3539 22913 7081 5830 22914 7083 5830 22915 7082 5830 22916 7083 3541 22917 7085 3541 22918 7084 3541 22919 7085 5831 22920 7087 5831 22921 7086 5831 22922 7087 5832 22923 7089 5832 22924 7088 5832 22925 7089 5833 22926 7091 5833 22927 7090 5833 22928 7091 3545 22929 7093 3545 22930 7092 3545 22931 7093 3546 22932 7095 3546 22933 7094 3546 22934 7095 5834 22935 7097 5834 22936 7096 5834 22937 7097 5835 22938 7099 5835 22939 7098 5835 22940 7099 5836 22941 7101 5836 22942 7100 5836 22943 7101 5837 22944 7103 5837 22945 7102 5837 22946 7103 5838 22947 7105 5838 22948 7104 5838 22949 7105 3552 22950 7107 3552 22951 7106 3552 22952 7107 5839 22953 7109 5839 22954 7108 5839 22955 7109 3554 22956 7111 3554 22957 7110 3554 22958 7111 5840 22959 7113 5840 22960 7112 5840 22961 7113 5841 22962 7115 5841 22963 7114 5841 22964 7115 5842 22965 7117 5842 22966 7116 5842 22967 7117 5843 22968 7119 5843 22969 7118 5843 22970 7119 5844 22971 7121 5844 22972 7120 5844 22973 7121 5845 22974 7123 5845 22975 7122 5845 22976 7123 5846 22977 7125 5846 22978 7124 5846 22979 7125 3562 22980 7127 3562 22981 7126 3562 22982 7127 5847 22983 7129 5847 22984 7128 5847 22985 7129 5848 22986 7131 5848 22987 7130 5848 22988 7131 5849 22989 7133 5849 22990 7132 5849 22991 7133 5850 22992 7135 5850 22993 7134 5850 22994 7135 5851 22995 7137 5851 22996 7136 5851 22997 7137 5852 22998 7139 5852 22999 7138 5852 23000 7139 5853 23001 7141 5853 23002 7140 5853 23003 7141 5854 23004 7143 5854 23005 7142 5854 23006 7143 3571 23007 7145 3571 23008 7144 3571 23009 7145 3572 23010 7147 3572 23011 7146 3572 23012 7147 5855 23013 7149 5855 23014 7148 5855 23015 7149 5856 23016 7151 5856 23017 7150 5856 23018 7151 5857 23019 7153 5857 23020 7152 5857 23021 7153 5858 23022 7155 5858 23023 7154 5858 23024 7155 5859 23025 7157 5859 23026 7156 5859 23027 7157 3578 23028 7159 3578 23029 7158 3578 23030 7159 3579 23031 7161 3579 23032 7160 3579 23033 7161 5860 23034 7163 5860 23035 7162 5860 23036 7163 3581 23037 7165 3581 23038 7164 3581 23039 7165 3582 23040 7167 3582 23041 7166 3582 23042 7167 3583 23043 7169 3583 23044 7168 3583 23045 7169 3584 23046 7171 3584 23047 7170 3584 23048 7171 3585 23049 7173 3585 23050 7172 3585 23051 7173 5861 23052 7175 5861 23053 7174 5861 23054 7175 3587 23055 7177 3587 23056 7176 3587 23057 7177 5862 23058 7179 5862 23059 7178 5862 23060 7179 5863 23061 7181 5863 23062 7180 5863 23063 7181 3590 23064 7183 3590 23065 7182 3590 23066 7183 3591 23067 7185 3591 23068 7184 3591 23069 7185 3592 23070 7187 3592 23071 7186 3592 23072 7187 5864 23073 7189 5864 23074 7188 5864 23075 7189 5865 23076 7191 5865 23077 7190 5865 23078 7191 5866 23079 7193 5866 23080 7192 5866 23081 7193 5867 23082 7195 5867 23083 7194 5867 23084 7195 5868 23085 7197 5868 23086 7196 5868 23087 7197 5869 23088 7199 5869 23089 7198 5869 23090 7199 5870 23091 7201 5870 23092 7200 5870 23093 7201 5871 23094 7203 5871 23095 7202 5871 23096 7203 3601 23097 7205 3601 23098 7204 3601 23099 7205 5872 23100 7207 5872 23101 7206 5872 23102 7207 3603 23103 7209 3603 23104 7208 3603 23105 7209 5873 23106 7211 5873 23107 7210 5873 23108 7211 3605 23109 7213 3605 23110 7212 3605 23111 7213 5874 23112 7215 5874 23113 7214 5874 23114 7215 5875 23115 7217 5875 23116 7216 5875 23117 7217 5876 23118 7219 5876 23119 7218 5876 23120 7219 5877 23121 7221 5877 23122 7220 5877 23123 7221 5878 23124 7223 5878 23125 7222 5878 23126 7223 5879 23127 7225 5879 23128 7224 5879 23129 7225 3612 23130 7227 3612 23131 7226 3612 23132 7227 5880 23133 7229 5880 23134 7228 5880 23135 7229 5881 23136 7231 5881 23137 7230 5881 23138 7231 3615 23139 7233 3615 23140 7232 3615 23141 7233 5882 23142 7235 5882 23143 7234 5882 23144 7235 3617 23145 7237 3617 23146 7236 3617 23147 7237 5883 23148 7239 5883 23149 7238 5883 23150 7239 3619 23151 7241 3619 23152 7240 3619 23153 7241 3620 23154 7243 3620 23155 7242 3620 23156 7243 3621 23157 7245 3621 23158 7244 3621 23159 7245 3622 23160 7247 3622 23161 7246 3622 23162 7247 5884 23163 7249 5884 23164 7248 5884 23165 7249 5885 23166 7251 5885 23167 7250 5885 23168 7251 5886 23169 7253 5886 23170 7252 5886 23171 7253 5887 23172 7255 5887 23173 7254 5887 23174 7255 5888 23175 7257 5888 23176 7256 5888 23177 7257 5889 23178 7259 5889 23179 7258 5889 23180 7259 5890 23181 7261 5890 23182 7260 5890 23183 7261 5891 23184 7263 5891 23185 7262 5891 23186 7263 3631 23187 7265 3631 23188 7264 3631 23189 7265 3632 23190 7267 3632 23191 7266 3632 23192 7267 3633 23193 7269 3633 23194 7268 3633 23195 7269 3634 23196 7271 3634 23197 7270 3634 23198 7271 5892 23199 7273 5892 23200 7272 5892 23201 7273 5893 23202 7275 5893 23203 7274 5893 23204 7275 5894 23205 7277 5894 23206 7276 5894 23207 7277 3638 23208 7279 3638 23209 7278 3638 23210 7279 3639 23211 7281 3639 23212 7280 3639 23213 7281 5895 23214 7283 5895 23215 7282 5895 23216 7283 3641 23217 7285 3641 23218 7284 3641 23219 7285 3642 23220 7287 3642 23221 7286 3642 23222 7287 5896 23223 7289 5896 23224 7288 5896 23225 7289 3644 23226 7291 3644 23227 7290 3644 23228 7291 3645 23229 7293 3645 23230 7292 3645 23231 7293 3646 23232 7295 3646 23233 7294 3646 23234 7295 5897 23235 7297 5897 23236 7296 5897 23237 7297 5898 23238 7299 5898 23239 7298 5898 23240 7299 3649 23241 7301 3649 23242 7300 3649 23243 7301 3650 23244 7303 3650 23245 7302 3650 23246 7303 3651 23247 7305 3651 23248 7304 3651 23249 7305 3652 23250 7307 3652 23251 7306 3652 23252 7307 3653 23253 7309 3653 23254 7308 3653 23255 7309 3654 23256 7311 3654 23257 7310 3654 23258 7311 3655 23259 7313 3655 23260 7312 3655 23261 7313 3656 23262 7315 3656 23263 7314 3656 23264 7315 3657 23265 7317 3657 23266 7316 3657 23267 7317 3658 23268 7319 3658 23269 7318 3658 23270 7319 5899 23271 7321 5899 23272 7320 5899 23273 7321 5900 23274 7323 5900 23275 7322 5900 23276 7323 3661 23277 7325 3661 23278 7324 3661 23279 7325 5901 23280 7327 5901 23281 7326 5901 23282 7327 3663 23283 7329 3663 23284 7328 3663 23285 7329 5902 23286 7331 5902 23287 7330 5902 23288 7331 3665 23289 7333 3665 23290 7332 3665 23291 7333 5903 23292 7335 5903 23293 7334 5903 23294 7335 3667 23295 7337 3667 23296 7336 3667 23297 7337 5904 23298 7339 5904 23299 7338 5904 23300 7339 3669 23301 7341 3669 23302 7340 3669 23303 7341 3670 23304 7343 3670 23305 7342 3670 23306 7343 3671 23307 7345 3671 23308 7344 3671 23309 7345 5905 23310 7347 5905 23311 7346 5905 23312 7347 5906 23313 7349 5906 23314 7348 5906 23315 7349 5907 23316 7351 5907 23317 7350 5907 23318 7351 5908 23319 7353 5908 23320 7352 5908 23321 7353 5909 23322 7355 5909 23323 7354 5909 23324 7355 3677 23325 7357 3677 23326 7356 3677 23327 7357 3678 23328 7359 3678 23329 7358 3678 23330 7359 3679 23331 7361 3679 23332 7360 3679 23333 7361 5910 23334 7363 5910 23335 7362 5910 23336 7363 3681 23337 7365 3681 23338 7364 3681 23339 7365 3682 23340 7367 3682 23341 7366 3682 23342 7367 3683 23343 7369 3683 23344 7368 3683 23345 7369 5911 23346 7371 5911 23347 7370 5911 23348 7371 5912 23349 7373 5912 23350 7372 5912 23351 7373 3686 23352 7375 3686 23353 7374 3686 23354 7375 5913 23355 7377 5913 23356 7376 5913 23357 7377 3688 23358 7379 3688 23359 7378 3688 23360 7379 3689 23361 7381 3689 23362 7380 3689 23363 7381 3690 23364 7383 3690 23365 7382 3690 23366 7383 3691 23367 7385 3691 23368 7384 3691 23369 7385 3692 23370 7387 3692 23371 7386 3692 23372 7387 3693 23373 7389 3693 23374 7388 3693 23375 7389 5914 23376 7391 5914 23377 7390 5914 23378 7391 3695 23379 7393 3695 23380 7392 3695 23381 7393 5915 23382 7395 5915 23383 7394 5915 23384 7395 3697 23385 7397 3697 23386 7396 3697 23387 7397 3698 23388 7399 3698 23389 7398 3698 23390 7399 3699 23391 7401 3699 23392 7400 3699 23393 7401 5916 23394 7403 5916 23395 7402 5916 23396 7403 5917 23397 7405 5917 23398 7404 5917 23399 7405 3702 23400 7407 3702 23401 7406 3702 23402 7407 5918 23403 7409 5918 23404 7408 5918 23405 7409 5919 23406 7411 5919 23407 7410 5919 23408 7411 5920 23409 7413 5920 23410 7412 5920 23411 7413 5921 23412 7415 5921 23413 7414 5921 23414 7415 5922 23415 7417 5922 23416 7416 5922 23417 7417 3708 23418 7419 3708 23419 7418 3708 23420 7419 3709 23421 7421 3709 23422 7420 3709 23423 7421 5923 23424 7423 5923 23425 7422 5923 23426 7423 3711 23427 7425 3711 23428 7424 3711 23429 7425 3712 23430 7427 3712 23431 7426 3712 23432 7427 5924 23433 7429 5924 23434 7428 5924 23435 7429 3714 23436 7431 3714 23437 7430 3714 23438 7431 3715 23439 7433 3715 23440 7432 3715 23441 7433 5925 23442 7435 5925 23443 7434 5925 23444 7435 5926 23445 7437 5926 23446 7436 5926 23447 7437 3718 23448 7439 3718 23449 7438 3718 23450 7439 3719 23451 7441 3719 23452 7440 3719 23453 7441 5927 23454 7443 5927 23455 7442 5927 23456 7443 5928 23457 7445 5928 23458 7444 5928 23459 7445 3722 23460 7447 3722 23461 7446 3722 23462 7447 5929 23463 7449 5929 23464 7448 5929 23465 7449 5930 23466 7451 5930 23467 7450 5930 23468 7451 5931 23469 7453 5931 23470 7452 5931 23471 7453 5932 23472 7455 5932 23473 7454 5932 23474 7455 5933 23475 7457 5933 23476 7456 5933 23477 7457 5934 23478 7459 5934 23479 7458 5934 23480 7459 3729 23481 7461 3729 23482 7460 3729 23483 7461 3730 23484 7463 3730 23485 7462 3730 23486 7463 5935 23487 7465 5935 23488 7464 5935 23489 7465 5936 23490 7467 5936 23491 7466 5936 23492 7467 5937 23493 7469 5937 23494 7468 5937 23495 7469 5938 23496 7471 5938 23497 7470 5938 23498 7471 3735 23499 7473 3735 23500 7472 3735 23501 7473 5939 23502 7475 5939 23503 7474 5939 23504 7475 3737 23505 7477 3737 23506 7476 3737 23507 7477 3738 23508 7479 3738 23509 7478 3738 23510 7479 3739 23511 7481 3739 23512 7480 3739 23513 7481 3740 23514 7483 3740 23515 7482 3740 23516 7483 5940 23517 7485 5940 23518 7484 5940 23519 7485 3742 23520 7487 3742 23521 7486 3742 23522 7487 3743 23523 7489 3743 23524 7488 3743 23525 7489 3744 23526 7491 3744 23527 7490 3744 23528 7491 5941 23529 7493 5941 23530 7492 5941 23531 7493 5942 23532 7495 5942 23533 7494 5942 23534 7495 5943 23535 7497 5943 23536 7496 5943 23537 7497 3748 23538 7499 3748 23539 7498 3748 23540 7499 5944 23541 7501 5944 23542 7500 5944 23543 7501 5945 23544 7503 5945 23545 7502 5945 23546 7503 3751 23547 7505 3751 23548 7504 3751 23549 7505 5946 23550 7507 5946 23551 7506 5946 23552 7507 5947 23553 7509 5947 23554 7508 5947 23555 7509 5948 23556 7511 5948 23557 7510 5948 23558 7511 5949 23559 7513 5949 23560 7512 5949 23561 7513 5950 23562 7515 5950 23563 7514 5950 23564 7515 5951 23565 7517 5951 23566 7516 5951 23567 7517 5952 23568 7519 5952 23569 7518 5952 23570 7519 5953 23571 7521 5953 23572 7520 5953 23573 7521 5954 23574 7523 5954 23575 7522 5954 23576 7523 5955 23577 7525 5955 23578 7524 5955 23579 7525 3762 23580 7527 3762 23581 7526 3762 23582 7527 5956 23583 7529 5956 23584 7528 5956 23585 7529 5957 23586 7531 5957 23587 7530 5957 23588 7531 3765 23589 7533 3765 23590 7532 3765 23591 7533 3766 23592 7535 3766 23593 7534 3766 23594 7535 3767 23595 7537 3767 23596 7536 3767 23597 7537 3768 23598 7539 3768 23599 7538 3768 23600 7539 3769 23601 7541 3769 23602 7540 3769 23603 7541 5958 23604 7543 5958 23605 7542 5958 23606 7543 5959 23607 7545 5959 23608 7544 5959 23609 7545 3772 23610 7547 3772 23611 7546 3772 23612 7547 5960 23613 7549 5960 23614 7548 5960 23615 7549 5961 23616 7551 5961 23617 7550 5961 23618 7551 3775 23619 7553 3775 23620 7552 3775 23621 7553 5962 23622 7555 5962 23623 7554 5962 23624 7555 5963 23625 7557 5963 23626 7556 5963 23627 7557 5964 23628 7559 5964 23629 7558 5964 23630 7559 3779 23631 7561 3779 23632 7560 3779 23633 7561 5965 23634 7563 5965 23635 7562 5965 23636 7563 3781 23637 7565 3781 23638 7564 3781 23639 7565 3782 23640 7567 3782 23641 7566 3782 23642 7567 5966 23643 7569 5966 23644 7568 5966 23645 7569 3784 23646 7571 3784 23647 7570 3784 23648 7571 5967 23649 7573 5967 23650 7572 5967 23651 7573 3786 23652 7575 3786 23653 7574 3786 23654 7575 5968 23655 7577 5968 23656 7576 5968 23657 7577 3788 23658 7579 3788 23659 7578 3788 23660 7579 5969 23661 7581 5969 23662 7580 5969 23663 7581 5970 23664 7583 5970 23665 7582 5970 23666 7583 3791 23667 7585 3791 23668 7584 3791 23669 7585 3792 23670 7587 3792 23671 7586 3792 23672 7587 5971 23673 7589 5971 23674 7588 5971 23675 7589 3794 23676 7591 3794 23677 7590 3794 23678 7591 5972 23679 7593 5972 23680 7592 5972 23681 7593 5973 23682 7595 5973 23683 7594 5973 23684 7595 5974 23685 7597 5974 23686 7596 5974 23687 7597 5975 23688 7599 5975 23689 7598 5975 23690 7599 5976 23691 7601 5976 23692 7600 5976 23693 7601 3800 23694 7603 3800 23695 7602 3800 23696 7603 5977 23697 7605 5977 23698 7604 5977 23699 7605 5978 23700 7607 5978 23701 7606 5978 23702 7607 5979 23703 7609 5979 23704 7608 5979 23705 7609 3804 23706 7611 3804 23707 7610 3804 23708 7611 5980 23709 7613 5980 23710 7612 5980 23711 7613 5981 23712 7615 5981 23713 7614 5981 23714 7615 3807 23715 7617 3807 23716 7616 3807 23717 7617 3808 23718 7619 3808 23719 7618 3808 23720 7619 3809 23721 7621 3809 23722 7620 3809 23723 7621 5982 23724 7623 5982 23725 7622 5982 23726 7623 5983 23727 7625 5983 23728 7624 5983 23729 7625 5984 23730 7627 5984 23731 7626 5984 23732 7627 3813 23733 7629 3813 23734 7628 3813 23735 7629 3814 23736 7631 3814 23737 7630 3814 23738 7631 5985 23739 7633 5985 23740 7632 5985 23741 7633 5986 23742 7635 5986 23743 7634 5986 23744 7635 3817 23745 7637 3817 23746 7636 3817 23747 7637 3818 23748 7639 3818 23749 7638 3818 23750 7639 5987 23751 7641 5987 23752 7640 5987 23753 7641 3820 23754 7643 3820 23755 7642 3820 23756 7643 3821 23757 7645 3821 23758 7644 3821 23759 7645 5988 23760 7647 5988 23761 7646 5988 23762 7647 3823 23763 7649 3823 23764 7648 3823 23765 7649 3824 23766 7651 3824 23767 7650 3824 23768 7651 3825 23769 7653 3825 23770 7652 3825 23771 7653 3826 23772 7655 3826 23773 7654 3826 23774 7655 3827 23775 7657 3827 23776 7656 3827 23777 7657 5989 23778 7659 5989 23779 7658 5989 23780 7659 5990 23781 7661 5990 23782 7660 5990 23783 7661 3830 23784 7663 3830 23785 7662 3830 23786 7663 5991 23787 7665 5991 23788 7664 5991 23789 7665 5992 23790 7667 5992 23791 7666 5992 23792 7667 5993 23793 7669 5993 23794 7668 5993 23795 7669 3834 23796 7671 3834 23797 7670 3834 23798 7671 5994 23799 7673 5994 23800 7672 5994 23801 7673 3836 23802 7675 3836 23803 7674 3836 23804 7675 3837 23805 7677 3837 23806 7676 3837 23807 7677 5995 23808 7679 5995 23809 7678 5995 23810 7679 3839 23811 7681 3839 23812 7680 3839 23813 7681 5996 23814 7683 5996 23815 7682 5996 23816 7683 3841 23817 7685 3841 23818 7684 3841 23819 7685 5997 23820 7687 5997 23821 7686 5997 23822 7687 3843 23823 7689 3843 23824 7688 3843 23825 7689 5998 23826 7691 5998 23827 7690 5998 23828 7691 3845 23829 7693 3845 23830 7692 3845 23831 7693 3846 23832 7695 3846 23833 7694 3846 23834 7695 5999 23835 7697 5999 23836 7696 5999 23837 7697 6000 23838 7699 6000 23839 7698 6000 23840 7699 3849 23841 7701 3849 23842 7700 3849 23843 7701 3850 23844 7703 3850 23845 7702 3850 23846 7703 3851 23847 7705 3851 23848 7704 3851 23849 7705 6001 23850 7707 6001 23851 7706 6001 23852 7707 6002 23853 7709 6002 23854 7708 6002 23855 7709 6003 23856 7711 6003 23857 7710 6003 23858 7711 3855 23859 7713 3855 23860 7712 3855 23861 7713 3856 23862 7715 3856 23863 7714 3856 23864 7715 3857 23865 7717 3857 23866 7716 3857 23867 7717 3858 23868 7719 3858 23869 7718 3858 23870 7719 3859 23871 7721 3859 23872 7720 3859 23873 7721 6004 23874 7723 6004 23875 7722 6004 23876 7723 3861 23877 7725 3861 23878 7724 3861 23879 7725 6005 23880 7727 6005 23881 7726 6005 23882 7727 6006 23883 7729 6006 23884 7728 6006 23885 7729 3864 23886 7731 3864 23887 7730 3864 23888 7731 3865 23889 7733 3865 23890 7732 3865 23891 7733 6007 23892 7735 6007 23893 7734 6007 23894 7735 3867 23895 7737 3867 23896 7736 3867 23897 7737 6008 23898 7739 6008 23899 7738 6008 23900 7739 6009 23901 7741 6009 23902 7740 6009 23903 7741 6010 23904 7743 6010 23905 7742 6010 23906 7743 6011 23907 7745 6011 23908 7744 6011 23909 7745 3872 23910 7747 3872 23911 7746 3872 23912 7747 6012 23913 7749 6012 23914 7748 6012 23915 7749 6013 23916 7751 6013 23917 7750 6013 23918 7751 3875 23919 7753 3875 23920 7752 3875 23921 7753 3876 23922 7755 3876 23923 7754 3876 23924 7755 6014 23925 7757 6014 23926 7756 6014 23927 7757 6015 23928 7759 6015 23929 7758 6015 23930 7759 6016 23931 7761 6016 23932 7760 6016 23933 7761 3880 23934 7763 3880 23935 7762 3880 23936 7763 3881 23937 7765 3881 23938 7764 3881 23939 7765 3882 23940 7767 3882 23941 7766 3882 23942 7767 3883 23943 7769 3883 23944 7768 3883 23945 7769 3884 23946 7771 3884 23947 7770 3884 23948 7771 6017 23949 7773 6017 23950 7772 6017 23951 7773 6018 23952 7775 6018 23953 7774 6018 23954 7775 3887 23955 7777 3887 23956 7776 3887 23957 7777 3888 23958 7779 3888 23959 7778 3888 23960 7779 3889 23961 7781 3889 23962 7780 3889 23963 7781 6019 23964 7783 6019 23965 7782 6019 23966 7783 6020 23967 7785 6020 23968 7784 6020 23969 7785 6021 23970 7787 6021 23971 7786 6021 23972 7787 3893 23973 7789 3893 23974 7788 3893 23975 7789 6022 23976 7791 6022 23977 7790 6022 23978 7791 6023 23979 7793 6023 23980 7792 6023 23981 7793 3896 23982 7795 3896 23983 7794 3896 23984 7795 3897 23985 7797 3897 23986 7796 3897 23987 7797 6024 23988 7799 6024 23989 7798 6024 23990 7799 3899 23991 7801 3899 23992 7800 3899 23993 7801 3900 23994 7803 3900 23995 7802 3900 23996 7803 3901 23997 7805 3901 23998 7804 3901 23999 7805 6025 24000 7807 6025 24001 7806 6025 24002 7807 3903 24003 7809 3903 24004 7808 3903 24005 7809 3904 24006 7811 3904 24007 7810 3904 24008 7811 3905 24009 7813 3905 24010 7812 3905 24011 7813 6026 24012 7815 6026 24013 7814 6026 24014 7815 6027 24015 7817 6027 24016 7816 6027 24017 7817 3908 24018 7819 3908 24019 7818 3908 24020 7819 3909 24021 7821 3909 24022 7820 3909 24023 7821 3910 24024 7823 3910 24025 7822 3910 24026 7823 3911 24027 7825 3911 24028 7824 3911 24029 7825 6028 24030 7827 6028 24031 7826 6028 24032 7827 6029 24033 7829 6029 24034 7828 6029 24035 7829 6030 24036 7831 6030 24037 7830 6030 24038 7831 3915 24039 7833 3915 24040 7832 3915 24041 7833 6031 24042 7835 6031 24043 7834 6031 24044 7835 3917 24045 7837 3917 24046 7836 3917 24047 7837 3918 24048 7839 3918 24049 7838 3918 24050 7839 3919 24051 7841 3919 24052 7840 3919 24053 7841 3920 24054 7843 3920 24055 7842 3920 24056 7843 6032 24057 7845 6032 24058 7844 6032 24059 7845 3922 24060 7847 3922 24061 7846 3922 24062 7847 3923 24063 7849 3923 24064 7848 3923 24065 7849 6033 24066 7851 6033 24067 7850 6033 24068 7851 3925 24069 7853 3925 24070 7852 3925 24071 7853 6034 24072 7855 6034 24073 7854 6034 24074 7855 3927 24075 7857 3927 24076 7856 3927 24077 7857 3928 24078 7859 3928 24079 7858 3928 24080 7859 6035 24081 7861 6035 24082 7860 6035 24083 7861 3930 24084 7863 3930 24085 7862 3930 24086 7863 6036 24087 7865 6036 24088 7864 6036 24089 7865 6037 24090 7867 6037 24091 7866 6037 24092 7867 3933 24093 7869 3933 24094 7868 3933 24095 7869 6038 24096 7871 6038 24097 7870 6038 24098 7871 3935 24099 7873 3935 24100 7872 3935 24101 7873 3936 24102 7875 3936 24103 7874 3936 24104 7875 6039 24105 7877 6039 24106 7876 6039 24107 7877 6040 24108 7879 6040 24109 7878 6040 24110 7879 6041 24111 7881 6041 24112 7880 6041 24113 7881 3940 24114 7883 3940 24115 7882 3940 24116 7883 3941 24117 7885 3941 24118 7884 3941 24119 7885 3942 24120 7887 3942 24121 7886 3942 24122 7887 3943 24123 7889 3943 24124 7888 3943 24125 7889 6042 24126 7891 6042 24127 7890 6042 24128 7891 3945 24129 7893 3945 24130 7892 3945 24131 7893 6043 24132 7895 6043 24133 7894 6043 24134 7895 3947 24135 7897 3947 24136 7896 3947 24137 7897 6044 24138 7899 6044 24139 7898 6044 24140 7899 3949 24141 7901 3949 24142 7900 3949 24143 7901 3950 24144 7903 3950 24145 7902 3950 24146 7903 3951 24147 7905 3951 24148 7904 3951 24149 7905 6045 24150 7907 6045 24151 7906 6045 24152 7907 3953 24153 7909 3953 24154 7908 3953 24155 7909 3954 24156 7911 3954 24157 7910 3954 24158 7911 3955 24159 7913 3955 24160 7912 3955 24161 7913 3956 24162 7915 3956 24163 7914 3956 24164 7915 6046 24165 7917 6046 24166 7916 6046 24167 7917 6047 24168 7919 6047 24169 7918 6047 24170 7919 3959 24171 7921 3959 24172 7920 3959 24173 7921 3960 24174 7923 3960 24175 7922 3960 24176 7923 6048 24177 7925 6048 24178 7924 6048 24179 7925 3962 24180 7927 3962 24181 7926 3962 24182 7927 6049 24183 7929 6049 24184 7928 6049 24185 7929 6050 24186 7931 6050 24187 7930 6050 24188 7931 3965 24189 7933 3965 24190 7932 3965 24191 7933 3966 24192 7935 3966 24193 7934 3966 24194 7935 6051 24195 7937 6051 24196 7936 6051 24197 7937 6052 24198 7939 6052 24199 7938 6052 24200 7939 6053 24201 7941 6053 24202 7940 6053 24203 7941 3970 24204 7943 3970 24205 7942 3970 24206 7943 3971 24207 7945 3971 24208 7944 3971 24209 7945 6054 24210 7947 6054 24211 7946 6054 24212 7947 3973 24213 7949 3973 24214 7948 3973 24215 7949 3974 24216 7951 3974 24217 7950 3974 24218 7951 3975 24219 7953 3975 24220 7952 3975 24221 7953 3976 24222 7955 3976 24223 7954 3976 24224 7955 3977 24225 7957 3977 24226 7956 3977 24227 7957 3978 24228 7959 3978 24229 7958 3978 24230 7959 6055 24231 7961 6055 24232 7960 6055 24233 7961 6056 24234 7963 6056 24235 7962 6056 24236 7963 6057 24237 7965 6057 24238 7964 6057 24239 7965 6058 24240 7967 6058 24241 7966 6058 24242 7967 3983 24243 7969 3983 24244 7968 3983 24245 7969 3984 24246 7971 3984 24247 7970 3984 24248 7971 6059 24249 7973 6059 24250 7972 6059 24251 7973 6060 24252 7975 6060 24253 7974 6060 24254 7975 3987 24255 7977 3987 24256 7976 3987 24257 7977 3988 24258 7979 3988 24259 7978 3988 24260 7979 6061 24261 7981 6061 24262 7980 6061 24263 7981 3990 24264 7983 3990 24265 7982 3990 24266 7983 3991 24267 7985 3991 24268 7984 3991 24269 7985 6062 24270 7987 6062 24271 7986 6062 24272 7987 6063 24273 7989 6063 24274 7988 6063 24275 7989 6064 24276 7991 6064 24277 7990 6064 24278 7991 6065 24279 7993 6065 24280 7992 6065 24281 7993 6066 24282 7995 6066 24283 7994 6066 24284 7995 6067 24285 7997 6067 24286 7996 6067 24287 7997 3998 24288 7999 3998 24289 7998 3998 24290 7999 6068 24291 8001 6068 24292 8000 6068 24293 8001 4000 24294 8003 4000 24295 8002 4000 24296 8003 4001 24297 8005 4001 24298 8004 4001 24299 8005 6069 24300 8007 6069 24301 8006 6069 24302 8007 6070 24303 8009 6070 24304 8008 6070 24305 8009 6071 24306 8011 6071 24307 8010 6071 24308 8011 4005 24309 8013 4005 24310 8012 4005 24311 8013 6072 24312 8015 6072 24313 8014 6072 24314 8015 4007 24315 8017 4007 24316 8016 4007 24317 8017 4008 24318 8019 4008 24319 8018 4008 24320 8019 6073 24321 8021 6073 24322 8020 6073 24323 8021 4010 24324 8023 4010 24325 8022 4010 24326 8023 6074 24327 8025 6074 24328 8024 6074 24329 8025 6075 24330 8027 6075 24331 8026 6075 24332 8027 6076 24333 8029 6076 24334 8028 6076 24335 8029 6077 24336 8031 6077 24337 8030 6077 24338 8031 4015 24339 8033 4015 24340 8032 4015 24341 8033 4016 24342 8035 4016 24343 8034 4016 24344 8035 6078 24345 8037 6078 24346 8036 6078 24347 8037 4018 24348 8039 4018 24349 8038 4018 24350 8039 6079 24351 8041 6079 24352 8040 6079 24353 8041 4020 24354 8043 4020 24355 8042 4020 24356 8043 6080 24357 8045 6080 24358 8044 6080 24359 8045 4022 24360 8047 4022 24361 8046 4022 24362 8047 4023 24363 8049 4023 24364 8048 4023 24365 8049 4024 24366 8051 4024 24367 8050 4024 24368 8051 4025 24369 8053 4025 24370 8052 4025 24371 8053 6081 24372 8055 6081 24373 8054 6081 24374 8055 6082 24375 8057 6082 24376 8056 6082 24377 8057 6083 24378 8059 6083 24379 8058 6083 24380 8059 6084 24381 8061 6084 24382 8060 6084 24383 8061 4030 24384 8063 4030 24385 8062 4030 24386 8063 4031 24387 8065 4031 24388 8064 4031 24389 8065 6085 24390 8067 6085 24391 8066 6085 24392 8067 4033 24393 8069 4033 24394 8068 4033 24395 8069 4034 24396 8071 4034 24397 8070 4034 24398 8071 4035 24399 8073 4035 24400 8072 4035 24401 8073 4036 24402 8075 4036 24403 8074 4036 24404 8075 6086 24405 8077 6086 24406 8076 6086 24407 8077 6087 24408 8079 6087 24409 8078 6087 24410 8079 4039 24411 8081 4039 24412 8080 4039 24413 8081 4040 24414 8083 4040 24415 8082 4040 24416 8083 4041 24417 8085 4041 24418 8084 4041 24419 8085 6088 24420 8087 6088 24421 8086 6088 24422 8087 4043 24423 8089 4043 24424 8088 4043 24425 8089 6089 24426 8091 6089 24427 8090 6089 24428 8091 4045 24429 8093 4045 24430 8092 4045 24431 8093 4046 24432 8095 4046 24433 8094 4046 24434 8095 4047 24435 8097 4047 24436 8096 4047 24437 8097 6090 24438 8099 6090 24439 8098 6090 24440 8099 4049 24441 8101 4049 24442 8100 4049 24443 8101 4050 24444 8103 4050 24445 8102 4050 24446 8103 4051 24447 8105 4051 24448 8104 4051 24449 8105 6091 24450 8107 6091 24451 8106 6091 24452 8107 4053 24453 8109 4053 24454 8108 4053 24455 8109 6092 24456 8111 6092 24457 8110 6092 24458 8111 6093 24459 8113 6093 24460 8112 6093 24461 8113 4056 24462 8115 4056 24463 8114 4056 24464 8115 6094 24465 8117 6094 24466 8116 6094 24467 8117 4058 24468 8119 4058 24469 8118 4058 24470 8119 6095 24471 8121 6095 24472 8120 6095 24473 8121 4060 24474 8123 4060 24475 8122 4060 24476 8123 4061 24477 8125 4061 24478 8124 4061 24479 8125 4062 24480 8127 4062 24481 8126 4062 24482 8127 6096 24483 8129 6096 24484 8128 6096 24485 8129 4064 24486 8131 4064 24487 8130 4064 24488 8131 6097 24489 8133 6097 24490 8132 6097 24491 8133 6098 24492 8135 6098 24493 8134 6098 24494 8135 6099 24495 8137 6099 24496 8136 6099 24497 8137 4068 24498 8139 4068 24499 8138 4068 24500 8139 6100 24501 8141 6100 24502 8140 6100 24503 8141 4070 24504 8143 4070 24505 8142 4070 24506 8143 4071 24507 8145 4071 24508 8144 4071 24509 8145 4072 24510 8147 4072 24511 8146 4072 24512 8147 4073 24513 8149 4073 24514 8148 4073 24515 8149 6101 24516 8151 6101 24517 8150 6101 24518 8151 4075 24519 8153 4075 24520 8152 4075 24521 8153 6102 24522 8155 6102 24523 8154 6102 24524 8155 6103 24525 8157 6103 24526 8156 6103 24527 8157 4078 24528 8159 4078 24529 8158 4078 24530 8159 4079 24531 8161 4079 24532 8160 4079 24533 8161 6104 24534 8163 6104 24535 8162 6104 24536 8163 6105 24537 8165 6105 24538 8164 6105 24539 8165 4082 24540 8167 4082 24541 8166 4082 24542 8167 4083 24543 8169 4083 24544 8168 4083 24545 8169 6106 24546 8171 6106 24547 8170 6106 24548 8171 6107 24549 8173 6107 24550 8172 6107 24551 8173 6108 24552 8175 6108 24553 8174 6108 24554 8175 6109 24555 8177 6109 24556 8176 6109 24557 8177 4088 24558 8179 4088 24559 8178 4088 24560 8179 4089 24561 8181 4089 24562 8180 4089 24563 8181 6110 24564 8183 6110 24565 8182 6110 24566 8183 6111 24567 8185 6111 24568 8184 6111 24569 8185 6112 24570 8187 6112 24571 8186 6112 24572 8187 4093 24573 8189 4093 24574 8188 4093 24575 5 4094 24576 3 4094 24577 8189 4094 24578 3 4094 24579 1 4094 24580 8189 4094 24581 1 4094 24582 8191 4094 24583 8189 4094 24584 8189 4094 24585 8187 4094 24586 8181 4094 24587 8187 4094 24588 8185 4094 24589 8181 4094 24590 8185 4094 24591 8183 4094 24592 8181 4094 24593 8181 4094 24594 8179 4094 24595 8177 4094 24596 8177 4094 24597 8175 4094 24598 8181 4094 24599 8175 4094 24600 8173 4094 24601 8181 4094 24602 8173 4094 24603 8171 4094 24604 8169 4094 24605 8169 4094 24606 8167 4094 24607 8173 4094 24608 8167 4094 24609 8165 4094 24610 8173 4094 24611 8165 4094 24612 8163 4094 24613 8161 4094 24614 8161 4094 24615 8159 4094 24616 8157 4094 24617 8157 4094 24618 8155 4094 24619 8153 4094 24620 8153 4094 24621 8151 4094 24622 8149 4094 24623 8149 4094 24624 8147 4094 24625 8145 4094 24626 8145 4094 24627 8143 4094 24628 8141 4094 24629 8141 4094 24630 8139 4094 24631 8133 4094 24632 8139 4094 24633 8137 4094 24634 8133 4094 24635 8137 4094 24636 8135 4094 24637 8133 4094 24638 8133 4094 24639 8131 4094 24640 8125 4094 24641 8131 4094 24642 8129 4094 24643 8125 4094 24644 8129 4094 24645 8127 4094 24646 8125 4094 24647 8125 4094 24648 8123 4094 24649 8121 4094 24650 8121 4094 24651 8119 4094 24652 8117 4094 24653 8117 4094 24654 8115 4094 24655 8113 4094 24656 8113 4094 24657 8111 4094 24658 8109 4094 24659 8109 4094 24660 8107 4094 24661 8101 4094 24662 8107 4094 24663 8105 4094 24664 8101 4094 24665 8105 4094 24666 8103 4094 24667 8101 4094 24668 8101 4094 24669 8099 4094 24670 8097 4094 24671 8097 4094 24672 8095 4094 24673 8093 4094 24674 8093 4094 24675 8091 4094 24676 8085 4094 24677 8091 4094 24678 8089 4094 24679 8085 4094 24680 8089 4094 24681 8087 4094 24682 8085 4094 24683 8085 4094 24684 8083 4094 24685 8077 4094 24686 8083 4094 24687 8081 4094 24688 8077 4094 24689 8081 4094 24690 8079 4094 24691 8077 4094 24692 8077 4094 24693 8075 4094 24694 8073 4094 24695 8073 4094 24696 8071 4094 24697 8077 4094 24698 8071 4094 24699 8069 4094 24700 8077 4094 24701 8069 4094 24702 8067 4094 24703 8061 4094 24704 8067 4094 24705 8065 4094 24706 8061 4094 24707 8065 4094 24708 8063 4094 24709 8061 4094 24710 8061 4094 24711 8059 4094 24712 8057 4094 24713 8057 4094 24714 8055 4094 24715 8061 4094 24716 8055 4094 24717 8053 4094 24718 8061 4094 24719 8053 4094 24720 8051 4094 24721 8045 4094 24722 8051 4094 24723 8049 4094 24724 8045 4094 24725 8049 4094 24726 8047 4094 24727 8045 4094 24728 8045 4094 24729 8043 4094 24730 8041 4094 24731 8041 4094 24732 8039 4094 24733 8037 4094 24734 8037 4094 24735 8035 4094 24736 8029 4094 24737 8035 4094 24738 8033 4094 24739 8029 4094 24740 8033 4094 24741 8031 4094 24742 8029 4094 24743 8029 4094 24744 8027 4094 24745 8025 4094 24746 8025 4094 24747 8023 4094 24748 8029 4094 24749 8023 4094 24750 8021 4094 24751 8029 4094 24752 8021 4094 24753 8019 4094 24754 8017 4094 24755 8017 4094 24756 8015 4094 24757 8021 4094 24758 8015 4094 24759 8013 4094 24760 8021 4094 24761 8013 4094 24762 8011 4094 24763 8009 4094 24764 8009 4094 24765 8007 4094 24766 8005 4094 24767 8005 4094 24768 8003 4094 24769 8001 4094 24770 8001 4094 24771 7999 4094 24772 8005 4094 24773 7999 4094 24774 7997 4094 24775 8005 4094 24776 7997 4094 24777 7995 4094 24778 7993 4094 24779 7993 4094 24780 7991 4094 24781 7997 4094 24782 7991 4094 24783 7989 4094 24784 7997 4094 24785 7989 4094 24786 7987 4094 24787 7981 4094 24788 7987 4094 24789 7985 4094 24790 7981 4094 24791 7985 4094 24792 7983 4094 24793 7981 4094 24794 7981 4094 24795 7979 4094 24796 7977 4094 24797 7977 4094 24798 7975 4094 24799 7981 4094 24800 7975 4094 24801 7973 4094 24802 7981 4094 24803 7973 4094 24804 7971 4094 24805 7965 4094 24806 7971 4094 24807 7969 4094 24808 7965 4094 24809 7969 4094 24810 7967 4094 24811 7965 4094 24812 7965 4094 24813 7963 4094 24814 7961 4094 24815 7961 4094 24816 7959 4094 24817 7957 4094 24818 7957 4094 24819 7955 4094 24820 7949 4094 24821 7955 4094 24822 7953 4094 24823 7949 4094 24824 7953 4094 24825 7951 4094 24826 7949 4094 24827 7949 4094 24828 7947 4094 24829 7941 4094 24830 7947 4094 24831 7945 4094 24832 7941 4094 24833 7945 4094 24834 7943 4094 24835 7941 4094 24836 7941 4094 24837 7939 4094 24838 7937 4094 24839 7937 4094 24840 7935 4094 24841 7933 4094 24842 7933 4094 24843 7931 4094 24844 7925 4094 24845 7931 4094 24846 7929 4094 24847 7925 4094 24848 7929 4094 24849 7927 4094 24850 7925 4094 24851 7925 4094 24852 7923 4094 24853 7921 4094 24854 7921 4094 24855 7919 4094 24856 7925 4094 24857 7919 4094 24858 7917 4094 24859 7925 4094 24860 7917 4094 24861 7915 4094 24862 7909 4094 24863 7915 4094 24864 7913 4094 24865 7909 4094 24866 7913 4094 24867 7911 4094 24868 7909 4094 24869 7909 4094 24870 7907 4094 24871 7905 4094 24872 7905 4094 24873 7903 4094 24874 7901 4094 24875 7901 4094 24876 7899 4094 24877 7897 4094 24878 7897 4094 24879 7895 4094 24880 7901 4094 24881 7895 4094 24882 7893 4094 24883 7901 4094 24884 7893 4094 24885 7891 4094 24886 7885 4094 24887 7891 4094 24888 7889 4094 24889 7885 4094 24890 7889 4094 24891 7887 4094 24892 7885 4094 24893 7885 4094 24894 7883 4094 24895 7877 4094 24896 7883 4094 24897 7881 4094 24898 7877 4094 24899 7881 4094 24900 7879 4094 24901 7877 4094 24902 7877 4094 24903 7875 4094 24904 7873 4094 24905 7873 4094 24906 7871 4094 24907 7877 4094 24908 7871 4094 24909 7869 4094 24910 7877 4094 24911 7869 4094 24912 7867 4094 24913 7865 4094 24914 7865 4094 24915 7863 4094 24916 7861 4094 24917 7861 4094 24918 7859 4094 24919 7853 4094 24920 7859 4094 24921 7857 4094 24922 7853 4094 24923 7857 4094 24924 7855 4094 24925 7853 4094 24926 7853 4094 24927 7851 4094 24928 7849 4094 24929 7849 4094 24930 7847 4094 24931 7853 4094 24932 7847 4094 24933 7845 4094 24934 7853 4094 24935 7845 4094 24936 7843 4094 24937 7841 4094 24938 7841 4094 24939 7839 4094 24940 7837 4094 24941 7837 4094 24942 7835 4094 24943 7833 4094 24944 7833 4094 24945 7831 4094 24946 7837 4094 24947 7831 4094 24948 7829 4094 24949 7837 4094 24950 7829 4094 24951 7827 4094 24952 7825 4094 24953 7825 4094 24954 7823 4094 24955 7829 4094 24956 7823 4094 24957 7821 4094 24958 7829 4094 24959 7821 4094 24960 7819 4094 24961 7817 4094 24962 7817 4094 24963 7815 4094 24964 7813 4094 24965 7813 4094 24966 7811 4094 24967 7809 4094 24968 7809 4094 24969 7807 4094 24970 7813 4094 24971 7807 4094 24972 7805 4094 24973 7813 4094 24974 7805 4094 24975 7803 4094 24976 7797 4094 24977 7803 4094 24978 7801 4094 24979 7797 4094 24980 7801 4094 24981 7799 4094 24982 7797 4094 24983 7797 4094 24984 7795 4094 24985 7793 4094 24986 7793 4094 24987 7791 4094 24988 7789 4094 24989 7789 4094 24990 7787 4094 24991 7785 4094 24992 7785 4094 24993 7783 4094 24994 7789 4094 24995 7783 4094 24996 7781 4094 24997 7789 4094 24998 7781 4094 24999 7779 4094 25000 7777 4094 25001 7777 4094 25002 7775 4094 25003 7773 4094 25004 7773 4094 25005 7771 4094 25006 7765 4094 25007 7771 4094 25008 7769 4094 25009 7765 4094 25010 7769 4094 25011 7767 4094 25012 7765 4094 25013 7765 4094 25014 7763 4094 25015 7761 4094 25016 7761 4094 25017 7759 4094 25018 7765 4094 25019 7759 4094 25020 7757 4094 25021 7765 4094 25022 7757 4094 25023 7755 4094 25024 7753 4094 25025 7753 4094 25026 7751 4094 25027 7757 4094 25028 7751 4094 25029 7749 4094 25030 7757 4094 25031 7749 4094 25032 7747 4094 25033 7745 4094 25034 7745 4094 25035 7743 4094 25036 7749 4094 25037 7743 4094 25038 7741 4094 25039 7749 4094 25040 7741 4094 25041 7739 4094 25042 7737 4094 25043 7737 4094 25044 7735 4094 25045 7741 4094 25046 7735 4094 25047 7733 4094 25048 7741 4094 25049 7733 4094 25050 7731 4094 25051 7725 4094 25052 7731 4094 25053 7729 4094 25054 7725 4094 25055 7729 4094 25056 7727 4094 25057 7725 4094 25058 7725 4094 25059 7723 4094 25060 7721 4094 25061 7721 4094 25062 7719 4094 25063 7725 4094 25064 7719 4094 25065 7717 4094 25066 7725 4094 25067 7717 4094 25068 7715 4094 25069 7713 4094 25070 7713 4094 25071 7711 4094 25072 7717 4094 25073 7711 4094 25074 7709 4094 25075 7717 4094 25076 7709 4094 25077 7707 4094 25078 7705 4094 25079 7705 4094 25080 7703 4094 25081 7701 4094 25082 7701 4094 25083 7699 4094 25084 7697 4094 25085 7697 4094 25086 7695 4094 25087 7701 4094 25088 7695 4094 25089 7693 4094 25090 7701 4094 25091 7693 4094 25092 7691 4094 25093 7689 4094 25094 7689 4094 25095 7687 4094 25096 7693 4094 25097 7687 4094 25098 7685 4094 25099 7693 4094 25100 7685 4094 25101 7683 4094 25102 7681 4094 25103 7681 4094 25104 7679 4094 25105 7677 4094 25106 7677 4094 25107 7675 4094 25108 7673 4094 25109 7673 4094 25110 7671 4094 25111 7677 4094 25112 7671 4094 25113 7669 4094 25114 7677 4094 25115 7669 4094 25116 7667 4094 25117 7661 4094 25118 7667 4094 25119 7665 4094 25120 7661 4094 25121 7665 4094 25122 7663 4094 25123 7661 4094 25124 7661 4094 25125 7659 4094 25126 7653 4094 25127 7659 4094 25128 7657 4094 25129 7653 4094 25130 7657 4094 25131 7655 4094 25132 7653 4094 25133 7653 4094 25134 7651 4094 25135 7649 4094 25136 7649 4094 25137 7647 4094 25138 7645 4094 25139 7645 4094 25140 7643 4094 25141 7637 4094 25142 7643 4094 25143 7641 4094 25144 7637 4094 25145 7641 4094 25146 7639 4094 25147 7637 4094 25148 7637 4094 25149 7635 4094 25150 7633 4094 25151 7633 4094 25152 7631 4094 25153 7637 4094 25154 7631 4094 25155 7629 4094 25156 7637 4094 25157 7629 4094 25158 7627 4094 25159 7625 4094 25160 7625 4094 25161 7623 4094 25162 7629 4094 25163 7623 4094 25164 7621 4094 25165 7629 4094 25166 7621 4094 25167 7619 4094 25168 7613 4094 25169 7619 4094 25170 7617 4094 25171 7613 4094 25172 7617 4094 25173 7615 4094 25174 7613 4094 25175 7613 4094 25176 7611 4094 25177 7605 4094 25178 7611 4094 25179 7609 4094 25180 7605 4094 25181 7609 4094 25182 7607 4094 25183 7605 4094 25184 7605 4094 25185 7603 4094 25186 7597 4094 25187 7603 4094 25188 7601 4094 25189 7597 4094 25190 7601 4094 25191 7599 4094 25192 7597 4094 25193 7597 4094 25194 7595 4094 25195 7589 4094 25196 7595 4094 25197 7593 4094 25198 7589 4094 25199 7593 4094 25200 7591 4094 25201 7589 4094 25202 7589 4094 25203 7587 4094 25204 7585 4094 25205 7585 4094 25206 7583 4094 25207 7589 4094 25208 7583 4094 25209 7581 4094 25210 7589 4094 25211 7581 4094 25212 7579 4094 25213 7577 4094 25214 7577 4094 25215 7575 4094 25216 7581 4094 25217 7575 4094 25218 7573 4094 25219 7581 4094 25220 7573 4094 25221 7571 4094 25222 7565 4094 25223 7571 4094 25224 7569 4094 25225 7565 4094 25226 7569 4094 25227 7567 4094 25228 7565 4094 25229 7565 4094 25230 7563 4094 25231 7557 4094 25232 7563 4094 25233 7561 4094 25234 7557 4094 25235 7561 4094 25236 7559 4094 25237 7557 4094 25238 7557 4094 25239 7555 4094 25240 7553 4094 25241 7553 4094 25242 7551 4094 25243 7549 4094 25244 7549 4094 25245 7547 4094 25246 7541 4094 25247 7547 4094 25248 7545 4094 25249 7541 4094 25250 7545 4094 25251 7543 4094 25252 7541 4094 25253 7541 4094 25254 7539 4094 25255 7537 4094 25256 7537 4094 25257 7535 4094 25258 7541 4094 25259 7535 4094 25260 7533 4094 25261 7541 4094 25262 7533 4094 25263 7531 4094 25264 7529 4094 25265 7529 4094 25266 7527 4094 25267 7533 4094 25268 7527 4094 25269 7525 4094 25270 7533 4094 25271 7525 4094 25272 7523 4094 25273 7517 4094 25274 7523 4094 25275 7521 4094 25276 7517 4094 25277 7521 4094 25278 7519 4094 25279 7517 4094 25280 7517 4094 25281 7515 4094 25282 7513 4094 25283 7513 4094 25284 7511 4094 25285 7509 4094 25286 7509 4094 25287 7507 4094 25288 7505 4094 25289 7505 4094 25290 7503 4094 25291 7501 4094 25292 7501 4094 25293 7499 4094 25294 7497 4094 25295 7497 4094 25296 7495 4094 25297 7493 4094 25298 7493 4094 25299 7491 4094 25300 7489 4094 25301 7489 4094 25302 7487 4094 25303 7493 4094 25304 7487 4094 25305 7485 4094 25306 7493 4094 25307 7485 4094 25308 7483 4094 25309 7477 4094 25310 7483 4094 25311 7481 4094 25312 7477 4094 25313 7481 4094 25314 7479 4094 25315 7477 4094 25316 7477 4094 25317 7475 4094 25318 7473 4094 25319 7473 4094 25320 7471 4094 25321 7477 4094 25322 7471 4094 25323 7469 4094 25324 7477 4094 25325 7469 4094 25326 7467 4094 25327 7465 4094 25328 7465 4094 25329 7463 4094 25330 7461 4094 25331 7461 4094 25332 7459 4094 25333 7457 4094 25334 7457 4094 25335 7455 4094 25336 7461 4094 25337 7455 4094 25338 7453 4094 25339 7461 4094 25340 7453 4094 25341 7451 4094 25342 7449 4094 25343 7449 4094 25344 7447 4094 25345 7453 4094 25346 7447 4094 25347 7445 4094 25348 7453 4094 25349 7445 4094 25350 7443 4094 25351 7441 4094 25352 7441 4094 25353 7439 4094 25354 7437 4094 25355 7437 4094 25356 7435 4094 25357 7433 4094 25358 7433 4094 25359 7431 4094 25360 7429 4094 25361 7429 4094 25362 7427 4094 25363 7421 4094 25364 7427 4094 25365 7425 4094 25366 7421 4094 25367 7425 4094 25368 7423 4094 25369 7421 4094 25370 7421 4094 25371 7419 4094 25372 7417 4094 25373 7417 4094 25374 7415 4094 25375 7413 4094 25376 7413 4094 25377 7411 4094 25378 7405 4094 25379 7411 4094 25380 7409 4094 25381 7405 4094 25382 7409 4094 25383 7407 4094 25384 7405 4094 25385 7405 4094 25386 7403 4094 25387 7401 4094 25388 7401 4094 25389 7399 4094 25390 7405 4094 25391 7399 4094 25392 7397 4094 25393 7405 4094 25394 7397 4094 25395 7395 4094 25396 7393 4094 25397 7393 4094 25398 7391 4094 25399 7389 4094 25400 7389 4094 25401 7387 4094 25402 7385 4094 25403 7385 4094 25404 7383 4094 25405 7389 4094 25406 7383 4094 25407 7381 4094 25408 7389 4094 25409 7381 4094 25410 7379 4094 25411 7373 4094 25412 7379 4094 25413 7377 4094 25414 7373 4094 25415 7377 4094 25416 7375 4094 25417 7373 4094 25418 7373 4094 25419 7371 4094 25420 7369 4094 25421 7369 4094 25422 7367 4094 25423 7365 4094 25424 7365 4094 25425 7363 4094 25426 7361 4094 25427 7361 4094 25428 7359 4094 25429 7357 4094 25430 7357 4094 25431 7355 4094 25432 7349 4094 25433 7355 4094 25434 7353 4094 25435 7349 4094 25436 7353 4094 25437 7351 4094 25438 7349 4094 25439 7349 4094 25440 7347 4094 25441 7341 4094 25442 7347 4094 25443 7345 4094 25444 7341 4094 25445 7345 4094 25446 7343 4094 25447 7341 4094 25448 7341 4094 25449 7339 4094 25450 7337 4094 25451 7337 4094 25452 7335 4094 25453 7333 4094 25454 7333 4094 25455 7331 4094 25456 7329 4094 25457 7329 4094 25458 7327 4094 25459 7333 4094 25460 7327 4094 25461 7325 4094 25462 7333 4094 25463 7325 4094 25464 7323 4094 25465 7317 4094 25466 7323 4094 25467 7321 4094 25468 7317 4094 25469 7321 4094 25470 7319 4094 25471 7317 4094 25472 7317 4094 25473 7315 4094 25474 7313 4094 25475 7313 4094 25476 7311 4094 25477 7317 4094 25478 7311 4094 25479 7309 4094 25480 7317 4094 25481 7309 4094 25482 7307 4094 25483 7305 4094 25484 7305 4094 25485 7303 4094 25486 7301 4094 25487 7301 4094 25488 7299 4094 25489 7293 4094 25490 7299 4094 25491 7297 4094 25492 7293 4094 25493 7297 4094 25494 7295 4094 25495 7293 4094 25496 7293 4094 25497 7291 4094 25498 7289 4094 25499 7289 4094 25500 7287 4094 25501 7293 4094 25502 7287 4094 25503 7285 4094 25504 7293 4094 25505 7285 4094 25506 7283 4094 25507 7281 4094 25508 7281 4094 25509 7279 4094 25510 7277 4094 25511 7277 4094 25512 7275 4094 25513 7273 4094 25514 7273 4094 25515 7271 4094 25516 7277 4094 25517 7271 4094 25518 7269 4094 25519 7277 4094 25520 7269 4094 25521 7267 4094 25522 7265 4094 25523 7265 4094 25524 7263 4094 25525 7269 4094 25526 7263 4094 25527 7261 4094 25528 7269 4094 25529 7261 4094 25530 7259 4094 25531 7257 4094 25532 7257 4094 25533 7255 4094 25534 7261 4094 25535 7255 4094 25536 7253 4094 25537 7261 4094 25538 7253 4094 25539 7251 4094 25540 7249 4094 25541 7249 4094 25542 7247 4094 25543 7253 4094 25544 7247 4094 25545 7245 4094 25546 7253 4094 25547 7245 4094 25548 7243 4094 25549 7241 4094 25550 7241 4094 25551 7239 4094 25552 7237 4094 25553 7237 4094 25554 7235 4094 25555 7229 4094 25556 7235 4094 25557 7233 4094 25558 7229 4094 25559 7233 4094 25560 7231 4094 25561 7229 4094 25562 7229 4094 25563 7227 4094 25564 7225 4094 25565 7225 4094 25566 7223 4094 25567 7229 4094 25568 7223 4094 25569 7221 4094 25570 7229 4094 25571 7221 4094 25572 7219 4094 25573 7213 4094 25574 7219 4094 25575 7217 4094 25576 7213 4094 25577 7217 4094 25578 7215 4094 25579 7213 4094 25580 7213 4094 25581 7211 4094 25582 7209 4094 25583 7209 4094 25584 7207 4094 25585 7205 4094 25586 7205 4094 25587 7203 4094 25588 7201 4094 25589 7201 4094 25590 7199 4094 25591 7205 4094 25592 7199 4094 25593 7197 4094 25594 7205 4094 25595 7197 4094 25596 7195 4094 25597 7193 4094 25598 7193 4094 25599 7191 4094 25600 7189 4094 25601 7189 4094 25602 7187 4094 25603 7185 4094 25604 7185 4094 25605 7183 4094 25606 7181 4094 25607 7181 4094 25608 7179 4094 25609 7177 4094 25610 7177 4094 25611 7175 4094 25612 7181 4094 25613 7175 4094 25614 7173 4094 25615 7181 4094 25616 7173 4094 25617 7171 4094 25618 7169 4094 25619 7169 4094 25620 7167 4094 25621 7173 4094 25622 7167 4094 25623 7165 4094 25624 7173 4094 25625 7165 4094 25626 7163 4094 25627 7161 4094 25628 7161 4094 25629 7159 4094 25630 7165 4094 25631 7159 4094 25632 7157 4094 25633 7165 4094 25634 7157 4094 25635 7155 4094 25636 7153 4094 25637 7153 4094 25638 7151 4094 25639 7157 4094 25640 7151 4094 25641 7149 4094 25642 7157 4094 25643 7149 4094 25644 7147 4094 25645 7145 4094 25646 7145 4094 25647 7143 4094 25648 7141 4094 25649 7141 4094 25650 7139 4094 25651 7133 4094 25652 7139 4094 25653 7137 4094 25654 7133 4094 25655 7137 4094 25656 7135 4094 25657 7133 4094 25658 7133 4094 25659 7131 4094 25660 7129 4094 25661 7129 4094 25662 7127 4094 25663 7125 4094 25664 7125 4094 25665 7123 4094 25666 7121 4094 25667 7121 4094 25668 7119 4094 25669 7125 4094 25670 7119 4094 25671 7117 4094 25672 7125 4094 25673 7117 4094 25674 7115 4094 25675 7109 4094 25676 7115 4094 25677 7113 4094 25678 7109 4094 25679 7113 4094 25680 7111 4094 25681 7109 4094 25682 7109 4094 25683 7107 4094 25684 7105 4094 25685 7105 4094 25686 7103 4094 25687 7109 4094 25688 7103 4094 25689 7101 4094 25690 7109 4094 25691 7101 4094 25692 7099 4094 25693 7097 4094 25694 7097 4094 25695 7095 4094 25696 7093 4094 25697 7093 4094 25698 7091 4094 25699 7085 4094 25700 7091 4094 25701 7089 4094 25702 7085 4094 25703 7089 4094 25704 7087 4094 25705 7085 4094 25706 7085 4094 25707 7083 4094 25708 7081 4094 25709 7081 4094 25710 7079 4094 25711 7085 4094 25712 7079 4094 25713 7077 4094 25714 7085 4094 25715 7077 4094 25716 7075 4094 25717 7069 4094 25718 7075 4094 25719 7073 4094 25720 7069 4094 25721 7073 4094 25722 7071 4094 25723 7069 4094 25724 7069 4094 25725 7067 4094 25726 7061 4094 25727 7067 4094 25728 7065 4094 25729 7061 4094 25730 7065 4094 25731 7063 4094 25732 7061 4094 25733 7061 4094 25734 7059 4094 25735 7057 4094 25736 7057 4094 25737 7055 4094 25738 7053 4094 25739 7053 4094 25740 7051 4094 25741 7045 4094 25742 7051 4094 25743 7049 4094 25744 7045 4094 25745 7049 4094 25746 7047 4094 25747 7045 4094 25748 7045 4094 25749 7043 4094 25750 7041 4094 25751 7041 4094 25752 7039 4094 25753 7045 4094 25754 7039 4094 25755 7037 4094 25756 7045 4094 25757 7037 4094 25758 7035 4094 25759 7033 4094 25760 7033 4094 25761 7031 4094 25762 7029 4094 25763 7029 4094 25764 7027 4094 25765 7021 4094 25766 7027 4094 25767 7025 4094 25768 7021 4094 25769 7025 4094 25770 7023 4094 25771 7021 4094 25772 7021 4094 25773 7019 4094 25774 7017 4094 25775 7017 4094 25776 7015 4094 25777 7021 4094 25778 7015 4094 25779 7013 4094 25780 7021 4094 25781 7013 4094 25782 7011 4094 25783 7005 4094 25784 7011 4094 25785 7009 4094 25786 7005 4094 25787 7009 4094 25788 7007 4094 25789 7005 4094 25790 7005 4094 25791 7003 4094 25792 7001 4094 25793 7001 4094 25794 6999 4094 25795 6997 4094 25796 6997 4094 25797 6995 4094 25798 6993 4094 25799 6993 4094 25800 6991 4094 25801 6997 4094 25802 6991 4094 25803 6989 4094 25804 6997 4094 25805 6989 4094 25806 6987 4094 25807 6985 4094 25808 6985 4094 25809 6983 4094 25810 6989 4094 25811 6983 4094 25812 6981 4094 25813 6989 4094 25814 6981 4094 25815 6979 4094 25816 6977 4094 25817 6977 4094 25818 6975 4094 25819 6973 4094 25820 6973 4094 25821 6971 4094 25822 6969 4094 25823 6969 4094 25824 6967 4094 25825 6965 4094 25826 6965 4094 25827 6963 4094 25828 6961 4094 25829 6961 4094 25830 6959 4094 25831 6965 4094 25832 6959 4094 25833 6957 4094 25834 6965 4094 25835 6957 4094 25836 6955 4094 25837 6949 4094 25838 6955 4094 25839 6953 4094 25840 6949 4094 25841 6953 4094 25842 6951 4094 25843 6949 4094 25844 6949 4094 25845 6947 4094 25846 6945 4094 25847 6945 4094 25848 6943 4094 25849 6941 4094 25850 6941 4094 25851 6939 4094 25852 6933 4094 25853 6939 4094 25854 6937 4094 25855 6933 4094 25856 6937 4094 25857 6935 4094 25858 6933 4094 25859 6933 4094 25860 6931 4094 25861 6929 4094 25862 6929 4094 25863 6927 4094 25864 6933 4094 25865 6927 4094 25866 6925 4094 25867 6933 4094 25868 6925 4094 25869 6923 4094 25870 6921 4094 25871 6921 4094 25872 6919 4094 25873 6917 4094 25874 6917 4094 25875 6915 4094 25876 6913 4094 25877 6913 4094 25878 6911 4094 25879 6917 4094 25880 6911 4094 25881 6909 4094 25882 6917 4094 25883 6909 4094 25884 6907 4094 25885 6905 4094 25886 6905 4094 25887 6903 4094 25888 6901 4094 25889 6901 4094 25890 6899 4094 25891 6897 4094 25892 6897 4094 25893 6895 4094 25894 6893 4094 25895 6893 4094 25896 6891 4094 25897 6885 4094 25898 6891 4094 25899 6889 4094 25900 6885 4094 25901 6889 4094 25902 6887 4094 25903 6885 4094 25904 6885 4094 25905 6883 4094 25906 6877 4094 25907 6883 4094 25908 6881 4094 25909 6877 4094 25910 6881 4094 25911 6879 4094 25912 6877 4094 25913 6877 4094 25914 6875 4094 25915 6873 4094 25916 6873 4094 25917 6871 4094 25918 6869 4094 25919 6869 4094 25920 6867 4094 25921 6861 4094 25922 6867 4094 25923 6865 4094 25924 6861 4094 25925 6865 4094 25926 6863 4094 25927 6861 4094 25928 6861 4094 25929 6859 4094 25930 6857 4094 25931 6857 4094 25932 6855 4094 25933 6861 4094 25934 6855 4094 25935 6853 4094 25936 6861 4094 25937 6853 4094 25938 6851 4094 25939 6845 4094 25940 6851 4094 25941 6849 4094 25942 6845 4094 25943 6849 4094 25944 6847 4094 25945 6845 4094 25946 6845 4094 25947 6843 4094 25948 6841 4094 25949 6841 4094 25950 6839 4094 25951 6837 4094 25952 6837 4094 25953 6835 4094 25954 6833 4094 25955 6833 4094 25956 6831 4094 25957 6829 4094 25958 6829 4094 25959 6827 4094 25960 6825 4094 25961 6825 4094 25962 6823 4094 25963 6821 4094 25964 6821 4094 25965 6819 4094 25966 6817 4094 25967 6817 4094 25968 6815 4094 25969 6821 4094 25970 6815 4094 25971 6813 4094 25972 6821 4094 25973 6813 4094 25974 6811 4094 25975 6805 4094 25976 6811 4094 25977 6809 4094 25978 6805 4094 25979 6809 4094 25980 6807 4094 25981 6805 4094 25982 6805 4094 25983 6803 4094 25984 6801 4094 25985 6801 4094 25986 6799 4094 25987 6797 4094 25988 6797 4094 25989 6795 4094 25990 6793 4094 25991 6793 4094 25992 6791 4094 25993 6797 4094 25994 6791 4094 25995 6789 4094 25996 6797 4094 25997 6789 4094 25998 6787 4094 25999 6785 4094 26000 6785 4094 26001 6783 4094 26002 6781 4094 26003 6781 4094 26004 6779 4094 26005 6777 4094 26006 6777 4094 26007 6775 4094 26008 6781 4094 26009 6775 4094 26010 6773 4094 26011 6781 4094 26012 6773 4094 26013 6771 4094 26014 6769 4094 26015 6769 4094 26016 6767 4094 26017 6773 4094 26018 6767 4094 26019 6765 4094 26020 6773 4094 26021 6765 4094 26022 6763 4094 26023 6757 4094 26024 6763 4094 26025 6761 4094 26026 6757 4094 26027 6761 4094 26028 6759 4094 26029 6757 4094 26030 6757 4094 26031 6755 4094 26032 6749 4094 26033 6755 4094 26034 6753 4094 26035 6749 4094 26036 6753 4094 26037 6751 4094 26038 6749 4094 26039 6749 4094 26040 6747 4094 26041 6745 4094 26042 6745 4094 26043 6743 4094 26044 6749 4094 26045 6743 4094 26046 6741 4094 26047 6749 4094 26048 6741 4094 26049 6739 4094 26050 6737 4094 26051 6737 4094 26052 6735 4094 26053 6741 4094 26054 6735 4094 26055 6733 4094 26056 6741 4094 26057 6733 4094 26058 6731 4094 26059 6729 4094 26060 6729 4094 26061 6727 4094 26062 6733 4094 26063 6727 4094 26064 6725 4094 26065 6733 4094 26066 6725 4094 26067 6723 4094 26068 6721 4094 26069 6721 4094 26070 6719 4094 26071 6725 4094 26072 6719 4094 26073 6717 4094 26074 6725 4094 26075 6717 4094 26076 6715 4094 26077 6709 4094 26078 6715 4094 26079 6713 4094 26080 6709 4094 26081 6713 4094 26082 6711 4094 26083 6709 4094 26084 6709 4094 26085 6707 4094 26086 6705 4094 26087 6705 4094 26088 6703 4094 26089 6701 4094 26090 6701 4094 26091 6699 4094 26092 6697 4094 26093 6697 4094 26094 6695 4094 26095 6701 4094 26096 6695 4094 26097 6693 4094 26098 6701 4094 26099 6693 4094 26100 6691 4094 26101 6689 4094 26102 6689 4094 26103 6687 4094 26104 6685 4094 26105 6685 4094 26106 6683 4094 26107 6681 4094 26108 6681 4094 26109 6679 4094 26110 6685 4094 26111 6679 4094 26112 6677 4094 26113 6685 4094 26114 6677 4094 26115 6675 4094 26116 6673 4094 26117 6673 4094 26118 6671 4094 26119 6677 4094 26120 6671 4094 26121 6669 4094 26122 6677 4094 26123 6669 4094 26124 6667 4094 26125 6661 4094 26126 6667 4094 26127 6665 4094 26128 6661 4094 26129 6665 4094 26130 6663 4094 26131 6661 4094 26132 6661 4094 26133 6659 4094 26134 6657 4094 26135 6657 4094 26136 6655 4094 26137 6653 4094 26138 6653 4094 26139 6651 4094 26140 6645 4094 26141 6651 4094 26142 6649 4094 26143 6645 4094 26144 6649 4094 26145 6647 4094 26146 6645 4094 26147 6645 4094 26148 6643 4094 26149 6637 4094 26150 6643 4094 26151 6641 4094 26152 6637 4094 26153 6641 4094 26154 6639 4094 26155 6637 4094 26156 6637 4094 26157 6635 4094 26158 6633 4094 26159 6633 4094 26160 6631 4094 26161 6629 4094 26162 6629 4094 26163 6627 4094 26164 6621 4094 26165 6627 4094 26166 6625 4094 26167 6621 4094 26168 6625 4094 26169 6623 4094 26170 6621 4094 26171 6621 4094 26172 6619 4094 26173 6613 4094 26174 6619 4094 26175 6617 4094 26176 6613 4094 26177 6617 4094 26178 6615 4094 26179 6613 4094 26180 6613 4094 26181 6611 4094 26182 6609 4094 26183 6609 4094 26184 6607 4094 26185 6613 4094 26186 6607 4094 26187 6605 4094 26188 6613 4094 26189 6605 4094 26190 6603 4094 26191 6601 4094 26192 6601 4094 26193 6599 4094 26194 6597 4094 26195 6597 4094 26196 6595 4094 26197 6589 4094 26198 6595 4094 26199 6593 4094 26200 6589 4094 26201 6593 4094 26202 6591 4094 26203 6589 4094 26204 6589 4094 26205 6587 4094 26206 6585 4094 26207 6585 4094 26208 6583 4094 26209 6581 4094 26210 6581 4094 26211 6579 4094 26212 6573 4094 26213 6579 4094 26214 6577 4094 26215 6573 4094 26216 6577 4094 26217 6575 4094 26218 6573 4094 26219 6573 4094 26220 6571 4094 26221 6569 4094 26222 6569 4094 26223 6567 4094 26224 6565 4094 26225 6565 4094 26226 6563 4094 26227 6561 4094 26228 6561 4094 26229 6559 4094 26230 6557 4094 26231 6557 4094 26232 6555 4094 26233 6549 4094 26234 6555 4094 26235 6553 4094 26236 6549 4094 26237 6553 4094 26238 6551 4094 26239 6549 4094 26240 6549 4094 26241 6547 4094 26242 6545 4094 26243 6545 4094 26244 6543 4094 26245 6541 4094 26246 6541 4094 26247 6539 4094 26248 6537 4094 26249 6537 4094 26250 6535 4094 26251 6541 4094 26252 6535 4094 26253 6533 4094 26254 6541 4094 26255 6533 4094 26256 6531 4094 26257 6525 4094 26258 6531 4094 26259 6529 4094 26260 6525 4094 26261 6529 4094 26262 6527 4094 26263 6525 4094 26264 6525 4094 26265 6523 4094 26266 6521 4094 26267 6521 4094 26268 6519 4094 26269 6517 4094 26270 6517 4094 26271 6515 4094 26272 6509 4094 26273 6515 4094 26274 6513 4094 26275 6509 4094 26276 6513 4094 26277 6511 4094 26278 6509 4094 26279 6509 4094 26280 6507 4094 26281 6501 4094 26282 6507 4094 26283 6505 4094 26284 6501 4094 26285 6505 4094 26286 6503 4094 26287 6501 4094 26288 6501 4094 26289 6499 4094 26290 6493 4094 26291 6499 4094 26292 6497 4094 26293 6493 4094 26294 6497 4094 26295 6495 4094 26296 6493 4094 26297 6493 4094 26298 6491 4094 26299 6485 4094 26300 6491 4094 26301 6489 4094 26302 6485 4094 26303 6489 4094 26304 6487 4094 26305 6485 4094 26306 6485 4094 26307 6483 4094 26308 6481 4094 26309 6481 4094 26310 6479 4094 26311 6485 4094 26312 6479 4094 26313 6477 4094 26314 6485 4094 26315 6477 4094 26316 6475 4094 26317 6473 4094 26318 6473 4094 26319 6471 4094 26320 6469 4094 26321 6469 4094 26322 6467 4094 26323 6461 4094 26324 6467 4094 26325 6465 4094 26326 6461 4094 26327 6465 4094 26328 6463 4094 26329 6461 4094 26330 6461 4094 26331 6459 4094 26332 6457 4094 26333 6457 4094 26334 6455 4094 26335 6461 4094 26336 6455 4094 26337 6453 4094 26338 6461 4094 26339 6453 4094 26340 6451 4094 26341 6449 4094 26342 6449 4094 26343 6447 4094 26344 6453 4094 26345 6447 4094 26346 6445 4094 26347 6453 4094 26348 6445 4094 26349 6443 4094 26350 6441 4094 26351 6441 4094 26352 6439 4094 26353 6437 4094 26354 6437 4094 26355 6435 4094 26356 6433 4094 26357 6433 4094 26358 6431 4094 26359 6429 4094 26360 6429 4094 26361 6427 4094 26362 6425 4094 26363 6425 4094 26364 6423 4094 26365 6429 4094 26366 6423 4094 26367 6421 4094 26368 6429 4094 26369 6421 4094 26370 6419 4094 26371 6413 4094 26372 6419 4094 26373 6417 4094 26374 6413 4094 26375 6417 4094 26376 6415 4094 26377 6413 4094 26378 6413 4094 26379 6411 4094 26380 6409 4094 26381 6409 4094 26382 6407 4094 26383 6413 4094 26384 6407 4094 26385 6405 4094 26386 6413 4094 26387 6405 4094 26388 6403 4094 26389 6401 4094 26390 6401 4094 26391 6399 4094 26392 6397 4094 26393 6397 4094 26394 6395 4094 26395 6393 4094 26396 6393 4094 26397 6391 4094 26398 6397 4094 26399 6391 4094 26400 6389 4094 26401 6397 4094 26402 6389 4094 26403 6387 4094 26404 6385 4094 26405 6385 4094 26406 6383 4094 26407 6389 4094 26408 6383 4094 26409 6381 4094 26410 6389 4094 26411 6381 4094 26412 6379 4094 26413 6377 4094 26414 6377 4094 26415 6375 4094 26416 6373 4094 26417 6373 4094 26418 6371 4094 26419 6369 4094 26420 6369 4094 26421 6367 4094 26422 6373 4094 26423 6367 4094 26424 6365 4094 26425 6373 4094 26426 6365 4094 26427 6363 4094 26428 6357 4094 26429 6363 4094 26430 6361 4094 26431 6357 4094 26432 6361 4094 26433 6359 4094 26434 6357 4094 26435 6357 4094 26436 6355 4094 26437 6353 4094 26438 6353 4094 26439 6351 4094 26440 6349 4094 26441 6349 4094 26442 6347 4094 26443 6341 4094 26444 6347 4094 26445 6345 4094 26446 6341 4094 26447 6345 4094 26448 6343 4094 26449 6341 4094 26450 6341 4094 26451 6339 4094 26452 6333 4094 26453 6339 4094 26454 6337 4094 26455 6333 4094 26456 6337 4094 26457 6335 4094 26458 6333 4094 26459 6333 4094 26460 6331 4094 26461 6329 4094 26462 6329 4094 26463 6327 4094 26464 6325 4094 26465 6325 4094 26466 6323 4094 26467 6317 4094 26468 6323 4094 26469 6321 4094 26470 6317 4094 26471 6321 4094 26472 6319 4094 26473 6317 4094 26474 6317 4094 26475 6315 4094 26476 6309 4094 26477 6315 4094 26478 6313 4094 26479 6309 4094 26480 6313 4094 26481 6311 4094 26482 6309 4094 26483 6309 4094 26484 6307 4094 26485 6305 4094 26486 6305 4094 26487 6303 4094 26488 6309 4094 26489 6303 4094 26490 6301 4094 26491 6309 4094 26492 6301 4094 26493 6299 4094 26494 6297 4094 26495 6297 4094 26496 6295 4094 26497 6293 4094 26498 6293 4094 26499 6291 4094 26500 6289 4094 26501 6289 4094 26502 6287 4094 26503 6293 4094 26504 6287 4094 26505 6285 4094 26506 6293 4094 26507 6285 4094 26508 6283 4094 26509 6277 4094 26510 6283 4094 26511 6281 4094 26512 6277 4094 26513 6281 4094 26514 6279 4094 26515 6277 4094 26516 6277 4094 26517 6275 4094 26518 6273 4094 26519 6273 4094 26520 6271 4094 26521 6277 4094 26522 6271 4094 26523 6269 4094 26524 6277 4094 26525 6269 4094 26526 6267 4094 26527 6265 4094 26528 6265 4094 26529 6263 4094 26530 6261 4094 26531 6261 4094 26532 6259 4094 26533 6257 4094 26534 6257 4094 26535 6255 4094 26536 6261 4094 26537 6255 4094 26538 6253 4094 26539 6261 4094 26540 6253 4094 26541 6251 4094 26542 6249 4094 26543 6249 4094 26544 6247 4094 26545 6253 4094 26546 6247 4094 26547 6245 4094 26548 6253 4094 26549 6245 4094 26550 6243 4094 26551 6237 4094 26552 6243 4094 26553 6241 4094 26554 6237 4094 26555 6241 4094 26556 6239 4094 26557 6237 4094 26558 6237 4094 26559 6235 4094 26560 6233 4094 26561 6233 4094 26562 6231 4094 26563 6229 4094 26564 6229 4094 26565 6227 4094 26566 6221 4094 26567 6227 4094 26568 6225 4094 26569 6221 4094 26570 6225 4094 26571 6223 4094 26572 6221 4094 26573 6221 4094 26574 6219 4094 26575 6217 4094 26576 6217 4094 26577 6215 4094 26578 6213 4094 26579 6213 4094 26580 6211 4094 26581 6209 4094 26582 6209 4094 26583 6207 4094 26584 6205 4094 26585 6205 4094 26586 6203 4094 26587 6201 4094 26588 6201 4094 26589 6199 4094 26590 6205 4094 26591 6199 4094 26592 6197 4094 26593 6205 4094 26594 6197 4094 26595 6195 4094 26596 6193 4094 26597 6193 4094 26598 6191 4094 26599 6189 4094 26600 6189 4094 26601 6187 4094 26602 6185 4094 26603 6185 4094 26604 6183 4094 26605 6181 4094 26606 6181 4094 26607 6179 4094 26608 6177 4094 26609 6177 4094 26610 6175 4094 26611 6173 4094 26612 6173 4094 26613 6171 4094 26614 6165 4094 26615 6171 4094 26616 6169 4094 26617 6165 4094 26618 6169 4094 26619 6167 4094 26620 6165 4094 26621 6165 4094 26622 6163 4094 26623 6157 4094 26624 6163 4094 26625 6161 4094 26626 6157 4094 26627 6161 4094 26628 6159 4094 26629 6157 4094 26630 6157 4094 26631 6155 4094 26632 6153 4094 26633 6153 4094 26634 6151 4094 26635 6157 4094 26636 6151 4094 26637 6149 4094 26638 6157 4094 26639 6149 4094 26640 6147 4094 26641 6141 4094 26642 6147 6113 26643 6145 6113 26644 6141 6113 26645 6145 4094 26646 6143 4094 26647 6141 4094 26648 6141 4094 26649 6139 4094 26650 6133 4094 26651 6139 4094 26652 6137 4094 26653 6133 4094 26654 6137 4094 26655 6135 4094 26656 6133 4094 26657 6133 4094 26658 6131 4094 26659 6129 4094 26660 6129 4094 26661 6127 4094 26662 6133 4094 26663 6127 4094 26664 6125 4094 26665 6133 4094 26666 6125 4094 26667 6123 4094 26668 6121 4094 26669 6121 4094 26670 6119 4094 26671 6125 4094 26672 6119 4094 26673 6117 4094 26674 6125 4094 26675 6117 4094 26676 6115 4094 26677 6113 4094 26678 6113 4094 26679 6111 4094 26680 6109 4094 26681 6109 4094 26682 6107 4094 26683 6105 4094 26684 6105 4094 26685 6103 4094 26686 6101 4094 26687 6101 4094 26688 6099 4094 26689 6097 4094 26690 6097 4094 26691 6095 4094 26692 6093 4094 26693 6093 4094 26694 6091 4094 26695 6085 4094 26696 6091 4094 26697 6089 4094 26698 6085 4094 26699 6089 4094 26700 6087 4094 26701 6085 4094 26702 6085 4094 26703 6083 4094 26704 6077 4094 26705 6083 4094 26706 6081 4094 26707 6077 4094 26708 6081 4094 26709 6079 4094 26710 6077 4094 26711 6077 4094 26712 6075 4094 26713 6073 4094 26714 6073 4094 26715 6071 4094 26716 6069 4094 26717 6069 4094 26718 6067 4094 26719 6065 4094 26720 6065 4094 26721 6063 4094 26722 6061 4094 26723 6061 4094 26724 6059 4094 26725 6053 4094 26726 6059 4094 26727 6057 4094 26728 6053 4094 26729 6057 4094 26730 6055 4094 26731 6053 4094 26732 6053 4094 26733 6051 4094 26734 6049 4094 26735 6049 4094 26736 6047 4094 26737 6045 4094 26738 6045 4094 26739 6043 4094 26740 6037 4094 26741 6043 4094 26742 6041 4094 26743 6037 4094 26744 6041 4094 26745 6039 4094 26746 6037 4094 26747 6037 4094 26748 6035 4094 26749 6029 4094 26750 6035 4094 26751 6033 4094 26752 6029 4094 26753 6033 4094 26754 6031 4094 26755 6029 4094 26756 6029 4094 26757 6027 4094 26758 6025 4094 26759 6025 4094 26760 6023 4094 26761 6029 4094 26762 6023 4094 26763 6021 4094 26764 6029 4094 26765 6021 4094 26766 6019 4094 26767 6013 4094 26768 6019 4094 26769 6017 4094 26770 6013 4094 26771 6017 4094 26772 6015 4094 26773 6013 4094 26774 6013 4094 26775 6011 4094 26776 6009 4094 26777 6009 4094 26778 6007 4094 26779 6013 4094 26780 6007 4094 26781 6005 4094 26782 6013 4094 26783 6005 4094 26784 6003 4094 26785 5997 4094 26786 6003 4094 26787 6001 4094 26788 5997 4094 26789 6001 4094 26790 5999 4094 26791 5997 4094 26792 5997 4094 26793 5995 4094 26794 5993 4094 26795 5993 4094 26796 5991 4094 26797 5989 4094 26798 5989 4094 26799 5987 4094 26800 5981 4094 26801 5987 4094 26802 5985 4094 26803 5981 4094 26804 5985 4094 26805 5983 4094 26806 5981 4094 26807 5981 4094 26808 5979 4094 26809 5977 4094 26810 5977 4094 26811 5975 4094 26812 5981 4094 26813 5975 4094 26814 5973 4094 26815 5981 4094 26816 5973 4094 26817 5971 4094 26818 5969 4094 26819 5969 4094 26820 5967 4094 26821 5973 4094 26822 5967 4094 26823 5965 4094 26824 5973 4094 26825 5965 4094 26826 5963 4094 26827 5961 4094 26828 5961 4094 26829 5959 4094 26830 5957 4094 26831 5957 4094 26832 5955 4094 26833 5953 4094 26834 5953 4094 26835 5951 4094 26836 5957 4094 26837 5951 4094 26838 5949 4094 26839 5957 4094 26840 5949 4094 26841 5947 4094 26842 5945 4094 26843 5945 4094 26844 5943 4094 26845 5949 4094 26846 5943 4094 26847 5941 4094 26848 5949 4094 26849 5941 4094 26850 5939 4094 26851 5933 4094 26852 5939 4094 26853 5937 4094 26854 5933 4094 26855 5937 4094 26856 5935 4094 26857 5933 4094 26858 5933 4094 26859 5931 4094 26860 5929 4094 26861 5929 4094 26862 5927 4094 26863 5933 4094 26864 5927 4094 26865 5925 4094 26866 5933 4094 26867 5925 4094 26868 5923 4094 26869 5917 4094 26870 5923 4094 26871 5921 4094 26872 5917 4094 26873 5921 4094 26874 5919 4094 26875 5917 4094 26876 5917 4094 26877 5915 4094 26878 5913 4094 26879 5913 4094 26880 5911 4094 26881 5909 4094 26882 5909 4094 26883 5907 4094 26884 5901 4094 26885 5907 4094 26886 5905 4094 26887 5901 4094 26888 5905 4094 26889 5903 4094 26890 5901 4094 26891 5901 4094 26892 5899 4094 26893 5893 4094 26894 5899 4094 26895 5897 4094 26896 5893 4094 26897 5897 4094 26898 5895 4094 26899 5893 4094 26900 5893 4094 26901 5891 4094 26902 5889 4094 26903 5889 4094 26904 5887 4094 26905 5885 4094 26906 5885 4094 26907 5883 4094 26908 5877 4094 26909 5883 4094 26910 5881 4094 26911 5877 4094 26912 5881 4094 26913 5879 4094 26914 5877 4094 26915 5877 4094 26916 5875 4094 26917 5873 4094 26918 5873 4094 26919 5871 4094 26920 5877 4094 26921 5871 4094 26922 5869 4094 26923 5877 4094 26924 5869 4094 26925 5867 4094 26926 5861 4094 26927 5867 4094 26928 5865 4094 26929 5861 4094 26930 5865 4094 26931 5863 4094 26932 5861 4094 26933 5861 4094 26934 5859 4094 26935 5857 4094 26936 5857 4094 26937 5855 4094 26938 5853 4094 26939 5853 4094 26940 5851 4094 26941 5849 4094 26942 5849 4094 26943 5847 4094 26944 5853 4094 26945 5847 4094 26946 5845 4094 26947 5853 4094 26948 5845 4094 26949 5843 4094 26950 5837 4094 26951 5843 4094 26952 5841 4094 26953 5837 4094 26954 5841 4094 26955 5839 4094 26956 5837 4094 26957 5837 4094 26958 5835 4094 26959 5829 4094 26960 5835 4094 26961 5833 4094 26962 5829 4094 26963 5833 4094 26964 5831 4094 26965 5829 4094 26966 5829 4094 26967 5827 4094 26968 5825 4094 26969 5825 4094 26970 5823 4094 26971 5829 4094 26972 5823 4094 26973 5821 4094 26974 5829 4094 26975 5821 4094 26976 5819 4094 26977 5817 4094 26978 5817 4094 26979 5815 4094 26980 5813 4094 26981 5813 4094 26982 5811 4094 26983 5805 4094 26984 5811 4094 26985 5809 4094 26986 5805 4094 26987 5809 4094 26988 5807 4094 26989 5805 4094 26990 5805 4094 26991 5803 4094 26992 5801 4094 26993 5801 4094 26994 5799 4094 26995 5805 4094 26996 5799 4094 26997 5797 4094 26998 5805 4094 26999 5797 4094 27000 5795 4094 27001 5793 4094 27002 5793 4094 27003 5791 4094 27004 5789 4094 27005 5789 4094 27006 5787 4094 27007 5785 4094 27008 5785 4094 27009 5783 4094 27010 5789 4094 27011 5783 4094 27012 5781 4094 27013 5789 4094 27014 5781 4094 27015 5779 4094 27016 5777 4094 27017 5777 4094 27018 5775 4094 27019 5781 4094 27020 5775 4094 27021 5773 4094 27022 5781 4094 27023 5773 4094 27024 5771 4094 27025 5769 4094 27026 5769 4094 27027 5767 4094 27028 5765 4094 27029 5765 4094 27030 5763 4094 27031 5761 4094 27032 5761 4094 27033 5759 4094 27034 5765 4094 27035 5759 4094 27036 5757 4094 27037 5765 4094 27038 5757 4094 27039 5755 4094 27040 5749 4094 27041 5755 4094 27042 5753 4094 27043 5749 4094 27044 5753 4094 27045 5751 4094 27046 5749 4094 27047 5749 4094 27048 5747 4094 27049 5745 4094 27050 5745 4094 27051 5743 4094 27052 5741 4094 27053 5741 4094 27054 5739 4094 27055 5737 4094 27056 5737 4094 27057 5735 4094 27058 5741 4094 27059 5735 4094 27060 5733 4094 27061 5741 4094 27062 5733 4094 27063 5731 4094 27064 5729 4094 27065 5729 4094 27066 5727 4094 27067 5725 4094 27068 5725 4094 27069 5723 4094 27070 5717 4094 27071 5723 4094 27072 5721 4094 27073 5717 4094 27074 5721 4094 27075 5719 4094 27076 5717 4094 27077 5717 4094 27078 5715 4094 27079 5713 4094 27080 5713 4094 27081 5711 4094 27082 5717 4094 27083 5711 4094 27084 5709 4094 27085 5717 4094 27086 5709 4094 27087 5707 4094 27088 5705 4094 27089 5705 4094 27090 5703 4094 27091 5709 4094 27092 5703 4094 27093 5701 4094 27094 5709 4094 27095 5701 4094 27096 5699 4094 27097 5697 4094 27098 5697 4094 27099 5695 4094 27100 5701 4094 27101 5695 4094 27102 5693 4094 27103 5701 4094 27104 5693 4094 27105 5691 4094 27106 5689 4094 27107 5689 4094 27108 5687 4094 27109 5693 4094 27110 5687 4094 27111 5685 4094 27112 5693 4094 27113 5685 4094 27114 5683 4094 27115 5677 4094 27116 5683 4094 27117 5681 4094 27118 5677 4094 27119 5681 4094 27120 5679 4094 27121 5677 4094 27122 5677 4094 27123 5675 4094 27124 5673 4094 27125 5673 4094 27126 5671 4094 27127 5677 4094 27128 5671 4094 27129 5669 4094 27130 5677 4094 27131 5669 4094 27132 5667 4094 27133 5665 4094 27134 5665 4094 27135 5663 4094 27136 5669 4094 27137 5663 4094 27138 5661 4094 27139 5669 4094 27140 5661 4094 27141 5659 4094 27142 5657 4094 27143 5657 4094 27144 5655 4094 27145 5653 4094 27146 5653 4094 27147 5651 4094 27148 5649 4094 27149 5649 4094 27150 5647 4094 27151 5653 4094 27152 5647 4094 27153 5645 4094 27154 5653 4094 27155 5645 4094 27156 5643 4094 27157 5641 4094 27158 5641 4094 27159 5639 4094 27160 5645 4094 27161 5639 4094 27162 5637 4094 27163 5645 4094 27164 5637 4094 27165 5635 4094 27166 5633 4094 27167 5633 4094 27168 5631 4094 27169 5629 4094 27170 5629 4094 27171 5627 4094 27172 5625 4094 27173 5625 4094 27174 5623 4094 27175 5629 4094 27176 5623 4094 27177 5621 4094 27178 5629 4094 27179 5621 4094 27180 5619 4094 27181 5613 4094 27182 5619 4094 27183 5617 4094 27184 5613 4094 27185 5617 4094 27186 5615 4094 27187 5613 4094 27188 5613 4094 27189 5611 4094 27190 5605 4094 27191 5611 4094 27192 5609 4094 27193 5605 4094 27194 5609 4094 27195 5607 4094 27196 5605 4094 27197 5605 4094 27198 5603 4094 27199 5601 4094 27200 5601 4094 27201 5599 4094 27202 5597 4094 27203 5597 4094 27204 5595 4094 27205 5589 4094 27206 5595 4094 27207 5593 4094 27208 5589 4094 27209 5593 4094 27210 5591 4094 27211 5589 4094 27212 5589 4094 27213 5587 4094 27214 5585 4094 27215 5585 4094 27216 5583 4094 27217 5589 4094 27218 5583 4094 27219 5581 4094 27220 5589 4094 27221 5581 4094 27222 5579 4094 27223 5577 4094 27224 5577 4094 27225 5575 4094 27226 5581 4094 27227 5575 4094 27228 5573 4094 27229 5581 4094 27230 5573 4094 27231 5571 4094 27232 5565 4094 27233 5571 4094 27234 5569 4094 27235 5565 4094 27236 5569 4094 27237 5567 4094 27238 5565 4094 27239 5565 4094 27240 5563 4094 27241 5557 4094 27242 5563 4094 27243 5561 4094 27244 5557 4094 27245 5561 4094 27246 5559 4094 27247 5557 4094 27248 5557 4094 27249 5555 4094 27250 5549 4094 27251 5555 4094 27252 5553 4094 27253 5549 4094 27254 5553 4094 27255 5551 4094 27256 5549 4094 27257 5549 4094 27258 5547 4094 27259 5541 4094 27260 5547 4094 27261 5545 4094 27262 5541 4094 27263 5545 4094 27264 5543 4094 27265 5541 4094 27266 5541 4094 27267 5539 4094 27268 5537 4094 27269 5537 4094 27270 5535 4094 27271 5541 4094 27272 5535 4094 27273 5533 4094 27274 5541 4094 27275 5533 4094 27276 5531 4094 27277 5529 4094 27278 5529 4094 27279 5527 4094 27280 5533 4094 27281 5527 4094 27282 5525 4094 27283 5533 4094 27284 5525 4094 27285 5523 4094 27286 5517 4094 27287 5523 4094 27288 5521 4094 27289 5517 4094 27290 5521 4094 27291 5519 4094 27292 5517 4094 27293 5517 4094 27294 5515 4094 27295 5509 4094 27296 5515 4094 27297 5513 4094 27298 5509 4094 27299 5513 4094 27300 5511 4094 27301 5509 4094 27302 5509 4094 27303 5507 4094 27304 5505 4094 27305 5505 4094 27306 5503 4094 27307 5501 4094 27308 5501 4094 27309 5499 4094 27310 5493 4094 27311 5499 4094 27312 5497 4094 27313 5493 4094 27314 5497 4094 27315 5495 4094 27316 5493 4094 27317 5493 4094 27318 5491 4094 27319 5489 4094 27320 5489 4094 27321 5487 4094 27322 5493 4094 27323 5487 4094 27324 5485 4094 27325 5493 4094 27326 5485 4094 27327 5483 4094 27328 5481 4094 27329 5481 4094 27330 5479 4094 27331 5485 4094 27332 5479 4094 27333 5477 4094 27334 5485 4094 27335 5477 4094 27336 5475 4094 27337 5469 4094 27338 5475 4094 27339 5473 4094 27340 5469 4094 27341 5473 4094 27342 5471 4094 27343 5469 4094 27344 5469 4094 27345 5467 4094 27346 5465 4094 27347 5465 4094 27348 5463 4094 27349 5461 4094 27350 5461 4094 27351 5459 4094 27352 5457 4094 27353 5457 4094 27354 5455 4094 27355 5453 4094 27356 5453 4094 27357 5451 4094 27358 5449 4094 27359 5449 4094 27360 5447 4094 27361 5445 4094 27362 5445 4094 27363 5443 4094 27364 5441 4094 27365 5441 4094 27366 5439 4094 27367 5445 4094 27368 5439 4094 27369 5437 4094 27370 5445 4094 27371 5437 4094 27372 5435 4094 27373 5429 4094 27374 5435 4094 27375 5433 4094 27376 5429 4094 27377 5433 4094 27378 5431 4094 27379 5429 4094 27380 5429 4094 27381 5427 4094 27382 5425 4094 27383 5425 4094 27384 5423 4094 27385 5429 4094 27386 5423 4094 27387 5421 4094 27388 5429 4094 27389 5421 4094 27390 5419 4094 27391 5417 4094 27392 5417 4094 27393 5415 4094 27394 5413 4094 27395 5413 4094 27396 5411 4094 27397 5409 4094 27398 5409 4094 27399 5407 4094 27400 5413 4094 27401 5407 4094 27402 5405 4094 27403 5413 4094 27404 5405 4094 27405 5403 4094 27406 5401 4094 27407 5401 4094 27408 5399 4094 27409 5405 4094 27410 5399 4094 27411 5397 4094 27412 5405 4094 27413 5397 4094 27414 5395 4094 27415 5393 4094 27416 5393 4094 27417 5391 4094 27418 5389 4094 27419 5389 4094 27420 5387 4094 27421 5385 4094 27422 5385 4094 27423 5383 4094 27424 5381 4094 27425 5381 4094 27426 5379 4094 27427 5373 4094 27428 5379 4094 27429 5377 4094 27430 5373 4094 27431 5377 4094 27432 5375 4094 27433 5373 4094 27434 5373 4094 27435 5371 4094 27436 5369 4094 27437 5369 4094 27438 5367 4094 27439 5365 4094 27440 5365 4094 27441 5363 4094 27442 5357 4094 27443 5363 4094 27444 5361 4094 27445 5357 4094 27446 5361 4094 27447 5359 4094 27448 5357 4094 27449 5357 4094 27450 5355 4094 27451 5353 4094 27452 5353 4094 27453 5351 4094 27454 5357 4094 27455 5351 4094 27456 5349 4094 27457 5357 4094 27458 5349 4094 27459 5347 4094 27460 5345 4094 27461 5345 4094 27462 5343 4094 27463 5341 4094 27464 5341 4094 27465 5339 4094 27466 5337 4094 27467 5337 4094 27468 5335 4094 27469 5341 4094 27470 5335 4094 27471 5333 4094 27472 5341 4094 27473 5333 4094 27474 5331 4094 27475 5325 4094 27476 5331 4094 27477 5329 4094 27478 5325 4094 27479 5329 4094 27480 5327 4094 27481 5325 4094 27482 5325 4094 27483 5323 4094 27484 5321 4094 27485 5321 4094 27486 5319 4094 27487 5317 4094 27488 5317 4094 27489 5315 4094 27490 5313 4094 27491 5313 4094 27492 5311 4094 27493 5309 4094 27494 5309 4094 27495 5307 4094 27496 5301 4094 27497 5307 4094 27498 5305 4094 27499 5301 4094 27500 5305 4094 27501 5303 4094 27502 5301 4094 27503 5301 4094 27504 5299 4094 27505 5293 4094 27506 5299 4094 27507 5297 4094 27508 5293 4094 27509 5297 4094 27510 5295 4094 27511 5293 4094 27512 5293 4094 27513 5291 4094 27514 5289 4094 27515 5289 4094 27516 5287 4094 27517 5285 4094 27518 5285 4094 27519 5283 4094 27520 5281 4094 27521 5281 4094 27522 5279 4094 27523 5285 4094 27524 5279 4094 27525 5277 4094 27526 5285 4094 27527 5277 4094 27528 5275 4094 27529 5269 4094 27530 5275 4094 27531 5273 4094 27532 5269 4094 27533 5273 4094 27534 5271 4094 27535 5269 4094 27536 5269 4094 27537 5267 4094 27538 5265 4094 27539 5265 4094 27540 5263 4094 27541 5269 4094 27542 5263 4094 27543 5261 4094 27544 5269 4094 27545 5261 4094 27546 5259 4094 27547 5257 4094 27548 5257 4094 27549 5255 4094 27550 5253 4094 27551 5253 4094 27552 5251 4094 27553 5245 4094 27554 5251 4094 27555 5249 4094 27556 5245 4094 27557 5249 4094 27558 5247 4094 27559 5245 4094 27560 5245 4094 27561 5243 4094 27562 5241 4094 27563 5241 4094 27564 5239 4094 27565 5245 4094 27566 5239 4094 27567 5237 4094 27568 5245 4094 27569 5237 4094 27570 5235 4094 27571 5233 4094 27572 5233 4094 27573 5231 4094 27574 5229 4094 27575 5229 4094 27576 5227 4094 27577 5225 4094 27578 5225 4094 27579 5223 4094 27580 5229 4094 27581 5223 4094 27582 5221 4094 27583 5229 4094 27584 5221 4094 27585 5219 4094 27586 5217 4094 27587 5217 4094 27588 5215 4094 27589 5221 4094 27590 5215 4094 27591 5213 4094 27592 5221 4094 27593 5213 4094 27594 5211 4094 27595 5209 4094 27596 5209 4094 27597 5207 4094 27598 5213 4094 27599 5207 4094 27600 5205 4094 27601 5213 4094 27602 5205 4094 27603 5203 4094 27604 5201 4094 27605 5201 4094 27606 5199 4094 27607 5205 4094 27608 5199 4094 27609 5197 4094 27610 5205 4094 27611 5197 4094 27612 5195 4094 27613 5193 4094 27614 5193 4094 27615 5191 4094 27616 5189 4094 27617 5189 4094 27618 5187 4094 27619 5181 4094 27620 5187 4094 27621 5185 4094 27622 5181 4094 27623 5185 4094 27624 5183 4094 27625 5181 4094 27626 5181 4094 27627 5179 4094 27628 5177 4094 27629 5177 4094 27630 5175 4094 27631 5181 4094 27632 5175 4094 27633 5173 4094 27634 5181 4094 27635 5173 4094 27636 5171 4094 27637 5165 4094 27638 5171 4094 27639 5169 4094 27640 5165 4094 27641 5169 4094 27642 5167 4094 27643 5165 4094 27644 5165 4094 27645 5163 4094 27646 5161 4094 27647 5161 4094 27648 5159 4094 27649 5157 4094 27650 5157 4094 27651 5155 4094 27652 5153 4094 27653 5153 4094 27654 5151 4094 27655 5157 4094 27656 5151 4094 27657 5149 4094 27658 5157 4094 27659 5149 4094 27660 5147 4094 27661 5145 4094 27662 5145 4094 27663 5143 4094 27664 5141 4094 27665 5141 4094 27666 5139 4094 27667 5137 4094 27668 5137 4094 27669 5135 4094 27670 5133 4094 27671 5133 4094 27672 5131 4094 27673 5129 4094 27674 5129 4094 27675 5127 4094 27676 5133 4094 27677 5127 4094 27678 5125 4094 27679 5133 4094 27680 5125 4094 27681 5123 4094 27682 5121 4094 27683 5121 4094 27684 5119 4094 27685 5125 4094 27686 5119 4094 27687 5117 4094 27688 5125 4094 27689 5117 4094 27690 5115 4094 27691 5113 4094 27692 5113 4094 27693 5111 4094 27694 5117 4094 27695 5111 4094 27696 5109 4094 27697 5117 4094 27698 5109 4094 27699 5107 4094 27700 5105 4094 27701 5105 4094 27702 5103 4094 27703 5109 4094 27704 5103 4094 27705 5101 4094 27706 5109 4094 27707 5101 4094 27708 5099 4094 27709 5097 4094 27710 5097 4094 27711 5095 4094 27712 5093 4094 27713 5093 4094 27714 5091 4094 27715 5085 4094 27716 5091 4094 27717 5089 4094 27718 5085 4094 27719 5089 4094 27720 5087 4094 27721 5085 4094 27722 5085 4094 27723 5083 4094 27724 5081 4094 27725 5081 4094 27726 5079 4094 27727 5077 4094 27728 5077 4094 27729 5075 4094 27730 5073 4094 27731 5073 4094 27732 5071 4094 27733 5077 4094 27734 5071 4094 27735 5069 4094 27736 5077 4094 27737 5069 4094 27738 5067 4094 27739 5061 4094 27740 5067 4094 27741 5065 4094 27742 5061 4094 27743 5065 4094 27744 5063 4094 27745 5061 4094 27746 5061 4094 27747 5059 4094 27748 5057 4094 27749 5057 4094 27750 5055 4094 27751 5061 4094 27752 5055 4094 27753 5053 4094 27754 5061 4094 27755 5053 4094 27756 5051 4094 27757 5049 4094 27758 5049 4094 27759 5047 4094 27760 5045 4094 27761 5045 4094 27762 5043 4094 27763 5037 4094 27764 5043 4094 27765 5041 4094 27766 5037 4094 27767 5041 4094 27768 5039 4094 27769 5037 4094 27770 5037 4094 27771 5035 4094 27772 5033 4094 27773 5033 4094 27774 5031 4094 27775 5037 4094 27776 5031 4094 27777 5029 4094 27778 5037 4094 27779 5029 4094 27780 5027 4094 27781 5021 4094 27782 5027 4094 27783 5025 4094 27784 5021 4094 27785 5025 4094 27786 5023 4094 27787 5021 4094 27788 5021 4094 27789 5019 4094 27790 5013 4094 27791 5019 4094 27792 5017 4094 27793 5013 4094 27794 5017 4094 27795 5015 4094 27796 5013 4094 27797 5013 4094 27798 5011 4094 27799 5009 4094 27800 5009 4094 27801 5007 4094 27802 5005 4094 27803 5005 4094 27804 5003 4094 27805 4997 4094 27806 5003 4094 27807 5001 4094 27808 4997 4094 27809 5001 4094 27810 4999 4094 27811 4997 4094 27812 4997 4094 27813 4995 4094 27814 4993 4094 27815 4993 4094 27816 4991 4094 27817 4997 4094 27818 4991 4094 27819 4989 4094 27820 4997 4094 27821 4989 4094 27822 4987 4094 27823 4985 4094 27824 4985 4094 27825 4983 4094 27826 4981 4094 27827 4981 4094 27828 4979 4094 27829 4973 4094 27830 4979 4094 27831 4977 4094 27832 4973 4094 27833 4977 4094 27834 4975 4094 27835 4973 4094 27836 4973 4094 27837 4971 4094 27838 4969 4094 27839 4969 4094 27840 4967 4094 27841 4973 4094 27842 4967 4094 27843 4965 4094 27844 4973 4094 27845 4965 4094 27846 4963 4094 27847 4957 4094 27848 4963 4094 27849 4961 4094 27850 4957 4094 27851 4961 4094 27852 4959 4094 27853 4957 4094 27854 4957 4094 27855 4955 4094 27856 4953 4094 27857 4953 4094 27858 4951 4094 27859 4949 4094 27860 4949 4094 27861 4947 4094 27862 4945 4094 27863 4945 4094 27864 4943 4094 27865 4949 4094 27866 4943 4094 27867 4941 4094 27868 4949 4094 27869 4941 4094 27870 4939 4094 27871 4937 4094 27872 4937 4094 27873 4935 4094 27874 4941 4094 27875 4935 4094 27876 4933 4094 27877 4941 4094 27878 4933 4094 27879 4931 4094 27880 4929 4094 27881 4929 4094 27882 4927 4094 27883 4925 4094 27884 4925 4094 27885 4923 4094 27886 4921 4094 27887 4921 4094 27888 4919 4094 27889 4917 4094 27890 4917 4094 27891 4915 4094 27892 4913 4094 27893 4913 4094 27894 4911 4094 27895 4917 4094 27896 4911 4094 27897 4909 4094 27898 4917 4094 27899 4909 4094 27900 4907 4094 27901 4901 4094 27902 4907 4094 27903 4905 4094 27904 4901 4094 27905 4905 4094 27906 4903 4094 27907 4901 4094 27908 4901 4094 27909 4899 4094 27910 4897 4094 27911 4897 4094 27912 4895 4094 27913 4893 4094 27914 4893 4094 27915 4891 4094 27916 4885 4094 27917 4891 4094 27918 4889 4094 27919 4885 4094 27920 4889 4094 27921 4887 4094 27922 4885 4094 27923 4885 4094 27924 4883 4094 27925 4881 4094 27926 4881 4094 27927 4879 4094 27928 4885 4094 27929 4879 4094 27930 4877 4094 27931 4885 4094 27932 4877 4094 27933 4875 4094 27934 4873 4094 27935 4873 4094 27936 4871 4094 27937 4869 4094 27938 4869 4094 27939 4867 4094 27940 4865 4094 27941 4865 4094 27942 4863 4094 27943 4869 4094 27944 4863 4094 27945 4861 4094 27946 4869 4094 27947 4861 4094 27948 4859 4094 27949 4857 4094 27950 4857 4094 27951 4855 4094 27952 4853 4094 27953 4853 4094 27954 4851 4094 27955 4849 4094 27956 4849 4094 27957 4847 4094 27958 4845 4094 27959 4845 4094 27960 4843 4094 27961 4837 4094 27962 4843 4094 27963 4841 4094 27964 4837 4094 27965 4841 4094 27966 4839 4094 27967 4837 4094 27968 4837 4094 27969 4835 4094 27970 4829 4094 27971 4835 4094 27972 4833 4094 27973 4829 4094 27974 4833 4094 27975 4831 4094 27976 4829 4094 27977 4829 4094 27978 4827 4094 27979 4825 4094 27980 4825 4094 27981 4823 4094 27982 4821 4094 27983 4821 4094 27984 4819 4094 27985 4813 4094 27986 4819 4094 27987 4817 4094 27988 4813 4094 27989 4817 4094 27990 4815 4094 27991 4813 4094 27992 4813 4094 27993 4811 4094 27994 4809 4094 27995 4809 4094 27996 4807 4094 27997 4813 4094 27998 4807 4094 27999 4805 4094 28000 4813 4094 28001 4805 4094 28002 4803 4094 28003 4797 4094 28004 4803 4094 28005 4801 4094 28006 4797 4094 28007 4801 4094 28008 4799 4094 28009 4797 4094 28010 4797 4094 28011 4795 4094 28012 4793 4094 28013 4793 4094 28014 4791 4094 28015 4789 4094 28016 4789 4094 28017 4787 4094 28018 4785 4094 28019 4785 4094 28020 4783 4094 28021 4781 4094 28022 4781 4094 28023 4779 4094 28024 4777 4094 28025 4777 4094 28026 4775 4094 28027 4773 4094 28028 4773 4094 28029 4771 4094 28030 4769 4094 28031 4769 4094 28032 4767 4094 28033 4773 4094 28034 4767 4094 28035 4765 4094 28036 4773 4094 28037 4765 4094 28038 4763 4094 28039 4757 4094 28040 4763 4094 28041 4761 4094 28042 4757 4094 28043 4761 4094 28044 4759 4094 28045 4757 4094 28046 4757 4094 28047 4755 4094 28048 4753 4094 28049 4753 4094 28050 4751 4094 28051 4749 4094 28052 4749 4094 28053 4747 4094 28054 4745 4094 28055 4745 4094 28056 4743 4094 28057 4749 4094 28058 4743 4094 28059 4741 4094 28060 4749 4094 28061 4741 4094 28062 4739 4094 28063 4737 4094 28064 4737 4094 28065 4735 4094 28066 4733 4094 28067 4733 4094 28068 4731 4094 28069 4729 4094 28070 4729 4094 28071 4727 4094 28072 4733 4094 28073 4727 4094 28074 4725 4094 28075 4733 4094 28076 4725 4094 28077 4723 4094 28078 4721 4094 28079 4721 4094 28080 4719 4094 28081 4725 4094 28082 4719 4094 28083 4717 4094 28084 4725 4094 28085 4717 4094 28086 4715 4094 28087 4709 4094 28088 4715 4094 28089 4713 4094 28090 4709 4094 28091 4713 4094 28092 4711 4094 28093 4709 4094 28094 4709 4094 28095 4707 4094 28096 4701 4094 28097 4707 4094 28098 4705 4094 28099 4701 4094 28100 4705 4094 28101 4703 4094 28102 4701 4094 28103 4701 4094 28104 4699 4094 28105 4697 4094 28106 4697 4094 28107 4695 4094 28108 4701 4094 28109 4695 4094 28110 4693 4094 28111 4701 4094 28112 4693 4094 28113 4691 4094 28114 4689 4094 28115 4689 4094 28116 4687 4094 28117 4693 4094 28118 4687 4094 28119 4685 4094 28120 4693 4094 28121 4685 4094 28122 4683 4094 28123 4681 4094 28124 4681 4094 28125 4679 4094 28126 4685 4094 28127 4679 4094 28128 4677 4094 28129 4685 4094 28130 4677 4094 28131 4675 4094 28132 4673 4094 28133 4673 4094 28134 4671 4094 28135 4677 4094 28136 4671 4094 28137 4669 4094 28138 4677 4094 28139 4669 4094 28140 4667 4094 28141 4661 4094 28142 4667 4094 28143 4665 4094 28144 4661 4094 28145 4665 4094 28146 4663 4094 28147 4661 4094 28148 4661 4094 28149 4659 4094 28150 4657 4094 28151 4657 4094 28152 4655 4094 28153 4653 4094 28154 4653 4094 28155 4651 4094 28156 4649 4094 28157 4649 4094 28158 4647 4094 28159 4653 4094 28160 4647 4094 28161 4645 4094 28162 4653 4094 28163 4645 4094 28164 4643 4094 28165 4641 4094 28166 4641 4094 28167 4639 4094 28168 4637 4094 28169 4637 4094 28170 4635 4094 28171 4633 4094 28172 4633 4094 28173 4631 4094 28174 4637 4094 28175 4631 4094 28176 4629 4094 28177 4637 4094 28178 4629 4094 28179 4627 4094 28180 4625 4094 28181 4625 4094 28182 4623 4094 28183 4629 4094 28184 4623 4094 28185 4621 4094 28186 4629 4094 28187 4621 4094 28188 4619 4094 28189 4613 4094 28190 4619 4094 28191 4617 4094 28192 4613 4094 28193 4617 4094 28194 4615 4094 28195 4613 4094 28196 4613 4094 28197 4611 4094 28198 4609 4094 28199 4609 4094 28200 4607 4094 28201 4605 4094 28202 4605 4094 28203 4603 4094 28204 4597 4094 28205 4603 4094 28206 4601 4094 28207 4597 4094 28208 4601 4094 28209 4599 4094 28210 4597 4094 28211 4597 4094 28212 4595 4094 28213 4589 4094 28214 4595 4094 28215 4593 4094 28216 4589 4094 28217 4593 4094 28218 4591 4094 28219 4589 4094 28220 4589 4094 28221 4587 4094 28222 4585 4094 28223 4585 4094 28224 4583 4094 28225 4581 4094 28226 4581 4094 28227 4579 4094 28228 4573 4094 28229 4579 4094 28230 4577 4094 28231 4573 4094 28232 4577 4094 28233 4575 4094 28234 4573 4094 28235 4573 4094 28236 4571 4094 28237 4565 4094 28238 4571 4094 28239 4569 4094 28240 4565 4094 28241 4569 4094 28242 4567 4094 28243 4565 4094 28244 4565 4094 28245 4563 4094 28246 4561 4094 28247 4561 4094 28248 4559 4094 28249 4565 4094 28250 4559 4094 28251 4557 4094 28252 4565 4094 28253 4557 4094 28254 4555 4094 28255 4553 4094 28256 4553 4094 28257 4551 4094 28258 4549 4094 28259 4549 4094 28260 4547 4094 28261 4541 4094 28262 4547 4094 28263 4545 4094 28264 4541 4094 28265 4545 4094 28266 4543 4094 28267 4541 4094 28268 4541 4094 28269 4539 4094 28270 4537 4094 28271 4537 4094 28272 4535 4094 28273 4533 4094 28274 4533 4094 28275 4531 4094 28276 4525 4094 28277 4531 4094 28278 4529 4094 28279 4525 4094 28280 4529 4094 28281 4527 4094 28282 4525 4094 28283 4525 4094 28284 4523 4094 28285 4521 4094 28286 4521 4094 28287 4519 4094 28288 4517 4094 28289 4517 4094 28290 4515 4094 28291 4513 4094 28292 4513 4094 28293 4511 4094 28294 4509 4094 28295 4509 4094 28296 4507 4094 28297 4501 4094 28298 4507 4094 28299 4505 4094 28300 4501 4094 28301 4505 4094 28302 4503 4094 28303 4501 4094 28304 4501 4094 28305 4499 4094 28306 4497 4094 28307 4497 4094 28308 4495 4094 28309 4493 4094 28310 4493 4094 28311 4491 4094 28312 4489 4094 28313 4489 4094 28314 4487 4094 28315 4493 4094 28316 4487 4094 28317 4485 4094 28318 4493 4094 28319 4485 4094 28320 4483 4094 28321 4477 4094 28322 4483 4094 28323 4481 4094 28324 4477 4094 28325 4481 4094 28326 4479 4094 28327 4477 4094 28328 4477 4094 28329 4475 4094 28330 4473 4094 28331 4473 4094 28332 4471 4094 28333 4469 4094 28334 4469 4094 28335 4467 4094 28336 4461 4094 28337 4467 4094 28338 4465 4094 28339 4461 4094 28340 4465 4094 28341 4463 4094 28342 4461 4094 28343 4461 4094 28344 4459 4094 28345 4453 4094 28346 4459 4094 28347 4457 4094 28348 4453 4094 28349 4457 4094 28350 4455 4094 28351 4453 4094 28352 4453 4094 28353 4451 4094 28354 4445 4094 28355 4451 4094 28356 4449 4094 28357 4445 4094 28358 4449 4094 28359 4447 4094 28360 4445 4094 28361 4445 4094 28362 4443 4094 28363 4437 4094 28364 4443 4094 28365 4441 4094 28366 4437 4094 28367 4441 4094 28368 4439 4094 28369 4437 4094 28370 4437 4094 28371 4435 4094 28372 4433 4094 28373 4433 4094 28374 4431 4094 28375 4437 4094 28376 4431 4094 28377 4429 4094 28378 4437 4094 28379 4429 4094 28380 4427 4094 28381 4425 4094 28382 4425 4094 28383 4423 4094 28384 4421 4094 28385 4421 4094 28386 4419 4094 28387 4413 4094 28388 4419 4094 28389 4417 4094 28390 4413 4094 28391 4417 4094 28392 4415 4094 28393 4413 4094 28394 4413 4094 28395 4411 4094 28396 4409 4094 28397 4409 4094 28398 4407 4094 28399 4413 4094 28400 4407 4094 28401 4405 4094 28402 4413 4094 28403 4405 4094 28404 4403 4094 28405 4401 4094 28406 4401 4094 28407 4399 4094 28408 4405 4094 28409 4399 4094 28410 4397 4094 28411 4405 4094 28412 4397 4094 28413 4395 4094 28414 4393 4094 28415 4393 4094 28416 4391 4094 28417 4389 4094 28418 4389 4094 28419 4387 4094 28420 4385 4094 28421 4385 4094 28422 4383 4094 28423 4381 4094 28424 4381 4094 28425 4379 4094 28426 4377 4094 28427 4377 4094 28428 4375 4094 28429 4381 4094 28430 4375 4094 28431 4373 4094 28432 4381 4094 28433 4373 4094 28434 4371 4094 28435 4365 4094 28436 4371 4094 28437 4369 4094 28438 4365 4094 28439 4369 4094 28440 4367 4094 28441 4365 4094 28442 4365 4094 28443 4363 4094 28444 4361 4094 28445 4361 4094 28446 4359 4094 28447 4365 4094 28448 4359 4094 28449 4357 4094 28450 4365 4094 28451 4357 4094 28452 4355 4094 28453 4353 4094 28454 4353 4094 28455 4351 4094 28456 4349 4094 28457 4349 4094 28458 4347 4094 28459 4345 4094 28460 4345 4094 28461 4343 4094 28462 4349 4094 28463 4343 4094 28464 4341 4094 28465 4349 4094 28466 4341 4094 28467 4339 4094 28468 4337 4094 28469 4337 4094 28470 4335 4094 28471 4341 4094 28472 4335 4094 28473 4333 4094 28474 4341 4094 28475 4333 4094 28476 4331 4094 28477 4329 4094 28478 4329 4094 28479 4327 4094 28480 4325 4094 28481 4325 4094 28482 4323 4094 28483 4321 4094 28484 4321 4094 28485 4319 4094 28486 4325 4094 28487 4319 4094 28488 4317 4094 28489 4325 4094 28490 4317 4094 28491 4315 4094 28492 4309 4094 28493 4315 4094 28494 4313 4094 28495 4309 4094 28496 4313 4094 28497 4311 4094 28498 4309 4094 28499 4309 4094 28500 4307 4094 28501 4305 4094 28502 4305 4094 28503 4303 4094 28504 4301 4094 28505 4301 4094 28506 4299 4094 28507 4293 4094 28508 4299 4094 28509 4297 4094 28510 4293 4094 28511 4297 4094 28512 4295 4094 28513 4293 4094 28514 4293 4094 28515 4291 4094 28516 4285 4094 28517 4291 4094 28518 4289 4094 28519 4285 4094 28520 4289 4094 28521 4287 4094 28522 4285 4094 28523 4285 4094 28524 4283 4094 28525 4281 4094 28526 4281 4094 28527 4279 4094 28528 4277 4094 28529 4277 4094 28530 4275 4094 28531 4269 4094 28532 4275 4094 28533 4273 4094 28534 4269 4094 28535 4273 4094 28536 4271 4094 28537 4269 4094 28538 4269 4094 28539 4267 4094 28540 4261 4094 28541 4267 4094 28542 4265 4094 28543 4261 4094 28544 4265 4094 28545 4263 4094 28546 4261 4094 28547 4261 4094 28548 4259 4094 28549 4257 4094 28550 4257 4094 28551 4255 4094 28552 4261 4094 28553 4255 4094 28554 4253 4094 28555 4261 4094 28556 4253 4094 28557 4251 4094 28558 4249 4094 28559 4249 4094 28560 4247 4094 28561 4245 4094 28562 4245 4094 28563 4243 4094 28564 4241 4094 28565 4241 4094 28566 4239 4094 28567 4245 4094 28568 4239 4094 28569 4237 4094 28570 4245 4094 28571 4237 4094 28572 4235 4094 28573 4229 4094 28574 4235 4094 28575 4233 4094 28576 4229 4094 28577 4233 4094 28578 4231 4094 28579 4229 4094 28580 4229 4094 28581 4227 4094 28582 4225 4094 28583 4225 4094 28584 4223 4094 28585 4229 4094 28586 4223 4094 28587 4221 4094 28588 4229 4094 28589 4221 4094 28590 4219 4094 28591 4217 4094 28592 4217 4094 28593 4215 4094 28594 4213 4094 28595 4213 4094 28596 4211 4094 28597 4209 4094 28598 4209 4094 28599 4207 4094 28600 4213 4094 28601 4207 4094 28602 4205 4094 28603 4213 4094 28604 4205 4094 28605 4203 4094 28606 4201 4094 28607 4201 4094 28608 4199 4094 28609 4205 4094 28610 4199 4094 28611 4197 4094 28612 4205 4094 28613 4197 4094 28614 4195 4094 28615 4189 4094 28616 4195 4094 28617 4193 4094 28618 4189 4094 28619 4193 4094 28620 4191 4094 28621 4189 4094 28622 4189 4094 28623 4187 4094 28624 4185 4094 28625 4185 4094 28626 4183 4094 28627 4181 4094 28628 4181 4094 28629 4179 4094 28630 4173 4094 28631 4179 4094 28632 4177 4094 28633 4173 4094 28634 4177 4094 28635 4175 4094 28636 4173 4094 28637 4173 4094 28638 4171 4094 28639 4169 4094 28640 4169 4094 28641 4167 4094 28642 4165 4094 28643 4165 4094 28644 4163 4094 28645 4161 4094 28646 4161 4094 28647 4159 4094 28648 4157 4094 28649 4157 4094 28650 4155 4094 28651 4153 4094 28652 4153 4094 28653 4151 4094 28654 4157 4094 28655 4151 4094 28656 4149 4094 28657 4157 4094 28658 4149 4094 28659 4147 4094 28660 4145 4094 28661 4145 4094 28662 4143 4094 28663 4141 4094 28664 4141 4094 28665 4139 4094 28666 4137 4094 28667 4137 4094 28668 4135 4094 28669 4133 4094 28670 4133 4094 28671 4131 4094 28672 4129 4094 28673 4129 4094 28674 4127 4094 28675 4125 4094 28676 4125 4094 28677 4123 4094 28678 4117 4094 28679 4123 4094 28680 4121 4094 28681 4117 4094 28682 4121 4094 28683 4119 4094 28684 4117 4094 28685 4117 4094 28686 4115 4094 28687 4109 4094 28688 4115 4094 28689 4113 4094 28690 4109 4094 28691 4113 4094 28692 4111 4094 28693 4109 4094 28694 4109 4094 28695 4107 4094 28696 4105 4094 28697 4105 4094 28698 4103 4094 28699 4109 4094 28700 4103 4094 28701 4101 4094 28702 4109 4094 28703 4101 4094 28704 4099 4094 28705 4093 4094 28706 4099 4094 28707 4097 4094 28708 4093 4094 28709 4097 4094 28710 4095 4094 28711 4093 4094 28712 4093 4094 28713 4091 4094 28714 4085 4094 28715 4091 4094 28716 4089 4094 28717 4085 4094 28718 4089 4094 28719 4087 4094 28720 4085 4094 28721 4085 4094 28722 4083 4094 28723 4081 4094 28724 4081 4094 28725 4079 4094 28726 4085 4094 28727 4079 4094 28728 4077 4094 28729 4085 4094 28730 4077 4094 28731 4075 4094 28732 4073 4094 28733 4073 4094 28734 4071 4094 28735 4077 4094 28736 4071 4094 28737 4069 4094 28738 4077 4094 28739 4069 4094 28740 4067 4094 28741 4065 4094 28742 4065 4094 28743 4063 4094 28744 4061 4094 28745 4061 4094 28746 4059 4094 28747 4057 4094 28748 4057 4094 28749 4055 4094 28750 4053 4094 28751 4053 4094 28752 4051 4094 28753 4049 4094 28754 4049 4094 28755 4047 4094 28756 4045 4094 28757 4045 4094 28758 4043 4094 28759 4037 4094 28760 4043 4094 28761 4041 4094 28762 4037 4094 28763 4041 4094 28764 4039 4094 28765 4037 4094 28766 4037 4094 28767 4035 4094 28768 4029 4094 28769 4035 4094 28770 4033 4094 28771 4029 4094 28772 4033 4094 28773 4031 4094 28774 4029 4094 28775 4029 4094 28776 4027 4094 28777 4025 4094 28778 4025 4094 28779 4023 4094 28780 4021 4094 28781 4021 4094 28782 4019 4094 28783 4017 4094 28784 4017 4094 28785 4015 4094 28786 4013 4094 28787 4013 4094 28788 4011 4094 28789 4005 4094 28790 4011 4094 28791 4009 4094 28792 4005 4094 28793 4009 4094 28794 4007 4094 28795 4005 4094 28796 4005 4094 28797 4003 4094 28798 4001 4094 28799 4001 4094 28800 3999 4094 28801 3997 4094 28802 3997 4094 28803 3995 4094 28804 3989 4094 28805 3995 4094 28806 3993 4094 28807 3989 4094 28808 3993 4094 28809 3991 4094 28810 3989 4094 28811 3989 4094 28812 3987 4094 28813 3981 4094 28814 3987 4094 28815 3985 4094 28816 3981 4094 28817 3985 4094 28818 3983 4094 28819 3981 4094 28820 3981 4094 28821 3979 4094 28822 3977 4094 28823 3977 4094 28824 3975 4094 28825 3981 4094 28826 3975 4094 28827 3973 4094 28828 3981 4094 28829 3973 4094 28830 3971 4094 28831 3965 4094 28832 3971 4094 28833 3969 4094 28834 3965 4094 28835 3969 4094 28836 3967 4094 28837 3965 4094 28838 3965 4094 28839 3963 4094 28840 3961 4094 28841 3961 4094 28842 3959 4094 28843 3965 4094 28844 3959 4094 28845 3957 4094 28846 3965 4094 28847 3957 4094 28848 3955 4094 28849 3949 4094 28850 3955 4094 28851 3953 4094 28852 3949 4094 28853 3953 4094 28854 3951 4094 28855 3949 4094 28856 3949 4094 28857 3947 4094 28858 3945 4094 28859 3945 4094 28860 3943 4094 28861 3941 4094 28862 3941 4094 28863 3939 4094 28864 3933 4094 28865 3939 4094 28866 3937 4094 28867 3933 4094 28868 3937 4094 28869 3935 4094 28870 3933 4094 28871 3933 4094 28872 3931 4094 28873 3929 4094 28874 3929 4094 28875 3927 4094 28876 3933 4094 28877 3927 4094 28878 3925 4094 28879 3933 4094 28880 3925 4094 28881 3923 4094 28882 3921 4094 28883 3921 4094 28884 3919 4094 28885 3925 4094 28886 3919 4094 28887 3917 4094 28888 3925 4094 28889 3917 4094 28890 3915 4094 28891 3913 4094 28892 3913 4094 28893 3911 4094 28894 3909 4094 28895 3909 4094 28896 3907 4094 28897 3905 4094 28898 3905 4094 28899 3903 4094 28900 3909 4094 28901 3903 4094 28902 3901 4094 28903 3909 4094 28904 3901 4094 28905 3899 4094 28906 3897 4094 28907 3897 4094 28908 3895 4094 28909 3901 4094 28910 3895 4094 28911 3893 4094 28912 3901 4094 28913 3893 4094 28914 3891 4094 28915 3885 4094 28916 3891 4094 28917 3889 4094 28918 3885 4094 28919 3889 4094 28920 3887 4094 28921 3885 4094 28922 3885 4094 28923 3883 4094 28924 3881 4094 28925 3881 4094 28926 3879 4094 28927 3885 4094 28928 3879 4094 28929 3877 4094 28930 3885 4094 28931 3877 4094 28932 3875 4094 28933 3869 4094 28934 3875 4094 28935 3873 4094 28936 3869 4094 28937 3873 4094 28938 3871 4094 28939 3869 4094 28940 3869 4094 28941 3867 4094 28942 3865 4094 28943 3865 4094 28944 3863 4094 28945 3861 4094 28946 3861 4094 28947 3859 4094 28948 3853 4094 28949 3859 4094 28950 3857 4094 28951 3853 4094 28952 3857 4094 28953 3855 4094 28954 3853 4094 28955 3853 4094 28956 3851 4094 28957 3845 4094 28958 3851 4094 28959 3849 4094 28960 3845 4094 28961 3849 4094 28962 3847 4094 28963 3845 4094 28964 3845 4094 28965 3843 4094 28966 3841 4094 28967 3841 4094 28968 3839 4094 28969 3837 4094 28970 3837 4094 28971 3835 4094 28972 3829 4094 28973 3835 4094 28974 3833 4094 28975 3829 4094 28976 3833 4094 28977 3831 4094 28978 3829 4094 28979 3829 4094 28980 3827 4094 28981 3825 4094 28982 3825 4094 28983 3823 4094 28984 3829 4094 28985 3823 4094 28986 3821 4094 28987 3829 4094 28988 3821 4094 28989 3819 4094 28990 3813 4094 28991 3819 4094 28992 3817 4094 28993 3813 4094 28994 3817 4094 28995 3815 4094 28996 3813 4094 28997 3813 4094 28998 3811 4094 28999 3809 4094 29000 3809 4094 29001 3807 4094 29002 3805 4094 29003 3805 4094 29004 3803 4094 29005 3801 4094 29006 3801 4094 29007 3799 4094 29008 3805 4094 29009 3799 4094 29010 3797 4094 29011 3805 4094 29012 3797 4094 29013 3795 4094 29014 3789 4094 29015 3795 4094 29016 3793 4094 29017 3789 4094 29018 3793 4094 29019 3791 4094 29020 3789 4094 29021 3789 4094 29022 3787 4094 29023 3781 4094 29024 3787 4094 29025 3785 4094 29026 3781 4094 29027 3785 4094 29028 3783 4094 29029 3781 4094 29030 3781 4094 29031 3779 4094 29032 3777 4094 29033 3777 4094 29034 3775 4094 29035 3781 4094 29036 3775 4094 29037 3773 4094 29038 3781 4094 29039 3773 4094 29040 3771 4094 29041 3769 4094 29042 3769 4094 29043 3767 4094 29044 3765 4094 29045 3765 4094 29046 3763 4094 29047 3757 4094 29048 3763 4094 29049 3761 4094 29050 3757 4094 29051 3761 4094 29052 3759 4094 29053 3757 4094 29054 3757 4094 29055 3755 4094 29056 3753 4094 29057 3753 4094 29058 3751 4094 29059 3757 4094 29060 3751 4094 29061 3749 4094 29062 3757 4094 29063 3749 4094 29064 3747 4094 29065 3745 4094 29066 3745 4094 29067 3743 4094 29068 3741 4094 29069 3741 4094 29070 3739 4094 29071 3737 4094 29072 3737 4094 29073 3735 4094 29074 3741 4094 29075 3735 4094 29076 3733 4094 29077 3741 4094 29078 3733 4094 29079 3731 4094 29080 3729 4094 29081 3729 4094 29082 3727 4094 29083 3733 4094 29084 3727 4094 29085 3725 4094 29086 3733 4094 29087 3725 4094 29088 3723 4094 29089 3721 4094 29090 3721 4094 29091 3719 4094 29092 3717 4094 29093 3717 4094 29094 3715 4094 29095 3713 4094 29096 3713 4094 29097 3711 4094 29098 3717 4094 29099 3711 4094 29100 3709 4094 29101 3717 4094 29102 3709 4094 29103 3707 4094 29104 3701 4094 29105 3707 4094 29106 3705 4094 29107 3701 4094 29108 3705 4094 29109 3703 4094 29110 3701 4094 29111 3701 4094 29112 3699 4094 29113 3697 4094 29114 3697 4094 29115 3695 4094 29116 3693 4094 29117 3693 4094 29118 3691 4094 29119 3689 4094 29120 3689 4094 29121 3687 4094 29122 3693 4094 29123 3687 4094 29124 3685 4094 29125 3693 4094 29126 3685 4094 29127 3683 4094 29128 3681 4094 29129 3681 4094 29130 3679 4094 29131 3677 4094 29132 3677 4094 29133 3675 4094 29134 3669 4094 29135 3675 4094 29136 3673 4094 29137 3669 4094 29138 3673 4094 29139 3671 4094 29140 3669 4094 29141 3669 4094 29142 3667 4094 29143 3665 4094 29144 3665 4094 29145 3663 4094 29146 3669 4094 29147 3663 4094 29148 3661 4094 29149 3669 4094 29150 3661 4094 29151 3659 4094 29152 3657 4094 29153 3657 4094 29154 3655 4094 29155 3661 4094 29156 3655 4094 29157 3653 4094 29158 3661 4094 29159 3653 4094 29160 3651 4094 29161 3649 4094 29162 3649 4094 29163 3647 4094 29164 3653 4094 29165 3647 4094 29166 3645 4094 29167 3653 4094 29168 3645 4094 29169 3643 4094 29170 3641 4094 29171 3641 4094 29172 3639 4094 29173 3645 4094 29174 3639 4094 29175 3637 4094 29176 3645 4094 29177 3637 4094 29178 3635 4094 29179 3629 4094 29180 3635 4094 29181 3633 4094 29182 3629 4094 29183 3633 4094 29184 3631 4094 29185 3629 4094 29186 3629 4094 29187 3627 4094 29188 3625 4094 29189 3625 4094 29190 3623 4094 29191 3629 4094 29192 3623 4094 29193 3621 4094 29194 3629 4094 29195 3621 4094 29196 3619 4094 29197 3617 4094 29198 3617 4094 29199 3615 4094 29200 3621 4094 29201 3615 4094 29202 3613 4094 29203 3621 4094 29204 3613 4094 29205 3611 4094 29206 3609 4094 29207 3609 4094 29208 3607 4094 29209 3605 4094 29210 3605 4094 29211 3603 4094 29212 3601 4094 29213 3601 4094 29214 3599 4094 29215 3605 4094 29216 3599 4094 29217 3597 4094 29218 3605 4094 29219 3597 4094 29220 3595 4094 29221 3593 4094 29222 3593 4094 29223 3591 4094 29224 3597 4094 29225 3591 4094 29226 3589 4094 29227 3597 4094 29228 3589 4094 29229 3587 4094 29230 3585 4094 29231 3585 4094 29232 3583 4094 29233 3581 4094 29234 3581 4094 29235 3579 4094 29236 3577 4094 29237 3577 4094 29238 3575 4094 29239 3581 4094 29240 3575 4094 29241 3573 4094 29242 3581 4094 29243 3573 4094 29244 3571 4094 29245 3565 4094 29246 3571 4094 29247 3569 4094 29248 3565 4094 29249 3569 4094 29250 3567 4094 29251 3565 4094 29252 3565 4094 29253 3563 4094 29254 3557 4094 29255 3563 4094 29256 3561 4094 29257 3557 4094 29258 3561 4094 29259 3559 4094 29260 3557 4094 29261 3557 4094 29262 3555 4094 29263 3553 4094 29264 3553 4094 29265 3551 4094 29266 3549 4094 29267 3549 4094 29268 3547 4094 29269 3541 4094 29270 3547 4094 29271 3545 4094 29272 3541 4094 29273 3545 4094 29274 3543 4094 29275 3541 4094 29276 3541 4094 29277 3539 4094 29278 3537 4094 29279 3537 4094 29280 3535 4094 29281 3541 4094 29282 3535 4094 29283 3533 4094 29284 3541 4094 29285 3533 4094 29286 3531 4094 29287 3529 4094 29288 3529 4094 29289 3527 4094 29290 3533 4094 29291 3527 4094 29292 3525 4094 29293 3533 4094 29294 3525 4094 29295 3523 4094 29296 3517 4094 29297 3523 4094 29298 3521 4094 29299 3517 4094 29300 3521 4094 29301 3519 4094 29302 3517 4094 29303 3517 4094 29304 3515 4094 29305 3509 4094 29306 3515 4094 29307 3513 4094 29308 3509 4094 29309 3513 4094 29310 3511 4094 29311 3509 4094 29312 3509 4094 29313 3507 4094 29314 3501 4094 29315 3507 4094 29316 3505 4094 29317 3501 4094 29318 3505 4094 29319 3503 4094 29320 3501 4094 29321 3501 4094 29322 3499 4094 29323 3493 4094 29324 3499 4094 29325 3497 4094 29326 3493 4094 29327 3497 4094 29328 3495 4094 29329 3493 4094 29330 3493 4094 29331 3491 4094 29332 3489 4094 29333 3489 4094 29334 3487 4094 29335 3493 4094 29336 3487 4094 29337 3485 4094 29338 3493 4094 29339 3485 4094 29340 3483 4094 29341 3481 4094 29342 3481 4094 29343 3479 4094 29344 3485 4094 29345 3479 4094 29346 3477 4094 29347 3485 4094 29348 3477 4094 29349 3475 4094 29350 3469 4094 29351 3475 4094 29352 3473 4094 29353 3469 4094 29354 3473 4094 29355 3471 4094 29356 3469 4094 29357 3469 4094 29358 3467 4094 29359 3461 4094 29360 3467 4094 29361 3465 4094 29362 3461 4094 29363 3465 4094 29364 3463 4094 29365 3461 4094 29366 3461 4094 29367 3459 4094 29368 3457 4094 29369 3457 4094 29370 3455 4094 29371 3453 4094 29372 3453 4094 29373 3451 4094 29374 3445 4094 29375 3451 4094 29376 3449 4094 29377 3445 4094 29378 3449 4094 29379 3447 4094 29380 3445 4094 29381 3445 4094 29382 3443 4094 29383 3441 4094 29384 3441 4094 29385 3439 4094 29386 3445 4094 29387 3439 4094 29388 3437 4094 29389 3445 4094 29390 3437 4094 29391 3435 4094 29392 3433 4094 29393 3433 4094 29394 3431 4094 29395 3437 4094 29396 3431 4094 29397 3429 4094 29398 3437 4094 29399 3429 4094 29400 3427 4094 29401 3421 4094 29402 3427 4094 29403 3425 4094 29404 3421 4094 29405 3425 4094 29406 3423 4094 29407 3421 4094 29408 3421 4094 29409 3419 4094 29410 3417 4094 29411 3417 4094 29412 3415 4094 29413 3413 4094 29414 3413 4094 29415 3411 4094 29416 3409 4094 29417 3409 4094 29418 3407 4094 29419 3405 4094 29420 3405 4094 29421 3403 4094 29422 3401 4094 29423 3401 4094 29424 3399 4094 29425 3397 4094 29426 3397 4094 29427 3395 4094 29428 3393 4094 29429 3393 4094 29430 3391 4094 29431 3397 4094 29432 3391 4094 29433 3389 4094 29434 3397 4094 29435 3389 4094 29436 3387 4094 29437 3381 4094 29438 3387 4094 29439 3385 4094 29440 3381 4094 29441 3385 4094 29442 3383 4094 29443 3381 4094 29444 3381 4094 29445 3379 4094 29446 3377 4094 29447 3377 4094 29448 3375 4094 29449 3381 4094 29450 3375 4094 29451 3373 4094 29452 3381 4094 29453 3373 4094 29454 3371 4094 29455 3369 4094 29456 3369 4094 29457 3367 4094 29458 3365 4094 29459 3365 4094 29460 3363 4094 29461 3361 4094 29462 3361 4094 29463 3359 4094 29464 3365 4094 29465 3359 4094 29466 3357 4094 29467 3365 4094 29468 3357 4094 29469 3355 4094 29470 3353 4094 29471 3353 4094 29472 3351 4094 29473 3357 4094 29474 3351 4094 29475 3349 4094 29476 3357 4094 29477 3349 4094 29478 3347 4094 29479 3345 4094 29480 3345 4094 29481 3343 4094 29482 3341 4094 29483 3341 4094 29484 3339 4094 29485 3337 4094 29486 3337 4094 29487 3335 4094 29488 3333 4094 29489 3333 4094 29490 3331 4094 29491 3325 4094 29492 3331 4094 29493 3329 4094 29494 3325 4094 29495 3329 4094 29496 3327 4094 29497 3325 4094 29498 3325 4094 29499 3323 4094 29500 3321 4094 29501 3321 4094 29502 3319 4094 29503 3317 4094 29504 3317 4094 29505 3315 4094 29506 3309 4094 29507 3315 4094 29508 3313 4094 29509 3309 4094 29510 3313 4094 29511 3311 4094 29512 3309 4094 29513 3309 4094 29514 3307 4094 29515 3305 4094 29516 3305 4094 29517 3303 4094 29518 3309 4094 29519 3303 4094 29520 3301 4094 29521 3309 4094 29522 3301 4094 29523 3299 4094 29524 3297 4094 29525 3297 4094 29526 3295 4094 29527 3293 4094 29528 3293 4094 29529 3291 4094 29530 3289 4094 29531 3289 4094 29532 3287 4094 29533 3293 4094 29534 3287 4094 29535 3285 4094 29536 3293 4094 29537 3285 4094 29538 3283 4094 29539 3277 4094 29540 3283 4094 29541 3281 4094 29542 3277 4094 29543 3281 4094 29544 3279 4094 29545 3277 4094 29546 3277 4094 29547 3275 4094 29548 3273 4094 29549 3273 4094 29550 3271 4094 29551 3269 4094 29552 3269 4094 29553 3267 4094 29554 3265 4094 29555 3265 4094 29556 3263 4094 29557 3261 4094 29558 3261 4094 29559 3259 4094 29560 3253 4094 29561 3259 4094 29562 3257 4094 29563 3253 4094 29564 3257 4094 29565 3255 4094 29566 3253 4094 29567 3253 4094 29568 3251 4094 29569 3245 4094 29570 3251 4094 29571 3249 4094 29572 3245 4094 29573 3249 4094 29574 3247 4094 29575 3245 4094 29576 3245 4094 29577 3243 4094 29578 3241 4094 29579 3241 4094 29580 3239 4094 29581 3237 4094 29582 3237 4094 29583 3235 4094 29584 3233 4094 29585 3233 4094 29586 3231 4094 29587 3237 4094 29588 3231 4094 29589 3229 4094 29590 3237 4094 29591 3229 4094 29592 3227 4094 29593 3221 4094 29594 3227 4094 29595 3225 4094 29596 3221 4094 29597 3225 4094 29598 3223 4094 29599 3221 4094 29600 3221 4094 29601 3219 4094 29602 3217 4094 29603 3217 4094 29604 3215 4094 29605 3221 4094 29606 3215 4094 29607 3213 4094 29608 3221 4094 29609 3213 4094 29610 3211 4094 29611 3209 4094 29612 3209 4094 29613 3207 4094 29614 3205 4094 29615 3205 4094 29616 3203 4094 29617 3197 4094 29618 3203 4094 29619 3201 4094 29620 3197 4094 29621 3201 4094 29622 3199 4094 29623 3197 4094 29624 3197 4094 29625 3195 4094 29626 3193 4094 29627 3193 4094 29628 3191 4094 29629 3197 4094 29630 3191 4094 29631 3189 4094 29632 3197 4094 29633 3189 4094 29634 3187 4094 29635 3185 4094 29636 3185 4094 29637 3183 4094 29638 3181 4094 29639 3181 4094 29640 3179 4094 29641 3177 4094 29642 3177 4094 29643 3175 4094 29644 3181 4094 29645 3175 4094 29646 3173 4094 29647 3181 4094 29648 3173 4094 29649 3171 4094 29650 3169 4094 29651 3169 4094 29652 3167 4094 29653 3173 4094 29654 3167 4094 29655 3165 4094 29656 3173 4094 29657 3165 4094 29658 3163 4094 29659 3161 4094 29660 3161 4094 29661 3159 4094 29662 3165 4094 29663 3159 4094 29664 3157 4094 29665 3165 4094 29666 3157 4094 29667 3155 4094 29668 3153 4094 29669 3153 4094 29670 3151 4094 29671 3157 4094 29672 3151 4094 29673 3149 4094 29674 3157 4094 29675 3149 4094 29676 3147 4094 29677 3145 4094 29678 3145 4094 29679 3143 4094 29680 3141 4094 29681 3141 4094 29682 3139 4094 29683 3133 4094 29684 3139 4094 29685 3137 4094 29686 3133 4094 29687 3137 4094 29688 3135 4094 29689 3133 4094 29690 3133 4094 29691 3131 4094 29692 3129 4094 29693 3129 4094 29694 3127 4094 29695 3133 4094 29696 3127 4094 29697 3125 4094 29698 3133 4094 29699 3125 4094 29700 3123 4094 29701 3117 4094 29702 3123 4094 29703 3121 4094 29704 3117 4094 29705 3121 4094 29706 3119 4094 29707 3117 4094 29708 3117 4094 29709 3115 4094 29710 3113 4094 29711 3113 4094 29712 3111 4094 29713 3109 4094 29714 3109 4094 29715 3107 4094 29716 3105 4094 29717 3105 4094 29718 3103 4094 29719 3109 4094 29720 3103 4094 29721 3101 4094 29722 3109 4094 29723 3101 4094 29724 3099 4094 29725 3097 4094 29726 3097 4094 29727 3095 4094 29728 3093 4094 29729 3093 4094 29730 3091 4094 29731 3089 4094 29732 3089 4094 29733 3087 4094 29734 3085 4094 29735 3085 4094 29736 3083 4094 29737 3081 4094 29738 3081 4094 29739 3079 4094 29740 3085 4094 29741 3079 4094 29742 3077 4094 29743 3085 4094 29744 3077 4094 29745 3075 4094 29746 3073 4094 29747 3073 4094 29748 3071 4094 29749 3077 4094 29750 3071 4094 29751 3069 4094 29752 3077 4094 29753 3069 4094 29754 3067 4094 29755 3065 4094 29756 3065 4094 29757 3063 4094 29758 3069 4094 29759 3063 4094 29760 3061 4094 29761 3069 4094 29762 3061 4094 29763 3059 4094 29764 3057 4094 29765 3057 4094 29766 3055 4094 29767 3061 4094 29768 3055 4094 29769 3053 4094 29770 3061 4094 29771 3053 4094 29772 3051 4094 29773 3049 4094 29774 3049 4094 29775 3047 4094 29776 3045 4094 29777 3045 4094 29778 3043 4094 29779 3037 4094 29780 3043 4094 29781 3041 4094 29782 3037 4094 29783 3041 4094 29784 3039 4094 29785 3037 4094 29786 3037 4094 29787 3035 4094 29788 3033 4094 29789 3033 4094 29790 3031 4094 29791 3029 4094 29792 3029 4094 29793 3027 4094 29794 3025 4094 29795 3025 4094 29796 3023 4094 29797 3029 4094 29798 3023 4094 29799 3021 4094 29800 3029 4094 29801 3021 4094 29802 3019 4094 29803 3013 4094 29804 3019 4094 29805 3017 4094 29806 3013 4094 29807 3017 4094 29808 3015 4094 29809 3013 4094 29810 3013 4094 29811 3011 4094 29812 3009 4094 29813 3009 4094 29814 3007 4094 29815 3013 4094 29816 3007 4094 29817 3005 4094 29818 3013 4094 29819 3005 4094 29820 3003 4094 29821 3001 4094 29822 3001 4094 29823 2999 4094 29824 2997 4094 29825 2997 4094 29826 2995 4094 29827 2989 4094 29828 2995 4094 29829 2993 4094 29830 2989 4094 29831 2993 4094 29832 2991 4094 29833 2989 4094 29834 2989 4094 29835 2987 4094 29836 2985 4094 29837 2985 4094 29838 2983 4094 29839 2989 4094 29840 2983 4094 29841 2981 4094 29842 2989 4094 29843 2981 4094 29844 2979 4094 29845 2973 4094 29846 2979 4094 29847 2977 4094 29848 2973 4094 29849 2977 4094 29850 2975 4094 29851 2973 4094 29852 2973 4094 29853 2971 4094 29854 2965 4094 29855 2971 4094 29856 2969 4094 29857 2965 4094 29858 2969 4094 29859 2967 4094 29860 2965 4094 29861 2965 4094 29862 2963 4094 29863 2961 4094 29864 2961 4094 29865 2959 4094 29866 2957 4094 29867 2957 4094 29868 2955 4094 29869 2949 4094 29870 2955 4094 29871 2953 4094 29872 2949 4094 29873 2953 4094 29874 2951 4094 29875 2949 4094 29876 2949 4094 29877 2947 4094 29878 2945 4094 29879 2945 4094 29880 2943 4094 29881 2949 4094 29882 2943 4094 29883 2941 4094 29884 2949 4094 29885 2941 4094 29886 2939 4094 29887 2937 4094 29888 2937 4094 29889 2935 4094 29890 2933 4094 29891 2933 4094 29892 2931 4094 29893 2925 4094 29894 2931 4094 29895 2929 4094 29896 2925 4094 29897 2929 4094 29898 2927 4094 29899 2925 4094 29900 2925 4094 29901 2923 4094 29902 2921 4094 29903 2921 4094 29904 2919 4094 29905 2925 4094 29906 2919 4094 29907 2917 4094 29908 2925 4094 29909 2917 4094 29910 2915 4094 29911 2909 4094 29912 2915 4094 29913 2913 4094 29914 2909 4094 29915 2913 4094 29916 2911 4094 29917 2909 4094 29918 2909 4094 29919 2907 4094 29920 2905 4094 29921 2905 4094 29922 2903 4094 29923 2901 4094 29924 2901 4094 29925 2899 4094 29926 2897 4094 29927 2897 4094 29928 2895 4094 29929 2901 4094 29930 2895 4094 29931 2893 4094 29932 2901 4094 29933 2893 4094 29934 2891 4094 29935 2889 4094 29936 2889 4094 29937 2887 4094 29938 2893 4094 29939 2887 4094 29940 2885 4094 29941 2893 4094 29942 2885 4094 29943 2883 4094 29944 2881 4094 29945 2881 4094 29946 2879 4094 29947 2877 4094 29948 2877 4094 29949 2875 4094 29950 2873 4094 29951 2873 4094 29952 2871 4094 29953 2869 4094 29954 2869 4094 29955 2867 4094 29956 2865 4094 29957 2865 4094 29958 2863 4094 29959 2869 4094 29960 2863 4094 29961 2861 4094 29962 2869 4094 29963 2861 4094 29964 2859 4094 29965 2853 4094 29966 2859 4094 29967 2857 4094 29968 2853 4094 29969 2857 4094 29970 2855 4094 29971 2853 4094 29972 2853 4094 29973 2851 4094 29974 2849 4094 29975 2849 4094 29976 2847 4094 29977 2845 4094 29978 2845 4094 29979 2843 4094 29980 2837 4094 29981 2843 4094 29982 2841 4094 29983 2837 4094 29984 2841 4094 29985 2839 4094 29986 2837 4094 29987 2837 4094 29988 2835 4094 29989 2833 4094 29990 2833 4094 29991 2831 4094 29992 2837 4094 29993 2831 4094 29994 2829 4094 29995 2837 4094 29996 2829 4094 29997 2827 4094 29998 2825 4094 29999 2825 4094 30000 2823 4094 30001 2821 4094 30002 2821 4094 30003 2819 4094 30004 2817 4094 30005 2817 4094 30006 2815 4094 30007 2821 4094 30008 2815 4094 30009 2813 4094 30010 2821 4094 30011 2813 4094 30012 2811 4094 30013 2809 4094 30014 2809 4094 30015 2807 4094 30016 2805 4094 30017 2805 4094 30018 2803 4094 30019 2801 4094 30020 2801 4094 30021 2799 4094 30022 2797 4094 30023 2797 4094 30024 2795 4094 30025 2789 4094 30026 2795 4094 30027 2793 4094 30028 2789 4094 30029 2793 4094 30030 2791 4094 30031 2789 4094 30032 2789 4094 30033 2787 4094 30034 2781 4094 30035 2787 4094 30036 2785 4094 30037 2781 4094 30038 2785 4094 30039 2783 4094 30040 2781 4094 30041 2781 4094 30042 2779 4094 30043 2777 4094 30044 2777 4094 30045 2775 4094 30046 2773 4094 30047 2773 4094 30048 2771 4094 30049 2765 4094 30050 2771 4094 30051 2769 4094 30052 2765 4094 30053 2769 4094 30054 2767 4094 30055 2765 4094 30056 2765 4094 30057 2763 4094 30058 2761 4094 30059 2761 4094 30060 2759 4094 30061 2765 4094 30062 2759 4094 30063 2757 4094 30064 2765 4094 30065 2757 4094 30066 2755 4094 30067 2749 4094 30068 2755 4094 30069 2753 4094 30070 2749 4094 30071 2753 4094 30072 2751 4094 30073 2749 4094 30074 2749 4094 30075 2747 4094 30076 2745 4094 30077 2745 4094 30078 2743 4094 30079 2741 4094 30080 2741 4094 30081 2739 4094 30082 2737 4094 30083 2737 4094 30084 2735 4094 30085 2733 4094 30086 2733 4094 30087 2731 4094 30088 2729 4094 30089 2729 4094 30090 2727 4094 30091 2725 4094 30092 2725 4094 30093 2723 4094 30094 2721 4094 30095 2721 4094 30096 2719 4094 30097 2725 4094 30098 2719 4094 30099 2717 4094 30100 2725 4094 30101 2717 4094 30102 2715 4094 30103 2709 4094 30104 2715 4094 30105 2713 4094 30106 2709 4094 30107 2713 4094 30108 2711 4094 30109 2709 4094 30110 2709 4094 30111 2707 4094 30112 2705 4094 30113 2705 4094 30114 2703 4094 30115 2701 4094 30116 2701 4094 30117 2699 4094 30118 2697 4094 30119 2697 4094 30120 2695 4094 30121 2701 4094 30122 2695 4094 30123 2693 4094 30124 2701 4094 30125 2693 4094 30126 2691 4094 30127 2689 4094 30128 2689 4094 30129 2687 4094 30130 2685 4094 30131 2685 4094 30132 2683 4094 30133 2681 4094 30134 2681 4094 30135 2679 4094 30136 2685 4094 30137 2679 4094 30138 2677 4094 30139 2685 4094 30140 2677 4094 30141 2675 4094 30142 2673 4094 30143 2673 4094 30144 2671 4094 30145 2677 4094 30146 2671 4094 30147 2669 4094 30148 2677 4094 30149 2669 4094 30150 2667 4094 30151 2661 4094 30152 2667 4094 30153 2665 4094 30154 2661 4094 30155 2665 4094 30156 2663 4094 30157 2661 4094 30158 2661 4094 30159 2659 4094 30160 2653 4094 30161 2659 4094 30162 2657 4094 30163 2653 4094 30164 2657 4094 30165 2655 4094 30166 2653 4094 30167 2653 4094 30168 2651 4094 30169 2649 4094 30170 2649 4094 30171 2647 4094 30172 2653 4094 30173 2647 4094 30174 2645 4094 30175 2653 4094 30176 2645 4094 30177 2643 4094 30178 2641 4094 30179 2641 4094 30180 2639 4094 30181 2645 4094 30182 2639 4094 30183 2637 4094 30184 2645 4094 30185 2637 4094 30186 2635 4094 30187 2633 4094 30188 2633 4094 30189 2631 4094 30190 2637 4094 30191 2631 4094 30192 2629 4094 30193 2637 4094 30194 2629 4094 30195 2627 4094 30196 2625 4094 30197 2625 4094 30198 2623 4094 30199 2629 4094 30200 2623 4094 30201 2621 4094 30202 2629 4094 30203 2621 4094 30204 2619 4094 30205 2613 4094 30206 2619 4094 30207 2617 4094 30208 2613 4094 30209 2617 4094 30210 2615 4094 30211 2613 4094 30212 2613 4094 30213 2611 4094 30214 2609 4094 30215 2609 4094 30216 2607 4094 30217 2605 4094 30218 2605 4094 30219 2603 4094 30220 2601 4094 30221 2601 4094 30222 2599 4094 30223 2605 4094 30224 2599 4094 30225 2597 4094 30226 2605 4094 30227 2597 4094 30228 2595 4094 30229 2593 4094 30230 2593 4094 30231 2591 4094 30232 2589 4094 30233 2589 4094 30234 2587 4094 30235 2585 4094 30236 2585 4094 30237 2583 4094 30238 2589 4094 30239 2583 4094 30240 2581 4094 30241 2589 4094 30242 2581 4094 30243 2579 4094 30244 2577 4094 30245 2577 4094 30246 2575 4094 30247 2581 4094 30248 2575 4094 30249 2573 4094 30250 2581 4094 30251 2573 4094 30252 2571 4094 30253 2565 4094 30254 2571 4094 30255 2569 4094 30256 2565 4094 30257 2569 4094 30258 2567 4094 30259 2565 4094 30260 2565 4094 30261 2563 4094 30262 2561 4094 30263 2561 4094 30264 2559 4094 30265 2557 4094 30266 2557 4094 30267 2555 4094 30268 2549 4094 30269 2555 4094 30270 2553 4094 30271 2549 4094 30272 2553 4094 30273 2551 4094 30274 2549 4094 30275 2549 4094 30276 2547 4094 30277 2541 4094 30278 2547 4094 30279 2545 4094 30280 2541 4094 30281 2545 4094 30282 2543 4094 30283 2541 4094 30284 2541 4094 30285 2539 4094 30286 2537 4094 30287 2537 4094 30288 2535 4094 30289 2533 4094 30290 2533 4094 30291 2531 4094 30292 2525 4094 30293 2531 4094 30294 2529 4094 30295 2525 4094 30296 2529 4094 30297 2527 4094 30298 2525 4094 30299 2525 4094 30300 2523 4094 30301 2517 4094 30302 2523 4094 30303 2521 4094 30304 2517 4094 30305 2521 4094 30306 2519 4094 30307 2517 4094 30308 2517 4094 30309 2515 4094 30310 2513 4094 30311 2513 4094 30312 2511 4094 30313 2517 4094 30314 2511 4094 30315 2509 4094 30316 2517 4094 30317 2509 4094 30318 2507 4094 30319 2505 4094 30320 2505 4094 30321 2503 4094 30322 2501 4094 30323 2501 4094 30324 2499 4094 30325 2493 4094 30326 2499 4094 30327 2497 4094 30328 2493 4094 30329 2497 4094 30330 2495 4094 30331 2493 4094 30332 2493 4094 30333 2491 4094 30334 2489 4094 30335 2489 4094 30336 2487 4094 30337 2485 4094 30338 2485 4094 30339 2483 4094 30340 2477 4094 30341 2483 4094 30342 2481 4094 30343 2477 4094 30344 2481 4094 30345 2479 4094 30346 2477 4094 30347 2477 4094 30348 2475 4094 30349 2473 4094 30350 2473 4094 30351 2471 4094 30352 2469 4094 30353 2469 4094 30354 2467 4094 30355 2465 4094 30356 2465 4094 30357 2463 4094 30358 2461 4094 30359 2461 4094 30360 2459 4094 30361 2453 4094 30362 2459 4094 30363 2457 4094 30364 2453 4094 30365 2457 4094 30366 2455 4094 30367 2453 4094 30368 2453 4094 30369 2451 4094 30370 2449 4094 30371 2449 4094 30372 2447 4094 30373 2445 4094 30374 2445 4094 30375 2443 4094 30376 2441 4094 30377 2441 4094 30378 2439 4094 30379 2445 4094 30380 2439 4094 30381 2437 4094 30382 2445 4094 30383 2437 4094 30384 2435 4094 30385 2429 4094 30386 2435 4094 30387 2433 4094 30388 2429 4094 30389 2433 4094 30390 2431 4094 30391 2429 4094 30392 2429 4094 30393 2427 4094 30394 2425 4094 30395 2425 4094 30396 2423 4094 30397 2421 4094 30398 2421 4094 30399 2419 4094 30400 2413 4094 30401 2419 4094 30402 2417 4094 30403 2413 4094 30404 2417 4094 30405 2415 4094 30406 2413 4094 30407 2413 4094 30408 2411 4094 30409 2405 4094 30410 2411 4094 30411 2409 4094 30412 2405 4094 30413 2409 4094 30414 2407 4094 30415 2405 4094 30416 2405 4094 30417 2403 4094 30418 2397 4094 30419 2403 4094 30420 2401 4094 30421 2397 4094 30422 2401 4094 30423 2399 4094 30424 2397 4094 30425 2397 4094 30426 2395 4094 30427 2389 4094 30428 2395 4094 30429 2393 4094 30430 2389 4094 30431 2393 4094 30432 2391 4094 30433 2389 4094 30434 2389 4094 30435 2387 4094 30436 2385 4094 30437 2385 4094 30438 2383 4094 30439 2389 4094 30440 2383 4094 30441 2381 4094 30442 2389 4094 30443 2381 4094 30444 2379 4094 30445 2377 4094 30446 2377 4094 30447 2375 4094 30448 2373 4094 30449 2373 4094 30450 2371 4094 30451 2365 4094 30452 2371 4094 30453 2369 4094 30454 2365 4094 30455 2369 4094 30456 2367 4094 30457 2365 4094 30458 2365 4094 30459 2363 4094 30460 2361 4094 30461 2361 4094 30462 2359 4094 30463 2365 4094 30464 2359 4094 30465 2357 4094 30466 2365 4094 30467 2357 4094 30468 2355 4094 30469 2353 4094 30470 2353 4094 30471 2351 4094 30472 2357 4094 30473 2351 4094 30474 2349 4094 30475 2357 4094 30476 2349 4094 30477 2347 4094 30478 2345 4094 30479 2345 4094 30480 2343 4094 30481 2341 4094 30482 2341 4094 30483 2339 4094 30484 2337 4094 30485 2337 4094 30486 2335 4094 30487 2333 4094 30488 2333 4094 30489 2331 4094 30490 2329 4094 30491 2329 4094 30492 2327 4094 30493 2333 4094 30494 2327 4094 30495 2325 4094 30496 2333 4094 30497 2325 4094 30498 2323 4094 30499 2317 4094 30500 2323 4094 30501 2321 4094 30502 2317 4094 30503 2321 4094 30504 2319 4094 30505 2317 4094 30506 2317 4094 30507 2315 4094 30508 2313 4094 30509 2313 4094 30510 2311 4094 30511 2317 4094 30512 2311 4094 30513 2309 4094 30514 2317 4094 30515 2309 4094 30516 2307 4094 30517 2305 4094 30518 2305 4094 30519 2303 4094 30520 2301 4094 30521 2301 4094 30522 2299 4094 30523 2297 4094 30524 2297 4094 30525 2295 4094 30526 2301 4094 30527 2295 4094 30528 2293 4094 30529 2301 4094 30530 2293 4094 30531 2291 4094 30532 2289 4094 30533 2289 4094 30534 2287 4094 30535 2293 4094 30536 2287 4094 30537 2285 4094 30538 2293 4094 30539 2285 4094 30540 2283 4094 30541 2281 4094 30542 2281 4094 30543 2279 4094 30544 2277 4094 30545 2277 4094 30546 2275 4094 30547 2273 4094 30548 2273 4094 30549 2271 4094 30550 2277 4094 30551 2271 4094 30552 2269 4094 30553 2277 4094 30554 2269 4094 30555 2267 4094 30556 2261 4094 30557 2267 4094 30558 2265 4094 30559 2261 4094 30560 2265 4094 30561 2263 4094 30562 2261 4094 30563 2261 4094 30564 2259 4094 30565 2257 4094 30566 2257 4094 30567 2255 4094 30568 2253 4094 30569 2253 4094 30570 2251 4094 30571 2245 4094 30572 2251 4094 30573 2249 4094 30574 2245 4094 30575 2249 4094 30576 2247 4094 30577 2245 4094 30578 2245 4094 30579 2243 4094 30580 2237 4094 30581 2243 4094 30582 2241 4094 30583 2237 4094 30584 2241 4094 30585 2239 4094 30586 2237 4094 30587 2237 4094 30588 2235 4094 30589 2233 4094 30590 2233 4094 30591 2231 4094 30592 2229 4094 30593 2229 4094 30594 2227 4094 30595 2221 4094 30596 2227 4094 30597 2225 4094 30598 2221 4094 30599 2225 4094 30600 2223 4094 30601 2221 4094 30602 2221 4094 30603 2219 4094 30604 2213 4094 30605 2219 4094 30606 2217 4094 30607 2213 4094 30608 2217 4094 30609 2215 4094 30610 2213 4094 30611 2213 4094 30612 2211 4094 30613 2209 4094 30614 2209 4094 30615 2207 4094 30616 2213 4094 30617 2207 4094 30618 2205 4094 30619 2213 4094 30620 2205 4094 30621 2203 4094 30622 2201 4094 30623 2201 4094 30624 2199 4094 30625 2197 4094 30626 2197 4094 30627 2195 4094 30628 2193 4094 30629 2193 4094 30630 2191 4094 30631 2197 4094 30632 2191 4094 30633 2189 4094 30634 2197 4094 30635 2189 4094 30636 2187 4094 30637 2181 4094 30638 2187 4094 30639 2185 4094 30640 2181 4094 30641 2185 4094 30642 2183 4094 30643 2181 4094 30644 2181 4094 30645 2179 4094 30646 2177 4094 30647 2177 4094 30648 2175 4094 30649 2181 4094 30650 2175 4094 30651 2173 4094 30652 2181 4094 30653 2173 4094 30654 2171 4094 30655 2169 4094 30656 2169 4094 30657 2167 4094 30658 2165 4094 30659 2165 4094 30660 2163 4094 30661 2161 4094 30662 2161 4094 30663 2159 4094 30664 2165 4094 30665 2159 4094 30666 2157 4094 30667 2165 4094 30668 2157 4094 30669 2155 4094 30670 2153 4094 30671 2153 4094 30672 2151 4094 30673 2157 4094 30674 2151 4094 30675 2149 4094 30676 2157 4094 30677 2149 4094 30678 2147 4094 30679 2141 4094 30680 2147 4094 30681 2145 4094 30682 2141 4094 30683 2145 4094 30684 2143 4094 30685 2141 4094 30686 2141 4094 30687 2139 4094 30688 2137 4094 30689 2137 4094 30690 2135 4094 30691 2133 4094 30692 2133 4094 30693 2131 4094 30694 2125 4094 30695 2131 4094 30696 2129 4094 30697 2125 4094 30698 2129 4094 30699 2127 4094 30700 2125 4094 30701 2125 4094 30702 2123 4094 30703 2121 4094 30704 2121 4094 30705 2119 4094 30706 2117 4094 30707 2117 4094 30708 2115 4094 30709 2113 4094 30710 2113 4094 30711 2111 4094 30712 2109 4094 30713 2109 4094 30714 2107 4094 30715 2105 4094 30716 2105 4094 30717 2103 4094 30718 2109 4094 30719 2103 4094 30720 2101 4094 30721 2109 4094 30722 2101 4094 30723 2099 4094 30724 2097 4094 30725 2097 4094 30726 2095 4094 30727 2093 4094 30728 2093 4094 30729 2091 4094 30730 2089 4094 30731 2089 4094 30732 2087 4094 30733 2085 4094 30734 2085 4094 30735 2083 4094 30736 2081 4094 30737 2081 4094 30738 2079 4094 30739 2077 4094 30740 2077 4094 30741 2075 4094 30742 2069 4094 30743 2075 4094 30744 2073 4094 30745 2069 4094 30746 2073 4094 30747 2071 4094 30748 2069 4094 30749 2069 4094 30750 2067 4094 30751 2061 4094 30752 2067 4094 30753 2065 4094 30754 2061 4094 30755 2065 4094 30756 2063 4094 30757 2061 4094 30758 2061 4094 30759 2059 4094 30760 2057 4094 30761 2057 4094 30762 2055 4094 30763 2061 4094 30764 2055 4094 30765 2053 4094 30766 2061 4094 30767 2053 4094 30768 2051 4094 30769 2045 4094 30770 2051 6114 30771 2049 6114 30772 2045 6114 30773 2049 4094 30774 2047 4094 30775 2045 4094 30776 2045 4094 30777 2043 4094 30778 2037 4094 30779 2043 4094 30780 2041 4094 30781 2037 4094 30782 2041 4094 30783 2039 4094 30784 2037 4094 30785 2037 4094 30786 2035 4094 30787 2033 4094 30788 2033 4094 30789 2031 4094 30790 2037 4094 30791 2031 4094 30792 2029 4094 30793 2037 4094 30794 2029 4094 30795 2027 4094 30796 2025 4094 30797 2025 4094 30798 2023 4094 30799 2029 4094 30800 2023 4094 30801 2021 4094 30802 2029 4094 30803 2021 4094 30804 2019 4094 30805 2017 4094 30806 2017 4094 30807 2015 4094 30808 2013 4094 30809 2013 4094 30810 2011 4094 30811 2009 4094 30812 2009 4094 30813 2007 4094 30814 2005 4094 30815 2005 4094 30816 2003 4094 30817 2001 4094 30818 2001 4094 30819 1999 4094 30820 1997 4094 30821 1997 4094 30822 1995 4094 30823 1989 4094 30824 1995 4094 30825 1993 4094 30826 1989 4094 30827 1993 4094 30828 1991 4094 30829 1989 4094 30830 1989 4094 30831 1987 4094 30832 1981 4094 30833 1987 4094 30834 1985 4094 30835 1981 4094 30836 1985 4094 30837 1983 4094 30838 1981 4094 30839 1981 4094 30840 1979 4094 30841 1977 4094 30842 1977 4094 30843 1975 4094 30844 1973 4094 30845 1973 4094 30846 1971 4094 30847 1969 4094 30848 1969 4094 30849 1967 4094 30850 1965 4094 30851 1965 4094 30852 1963 4094 30853 1957 4094 30854 1963 4094 30855 1961 4094 30856 1957 4094 30857 1961 4094 30858 1959 4094 30859 1957 4094 30860 1957 4094 30861 1955 4094 30862 1953 4094 30863 1953 4094 30864 1951 4094 30865 1949 4094 30866 1949 4094 30867 1947 4094 30868 1941 4094 30869 1947 4094 30870 1945 4094 30871 1941 4094 30872 1945 4094 30873 1943 4094 30874 1941 4094 30875 1941 4094 30876 1939 4094 30877 1933 4094 30878 1939 4094 30879 1937 4094 30880 1933 4094 30881 1937 4094 30882 1935 4094 30883 1933 4094 30884 1933 4094 30885 1931 4094 30886 1929 4094 30887 1929 4094 30888 1927 4094 30889 1933 4094 30890 1927 4094 30891 1925 4094 30892 1933 4094 30893 1925 4094 30894 1923 4094 30895 1917 4094 30896 1923 4094 30897 1921 4094 30898 1917 4094 30899 1921 4094 30900 1919 4094 30901 1917 4094 30902 1917 4094 30903 1915 4094 30904 1913 4094 30905 1913 4094 30906 1911 4094 30907 1917 4094 30908 1911 4094 30909 1909 4094 30910 1917 4094 30911 1909 4094 30912 1907 4094 30913 1901 4094 30914 1907 4094 30915 1905 4094 30916 1901 4094 30917 1905 4094 30918 1903 4094 30919 1901 4094 30920 1901 4094 30921 1899 4094 30922 1897 4094 30923 1897 4094 30924 1895 4094 30925 1893 4094 30926 1893 4094 30927 1891 4094 30928 1885 4094 30929 1891 4094 30930 1889 4094 30931 1885 4094 30932 1889 4094 30933 1887 4094 30934 1885 4094 30935 1885 4094 30936 1883 4094 30937 1881 4094 30938 1881 4094 30939 1879 4094 30940 1885 4094 30941 1879 4094 30942 1877 4094 30943 1885 4094 30944 1877 4094 30945 1875 4094 30946 1873 4094 30947 1873 4094 30948 1871 4094 30949 1877 4094 30950 1871 4094 30951 1869 4094 30952 1877 4094 30953 1869 4094 30954 1867 4094 30955 1865 4094 30956 1865 4094 30957 1863 4094 30958 1861 4094 30959 1861 4094 30960 1859 4094 30961 1857 4094 30962 1857 4094 30963 1855 4094 30964 1861 4094 30965 1855 4094 30966 1853 4094 30967 1861 4094 30968 1853 4094 30969 1851 4094 30970 1849 4094 30971 1849 4094 30972 1847 4094 30973 1853 4094 30974 1847 4094 30975 1845 4094 30976 1853 4094 30977 1845 4094 30978 1843 4094 30979 1837 4094 30980 1843 4094 30981 1841 4094 30982 1837 4094 30983 1841 4094 30984 1839 4094 30985 1837 4094 30986 1837 4094 30987 1835 4094 30988 1833 4094 30989 1833 4094 30990 1831 4094 30991 1837 4094 30992 1831 4094 30993 1829 4094 30994 1837 4094 30995 1829 4094 30996 1827 4094 30997 1821 4094 30998 1827 4094 30999 1825 4094 31000 1821 4094 31001 1825 4094 31002 1823 4094 31003 1821 4094 31004 1821 4094 31005 1819 4094 31006 1817 4094 31007 1817 4094 31008 1815 4094 31009 1813 4094 31010 1813 4094 31011 1811 4094 31012 1805 4094 31013 1811 4094 31014 1809 4094 31015 1805 4094 31016 1809 4094 31017 1807 4094 31018 1805 4094 31019 1805 4094 31020 1803 4094 31021 1797 4094 31022 1803 4094 31023 1801 4094 31024 1797 4094 31025 1801 4094 31026 1799 4094 31027 1797 4094 31028 1797 4094 31029 1795 4094 31030 1793 4094 31031 1793 4094 31032 1791 4094 31033 1789 4094 31034 1789 4094 31035 1787 4094 31036 1781 4094 31037 1787 4094 31038 1785 4094 31039 1781 4094 31040 1785 4094 31041 1783 4094 31042 1781 4094 31043 1781 4094 31044 1779 4094 31045 1777 4094 31046 1777 4094 31047 1775 4094 31048 1781 4094 31049 1775 4094 31050 1773 4094 31051 1781 4094 31052 1773 4094 31053 1771 4094 31054 1765 4094 31055 1771 4094 31056 1769 4094 31057 1765 4094 31058 1769 4094 31059 1767 4094 31060 1765 4094 31061 1765 4094 31062 1763 4094 31063 1761 4094 31064 1761 4094 31065 1759 4094 31066 1757 4094 31067 1757 4094 31068 1755 4094 31069 1753 4094 31070 1753 4094 31071 1751 4094 31072 1757 4094 31073 1751 4094 31074 1749 4094 31075 1757 4094 31076 1749 4094 31077 1747 4094 31078 1741 4094 31079 1747 4094 31080 1745 4094 31081 1741 4094 31082 1745 4094 31083 1743 4094 31084 1741 4094 31085 1741 4094 31086 1739 4094 31087 1733 4094 31088 1739 4094 31089 1737 4094 31090 1733 4094 31091 1737 4094 31092 1735 4094 31093 1733 4094 31094 1733 4094 31095 1731 4094 31096 1729 4094 31097 1729 4094 31098 1727 4094 31099 1733 4094 31100 1727 4094 31101 1725 4094 31102 1733 4094 31103 1725 4094 31104 1723 4094 31105 1721 4094 31106 1721 4094 31107 1719 4094 31108 1717 4094 31109 1717 4094 31110 1715 4094 31111 1709 4094 31112 1715 4094 31113 1713 4094 31114 1709 4094 31115 1713 4094 31116 1711 4094 31117 1709 4094 31118 1709 4094 31119 1707 4094 31120 1705 4094 31121 1705 4094 31122 1703 4094 31123 1709 4094 31124 1703 4094 31125 1701 4094 31126 1709 4094 31127 1701 4094 31128 1699 4094 31129 1697 4094 31130 1697 4094 31131 1695 4094 31132 1693 4094 31133 1693 4094 31134 1691 4094 31135 1689 4094 31136 1689 4094 31137 1687 4094 31138 1693 4094 31139 1687 4094 31140 1685 4094 31141 1693 4094 31142 1685 4094 31143 1683 4094 31144 1681 4094 31145 1681 4094 31146 1679 4094 31147 1685 4094 31148 1679 4094 31149 1677 4094 31150 1685 4094 31151 1677 4094 31152 1675 4094 31153 1673 4094 31154 1673 4094 31155 1671 4094 31156 1669 4094 31157 1669 4094 31158 1667 4094 31159 1665 4094 31160 1665 4094 31161 1663 4094 31162 1669 4094 31163 1663 4094 31164 1661 4094 31165 1669 4094 31166 1661 4094 31167 1659 4094 31168 1653 4094 31169 1659 4094 31170 1657 4094 31171 1653 4094 31172 1657 4094 31173 1655 4094 31174 1653 4094 31175 1653 4094 31176 1651 4094 31177 1649 4094 31178 1649 4094 31179 1647 4094 31180 1645 4094 31181 1645 4094 31182 1643 4094 31183 1641 4094 31184 1641 4094 31185 1639 4094 31186 1645 4094 31187 1639 4094 31188 1637 4094 31189 1645 4094 31190 1637 4094 31191 1635 4094 31192 1633 4094 31193 1633 4094 31194 1631 4094 31195 1629 4094 31196 1629 4094 31197 1627 4094 31198 1621 4094 31199 1627 4094 31200 1625 4094 31201 1621 4094 31202 1625 4094 31203 1623 4094 31204 1621 4094 31205 1621 4094 31206 1619 4094 31207 1617 4094 31208 1617 4094 31209 1615 4094 31210 1621 4094 31211 1615 4094 31212 1613 4094 31213 1621 4094 31214 1613 4094 31215 1611 4094 31216 1609 4094 31217 1609 4094 31218 1607 4094 31219 1613 4094 31220 1607 4094 31221 1605 4094 31222 1613 4094 31223 1605 4094 31224 1603 4094 31225 1601 4094 31226 1601 4094 31227 1599 4094 31228 1605 4094 31229 1599 4094 31230 1597 4094 31231 1605 4094 31232 1597 4094 31233 1595 4094 31234 1593 4094 31235 1593 4094 31236 1591 4094 31237 1597 4094 31238 1591 4094 31239 1589 4094 31240 1597 4094 31241 1589 4094 31242 1587 4094 31243 1581 4094 31244 1587 4094 31245 1585 4094 31246 1581 4094 31247 1585 4094 31248 1583 4094 31249 1581 4094 31250 1581 4094 31251 1579 4094 31252 1577 4094 31253 1577 4094 31254 1575 4094 31255 1581 4094 31256 1575 4094 31257 1573 4094 31258 1581 4094 31259 1573 4094 31260 1571 4094 31261 1569 4094 31262 1569 4094 31263 1567 4094 31264 1573 4094 31265 1567 4094 31266 1565 4094 31267 1573 4094 31268 1565 4094 31269 1563 4094 31270 1561 4094 31271 1561 4094 31272 1559 4094 31273 1557 4094 31274 1557 4094 31275 1555 4094 31276 1553 4094 31277 1553 4094 31278 1551 4094 31279 1557 4094 31280 1551 4094 31281 1549 4094 31282 1557 4094 31283 1549 4094 31284 1547 4094 31285 1545 4094 31286 1545 4094 31287 1543 4094 31288 1549 4094 31289 1543 4094 31290 1541 4094 31291 1549 4094 31292 1541 4094 31293 1539 4094 31294 1537 4094 31295 1537 4094 31296 1535 4094 31297 1533 4094 31298 1533 4094 31299 1531 4094 31300 1529 4094 31301 1529 4094 31302 1527 4094 31303 1533 4094 31304 1527 4094 31305 1525 4094 31306 1533 4094 31307 1525 4094 31308 1523 4094 31309 1517 4094 31310 1523 4094 31311 1521 4094 31312 1517 4094 31313 1521 4094 31314 1519 4094 31315 1517 4094 31316 1517 4094 31317 1515 4094 31318 1509 4094 31319 1515 4094 31320 1513 4094 31321 1509 4094 31322 1513 4094 31323 1511 4094 31324 1509 4094 31325 1509 4094 31326 1507 4094 31327 1505 4094 31328 1505 4094 31329 1503 4094 31330 1501 4094 31331 1501 4094 31332 1499 4094 31333 1493 4094 31334 1499 4094 31335 1497 4094 31336 1493 4094 31337 1497 4094 31338 1495 4094 31339 1493 4094 31340 1493 4094 31341 1491 4094 31342 1489 4094 31343 1489 4094 31344 1487 4094 31345 1493 4094 31346 1487 4094 31347 1485 4094 31348 1493 4094 31349 1485 4094 31350 1483 4094 31351 1481 4094 31352 1481 4094 31353 1479 4094 31354 1485 4094 31355 1479 4094 31356 1477 4094 31357 1485 4094 31358 1477 4094 31359 1475 4094 31360 1469 4094 31361 1475 4094 31362 1473 4094 31363 1469 4094 31364 1473 4094 31365 1471 4094 31366 1469 4094 31367 1469 4094 31368 1467 4094 31369 1461 4094 31370 1467 4094 31371 1465 4094 31372 1461 4094 31373 1465 4094 31374 1463 4094 31375 1461 4094 31376 1461 4094 31377 1459 4094 31378 1453 4094 31379 1459 4094 31380 1457 4094 31381 1453 4094 31382 1457 4094 31383 1455 4094 31384 1453 4094 31385 1453 4094 31386 1451 4094 31387 1445 4094 31388 1451 4094 31389 1449 4094 31390 1445 4094 31391 1449 4094 31392 1447 4094 31393 1445 4094 31394 1445 4094 31395 1443 4094 31396 1441 4094 31397 1441 4094 31398 1439 4094 31399 1445 4094 31400 1439 4094 31401 1437 4094 31402 1445 4094 31403 1437 4094 31404 1435 4094 31405 1433 4094 31406 1433 4094 31407 1431 4094 31408 1437 4094 31409 1431 4094 31410 1429 4094 31411 1437 4094 31412 1429 4094 31413 1427 4094 31414 1421 4094 31415 1427 4094 31416 1425 4094 31417 1421 4094 31418 1425 4094 31419 1423 4094 31420 1421 4094 31421 1421 4094 31422 1419 4094 31423 1413 4094 31424 1419 4094 31425 1417 4094 31426 1413 4094 31427 1417 4094 31428 1415 4094 31429 1413 4094 31430 1413 4094 31431 1411 4094 31432 1409 4094 31433 1409 4094 31434 1407 4094 31435 1405 4094 31436 1405 4094 31437 1403 4094 31438 1397 4094 31439 1403 4094 31440 1401 4094 31441 1397 4094 31442 1401 4094 31443 1399 4094 31444 1397 4094 31445 1397 4094 31446 1395 4094 31447 1393 4094 31448 1393 4094 31449 1391 4094 31450 1397 4094 31451 1391 4094 31452 1389 4094 31453 1397 4094 31454 1389 4094 31455 1387 4094 31456 1385 4094 31457 1385 4094 31458 1383 4094 31459 1389 4094 31460 1383 4094 31461 1381 4094 31462 1389 4094 31463 1381 4094 31464 1379 4094 31465 1373 4094 31466 1379 4094 31467 1377 4094 31468 1373 4094 31469 1377 4094 31470 1375 4094 31471 1373 4094 31472 1373 4094 31473 1371 4094 31474 1369 4094 31475 1369 4094 31476 1367 4094 31477 1365 4094 31478 1365 4094 31479 1363 4094 31480 1361 4094 31481 1361 4094 31482 1359 4094 31483 1357 4094 31484 1357 4094 31485 1355 4094 31486 1353 4094 31487 1353 4094 31488 1351 4094 31489 1349 4094 31490 1349 4094 31491 1347 4094 31492 1345 4094 31493 1345 4094 31494 1343 4094 31495 1349 4094 31496 1343 4094 31497 1341 4094 31498 1349 4094 31499 1341 4094 31500 1339 4094 31501 1333 4094 31502 1339 4094 31503 1337 4094 31504 1333 4094 31505 1337 4094 31506 1335 4094 31507 1333 4094 31508 1333 4094 31509 1331 4094 31510 1329 4094 31511 1329 4094 31512 1327 4094 31513 1333 4094 31514 1327 4094 31515 1325 4094 31516 1333 4094 31517 1325 4094 31518 1323 4094 31519 1321 4094 31520 1321 4094 31521 1319 4094 31522 1317 4094 31523 1317 4094 31524 1315 4094 31525 1313 4094 31526 1313 4094 31527 1311 4094 31528 1317 4094 31529 1311 4094 31530 1309 4094 31531 1317 4094 31532 1309 4094 31533 1307 4094 31534 1305 4094 31535 1305 4094 31536 1303 4094 31537 1309 4094 31538 1303 4094 31539 1301 4094 31540 1309 4094 31541 1301 4094 31542 1299 4094 31543 1297 4094 31544 1297 4094 31545 1295 4094 31546 1293 4094 31547 1293 4094 31548 1291 4094 31549 1289 4094 31550 1289 4094 31551 1287 4094 31552 1285 4094 31553 1285 4094 31554 1283 4094 31555 1277 4094 31556 1283 4094 31557 1281 4094 31558 1277 4094 31559 1281 4094 31560 1279 4094 31561 1277 4094 31562 1277 4094 31563 1275 4094 31564 1273 4094 31565 1273 4094 31566 1271 4094 31567 1269 4094 31568 1269 4094 31569 1267 4094 31570 1261 4094 31571 1267 4094 31572 1265 4094 31573 1261 4094 31574 1265 4094 31575 1263 4094 31576 1261 4094 31577 1261 4094 31578 1259 4094 31579 1257 4094 31580 1257 4094 31581 1255 4094 31582 1261 4094 31583 1255 4094 31584 1253 4094 31585 1261 4094 31586 1253 4094 31587 1251 4094 31588 1249 4094 31589 1249 4094 31590 1247 4094 31591 1245 4094 31592 1245 4094 31593 1243 4094 31594 1241 4094 31595 1241 4094 31596 1239 4094 31597 1245 4094 31598 1239 4094 31599 1237 4094 31600 1245 4094 31601 1237 4094 31602 1235 4094 31603 1229 4094 31604 1235 4094 31605 1233 4094 31606 1229 4094 31607 1233 4094 31608 1231 4094 31609 1229 4094 31610 1229 4094 31611 1227 4094 31612 1225 4094 31613 1225 4094 31614 1223 4094 31615 1221 4094 31616 1221 4094 31617 1219 4094 31618 1217 4094 31619 1217 4094 31620 1215 4094 31621 1213 4094 31622 1213 4094 31623 1211 4094 31624 1205 4094 31625 1211 4094 31626 1209 4094 31627 1205 4094 31628 1209 4094 31629 1207 4094 31630 1205 4094 31631 1205 4094 31632 1203 4094 31633 1197 4094 31634 1203 4094 31635 1201 4094 31636 1197 4094 31637 1201 4094 31638 1199 4094 31639 1197 4094 31640 1197 4094 31641 1195 4094 31642 1193 4094 31643 1193 4094 31644 1191 4094 31645 1189 4094 31646 1189 4094 31647 1187 4094 31648 1185 4094 31649 1185 4094 31650 1183 4094 31651 1189 4094 31652 1183 4094 31653 1181 4094 31654 1189 4094 31655 1181 4094 31656 1179 4094 31657 1173 4094 31658 1179 4094 31659 1177 4094 31660 1173 4094 31661 1177 4094 31662 1175 4094 31663 1173 4094 31664 1173 4094 31665 1171 4094 31666 1169 4094 31667 1169 4094 31668 1167 4094 31669 1173 4094 31670 1167 4094 31671 1165 4094 31672 1173 4094 31673 1165 4094 31674 1163 4094 31675 1161 4094 31676 1161 4094 31677 1159 4094 31678 1157 4094 31679 1157 4094 31680 1155 4094 31681 1149 4094 31682 1155 4094 31683 1153 4094 31684 1149 4094 31685 1153 4094 31686 1151 4094 31687 1149 4094 31688 1149 4094 31689 1147 4094 31690 1145 4094 31691 1145 4094 31692 1143 4094 31693 1149 4094 31694 1143 4094 31695 1141 4094 31696 1149 4094 31697 1141 4094 31698 1139 4094 31699 1137 4094 31700 1137 4094 31701 1135 4094 31702 1133 4094 31703 1133 4094 31704 1131 4094 31705 1129 4094 31706 1129 4094 31707 1127 4094 31708 1133 4094 31709 1127 4094 31710 1125 4094 31711 1133 4094 31712 1125 4094 31713 1123 4094 31714 1121 4094 31715 1121 4094 31716 1119 4094 31717 1125 4094 31718 1119 4094 31719 1117 4094 31720 1125 4094 31721 1117 4094 31722 1115 4094 31723 1113 4094 31724 1113 4094 31725 1111 4094 31726 1117 4094 31727 1111 4094 31728 1109 4094 31729 1117 4094 31730 1109 4094 31731 1107 4094 31732 1105 4094 31733 1105 4094 31734 1103 4094 31735 1109 4094 31736 1103 4094 31737 1101 4094 31738 1109 4094 31739 1101 4094 31740 1099 4094 31741 1097 4094 31742 1097 4094 31743 1095 4094 31744 1093 4094 31745 1093 4094 31746 1091 4094 31747 1085 4094 31748 1091 4094 31749 1089 4094 31750 1085 4094 31751 1089 4094 31752 1087 4094 31753 1085 4094 31754 1085 4094 31755 1083 4094 31756 1081 4094 31757 1081 4094 31758 1079 4094 31759 1085 4094 31760 1079 4094 31761 1077 4094 31762 1085 4094 31763 1077 4094 31764 1075 4094 31765 1069 4094 31766 1075 4094 31767 1073 4094 31768 1069 4094 31769 1073 4094 31770 1071 4094 31771 1069 4094 31772 1069 4094 31773 1067 4094 31774 1065 4094 31775 1065 4094 31776 1063 4094 31777 1061 4094 31778 1061 4094 31779 1059 4094 31780 1057 4094 31781 1057 4094 31782 1055 4094 31783 1061 4094 31784 1055 4094 31785 1053 4094 31786 1061 4094 31787 1053 4094 31788 1051 4094 31789 1049 4094 31790 1049 4094 31791 1047 4094 31792 1045 4094 31793 1045 4094 31794 1043 4094 31795 1041 4094 31796 1041 4094 31797 1039 4094 31798 1037 4094 31799 1037 4094 31800 1035 4094 31801 1033 4094 31802 1033 4094 31803 1031 4094 31804 1037 4094 31805 1031 4094 31806 1029 4094 31807 1037 4094 31808 1029 4094 31809 1027 4094 31810 1025 4094 31811 1025 4094 31812 1023 4094 31813 1029 4094 31814 1023 4094 31815 1021 4094 31816 1029 4094 31817 1021 4094 31818 1019 4094 31819 1017 4094 31820 1017 4094 31821 1015 4094 31822 1021 4094 31823 1015 4094 31824 1013 4094 31825 1021 4094 31826 1013 4094 31827 1011 4094 31828 1009 4094 31829 1009 4094 31830 1007 4094 31831 1013 4094 31832 1007 4094 31833 1005 4094 31834 1013 4094 31835 1005 4094 31836 1003 4094 31837 1001 4094 31838 1001 4094 31839 999 4094 31840 997 4094 31841 997 4094 31842 995 4094 31843 989 4094 31844 995 4094 31845 993 4094 31846 989 4094 31847 993 4094 31848 991 4094 31849 989 4094 31850 989 4094 31851 987 4094 31852 985 4094 31853 985 4094 31854 983 4094 31855 981 4094 31856 981 4094 31857 979 4094 31858 977 4094 31859 977 4094 31860 975 4094 31861 981 4094 31862 975 4094 31863 973 4094 31864 981 4094 31865 973 4094 31866 971 4094 31867 965 4094 31868 971 4094 31869 969 4094 31870 965 4094 31871 969 4094 31872 967 4094 31873 965 4094 31874 965 4094 31875 963 4094 31876 961 4094 31877 961 4094 31878 959 4094 31879 965 4094 31880 959 4094 31881 957 4094 31882 965 4094 31883 957 4094 31884 955 4094 31885 953 4094 31886 953 4094 31887 951 4094 31888 949 4094 31889 949 4094 31890 947 4094 31891 941 4094 31892 947 4094 31893 945 4094 31894 941 4094 31895 945 4094 31896 943 4094 31897 941 4094 31898 941 4094 31899 939 4094 31900 937 4094 31901 937 4094 31902 935 4094 31903 941 4094 31904 935 4094 31905 933 4094 31906 941 4094 31907 933 4094 31908 931 4094 31909 925 4094 31910 931 4094 31911 929 4094 31912 925 4094 31913 929 4094 31914 927 4094 31915 925 4094 31916 925 4094 31917 923 4094 31918 917 4094 31919 923 4094 31920 921 4094 31921 917 4094 31922 921 4094 31923 919 4094 31924 917 4094 31925 917 4094 31926 915 4094 31927 913 4094 31928 913 4094 31929 911 4094 31930 909 4094 31931 909 4094 31932 907 4094 31933 901 4094 31934 907 4094 31935 905 4094 31936 901 4094 31937 905 4094 31938 903 4094 31939 901 4094 31940 901 4094 31941 899 4094 31942 897 4094 31943 897 4094 31944 895 4094 31945 901 4094 31946 895 4094 31947 893 4094 31948 901 4094 31949 893 4094 31950 891 4094 31951 889 4094 31952 889 4094 31953 887 4094 31954 885 4094 31955 885 4094 31956 883 4094 31957 877 4094 31958 883 4094 31959 881 4094 31960 877 4094 31961 881 4094 31962 879 4094 31963 877 4094 31964 877 4094 31965 875 4094 31966 873 4094 31967 873 4094 31968 871 4094 31969 877 4094 31970 871 4094 31971 869 4094 31972 877 4094 31973 869 4094 31974 867 4094 31975 861 4094 31976 867 4094 31977 865 4094 31978 861 4094 31979 865 4094 31980 863 4094 31981 861 4094 31982 861 4094 31983 859 4094 31984 857 4094 31985 857 4094 31986 855 4094 31987 853 4094 31988 853 4094 31989 851 4094 31990 849 4094 31991 849 4094 31992 847 4094 31993 853 4094 31994 847 4094 31995 845 4094 31996 853 4094 31997 845 4094 31998 843 4094 31999 841 4094 32000 841 4094 32001 839 4094 32002 845 4094 32003 839 4094 32004 837 4094 32005 845 4094 32006 837 4094 32007 835 4094 32008 833 4094 32009 833 4094 32010 831 4094 32011 829 4094 32012 829 4094 32013 827 4094 32014 825 4094 32015 825 4094 32016 823 4094 32017 821 4094 32018 821 4094 32019 819 4094 32020 817 4094 32021 817 4094 32022 815 4094 32023 821 4094 32024 815 4094 32025 813 4094 32026 821 4094 32027 813 4094 32028 811 4094 32029 805 4094 32030 811 4094 32031 809 4094 32032 805 4094 32033 809 4094 32034 807 4094 32035 805 4094 32036 805 4094 32037 803 4094 32038 801 4094 32039 801 4094 32040 799 4094 32041 797 4094 32042 797 4094 32043 795 4094 32044 789 4094 32045 795 4094 32046 793 4094 32047 789 4094 32048 793 4094 32049 791 4094 32050 789 4094 32051 789 4094 32052 787 4094 32053 785 4094 32054 785 4094 32055 783 4094 32056 789 4094 32057 783 4094 32058 781 4094 32059 789 4094 32060 781 4094 32061 779 4094 32062 777 4094 32063 777 4094 32064 775 4094 32065 773 4094 32066 773 4094 32067 771 4094 32068 769 4094 32069 769 4094 32070 767 4094 32071 773 4094 32072 767 4094 32073 765 4094 32074 773 4094 32075 765 4094 32076 763 4094 32077 761 4094 32078 761 4094 32079 759 4094 32080 757 4094 32081 757 4094 32082 755 4094 32083 753 4094 32084 753 4094 32085 751 4094 32086 749 4094 32087 749 4094 32088 747 4094 32089 741 4094 32090 747 4094 32091 745 4094 32092 741 4094 32093 745 4094 32094 743 4094 32095 741 4094 32096 741 4094 32097 739 4094 32098 733 4094 32099 739 4094 32100 737 4094 32101 733 4094 32102 737 4094 32103 735 4094 32104 733 4094 32105 733 4094 32106 731 4094 32107 729 4094 32108 729 4094 32109 727 4094 32110 725 4094 32111 725 4094 32112 723 4094 32113 717 4094 32114 723 4094 32115 721 4094 32116 717 4094 32117 721 4094 32118 719 4094 32119 717 4094 32120 717 4094 32121 715 4094 32122 713 4094 32123 713 4094 32124 711 4094 32125 717 4094 32126 711 4094 32127 709 4094 32128 717 4094 32129 709 4094 32130 707 4094 32131 701 4094 32132 707 4094 32133 705 4094 32134 701 4094 32135 705 4094 32136 703 4094 32137 701 4094 32138 701 4094 32139 699 4094 32140 697 4094 32141 697 4094 32142 695 4094 32143 693 4094 32144 693 4094 32145 691 4094 32146 689 4094 32147 689 4094 32148 687 4094 32149 685 4094 32150 685 4094 32151 683 4094 32152 681 4094 32153 681 4094 32154 679 4094 32155 677 4094 32156 677 4094 32157 675 4094 32158 673 4094 32159 673 4094 32160 671 4094 32161 677 4094 32162 671 4094 32163 669 4094 32164 677 4094 32165 669 4094 32166 667 4094 32167 661 4094 32168 667 4094 32169 665 4094 32170 661 4094 32171 665 4094 32172 663 4094 32173 661 4094 32174 661 4094 32175 659 4094 32176 657 4094 32177 657 4094 32178 655 4094 32179 653 4094 32180 653 4094 32181 651 4094 32182 649 4094 32183 649 4094 32184 647 4094 32185 653 4094 32186 647 4094 32187 645 4094 32188 653 4094 32189 645 4094 32190 643 4094 32191 641 4094 32192 641 4094 32193 639 4094 32194 637 4094 32195 637 4094 32196 635 4094 32197 633 4094 32198 633 4094 32199 631 4094 32200 637 4094 32201 631 4094 32202 629 4094 32203 637 4094 32204 629 4094 32205 627 4094 32206 625 4094 32207 625 4094 32208 623 4094 32209 629 4094 32210 623 4094 32211 621 4094 32212 629 4094 32213 621 4094 32214 619 4094 32215 613 4094 32216 619 4094 32217 617 4094 32218 613 4094 32219 617 4094 32220 615 4094 32221 613 4094 32222 613 4094 32223 611 4094 32224 605 4094 32225 611 4094 32226 609 4094 32227 605 4094 32228 609 4094 32229 607 4094 32230 605 4094 32231 605 4094 32232 603 4094 32233 601 4094 32234 601 4094 32235 599 4094 32236 605 4094 32237 599 4094 32238 597 4094 32239 605 4094 32240 597 4094 32241 595 4094 32242 593 4094 32243 593 4094 32244 591 4094 32245 597 4094 32246 591 4094 32247 589 4094 32248 597 4094 32249 589 4094 32250 587 4094 32251 585 4094 32252 585 4094 32253 583 4094 32254 589 4094 32255 583 4094 32256 581 4094 32257 589 4094 32258 581 4094 32259 579 4094 32260 577 4094 32261 577 4094 32262 575 4094 32263 581 4094 32264 575 4094 32265 573 4094 32266 581 4094 32267 573 4094 32268 571 4094 32269 565 4094 32270 571 4094 32271 569 4094 32272 565 4094 32273 569 4094 32274 567 4094 32275 565 4094 32276 565 4094 32277 563 4094 32278 561 4094 32279 561 4094 32280 559 4094 32281 557 4094 32282 557 4094 32283 555 4094 32284 553 4094 32285 553 4094 32286 551 4094 32287 557 4094 32288 551 4094 32289 549 4094 32290 557 4094 32291 549 4094 32292 547 4094 32293 545 4094 32294 545 4094 32295 543 4094 32296 541 4094 32297 541 4094 32298 539 4094 32299 537 4094 32300 537 4094 32301 535 4094 32302 541 4094 32303 535 4094 32304 533 4094 32305 541 4094 32306 533 4094 32307 531 4094 32308 529 4094 32309 529 4094 32310 527 4094 32311 533 4094 32312 527 4094 32313 525 4094 32314 533 4094 32315 525 4094 32316 523 4094 32317 517 4094 32318 523 4094 32319 521 4094 32320 517 4094 32321 521 4094 32322 519 4094 32323 517 4094 32324 517 4094 32325 515 4094 32326 513 4094 32327 513 4094 32328 511 4094 32329 509 4094 32330 509 4094 32331 507 4094 32332 501 4094 32333 507 4094 32334 505 4094 32335 501 4094 32336 505 4094 32337 503 4094 32338 501 4094 32339 501 4094 32340 499 4094 32341 493 4094 32342 499 4094 32343 497 4094 32344 493 4094 32345 497 4094 32346 495 4094 32347 493 4094 32348 493 4094 32349 491 4094 32350 489 4094 32351 489 4094 32352 487 4094 32353 485 4094 32354 485 4094 32355 483 4094 32356 477 4094 32357 483 4094 32358 481 4094 32359 477 4094 32360 481 4094 32361 479 4094 32362 477 4094 32363 477 4094 32364 475 4094 32365 469 4094 32366 475 4094 32367 473 4094 32368 469 4094 32369 473 4094 32370 471 4094 32371 469 4094 32372 469 4094 32373 467 4094 32374 465 4094 32375 465 4094 32376 463 4094 32377 469 4094 32378 463 4094 32379 461 4094 32380 469 4094 32381 461 4094 32382 459 4094 32383 457 4094 32384 457 4094 32385 455 4094 32386 453 4094 32387 453 4094 32388 451 4094 32389 445 4094 32390 451 4094 32391 449 4094 32392 445 4094 32393 449 4094 32394 447 4094 32395 445 4094 32396 445 4094 32397 443 4094 32398 441 4094 32399 441 4094 32400 439 4094 32401 437 4094 32402 437 4094 32403 435 4094 32404 429 4094 32405 435 4094 32406 433 4094 32407 429 4094 32408 433 4094 32409 431 4094 32410 429 4094 32411 429 4094 32412 427 4094 32413 425 4094 32414 425 4094 32415 423 4094 32416 421 4094 32417 421 4094 32418 419 4094 32419 417 4094 32420 417 4094 32421 415 4094 32422 413 4094 32423 413 4094 32424 411 4094 32425 405 4094 32426 411 4094 32427 409 4094 32428 405 4094 32429 409 4094 32430 407 4094 32431 405 4094 32432 405 4094 32433 403 4094 32434 401 4094 32435 401 4094 32436 399 4094 32437 397 4094 32438 397 4094 32439 395 4094 32440 393 4094 32441 393 4094 32442 391 4094 32443 397 4094 32444 391 4094 32445 389 4094 32446 397 4094 32447 389 4094 32448 387 4094 32449 381 4094 32450 387 4094 32451 385 4094 32452 381 4094 32453 385 4094 32454 383 4094 32455 381 4094 32456 381 4094 32457 379 4094 32458 377 4094 32459 377 4094 32460 375 4094 32461 373 4094 32462 373 4094 32463 371 4094 32464 365 4094 32465 371 4094 32466 369 4094 32467 365 4094 32468 369 4094 32469 367 4094 32470 365 4094 32471 365 4094 32472 363 4094 32473 357 4094 32474 363 4094 32475 361 4094 32476 357 4094 32477 361 4094 32478 359 4094 32479 357 4094 32480 357 4094 32481 355 4094 32482 349 4094 32483 355 4094 32484 353 4094 32485 349 4094 32486 353 4094 32487 351 4094 32488 349 4094 32489 349 4094 32490 347 4094 32491 341 4094 32492 347 4094 32493 345 4094 32494 341 4094 32495 345 4094 32496 343 4094 32497 341 4094 32498 341 4094 32499 339 4094 32500 337 4094 32501 337 4094 32502 335 4094 32503 341 4094 32504 335 4094 32505 333 4094 32506 341 4094 32507 333 4094 32508 331 4094 32509 329 4094 32510 329 4094 32511 327 4094 32512 325 4094 32513 325 4094 32514 323 4094 32515 317 4094 32516 323 4094 32517 321 4094 32518 317 4094 32519 321 4094 32520 319 4094 32521 317 4094 32522 317 4094 32523 315 4094 32524 313 4094 32525 313 4094 32526 311 4094 32527 317 4094 32528 311 4094 32529 309 4094 32530 317 4094 32531 309 4094 32532 307 4094 32533 305 4094 32534 305 4094 32535 303 4094 32536 309 4094 32537 303 4094 32538 301 4094 32539 309 4094 32540 301 4094 32541 299 4094 32542 297 4094 32543 297 4094 32544 295 4094 32545 293 4094 32546 293 4094 32547 291 4094 32548 289 4094 32549 289 4094 32550 287 4094 32551 285 4094 32552 285 4094 32553 283 4094 32554 281 4094 32555 281 4094 32556 279 4094 32557 285 4094 32558 279 4094 32559 277 4094 32560 285 4094 32561 277 4094 32562 275 4094 32563 269 4094 32564 275 4094 32565 273 4094 32566 269 4094 32567 273 4094 32568 271 4094 32569 269 4094 32570 269 4094 32571 267 4094 32572 265 4094 32573 265 4094 32574 263 4094 32575 269 4094 32576 263 4094 32577 261 4094 32578 269 4094 32579 261 4094 32580 259 4094 32581 257 4094 32582 257 4094 32583 255 4094 32584 253 4094 32585 253 4094 32586 251 4094 32587 249 4094 32588 249 4094 32589 247 4094 32590 253 4094 32591 247 4094 32592 245 4094 32593 253 4094 32594 245 4094 32595 243 4094 32596 241 4094 32597 241 4094 32598 239 4094 32599 245 4094 32600 239 4094 32601 237 4094 32602 245 4094 32603 237 4094 32604 235 4094 32605 233 4094 32606 233 4094 32607 231 4094 32608 229 4094 32609 229 4094 32610 227 4094 32611 225 4094 32612 225 4094 32613 223 4094 32614 229 4094 32615 223 4094 32616 221 4094 32617 229 4094 32618 221 4094 32619 219 4094 32620 213 4094 32621 219 4094 32622 217 4094 32623 213 4094 32624 217 4094 32625 215 4094 32626 213 4094 32627 213 4094 32628 211 4094 32629 209 4094 32630 209 4094 32631 207 4094 32632 205 4094 32633 205 4094 32634 203 4094 32635 197 4094 32636 203 4094 32637 201 4094 32638 197 4094 32639 201 4094 32640 199 4094 32641 197 4094 32642 197 4094 32643 195 4094 32644 189 4094 32645 195 4094 32646 193 4094 32647 189 4094 32648 193 4094 32649 191 4094 32650 189 4094 32651 189 4094 32652 187 4094 32653 185 4094 32654 185 4094 32655 183 4094 32656 181 4094 32657 181 4094 32658 179 4094 32659 173 4094 32660 179 4094 32661 177 4094 32662 173 4094 32663 177 4094 32664 175 4094 32665 173 4094 32666 173 4094 32667 171 4094 32668 165 4094 32669 171 4094 32670 169 4094 32671 165 4094 32672 169 4094 32673 167 4094 32674 165 4094 32675 165 4094 32676 163 4094 32677 161 4094 32678 161 4094 32679 159 4094 32680 165 4094 32681 159 4094 32682 157 4094 32683 165 4094 32684 157 4094 32685 155 4094 32686 153 4094 32687 153 4094 32688 151 4094 32689 149 4094 32690 149 4094 32691 147 4094 32692 145 4094 32693 145 4094 32694 143 4094 32695 149 4094 32696 143 4094 32697 141 4094 32698 149 4094 32699 141 4094 32700 139 4094 32701 133 4094 32702 139 4094 32703 137 4094 32704 133 4094 32705 137 4094 32706 135 4094 32707 133 4094 32708 133 4094 32709 131 4094 32710 129 4094 32711 129 4094 32712 127 4094 32713 133 4094 32714 127 4094 32715 125 4094 32716 133 4094 32717 125 4094 32718 123 4094 32719 121 4094 32720 121 4094 32721 119 4094 32722 117 4094 32723 117 4094 32724 115 4094 32725 113 4094 32726 113 4094 32727 111 4094 32728 117 4094 32729 111 4094 32730 109 4094 32731 117 4094 32732 109 4094 32733 107 4094 32734 105 4094 32735 105 4094 32736 103 4094 32737 109 4094 32738 103 4094 32739 101 4094 32740 109 4094 32741 101 4094 32742 99 4094 32743 93 4094 32744 99 4094 32745 97 4094 32746 93 4094 32747 97 4094 32748 95 4094 32749 93 4094 32750 93 4094 32751 91 4094 32752 89 4094 32753 89 4094 32754 87 4094 32755 85 4094 32756 85 4094 32757 83 4094 32758 77 4094 32759 83 4094 32760 81 4094 32761 77 4094 32762 81 4094 32763 79 4094 32764 77 4094 32765 77 4094 32766 75 4094 32767 73 4094 32768 73 4094 32769 71 4094 32770 69 4094 32771 69 4094 32772 67 4094 32773 65 4094 32774 65 4094 32775 63 4094 32776 61 4094 32777 61 4094 32778 59 4094 32779 57 4094 32780 57 4094 32781 55 4094 32782 61 4094 32783 55 4094 32784 53 4094 32785 61 4094 32786 53 4094 32787 51 4094 32788 49 4094 32789 49 4094 32790 47 4094 32791 45 4094 32792 45 4094 32793 43 4094 32794 41 4094 32795 41 4094 32796 39 4094 32797 37 4094 32798 37 4094 32799 35 4094 32800 33 4094 32801 33 4094 32802 31 4094 32803 29 4094 32804 29 4094 32805 27 4094 32806 21 4094 32807 27 4094 32808 25 4094 32809 21 4094 32810 25 4094 32811 23 4094 32812 21 4094 32813 21 4094 32814 19 4094 32815 13 4094 32816 19 4094 32817 17 4094 32818 13 4094 32819 17 4094 32820 15 4094 32821 13 4094 32822 13 4094 32823 11 4094 32824 9 4094 32825 9 4094 32826 7 4094 32827 13 4094 32828 7 4094 32829 5 4094 32830 13 4094 32831 8165 4094 32832 8161 4094 32833 8149 4094 32834 8161 4094 32835 8157 4094 32836 8149 4094 32837 8157 4094 32838 8153 4094 32839 8149 4094 32840 8149 4094 32841 8145 4094 32842 8133 4094 32843 8145 4094 32844 8141 4094 32845 8133 4094 32846 8125 4094 32847 8121 4094 32848 8133 4094 32849 8121 4094 32850 8117 4094 32851 8133 4094 32852 8117 4094 32853 8113 4094 32854 8101 4094 32855 8113 4094 32856 8109 4094 32857 8101 4094 32858 8101 4094 32859 8097 4094 32860 8085 4094 32861 8097 4094 32862 8093 4094 32863 8085 4094 32864 8045 4094 32865 8041 4094 32866 8053 4094 32867 8041 4094 32868 8037 4094 32869 8053 4094 32870 8013 4094 32871 8009 4094 32872 8021 4094 32873 8009 4094 32874 8005 4094 32875 8021 4094 32876 7965 4094 32877 7961 4094 32878 7957 4094 32879 7941 4094 32880 7937 4094 32881 7933 4094 32882 7909 4094 32883 7905 4094 32884 7893 4094 32885 7905 4094 32886 7901 4094 32887 7893 4094 32888 7869 4094 32889 7865 4094 32890 7877 4094 32891 7865 4094 32892 7861 4094 32893 7877 4094 32894 7845 4094 32895 7841 4094 32896 7829 4094 32897 7841 4094 32898 7837 4094 32899 7829 4094 32900 7821 4094 32901 7817 4094 32902 7829 4094 32903 7817 4094 32904 7813 4094 32905 7829 4094 32906 7797 4094 32907 7793 4094 32908 7781 4094 32909 7793 4094 32910 7789 4094 32911 7781 4094 32912 7781 4094 32913 7777 4094 32914 7765 4094 32915 7777 4094 32916 7773 4094 32917 7765 4094 32918 7709 4094 32919 7705 4094 32920 7717 4094 32921 7705 4094 32922 7701 4094 32923 7717 4094 32924 7685 4094 32925 7681 4094 32926 7669 4094 32927 7681 4094 32928 7677 4094 32929 7669 4094 32930 7653 4094 32931 7649 4094 32932 7637 4094 32933 7649 4094 32934 7645 4094 32935 7637 4094 32936 7557 4094 32937 7553 4094 32938 7541 4094 32939 7553 4094 32940 7549 4094 32941 7541 4094 32942 7517 4094 32943 7513 4094 32944 7525 4094 32945 7513 4094 32946 7509 4094 32947 7525 4094 32948 7509 4094 32949 7505 4094 32950 7493 4094 32951 7505 4094 32952 7501 4094 32953 7493 4094 32954 7501 4094 32955 7497 4094 32956 7493 4094 32957 7469 4094 32958 7465 4094 32959 7477 4094 32960 7465 4094 32961 7461 4094 32962 7477 4094 32963 7445 4094 32964 7441 4094 32965 7437 4094 32966 7437 4094 32967 7433 4094 32968 7445 4094 32969 7433 4094 32970 7429 4094 32971 7445 4094 32972 7421 4094 32973 7417 4094 32974 7413 4094 32975 7397 4094 32976 7393 4094 32977 7389 4094 32978 7373 4094 32979 7369 4094 32980 7365 4094 32981 7365 4094 32982 7361 4094 32983 7349 4094 32984 7361 4094 32985 7357 4094 32986 7349 4094 32987 7341 4094 32988 7337 4094 32989 7349 4094 32990 7337 4094 32991 7333 4094 32992 7349 4094 32993 7309 4094 32994 7305 4094 32995 7317 4094 32996 7305 4094 32997 7301 4094 32998 7317 4094 32999 7285 4094 33000 7281 4094 33001 7269 4094 33002 7281 4094 33003 7277 4094 33004 7269 4094 33005 7245 4094 33006 7241 4094 33007 7253 4094 33008 7241 4094 33009 7237 4094 33010 7253 4094 33011 7213 4094 33012 7209 4094 33013 7221 4094 33014 7209 4094 33015 7205 4094 33016 7221 4094 33017 7197 4094 33018 7193 4094 33019 7205 4094 33020 7193 4094 33021 7189 4094 33022 7205 4094 33023 7189 4094 33024 7185 4094 33025 7173 4094 33026 7185 4094 33027 7181 4094 33028 7173 4094 33029 7149 4094 33030 7145 4094 33031 7157 4094 33032 7145 4094 33033 7141 4094 33034 7157 4094 33035 7133 4094 33036 7129 4094 33037 7125 4094 33038 7101 4094 33039 7097 4094 33040 7109 4094 33041 7097 4094 33042 7093 4094 33043 7109 4094 33044 7061 4094 33045 7057 4094 33046 7045 4094 33047 7057 4094 33048 7053 4094 33049 7045 4094 33050 7037 4094 33051 7033 4094 33052 7045 4094 33053 7033 4094 33054 7029 4094 33055 7045 4094 33056 7005 4094 33057 7001 4094 33058 7013 4094 33059 7001 4094 33060 6997 4094 33061 7013 4094 33062 6981 4094 33063 6977 4094 33064 6965 4094 33065 6977 4094 33066 6973 4094 33067 6965 4094 33068 6973 4094 33069 6969 4094 33070 6965 4094 33071 6949 4094 33072 6945 4094 33073 6941 4094 33074 6925 4094 33075 6921 4094 33076 6917 4094 33077 6909 4094 33078 6905 4094 33079 6917 4094 33080 6905 4094 33081 6901 4094 33082 6917 4094 33083 6901 4094 33084 6897 4094 33085 6893 4094 33086 6877 4094 33087 6873 4094 33088 6885 4094 33089 6873 4094 33090 6869 4094 33091 6885 4094 33092 6845 4094 33093 6841 4094 33094 6853 4094 33095 6841 4094 33096 6837 4094 33097 6853 4094 33098 6837 4094 33099 6833 4094 33100 6821 4094 33101 6833 4094 33102 6829 4094 33103 6821 4094 33104 6829 4094 33105 6825 4094 33106 6821 4094 33107 6805 4094 33108 6801 4094 33109 6789 4094 33110 6801 4094 33111 6797 4094 33112 6789 4094 33113 6789 4094 33114 6785 4094 33115 6781 4094 33116 6709 4094 33117 6705 4094 33118 6693 4094 33119 6705 4094 33120 6701 4094 33121 6693 4094 33122 6693 4094 33123 6689 4094 33124 6677 4094 33125 6689 4094 33126 6685 4094 33127 6677 4094 33128 6661 4094 33129 6657 4094 33130 6645 4094 33131 6657 4094 33132 6653 4094 33133 6645 4094 33134 6637 4094 33135 6633 4094 33136 6645 4094 33137 6633 4094 33138 6629 4094 33139 6645 4094 33140 6605 4094 33141 6601 4094 33142 6613 4094 33143 6601 4094 33144 6597 4094 33145 6613 4094 33146 6589 4094 33147 6585 4094 33148 6597 4094 33149 6585 4094 33150 6581 4094 33151 6597 4094 33152 6573 4094 33153 6569 4094 33154 6581 4094 33155 6569 4094 33156 6565 4094 33157 6581 4094 33158 6565 4094 33159 6561 4094 33160 6549 4094 33161 6561 4094 33162 6557 4094 33163 6549 4094 33164 6549 4094 33165 6545 4094 33166 6533 4094 33167 6545 4094 33168 6541 4094 33169 6533 4094 33170 6525 4094 33171 6521 4094 33172 6533 4094 33173 6521 4094 33174 6517 4094 33175 6533 4094 33176 6477 4094 33177 6473 4094 33178 6485 4094 33179 6473 4094 33180 6469 4094 33181 6485 4094 33182 6445 4094 33183 6441 4094 33184 6453 4094 33185 6441 4094 33186 6437 4094 33187 6453 4094 33188 6437 4094 33189 6433 4094 33190 6421 4094 33191 6433 4094 33192 6429 4094 33193 6421 4094 33194 6405 4094 33195 6401 4094 33196 6389 4094 33197 6401 4094 33198 6397 4094 33199 6389 4094 33200 6381 4094 33201 6377 4094 33202 6389 4094 33203 6377 4094 33204 6373 4094 33205 6389 4094 33206 6357 4094 33207 6353 4094 33208 6341 4094 33209 6353 4094 33210 6349 4094 33211 6341 4094 33212 6333 4094 33213 6329 4094 33214 6341 4094 33215 6329 4094 33216 6325 4094 33217 6341 4094 33218 6301 4094 33219 6297 4094 33220 6309 4094 33221 6297 4094 33222 6293 4094 33223 6309 4094 33224 6269 4094 33225 6265 4094 33226 6277 4094 33227 6265 4094 33228 6261 4094 33229 6277 4094 33230 6237 4094 33231 6233 4094 33232 6245 4094 33233 6233 4094 33234 6229 4094 33235 6245 4094 33236 6221 4094 33237 6217 4094 33238 6229 4094 33239 6217 4094 33240 6213 4094 33241 6229 4094 33242 6213 4094 33243 6209 4094 33244 6197 4094 33245 6209 4094 33246 6205 4094 33247 6197 4094 33248 6197 4094 33249 6193 4094 33250 6181 4094 33251 6193 4094 33252 6189 4094 33253 6181 4094 33254 6189 4094 33255 6185 4094 33256 6181 4094 33257 6181 4094 33258 6177 4094 33259 6173 4094 33260 6117 4094 33261 6113 4094 33262 6101 4094 33263 6113 4094 33264 6109 4094 33265 6101 4094 33266 6109 4094 33267 6105 4094 33268 6101 4094 33269 6101 4094 33270 6097 4094 33271 6085 4094 33272 6097 4094 33273 6093 4094 33274 6085 4094 33275 6077 4094 33276 6073 4094 33277 6085 4094 33278 6073 4094 33279 6069 4094 33280 6085 4094 33281 6069 4094 33282 6065 4094 33283 6053 4094 33284 6065 4094 33285 6061 4094 33286 6053 4094 33287 6053 4094 33288 6049 4094 33289 6037 4094 33290 6049 4094 33291 6045 4094 33292 6037 4094 33293 5997 4094 33294 5993 4094 33295 6005 4094 33296 5993 4094 33297 5989 4094 33298 6005 4094 33299 5965 4094 33300 5961 4094 33301 5973 4094 33302 5961 4094 33303 5957 4094 33304 5973 4094 33305 5917 4094 33306 5913 4094 33307 5909 4094 33308 5893 4094 33309 5889 4094 33310 5885 4094 33311 5861 4094 33312 5857 4094 33313 5845 4094 33314 5857 4094 33315 5853 4094 33316 5845 4094 33317 5821 4094 33318 5817 4094 33319 5829 4094 33320 5817 4094 33321 5813 4094 33322 5829 4094 33323 5797 4094 33324 5793 4094 33325 5781 4094 33326 5793 4094 33327 5789 4094 33328 5781 4094 33329 5773 4094 33330 5769 4094 33331 5781 4094 33332 5769 4094 33333 5765 4094 33334 5781 4094 33335 5749 4094 33336 5745 4094 33337 5733 4094 33338 5745 4094 33339 5741 4094 33340 5733 4094 33341 5733 4094 33342 5729 4094 33343 5717 4094 33344 5729 4094 33345 5725 4094 33346 5717 4094 33347 5661 4094 33348 5657 4094 33349 5669 4094 33350 5657 4094 33351 5653 4094 33352 5669 4094 33353 5637 4094 33354 5633 4094 33355 5621 4094 33356 5633 4094 33357 5629 4094 33358 5621 4094 33359 5605 4094 33360 5601 4094 33361 5589 4094 33362 5601 4094 33363 5597 4094 33364 5589 4094 33365 5509 4094 33366 5505 4094 33367 5493 4094 33368 5505 4094 33369 5501 4094 33370 5493 4094 33371 5469 4094 33372 5465 4094 33373 5477 4094 33374 5465 4094 33375 5461 4094 33376 5477 4094 33377 5461 4094 33378 5457 4094 33379 5445 4094 33380 5457 4094 33381 5453 4094 33382 5445 4094 33383 5453 4094 33384 5449 4094 33385 5445 4094 33386 5421 4094 33387 5417 4094 33388 5429 4094 33389 5417 4094 33390 5413 4094 33391 5429 4094 33392 5397 4094 33393 5393 4094 33394 5389 4094 33395 5389 4094 33396 5385 4094 33397 5397 4094 33398 5385 4094 33399 5381 4094 33400 5397 4094 33401 5373 4094 33402 5369 4094 33403 5365 4094 33404 5349 4094 33405 5345 4094 33406 5341 4094 33407 5325 4094 33408 5321 4094 33409 5317 4094 33410 5317 4094 33411 5313 4094 33412 5301 4094 33413 5313 4094 33414 5309 4094 33415 5301 4094 33416 5293 4094 33417 5289 4094 33418 5301 4094 33419 5289 4094 33420 5285 4094 33421 5301 4094 33422 5261 4094 33423 5257 4094 33424 5269 4094 33425 5257 4094 33426 5253 4094 33427 5269 4094 33428 5237 4094 33429 5233 4094 33430 5221 4094 33431 5233 4094 33432 5229 4094 33433 5221 4094 33434 5197 4094 33435 5193 4094 33436 5205 4094 33437 5193 4094 33438 5189 4094 33439 5205 4094 33440 5165 4094 33441 5161 4094 33442 5173 4094 33443 5161 4094 33444 5157 4094 33445 5173 4094 33446 5149 4094 33447 5145 4094 33448 5157 4094 33449 5145 4094 33450 5141 4094 33451 5157 4094 33452 5141 4094 33453 5137 4094 33454 5125 4094 33455 5137 4094 33456 5133 4094 33457 5125 4094 33458 5101 4094 33459 5097 4094 33460 5109 4094 33461 5097 4094 33462 5093 4094 33463 5109 4094 33464 5085 4094 33465 5081 4094 33466 5077 4094 33467 5053 4094 33468 5049 4094 33469 5061 4094 33470 5049 4094 33471 5045 4094 33472 5061 4094 33473 5013 4094 33474 5009 4094 33475 4997 4094 33476 5009 4094 33477 5005 4094 33478 4997 4094 33479 4989 4094 33480 4985 4094 33481 4997 4094 33482 4985 4094 33483 4981 4094 33484 4997 4094 33485 4957 4094 33486 4953 4094 33487 4965 4094 33488 4953 4094 33489 4949 4094 33490 4965 4094 33491 4933 4094 33492 4929 4094 33493 4917 4094 33494 4929 4094 33495 4925 4094 33496 4917 4094 33497 4925 4094 33498 4921 4094 33499 4917 4094 33500 4901 4094 33501 4897 4094 33502 4893 4094 33503 4877 4094 33504 4873 4094 33505 4869 4094 33506 4861 4094 33507 4857 4094 33508 4869 4094 33509 4857 4094 33510 4853 4094 33511 4869 4094 33512 4853 4094 33513 4849 4094 33514 4845 4094 33515 4829 4094 33516 4825 4094 33517 4837 4094 33518 4825 4094 33519 4821 4094 33520 4837 4094 33521 4797 4094 33522 4793 4094 33523 4805 4094 33524 4793 4094 33525 4789 4094 33526 4805 4094 33527 4789 4094 33528 4785 4094 33529 4773 4094 33530 4785 4094 33531 4781 4094 33532 4773 4094 33533 4781 4094 33534 4777 4094 33535 4773 4094 33536 4757 4094 33537 4753 4094 33538 4741 4094 33539 4753 4094 33540 4749 4094 33541 4741 4094 33542 4741 4094 33543 4737 4094 33544 4733 4094 33545 4661 4094 33546 4657 4094 33547 4645 4094 33548 4657 4094 33549 4653 4094 33550 4645 4094 33551 4645 4094 33552 4641 4094 33553 4629 4094 33554 4641 4094 33555 4637 4094 33556 4629 4094 33557 4613 4094 33558 4609 4094 33559 4597 4094 33560 4609 4094 33561 4605 4094 33562 4597 4094 33563 4589 4094 33564 4585 4094 33565 4597 4094 33566 4585 4094 33567 4581 4094 33568 4597 4094 33569 4557 4094 33570 4553 4094 33571 4565 4094 33572 4553 4094 33573 4549 4094 33574 4565 4094 33575 4541 4094 33576 4537 4094 33577 4549 4094 33578 4537 4094 33579 4533 4094 33580 4549 4094 33581 4525 4094 33582 4521 4094 33583 4533 4094 33584 4521 4094 33585 4517 4094 33586 4533 4094 33587 4517 4094 33588 4513 4094 33589 4501 4094 33590 4513 4094 33591 4509 4094 33592 4501 4094 33593 4501 4094 33594 4497 4094 33595 4485 4094 33596 4497 4094 33597 4493 4094 33598 4485 4094 33599 4477 4094 33600 4473 4094 33601 4485 4094 33602 4473 4094 33603 4469 4094 33604 4485 4094 33605 4429 4094 33606 4425 4094 33607 4437 4094 33608 4425 4094 33609 4421 4094 33610 4437 4094 33611 4397 4094 33612 4393 4094 33613 4405 4094 33614 4393 4094 33615 4389 4094 33616 4405 4094 33617 4389 4094 33618 4385 4094 33619 4373 4094 33620 4385 4094 33621 4381 4094 33622 4373 4094 33623 4357 4094 33624 4353 4094 33625 4341 4094 33626 4353 4094 33627 4349 4094 33628 4341 4094 33629 4333 4094 33630 4329 4094 33631 4341 4094 33632 4329 4094 33633 4325 4094 33634 4341 4094 33635 4309 4094 33636 4305 4094 33637 4293 4094 33638 4305 4094 33639 4301 4094 33640 4293 4094 33641 4285 4094 33642 4281 4094 33643 4293 4094 33644 4281 4094 33645 4277 4094 33646 4293 4094 33647 4253 4094 33648 4249 4094 33649 4261 4094 33650 4249 4094 33651 4245 4094 33652 4261 4094 33653 4221 4094 33654 4217 4094 33655 4229 4094 33656 4217 4094 33657 4213 4094 33658 4229 4094 33659 4189 4094 33660 4185 4094 33661 4197 4094 33662 4185 4094 33663 4181 4094 33664 4197 4094 33665 4173 4094 33666 4169 4094 33667 4181 4094 33668 4169 4094 33669 4165 4094 33670 4181 4094 33671 4165 4094 33672 4161 4094 33673 4149 4094 33674 4161 4094 33675 4157 4094 33676 4149 4094 33677 4149 4094 33678 4145 4094 33679 4133 4094 33680 4145 4094 33681 4141 4094 33682 4133 4094 33683 4141 4094 33684 4137 4094 33685 4133 4094 33686 4133 4094 33687 4129 4094 33688 4125 4094 33689 4069 4094 33690 4065 4094 33691 4053 4094 33692 4065 4094 33693 4061 4094 33694 4053 4094 33695 4061 4094 33696 4057 4094 33697 4053 4094 33698 4053 4094 33699 4049 4094 33700 4037 4094 33701 4049 4094 33702 4045 4094 33703 4037 4094 33704 4029 4094 33705 4025 4094 33706 4037 4094 33707 4025 4094 33708 4021 4094 33709 4037 4094 33710 4021 4094 33711 4017 4094 33712 4005 4094 33713 4017 4094 33714 4013 4094 33715 4005 4094 33716 4005 4094 33717 4001 4094 33718 3989 4094 33719 4001 4094 33720 3997 4094 33721 3989 4094 33722 3949 4094 33723 3945 4094 33724 3957 4094 33725 3945 4094 33726 3941 4094 33727 3957 4094 33728 3917 4094 33729 3913 4094 33730 3925 4094 33731 3913 4094 33732 3909 4094 33733 3925 4094 33734 3869 4094 33735 3865 4094 33736 3861 4094 33737 3845 4094 33738 3841 4094 33739 3837 4094 33740 3813 4094 33741 3809 4094 33742 3797 4094 33743 3809 4094 33744 3805 4094 33745 3797 4094 33746 3773 4094 33747 3769 4094 33748 3781 4094 33749 3769 4094 33750 3765 4094 33751 3781 4094 33752 3749 4094 33753 3745 4094 33754 3733 4094 33755 3745 4094 33756 3741 4094 33757 3733 4094 33758 3725 4094 33759 3721 4094 33760 3733 4094 33761 3721 4094 33762 3717 4094 33763 3733 4094 33764 3701 4094 33765 3697 4094 33766 3685 4094 33767 3697 4094 33768 3693 4094 33769 3685 4094 33770 3685 4094 33771 3681 4094 33772 3669 4094 33773 3681 4094 33774 3677 4094 33775 3669 4094 33776 3613 4094 33777 3609 4094 33778 3621 4094 33779 3609 4094 33780 3605 4094 33781 3621 4094 33782 3589 4094 33783 3585 4094 33784 3573 4094 33785 3585 4094 33786 3581 4094 33787 3573 4094 33788 3557 4094 33789 3553 4094 33790 3541 4094 33791 3553 4094 33792 3549 4094 33793 3541 4094 33794 3461 4094 33795 3457 4094 33796 3445 4094 33797 3457 4094 33798 3453 4094 33799 3445 4094 33800 3421 4094 33801 3417 4094 33802 3429 4094 33803 3417 4094 33804 3413 4094 33805 3429 4094 33806 3413 4094 33807 3409 4094 33808 3397 4094 33809 3409 4094 33810 3405 4094 33811 3397 4094 33812 3405 4094 33813 3401 4094 33814 3397 4094 33815 3373 4094 33816 3369 4094 33817 3381 4094 33818 3369 4094 33819 3365 4094 33820 3381 4094 33821 3349 4094 33822 3345 4094 33823 3341 4094 33824 3341 4094 33825 3337 4094 33826 3349 4094 33827 3337 4094 33828 3333 4094 33829 3349 4094 33830 3325 4094 33831 3321 4094 33832 3317 4094 33833 3301 4094 33834 3297 4094 33835 3293 4094 33836 3277 4094 33837 3273 4094 33838 3269 4094 33839 3269 4094 33840 3265 4094 33841 3253 4094 33842 3265 4094 33843 3261 4094 33844 3253 4094 33845 3245 4094 33846 3241 4094 33847 3253 4094 33848 3241 4094 33849 3237 4094 33850 3253 4094 33851 3213 4094 33852 3209 4094 33853 3221 4094 33854 3209 4094 33855 3205 4094 33856 3221 4094 33857 3189 4094 33858 3185 4094 33859 3173 4094 33860 3185 4094 33861 3181 4094 33862 3173 4094 33863 3149 4094 33864 3145 4094 33865 3157 4094 33866 3145 4094 33867 3141 4094 33868 3157 4094 33869 3117 4094 33870 3113 4094 33871 3125 4094 33872 3113 4094 33873 3109 4094 33874 3125 4094 33875 3101 4094 33876 3097 4094 33877 3109 4094 33878 3097 4094 33879 3093 4094 33880 3109 4094 33881 3093 4094 33882 3089 4094 33883 3077 4094 33884 3089 4094 33885 3085 4094 33886 3077 4094 33887 3053 4094 33888 3049 4094 33889 3061 4094 33890 3049 4094 33891 3045 4094 33892 3061 4094 33893 3037 4094 33894 3033 4094 33895 3029 4094 33896 3005 4094 33897 3001 4094 33898 3013 4094 33899 3001 4094 33900 2997 4094 33901 3013 4094 33902 2965 4094 33903 2961 4094 33904 2949 4094 33905 2961 4094 33906 2957 4094 33907 2949 4094 33908 2941 4094 33909 2937 4094 33910 2949 4094 33911 2937 4094 33912 2933 4094 33913 2949 4094 33914 2909 4094 33915 2905 4094 33916 2917 4094 33917 2905 4094 33918 2901 4094 33919 2917 4094 33920 2885 4094 33921 2881 4094 33922 2869 4094 33923 2881 4094 33924 2877 4094 33925 2869 4094 33926 2877 4094 33927 2873 4094 33928 2869 4094 33929 2853 4094 33930 2849 4094 33931 2845 4094 33932 2829 4094 33933 2825 4094 33934 2821 4094 33935 2813 4094 33936 2809 4094 33937 2821 4094 33938 2809 4094 33939 2805 4094 33940 2821 4094 33941 2805 4094 33942 2801 4094 33943 2797 4094 33944 2781 4094 33945 2777 4094 33946 2789 4094 33947 2777 4094 33948 2773 4094 33949 2789 4094 33950 2749 4094 33951 2745 4094 33952 2757 4094 33953 2745 4094 33954 2741 4094 33955 2757 4094 33956 2741 4094 33957 2737 4094 33958 2725 4094 33959 2737 4094 33960 2733 4094 33961 2725 4094 33962 2733 4094 33963 2729 4094 33964 2725 4094 33965 2709 4094 33966 2705 4094 33967 2693 4094 33968 2705 4094 33969 2701 4094 33970 2693 4094 33971 2693 4094 33972 2689 4094 33973 2685 4094 33974 2613 4094 33975 2609 4094 33976 2597 4094 33977 2609 4094 33978 2605 4094 33979 2597 4094 33980 2597 4094 33981 2593 4094 33982 2581 4094 33983 2593 4094 33984 2589 4094 33985 2581 4094 33986 2565 4094 33987 2561 4094 33988 2549 4094 33989 2561 4094 33990 2557 4094 33991 2549 4094 33992 2541 4094 33993 2537 4094 33994 2549 4094 33995 2537 4094 33996 2533 4094 33997 2549 4094 33998 2509 4094 33999 2505 4094 34000 2517 4094 34001 2505 4094 34002 2501 4094 34003 2517 4094 34004 2493 4094 34005 2489 4094 34006 2501 4094 34007 2489 4094 34008 2485 4094 34009 2501 4094 34010 2477 4094 34011 2473 4094 34012 2485 4094 34013 2473 4094 34014 2469 4094 34015 2485 4094 34016 2469 4094 34017 2465 4094 34018 2453 4094 34019 2465 4094 34020 2461 4094 34021 2453 4094 34022 2453 4094 34023 2449 4094 34024 2437 4094 34025 2449 4094 34026 2445 4094 34027 2437 4094 34028 2429 4094 34029 2425 4094 34030 2437 4094 34031 2425 4094 34032 2421 4094 34033 2437 4094 34034 2381 4094 34035 2377 4094 34036 2389 4094 34037 2377 4094 34038 2373 4094 34039 2389 4094 34040 2349 4094 34041 2345 4094 34042 2357 4094 34043 2345 4094 34044 2341 4094 34045 2357 4094 34046 2341 4094 34047 2337 4094 34048 2325 4094 34049 2337 4094 34050 2333 4094 34051 2325 4094 34052 2309 4094 34053 2305 4094 34054 2293 4094 34055 2305 4094 34056 2301 4094 34057 2293 4094 34058 2285 4094 34059 2281 4094 34060 2293 4094 34061 2281 4094 34062 2277 4094 34063 2293 4094 34064 2261 4094 34065 2257 4094 34066 2245 4094 34067 2257 4094 34068 2253 4094 34069 2245 4094 34070 2237 4094 34071 2233 4094 34072 2245 4094 34073 2233 4094 34074 2229 4094 34075 2245 4094 34076 2205 4094 34077 2201 4094 34078 2213 4094 34079 2201 4094 34080 2197 4094 34081 2213 4094 34082 2173 4094 34083 2169 4094 34084 2181 4094 34085 2169 4094 34086 2165 4094 34087 2181 4094 34088 2141 4094 34089 2137 4094 34090 2149 4094 34091 2137 4094 34092 2133 4094 34093 2149 4094 34094 2125 4094 34095 2121 4094 34096 2133 4094 34097 2121 4094 34098 2117 4094 34099 2133 4094 34100 2117 4094 34101 2113 4094 34102 2101 4094 34103 2113 4094 34104 2109 4094 34105 2101 4094 34106 2101 4094 34107 2097 4094 34108 2085 4094 34109 2097 4094 34110 2093 4094 34111 2085 4094 34112 2093 4094 34113 2089 4094 34114 2085 4094 34115 2085 4094 34116 2081 4094 34117 2077 4094 34118 2021 4094 34119 2017 4094 34120 2005 4094 34121 2017 4094 34122 2013 4094 34123 2005 4094 34124 2013 4094 34125 2009 4094 34126 2005 4094 34127 2005 4094 34128 2001 4094 34129 1989 4094 34130 2001 4094 34131 1997 4094 34132 1989 4094 34133 1981 4094 34134 1977 4094 34135 1989 4094 34136 1977 4094 34137 1973 4094 34138 1989 4094 34139 1973 4094 34140 1969 4094 34141 1957 4094 34142 1969 4094 34143 1965 4094 34144 1957 4094 34145 1957 4094 34146 1953 4094 34147 1941 4094 34148 1953 4094 34149 1949 4094 34150 1941 4094 34151 1901 4094 34152 1897 4094 34153 1909 4094 34154 1897 4094 34155 1893 4094 34156 1909 4094 34157 1869 4094 34158 1865 4094 34159 1877 4094 34160 1865 4094 34161 1861 4094 34162 1877 4094 34163 1821 4094 34164 1817 4094 34165 1813 4094 34166 1797 4094 34167 1793 4094 34168 1789 4094 34169 1765 4094 34170 1761 4094 34171 1749 4094 34172 1761 4094 34173 1757 4094 34174 1749 4094 34175 1725 4094 34176 1721 4094 34177 1733 4094 34178 1721 4094 34179 1717 4094 34180 1733 4094 34181 1701 4094 34182 1697 4094 34183 1685 4094 34184 1697 4094 34185 1693 4094 34186 1685 4094 34187 1677 4094 34188 1673 4094 34189 1685 4094 34190 1673 4094 34191 1669 4094 34192 1685 4094 34193 1653 4094 34194 1649 4094 34195 1637 4094 34196 1649 4094 34197 1645 4094 34198 1637 4094 34199 1637 4094 34200 1633 4094 34201 1621 4094 34202 1633 4094 34203 1629 4094 34204 1621 4094 34205 1565 4094 34206 1561 4094 34207 1573 4094 34208 1561 4094 34209 1557 4094 34210 1573 4094 34211 1541 4094 34212 1537 4094 34213 1525 4094 34214 1537 4094 34215 1533 4094 34216 1525 4094 34217 1509 4094 34218 1505 4094 34219 1493 4094 34220 1505 4094 34221 1501 4094 34222 1493 4094 34223 1413 4094 34224 1409 4094 34225 1397 4094 34226 1409 4094 34227 1405 4094 34228 1397 4094 34229 1373 4094 34230 1369 4094 34231 1381 4094 34232 1369 4094 34233 1365 4094 34234 1381 4094 34235 1365 4094 34236 1361 4094 34237 1349 4094 34238 1361 4094 34239 1357 4094 34240 1349 4094 34241 1357 4094 34242 1353 4094 34243 1349 4094 34244 1325 4094 34245 1321 4094 34246 1333 4094 34247 1321 4094 34248 1317 4094 34249 1333 4094 34250 1301 4094 34251 1297 4094 34252 1293 4094 34253 1293 4094 34254 1289 4094 34255 1301 4094 34256 1289 4094 34257 1285 4094 34258 1301 4094 34259 1277 4094 34260 1273 4094 34261 1269 4094 34262 1253 4094 34263 1249 4094 34264 1245 4094 34265 1229 4094 34266 1225 4094 34267 1221 4094 34268 1221 4094 34269 1217 4094 34270 1205 4094 34271 1217 4094 34272 1213 4094 34273 1205 4094 34274 1197 4094 34275 1193 4094 34276 1205 4094 34277 1193 4094 34278 1189 4094 34279 1205 4094 34280 1165 4094 34281 1161 4094 34282 1173 4094 34283 1161 4094 34284 1157 4094 34285 1173 4094 34286 1141 4094 34287 1137 4094 34288 1125 4094 34289 1137 4094 34290 1133 4094 34291 1125 4094 34292 1101 4094 34293 1097 4094 34294 1109 4094 34295 1097 4094 34296 1093 4094 34297 1109 4094 34298 1069 4094 34299 1065 4094 34300 1077 4094 34301 1065 4094 34302 1061 4094 34303 1077 4094 34304 1053 4094 34305 1049 4094 34306 1061 4094 34307 1049 4094 34308 1045 4094 34309 1061 4094 34310 1045 4094 34311 1041 4094 34312 1029 4094 34313 1041 4094 34314 1037 4094 34315 1029 4094 34316 1005 4094 34317 1001 4094 34318 1013 4094 34319 1001 4094 34320 997 4094 34321 1013 4094 34322 989 4094 34323 985 4094 34324 981 4094 34325 957 4094 34326 953 4094 34327 965 4094 34328 953 4094 34329 949 4094 34330 965 4094 34331 917 4094 34332 913 4094 34333 901 4094 34334 913 4094 34335 909 4094 34336 901 4094 34337 893 4094 34338 889 4094 34339 901 4094 34340 889 4094 34341 885 4094 34342 901 4094 34343 861 4094 34344 857 4094 34345 869 4094 34346 857 4094 34347 853 4094 34348 869 4094 34349 837 4094 34350 833 4094 34351 821 4094 34352 833 4094 34353 829 4094 34354 821 4094 34355 829 4094 34356 825 4094 34357 821 4094 34358 805 4094 34359 801 4094 34360 797 4094 34361 781 4094 34362 777 4094 34363 773 4094 34364 765 4094 34365 761 4094 34366 773 4094 34367 761 4094 34368 757 4094 34369 773 4094 34370 757 4094 34371 753 4094 34372 749 4094 34373 733 4094 34374 729 4094 34375 741 4094 34376 729 4094 34377 725 4094 34378 741 4094 34379 701 4094 34380 697 4094 34381 709 4094 34382 697 4094 34383 693 4094 34384 709 4094 34385 693 4094 34386 689 4094 34387 677 4094 34388 689 4094 34389 685 4094 34390 677 4094 34391 685 4094 34392 681 4094 34393 677 4094 34394 661 4094 34395 657 4094 34396 645 4094 34397 657 4094 34398 653 4094 34399 645 4094 34400 645 4094 34401 641 4094 34402 637 4094 34403 565 4094 34404 561 4094 34405 549 4094 34406 561 4094 34407 557 4094 34408 549 4094 34409 549 4094 34410 545 4094 34411 533 4094 34412 545 4094 34413 541 4094 34414 533 4094 34415 517 4094 34416 513 4094 34417 501 4094 34418 513 4094 34419 509 4094 34420 501 4094 34421 493 4094 34422 489 4094 34423 501 4094 34424 489 4094 34425 485 4094 34426 501 4094 34427 461 4094 34428 457 4094 34429 469 4094 34430 457 4094 34431 453 4094 34432 469 4094 34433 445 4094 34434 441 4094 34435 453 4094 34436 441 4094 34437 437 4094 34438 453 4094 34439 429 4094 34440 425 4094 34441 437 4094 34442 425 4094 34443 421 4094 34444 437 4094 34445 421 4094 34446 417 4094 34447 405 4094 34448 417 4094 34449 413 4094 34450 405 4094 34451 405 4094 34452 401 4094 34453 389 4094 34454 401 4094 34455 397 4094 34456 389 4094 34457 381 4094 34458 377 4094 34459 389 4094 34460 377 4094 34461 373 4094 34462 389 4094 34463 333 4094 34464 329 4094 34465 341 4094 34466 329 4094 34467 325 4094 34468 341 4094 34469 301 4094 34470 297 4094 34471 309 4094 34472 297 4094 34473 293 4094 34474 309 4094 34475 293 4094 34476 289 4094 34477 277 4094 34478 289 4094 34479 285 4094 34480 277 4094 34481 261 4094 34482 257 4094 34483 245 4094 34484 257 4094 34485 253 4094 34486 245 4094 34487 237 4094 34488 233 4094 34489 245 4094 34490 233 4094 34491 229 4094 34492 245 4094 34493 213 4094 34494 209 4094 34495 197 4094 34496 209 4094 34497 205 4094 34498 197 4094 34499 189 4094 34500 185 4094 34501 197 4094 34502 185 4094 34503 181 4094 34504 197 4094 34505 157 4094 34506 153 4094 34507 165 4094 34508 153 4094 34509 149 4094 34510 165 4094 34511 125 4094 34512 121 4094 34513 133 4094 34514 121 4094 34515 117 4094 34516 133 4094 34517 93 4094 34518 89 4094 34519 101 4094 34520 89 4094 34521 85 4094 34522 101 4094 34523 77 4094 34524 73 4094 34525 85 4094 34526 73 4094 34527 69 4094 34528 85 4094 34529 69 4094 34530 65 4094 34531 53 4094 34532 65 4094 34533 61 4094 34534 53 4094 34535 53 4094 34536 49 4094 34537 37 4094 34538 49 4094 34539 45 4094 34540 37 4094 34541 45 4094 34542 41 4094 34543 37 4094 34544 37 4094 34545 33 4094 34546 29 4094 34547 5 4094 34548 8189 4094 34549 8181 4094 34550 8181 4094 34551 8173 4094 34552 8165 4094 34553 8085 4094 34554 8077 4094 34555 8069 4094 34556 8069 4094 34557 8061 4094 34558 8037 4094 34559 8061 4094 34560 8053 4094 34561 8037 4094 34562 8037 4094 34563 8029 4094 34564 8021 4094 34565 8005 4094 34566 7997 4094 34567 7989 4094 34568 7989 4094 34569 7981 4094 34570 8005 4094 34571 7981 4094 34572 7973 4094 34573 8005 4094 34574 7973 4094 34575 7965 4094 34576 7941 4094 34577 7965 4094 34578 7957 4094 34579 7941 4094 34580 7957 4094 34581 7949 4094 34582 7941 4094 34583 7941 4094 34584 7933 4094 34585 7909 4094 34586 7933 4094 34587 7925 4094 34588 7909 4094 34589 7925 4094 34590 7917 4094 34591 7909 4094 34592 7893 4094 34593 7885 4094 34594 7909 4094 34595 7885 4094 34596 7877 4094 34597 7909 4094 34598 7861 4094 34599 7853 4094 34600 7877 4094 34601 7853 4094 34602 7845 4094 34603 7877 4094 34604 7813 4094 34605 7805 4094 34606 7797 4094 34607 7765 4094 34608 7757 4094 34609 7781 4094 34610 7757 4094 34611 7749 4094 34612 7781 4094 34613 7749 4094 34614 7741 4094 34615 7717 4094 34616 7741 4094 34617 7733 4094 34618 7717 4094 34619 7733 4094 34620 7725 4094 34621 7717 4094 34622 7701 4094 34623 7693 4094 34624 7717 4094 34625 7693 4094 34626 7685 4094 34627 7717 4094 34628 7669 4094 34629 7661 4094 34630 7653 4094 34631 7637 4094 34632 7629 4094 34633 7653 4094 34634 7629 4094 34635 7621 4094 34636 7653 4094 34637 7621 4094 34638 7613 4094 34639 7605 4094 34640 7605 4094 34641 7597 4094 34642 7621 4094 34643 7597 4094 34644 7589 4094 34645 7621 4094 34646 7589 4094 34647 7581 4094 34648 7573 4094 34649 7573 4094 34650 7565 4094 34651 7557 4094 34652 7541 4094 34653 7533 4094 34654 7557 4094 34655 7533 4094 34656 7525 4094 34657 7557 4094 34658 7493 4094 34659 7485 4094 34660 7477 4094 34661 7461 4094 34662 7453 4094 34663 7445 4094 34664 7429 4094 34665 7421 4094 34666 7397 4094 34667 7421 4094 34668 7413 4094 34669 7397 4094 34670 7413 4094 34671 7405 4094 34672 7397 4094 34673 7397 4094 34674 7389 4094 34675 7381 4094 34676 7381 4094 34677 7373 4094 34678 7397 4094 34679 7373 4094 34680 7365 4094 34681 7397 4094 34682 7333 4094 34683 7325 4094 34684 7317 4094 34685 7301 4094 34686 7293 4094 34687 7269 4094 34688 7293 4094 34689 7285 4094 34690 7269 4094 34691 7269 4094 34692 7261 4094 34693 7253 4094 34694 7237 4094 34695 7229 4094 34696 7205 4094 34697 7229 4094 34698 7221 4094 34699 7205 4094 34700 7173 4094 34701 7165 4094 34702 7141 4094 34703 7165 4094 34704 7157 4094 34705 7141 4094 34706 7141 4094 34707 7133 4094 34708 7109 4094 34709 7133 4094 34710 7125 4094 34711 7109 4094 34712 7125 4094 34713 7117 4094 34714 7109 4094 34715 7093 4094 34716 7085 4094 34717 7109 4094 34718 7085 4094 34719 7077 4094 34720 7109 4094 34721 7077 4094 34722 7069 4094 34723 7045 4094 34724 7069 4094 34725 7061 4094 34726 7045 4094 34727 7029 4094 34728 7021 4094 34729 7045 4094 34730 7021 4094 34731 7013 4094 34732 7045 4094 34733 6997 4094 34734 6989 4094 34735 6981 4094 34736 6965 4094 34737 6957 4094 34738 6949 4094 34739 6949 4094 34740 6941 4094 34741 6917 4094 34742 6941 4094 34743 6933 4094 34744 6917 4094 34745 6933 4094 34746 6925 4094 34747 6917 4094 34748 6901 4094 34749 6893 4094 34750 6917 4094 34751 6893 4094 34752 6885 4094 34753 6917 4094 34754 6869 4094 34755 6861 4094 34756 6885 4094 34757 6861 4094 34758 6853 4094 34759 6885 4094 34760 6821 4094 34761 6813 4094 34762 6805 4094 34763 6789 4094 34764 6781 4094 34765 6757 4094 34766 6781 4094 34767 6773 4094 34768 6757 4094 34769 6773 4094 34770 6765 4094 34771 6757 4094 34772 6757 4094 34773 6749 4094 34774 6741 4094 34775 6741 4094 34776 6733 4094 34777 6725 4094 34778 6725 4094 34779 6717 4094 34780 6709 4094 34781 6677 4094 34782 6669 4094 34783 6661 4094 34784 6629 4094 34785 6621 4094 34786 6597 4094 34787 6621 4094 34788 6613 4094 34789 6597 4094 34790 6517 4094 34791 6509 4094 34792 6533 4094 34793 6509 4094 34794 6501 4094 34795 6533 4094 34796 6501 4094 34797 6493 4094 34798 6485 4094 34799 6469 4094 34800 6461 4094 34801 6453 4094 34802 6421 4094 34803 6413 4094 34804 6405 4094 34805 6373 4094 34806 6365 4094 34807 6357 4094 34808 6325 4094 34809 6317 4094 34810 6341 4094 34811 6317 4094 34812 6309 4094 34813 6341 4094 34814 6293 4094 34815 6285 4094 34816 6277 4094 34817 6261 4094 34818 6253 4094 34819 6277 4094 34820 6253 4094 34821 6245 4094 34822 6277 4094 34823 6181 4094 34824 6173 4094 34825 6165 4094 34826 6165 4094 34827 6157 4094 34828 6181 4094 34829 6157 4094 34830 6149 4094 34831 6181 4094 34832 6149 6115 34833 6141 6115 34834 6133 6115 34835 6133 4094 34836 6125 4094 34837 6117 4094 34838 6037 4094 34839 6029 4094 34840 6021 4094 34841 6021 4094 34842 6013 4094 34843 5989 4094 34844 6013 4094 34845 6005 4094 34846 5989 4094 34847 5989 4094 34848 5981 4094 34849 5973 4094 34850 5957 4094 34851 5949 4094 34852 5941 4094 34853 5941 4094 34854 5933 4094 34855 5957 4094 34856 5933 4094 34857 5925 4094 34858 5957 4094 34859 5925 4094 34860 5917 4094 34861 5893 4094 34862 5917 4094 34863 5909 4094 34864 5893 4094 34865 5909 4094 34866 5901 4094 34867 5893 4094 34868 5893 4094 34869 5885 4094 34870 5861 4094 34871 5885 4094 34872 5877 4094 34873 5861 4094 34874 5877 4094 34875 5869 4094 34876 5861 4094 34877 5845 4094 34878 5837 4094 34879 5861 4094 34880 5837 4094 34881 5829 4094 34882 5861 4094 34883 5813 4094 34884 5805 4094 34885 5829 4094 34886 5805 4094 34887 5797 4094 34888 5829 4094 34889 5765 4094 34890 5757 4094 34891 5749 4094 34892 5717 4094 34893 5709 4094 34894 5733 4094 34895 5709 4094 34896 5701 4094 34897 5733 4094 34898 5701 4094 34899 5693 4094 34900 5669 4094 34901 5693 4094 34902 5685 4094 34903 5669 4094 34904 5685 4094 34905 5677 4094 34906 5669 4094 34907 5653 4094 34908 5645 4094 34909 5669 4094 34910 5645 4094 34911 5637 4094 34912 5669 4094 34913 5621 4094 34914 5613 4094 34915 5605 4094 34916 5589 4094 34917 5581 4094 34918 5605 4094 34919 5581 4094 34920 5573 4094 34921 5605 4094 34922 5573 4094 34923 5565 4094 34924 5557 4094 34925 5557 4094 34926 5549 4094 34927 5573 4094 34928 5549 4094 34929 5541 4094 34930 5573 4094 34931 5541 4094 34932 5533 4094 34933 5525 4094 34934 5525 4094 34935 5517 4094 34936 5509 4094 34937 5493 4094 34938 5485 4094 34939 5509 4094 34940 5485 4094 34941 5477 4094 34942 5509 4094 34943 5445 4094 34944 5437 4094 34945 5429 4094 34946 5413 4094 34947 5405 4094 34948 5397 4094 34949 5381 4094 34950 5373 4094 34951 5349 4094 34952 5373 4094 34953 5365 4094 34954 5349 4094 34955 5365 4094 34956 5357 4094 34957 5349 4094 34958 5349 4094 34959 5341 4094 34960 5333 4094 34961 5333 4094 34962 5325 4094 34963 5349 4094 34964 5325 4094 34965 5317 4094 34966 5349 4094 34967 5285 4094 34968 5277 4094 34969 5269 4094 34970 5253 4094 34971 5245 4094 34972 5221 4094 34973 5245 4094 34974 5237 4094 34975 5221 4094 34976 5221 4094 34977 5213 4094 34978 5205 4094 34979 5189 4094 34980 5181 4094 34981 5157 4094 34982 5181 4094 34983 5173 4094 34984 5157 4094 34985 5125 4094 34986 5117 4094 34987 5093 4094 34988 5117 4094 34989 5109 4094 34990 5093 4094 34991 5093 4094 34992 5085 4094 34993 5061 4094 34994 5085 4094 34995 5077 4094 34996 5061 4094 34997 5077 4094 34998 5069 4094 34999 5061 4094 35000 5045 4094 35001 5037 4094 35002 5061 4094 35003 5037 4094 35004 5029 4094 35005 5061 4094 35006 5029 4094 35007 5021 4094 35008 4997 4094 35009 5021 4094 35010 5013 4094 35011 4997 4094 35012 4981 4094 35013 4973 4094 35014 4997 4094 35015 4973 4094 35016 4965 4094 35017 4997 4094 35018 4949 4094 35019 4941 4094 35020 4933 4094 35021 4917 4094 35022 4909 4094 35023 4901 4094 35024 4901 4094 35025 4893 4094 35026 4869 4094 35027 4893 4094 35028 4885 4094 35029 4869 4094 35030 4885 4094 35031 4877 4094 35032 4869 4094 35033 4853 4094 35034 4845 4094 35035 4869 4094 35036 4845 4094 35037 4837 4094 35038 4869 4094 35039 4821 4094 35040 4813 4094 35041 4837 4094 35042 4813 4094 35043 4805 4094 35044 4837 4094 35045 4773 4094 35046 4765 4094 35047 4757 4094 35048 4741 4094 35049 4733 4094 35050 4709 4094 35051 4733 4094 35052 4725 4094 35053 4709 4094 35054 4725 4094 35055 4717 4094 35056 4709 4094 35057 4709 4094 35058 4701 4094 35059 4693 4094 35060 4693 4094 35061 4685 4094 35062 4677 4094 35063 4677 4094 35064 4669 4094 35065 4661 4094 35066 4629 4094 35067 4621 4094 35068 4613 4094 35069 4581 4094 35070 4573 4094 35071 4549 4094 35072 4573 4094 35073 4565 4094 35074 4549 4094 35075 4469 4094 35076 4461 4094 35077 4485 4094 35078 4461 4094 35079 4453 4094 35080 4485 4094 35081 4453 4094 35082 4445 4094 35083 4437 4094 35084 4421 4094 35085 4413 4094 35086 4405 4094 35087 4373 4094 35088 4365 4094 35089 4357 4094 35090 4325 4094 35091 4317 4094 35092 4309 4094 35093 4277 4094 35094 4269 4094 35095 4293 4094 35096 4269 4094 35097 4261 4094 35098 4293 4094 35099 4245 4094 35100 4237 4094 35101 4229 4094 35102 4213 4094 35103 4205 4094 35104 4229 4094 35105 4205 4094 35106 4197 4094 35107 4229 4094 35108 4133 4094 35109 4125 4094 35110 4117 4094 35111 4117 4094 35112 4109 4094 35113 4133 4094 35114 4109 4094 35115 4101 4094 35116 4133 4094 35117 4101 4094 35118 4093 4094 35119 4085 4094 35120 4085 4094 35121 4077 4094 35122 4069 4094 35123 3989 4094 35124 3981 4094 35125 3973 4094 35126 3973 4094 35127 3965 4094 35128 3941 4094 35129 3965 4094 35130 3957 4094 35131 3941 4094 35132 3941 4094 35133 3933 4094 35134 3925 4094 35135 3909 4094 35136 3901 4094 35137 3893 4094 35138 3893 4094 35139 3885 4094 35140 3909 4094 35141 3885 4094 35142 3877 4094 35143 3909 4094 35144 3877 4094 35145 3869 4094 35146 3845 4094 35147 3869 4094 35148 3861 4094 35149 3845 4094 35150 3861 4094 35151 3853 4094 35152 3845 4094 35153 3845 4094 35154 3837 4094 35155 3813 4094 35156 3837 4094 35157 3829 4094 35158 3813 4094 35159 3829 4094 35160 3821 4094 35161 3813 4094 35162 3797 4094 35163 3789 4094 35164 3813 4094 35165 3789 4094 35166 3781 4094 35167 3813 4094 35168 3765 4094 35169 3757 4094 35170 3781 4094 35171 3757 4094 35172 3749 4094 35173 3781 4094 35174 3717 4094 35175 3709 4094 35176 3701 4094 35177 3669 4094 35178 3661 4094 35179 3685 4094 35180 3661 4094 35181 3653 4094 35182 3685 4094 35183 3653 4094 35184 3645 4094 35185 3621 4094 35186 3645 4094 35187 3637 4094 35188 3621 4094 35189 3637 4094 35190 3629 4094 35191 3621 4094 35192 3605 4094 35193 3597 4094 35194 3621 4094 35195 3597 4094 35196 3589 4094 35197 3621 4094 35198 3573 4094 35199 3565 4094 35200 3557 4094 35201 3541 4094 35202 3533 4094 35203 3557 4094 35204 3533 4094 35205 3525 4094 35206 3557 4094 35207 3525 4094 35208 3517 4094 35209 3509 4094 35210 3509 4094 35211 3501 4094 35212 3525 4094 35213 3501 4094 35214 3493 4094 35215 3525 4094 35216 3493 4094 35217 3485 4094 35218 3477 4094 35219 3477 4094 35220 3469 4094 35221 3461 4094 35222 3445 4094 35223 3437 4094 35224 3461 4094 35225 3437 4094 35226 3429 4094 35227 3461 4094 35228 3397 4094 35229 3389 4094 35230 3381 4094 35231 3365 4094 35232 3357 4094 35233 3349 4094 35234 3333 4094 35235 3325 4094 35236 3301 4094 35237 3325 4094 35238 3317 4094 35239 3301 4094 35240 3317 4094 35241 3309 4094 35242 3301 4094 35243 3301 4094 35244 3293 4094 35245 3285 4094 35246 3285 4094 35247 3277 4094 35248 3301 4094 35249 3277 4094 35250 3269 4094 35251 3301 4094 35252 3237 4094 35253 3229 4094 35254 3221 4094 35255 3205 4094 35256 3197 4094 35257 3173 4094 35258 3197 4094 35259 3189 4094 35260 3173 4094 35261 3173 4094 35262 3165 4094 35263 3157 4094 35264 3141 4094 35265 3133 4094 35266 3109 4094 35267 3133 4094 35268 3125 4094 35269 3109 4094 35270 3077 4094 35271 3069 4094 35272 3045 4094 35273 3069 4094 35274 3061 4094 35275 3045 4094 35276 3045 4094 35277 3037 4094 35278 3013 4094 35279 3037 4094 35280 3029 4094 35281 3013 4094 35282 3029 4094 35283 3021 4094 35284 3013 4094 35285 2997 4094 35286 2989 4094 35287 3013 4094 35288 2989 4094 35289 2981 4094 35290 3013 4094 35291 2981 4094 35292 2973 4094 35293 2949 4094 35294 2973 4094 35295 2965 4094 35296 2949 4094 35297 2933 4094 35298 2925 4094 35299 2949 4094 35300 2925 4094 35301 2917 4094 35302 2949 4094 35303 2901 4094 35304 2893 4094 35305 2885 4094 35306 2869 4094 35307 2861 4094 35308 2853 4094 35309 2853 4094 35310 2845 4094 35311 2821 4094 35312 2845 4094 35313 2837 4094 35314 2821 4094 35315 2837 4094 35316 2829 4094 35317 2821 4094 35318 2805 4094 35319 2797 4094 35320 2821 4094 35321 2797 4094 35322 2789 4094 35323 2821 4094 35324 2773 4094 35325 2765 4094 35326 2789 4094 35327 2765 4094 35328 2757 4094 35329 2789 4094 35330 2725 4094 35331 2717 4094 35332 2709 4094 35333 2693 4094 35334 2685 4094 35335 2661 4094 35336 2685 4094 35337 2677 4094 35338 2661 4094 35339 2677 4094 35340 2669 4094 35341 2661 4094 35342 2661 4094 35343 2653 4094 35344 2645 4094 35345 2645 4094 35346 2637 4094 35347 2629 4094 35348 2629 4094 35349 2621 4094 35350 2613 4094 35351 2581 4094 35352 2573 4094 35353 2565 4094 35354 2533 4094 35355 2525 4094 35356 2501 4094 35357 2525 4094 35358 2517 4094 35359 2501 4094 35360 2421 4094 35361 2413 4094 35362 2437 4094 35363 2413 4094 35364 2405 4094 35365 2437 4094 35366 2405 4094 35367 2397 4094 35368 2389 4094 35369 2373 4094 35370 2365 4094 35371 2357 4094 35372 2325 4094 35373 2317 4094 35374 2309 4094 35375 2277 4094 35376 2269 4094 35377 2261 4094 35378 2229 4094 35379 2221 4094 35380 2245 4094 35381 2221 4094 35382 2213 4094 35383 2245 4094 35384 2197 4094 35385 2189 4094 35386 2181 4094 35387 2165 4094 35388 2157 4094 35389 2181 4094 35390 2157 4094 35391 2149 4094 35392 2181 4094 35393 2085 4094 35394 2077 4094 35395 2069 4094 35396 2069 4094 35397 2061 4094 35398 2085 4094 35399 2061 4094 35400 2053 4094 35401 2085 4094 35402 2053 6116 35403 2045 6116 35404 2037 6116 35405 2037 4094 35406 2029 4094 35407 2021 4094 35408 1941 4094 35409 1933 4094 35410 1925 4094 35411 1925 4094 35412 1917 4094 35413 1893 4094 35414 1917 4094 35415 1909 4094 35416 1893 4094 35417 1893 4094 35418 1885 4094 35419 1877 4094 35420 1861 4094 35421 1853 4094 35422 1845 4094 35423 1845 4094 35424 1837 4094 35425 1861 4094 35426 1837 4094 35427 1829 4094 35428 1861 4094 35429 1829 4094 35430 1821 4094 35431 1797 4094 35432 1821 4094 35433 1813 4094 35434 1797 4094 35435 1813 4094 35436 1805 4094 35437 1797 4094 35438 1797 4094 35439 1789 4094 35440 1765 4094 35441 1789 4094 35442 1781 4094 35443 1765 4094 35444 1781 4094 35445 1773 4094 35446 1765 4094 35447 1749 4094 35448 1741 4094 35449 1765 4094 35450 1741 4094 35451 1733 4094 35452 1765 4094 35453 1717 4094 35454 1709 4094 35455 1733 4094 35456 1709 4094 35457 1701 4094 35458 1733 4094 35459 1669 4094 35460 1661 4094 35461 1653 4094 35462 1621 4094 35463 1613 4094 35464 1637 4094 35465 1613 4094 35466 1605 4094 35467 1637 4094 35468 1605 4094 35469 1597 4094 35470 1573 4094 35471 1597 4094 35472 1589 4094 35473 1573 4094 35474 1589 4094 35475 1581 4094 35476 1573 4094 35477 1557 4094 35478 1549 4094 35479 1573 4094 35480 1549 4094 35481 1541 4094 35482 1573 4094 35483 1525 4094 35484 1517 4094 35485 1509 4094 35486 1493 4094 35487 1485 4094 35488 1509 4094 35489 1485 4094 35490 1477 4094 35491 1509 4094 35492 1477 4094 35493 1469 4094 35494 1461 4094 35495 1461 4094 35496 1453 4094 35497 1477 4094 35498 1453 4094 35499 1445 4094 35500 1477 4094 35501 1445 4094 35502 1437 4094 35503 1429 4094 35504 1429 4094 35505 1421 4094 35506 1413 4094 35507 1397 4094 35508 1389 4094 35509 1413 4094 35510 1389 4094 35511 1381 4094 35512 1413 4094 35513 1349 4094 35514 1341 4094 35515 1333 4094 35516 1317 4094 35517 1309 4094 35518 1301 4094 35519 1285 4094 35520 1277 4094 35521 1253 4094 35522 1277 4094 35523 1269 4094 35524 1253 4094 35525 1269 4094 35526 1261 4094 35527 1253 4094 35528 1253 4094 35529 1245 4094 35530 1237 4094 35531 1237 4094 35532 1229 4094 35533 1253 4094 35534 1229 4094 35535 1221 4094 35536 1253 4094 35537 1189 4094 35538 1181 4094 35539 1173 4094 35540 1157 4094 35541 1149 4094 35542 1125 4094 35543 1149 4094 35544 1141 4094 35545 1125 4094 35546 1125 4094 35547 1117 4094 35548 1109 4094 35549 1093 4094 35550 1085 4094 35551 1061 4094 35552 1085 4094 35553 1077 4094 35554 1061 4094 35555 1029 4094 35556 1021 4094 35557 997 4094 35558 1021 4094 35559 1013 4094 35560 997 4094 35561 997 4094 35562 989 4094 35563 965 4094 35564 989 4094 35565 981 4094 35566 965 4094 35567 981 4094 35568 973 4094 35569 965 4094 35570 949 4094 35571 941 4094 35572 965 4094 35573 941 4094 35574 933 4094 35575 965 4094 35576 933 4094 35577 925 4094 35578 901 4094 35579 925 4094 35580 917 4094 35581 901 4094 35582 885 4094 35583 877 4094 35584 901 4094 35585 877 4094 35586 869 4094 35587 901 4094 35588 853 4094 35589 845 4094 35590 837 4094 35591 821 4094 35592 813 4094 35593 805 4094 35594 805 4094 35595 797 4094 35596 773 4094 35597 797 4094 35598 789 4094 35599 773 4094 35600 789 4094 35601 781 4094 35602 773 4094 35603 757 4094 35604 749 4094 35605 773 4094 35606 749 4094 35607 741 4094 35608 773 4094 35609 725 4094 35610 717 4094 35611 741 4094 35612 717 4094 35613 709 4094 35614 741 4094 35615 677 4094 35616 669 4094 35617 661 4094 35618 645 4094 35619 637 4094 35620 613 4094 35621 637 4094 35622 629 4094 35623 613 4094 35624 629 4094 35625 621 4094 35626 613 4094 35627 613 4094 35628 605 4094 35629 597 4094 35630 597 4094 35631 589 4094 35632 581 4094 35633 581 4094 35634 573 4094 35635 565 4094 35636 533 4094 35637 525 4094 35638 517 4094 35639 485 4094 35640 477 4094 35641 453 4094 35642 477 4094 35643 469 4094 35644 453 4094 35645 373 4094 35646 365 4094 35647 389 4094 35648 365 4094 35649 357 4094 35650 389 4094 35651 357 4094 35652 349 4094 35653 341 4094 35654 325 4094 35655 317 4094 35656 309 4094 35657 277 4094 35658 269 4094 35659 261 4094 35660 229 4094 35661 221 4094 35662 213 4094 35663 181 4094 35664 173 4094 35665 197 4094 35666 173 4094 35667 165 4094 35668 197 4094 35669 149 4094 35670 141 4094 35671 133 4094 35672 117 4094 35673 109 4094 35674 133 4094 35675 109 4094 35676 101 4094 35677 133 4094 35678 37 4094 35679 29 4094 35680 21 4094 35681 21 4094 35682 13 4094 35683 37 4094 35684 13 4094 35685 5 4094 35686 37 4094 35687 5 4094 35688 8181 4094 35689 8133 4094 35690 8181 4094 35691 8165 4094 35692 8133 4094 35693 8165 4094 35694 8149 4094 35695 8133 4094 35696 8133 4094 35697 8117 4094 35698 8101 4094 35699 8101 4094 35700 8085 4094 35701 8069 4094 35702 8037 4094 35703 8021 4094 35704 8069 4094 35705 8021 4094 35706 8005 4094 35707 8069 4094 35708 7845 4094 35709 7829 4094 35710 7813 4094 35711 7813 4094 35712 7797 4094 35713 7781 4094 35714 7685 4094 35715 7669 4094 35716 7621 4094 35717 7669 4094 35718 7653 4094 35719 7621 4094 35720 7589 4094 35721 7573 4094 35722 7621 4094 35723 7573 4094 35724 7557 4094 35725 7621 4094 35726 7525 4094 35727 7509 4094 35728 7557 4094 35729 7509 4094 35730 7493 4094 35731 7557 4094 35732 7493 4094 35733 7477 4094 35734 7461 4094 35735 7461 4094 35736 7445 4094 35737 7493 4094 35738 7445 4094 35739 7429 4094 35740 7493 4094 35741 7365 4094 35742 7349 4094 35743 7301 4094 35744 7349 4094 35745 7333 4094 35746 7301 4094 35747 7333 4094 35748 7317 4094 35749 7301 4094 35750 7269 4094 35751 7253 4094 35752 7301 4094 35753 7253 4094 35754 7237 4094 35755 7301 4094 35756 7205 4094 35757 7189 4094 35758 7173 4094 35759 7013 4094 35760 6997 4094 35761 7045 4094 35762 6997 4094 35763 6981 4094 35764 7045 4094 35765 6981 4094 35766 6965 4094 35767 6949 4094 35768 6853 4094 35769 6837 4094 35770 6821 4094 35771 6821 4094 35772 6805 4094 35773 6789 4094 35774 6757 4094 35775 6741 4094 35776 6789 4094 35777 6741 4094 35778 6725 4094 35779 6789 4094 35780 6725 4094 35781 6709 4094 35782 6693 4094 35783 6693 4094 35784 6677 4094 35785 6725 4094 35786 6677 4094 35787 6661 4094 35788 6725 4094 35789 6661 4094 35790 6645 4094 35791 6597 4094 35792 6645 4094 35793 6629 4094 35794 6597 4094 35795 6597 4094 35796 6581 4094 35797 6565 4094 35798 6565 4094 35799 6549 4094 35800 6597 4094 35801 6549 4094 35802 6533 4094 35803 6597 4094 35804 6501 4094 35805 6485 4094 35806 6533 4094 35807 6485 4094 35808 6469 4094 35809 6533 4094 35810 6469 4094 35811 6453 4094 35812 6405 4094 35813 6453 4094 35814 6437 4094 35815 6405 4094 35816 6437 4094 35817 6421 4094 35818 6405 4094 35819 6405 4094 35820 6389 4094 35821 6373 4094 35822 6373 4094 35823 6357 4094 35824 6405 4094 35825 6357 4094 35826 6341 4094 35827 6405 4094 35828 6309 4094 35829 6293 4094 35830 6277 4094 35831 6245 4094 35832 6229 4094 35833 6213 4094 35834 6213 4094 35835 6197 4094 35836 6149 4094 35837 6197 6117 35838 6181 6117 35839 6149 6117 35840 6149 6118 35841 6133 6118 35842 6085 6118 35843 6133 4094 35844 6117 4094 35845 6085 4094 35846 6117 4094 35847 6101 4094 35848 6085 4094 35849 6085 4094 35850 6069 4094 35851 6053 4094 35852 6053 4094 35853 6037 4094 35854 6021 4094 35855 5989 4094 35856 5973 4094 35857 6021 4094 35858 5973 4094 35859 5957 4094 35860 6021 4094 35861 5797 4094 35862 5781 4094 35863 5765 4094 35864 5765 4094 35865 5749 4094 35866 5733 4094 35867 5637 4094 35868 5621 4094 35869 5573 4094 35870 5621 4094 35871 5605 4094 35872 5573 4094 35873 5541 4094 35874 5525 4094 35875 5573 4094 35876 5525 4094 35877 5509 4094 35878 5573 4094 35879 5477 4094 35880 5461 4094 35881 5509 4094 35882 5461 4094 35883 5445 4094 35884 5509 4094 35885 5445 4094 35886 5429 4094 35887 5413 4094 35888 5413 4094 35889 5397 4094 35890 5445 4094 35891 5397 4094 35892 5381 4094 35893 5445 4094 35894 5317 4094 35895 5301 4094 35896 5253 4094 35897 5301 4094 35898 5285 4094 35899 5253 4094 35900 5285 4094 35901 5269 4094 35902 5253 4094 35903 5221 4094 35904 5205 4094 35905 5253 4094 35906 5205 4094 35907 5189 4094 35908 5253 4094 35909 5157 4094 35910 5141 4094 35911 5125 4094 35912 4965 4094 35913 4949 4094 35914 4997 4094 35915 4949 4094 35916 4933 4094 35917 4997 4094 35918 4933 4094 35919 4917 4094 35920 4901 4094 35921 4805 4094 35922 4789 4094 35923 4773 4094 35924 4773 4094 35925 4757 4094 35926 4741 4094 35927 4709 4094 35928 4693 4094 35929 4741 4094 35930 4693 4094 35931 4677 4094 35932 4741 4094 35933 4677 4094 35934 4661 4094 35935 4645 4094 35936 4645 4094 35937 4629 4094 35938 4677 4094 35939 4629 4094 35940 4613 4094 35941 4677 4094 35942 4613 4094 35943 4597 4094 35944 4549 4094 35945 4597 4094 35946 4581 4094 35947 4549 4094 35948 4549 4094 35949 4533 4094 35950 4517 4094 35951 4517 4094 35952 4501 4094 35953 4549 4094 35954 4501 4094 35955 4485 4094 35956 4549 4094 35957 4453 4094 35958 4437 4094 35959 4485 4094 35960 4437 4094 35961 4421 4094 35962 4485 4094 35963 4421 4094 35964 4405 4094 35965 4357 4094 35966 4405 4094 35967 4389 4094 35968 4357 4094 35969 4389 4094 35970 4373 4094 35971 4357 4094 35972 4357 4094 35973 4341 4094 35974 4325 4094 35975 4325 4094 35976 4309 4094 35977 4357 4094 35978 4309 4094 35979 4293 4094 35980 4357 4094 35981 4261 4094 35982 4245 4094 35983 4229 4094 35984 4197 4094 35985 4181 4094 35986 4165 4094 35987 4165 4094 35988 4149 4094 35989 4101 4094 35990 4149 4094 35991 4133 4094 35992 4101 4094 35993 4101 4094 35994 4085 4094 35995 4037 4094 35996 4085 4094 35997 4069 4094 35998 4037 4094 35999 4069 4094 36000 4053 4094 36001 4037 4094 36002 4037 4094 36003 4021 4094 36004 4005 4094 36005 4005 4094 36006 3989 4094 36007 3973 4094 36008 3941 4094 36009 3925 4094 36010 3973 4094 36011 3925 4094 36012 3909 4094 36013 3973 4094 36014 3749 4094 36015 3733 4094 36016 3717 4094 36017 3717 4094 36018 3701 4094 36019 3685 4094 36020 3589 4094 36021 3573 4094 36022 3525 4094 36023 3573 4094 36024 3557 4094 36025 3525 4094 36026 3493 4094 36027 3477 4094 36028 3525 4094 36029 3477 4094 36030 3461 4094 36031 3525 4094 36032 3429 4094 36033 3413 4094 36034 3461 4094 36035 3413 4094 36036 3397 4094 36037 3461 4094 36038 3397 4094 36039 3381 4094 36040 3365 4094 36041 3365 4094 36042 3349 4094 36043 3397 4094 36044 3349 4094 36045 3333 4094 36046 3397 4094 36047 3269 4094 36048 3253 4094 36049 3205 4094 36050 3253 4094 36051 3237 4094 36052 3205 4094 36053 3237 4094 36054 3221 4094 36055 3205 4094 36056 3173 4094 36057 3157 4094 36058 3205 4094 36059 3157 4094 36060 3141 4094 36061 3205 4094 36062 3109 4094 36063 3093 4094 36064 3077 4094 36065 2917 4094 36066 2901 4094 36067 2949 4094 36068 2901 4094 36069 2885 4094 36070 2949 4094 36071 2885 4094 36072 2869 4094 36073 2853 4094 36074 2757 4094 36075 2741 4094 36076 2725 4094 36077 2725 4094 36078 2709 4094 36079 2693 4094 36080 2661 4094 36081 2645 4094 36082 2693 4094 36083 2645 4094 36084 2629 4094 36085 2693 4094 36086 2629 4094 36087 2613 4094 36088 2597 4094 36089 2597 4094 36090 2581 4094 36091 2629 4094 36092 2581 4094 36093 2565 4094 36094 2629 4094 36095 2565 4094 36096 2549 4094 36097 2501 4094 36098 2549 4094 36099 2533 4094 36100 2501 4094 36101 2501 4094 36102 2485 4094 36103 2469 4094 36104 2469 4094 36105 2453 4094 36106 2501 4094 36107 2453 4094 36108 2437 4094 36109 2501 4094 36110 2405 4094 36111 2389 4094 36112 2437 4094 36113 2389 4094 36114 2373 4094 36115 2437 4094 36116 2373 4094 36117 2357 4094 36118 2309 4094 36119 2357 4094 36120 2341 4094 36121 2309 4094 36122 2341 4094 36123 2325 4094 36124 2309 4094 36125 2309 4094 36126 2293 4094 36127 2277 4094 36128 2277 4094 36129 2261 4094 36130 2309 4094 36131 2261 4094 36132 2245 4094 36133 2309 4094 36134 2213 4094 36135 2197 4094 36136 2181 4094 36137 2149 4094 36138 2133 4094 36139 2117 4094 36140 2117 4094 36141 2101 4094 36142 2053 4094 36143 2101 6119 36144 2085 6119 36145 2053 6119 36146 2053 6120 36147 2037 6120 36148 1989 6120 36149 2037 4094 36150 2021 4094 36151 1989 4094 36152 2021 4094 36153 2005 4094 36154 1989 4094 36155 1989 4094 36156 1973 4094 36157 1957 4094 36158 1957 4094 36159 1941 4094 36160 1925 4094 36161 1893 4094 36162 1877 4094 36163 1925 4094 36164 1877 4094 36165 1861 4094 36166 1925 4094 36167 1701 4094 36168 1685 4094 36169 1669 4094 36170 1669 4094 36171 1653 4094 36172 1637 4094 36173 1541 4094 36174 1525 4094 36175 1477 4094 36176 1525 4094 36177 1509 4094 36178 1477 4094 36179 1445 4094 36180 1429 4094 36181 1477 4094 36182 1429 4094 36183 1413 4094 36184 1477 4094 36185 1381 4094 36186 1365 4094 36187 1413 4094 36188 1365 4094 36189 1349 4094 36190 1413 4094 36191 1349 4094 36192 1333 4094 36193 1317 4094 36194 1317 4094 36195 1301 4094 36196 1349 4094 36197 1301 4094 36198 1285 4094 36199 1349 4094 36200 1221 4094 36201 1205 4094 36202 1157 4094 36203 1205 4094 36204 1189 4094 36205 1157 4094 36206 1189 4094 36207 1173 4094 36208 1157 4094 36209 1125 4094 36210 1109 4094 36211 1157 4094 36212 1109 4094 36213 1093 4094 36214 1157 4094 36215 1061 4094 36216 1045 4094 36217 1029 4094 36218 869 4094 36219 853 4094 36220 901 4094 36221 853 4094 36222 837 4094 36223 901 4094 36224 837 4094 36225 821 4094 36226 805 4094 36227 709 4094 36228 693 4094 36229 677 4094 36230 677 4094 36231 661 4094 36232 645 4094 36233 613 4094 36234 597 4094 36235 645 4094 36236 597 4094 36237 581 4094 36238 645 4094 36239 581 4094 36240 565 4094 36241 549 4094 36242 549 4094 36243 533 4094 36244 581 4094 36245 533 4094 36246 517 4094 36247 581 4094 36248 517 4094 36249 501 4094 36250 453 4094 36251 501 4094 36252 485 4094 36253 453 4094 36254 453 4094 36255 437 4094 36256 421 4094 36257 421 4094 36258 405 4094 36259 453 4094 36260 405 4094 36261 389 4094 36262 453 4094 36263 357 4094 36264 341 4094 36265 389 4094 36266 341 4094 36267 325 4094 36268 389 4094 36269 325 4094 36270 309 4094 36271 261 4094 36272 309 4094 36273 293 4094 36274 261 4094 36275 293 4094 36276 277 4094 36277 261 4094 36278 261 4094 36279 245 4094 36280 229 4094 36281 229 4094 36282 213 4094 36283 261 4094 36284 213 4094 36285 197 4094 36286 261 4094 36287 165 4094 36288 149 4094 36289 133 4094 36290 101 4094 36291 85 4094 36292 69 4094 36293 69 4094 36294 53 4094 36295 5 4094 36296 53 4094 36297 37 4094 36298 5 4094 36299 8133 4094 36300 8101 4094 36301 5 4094 36302 8101 4094 36303 8069 4094 36304 5 4094 36305 8005 4094 36306 7973 4094 36307 7941 4094 36308 7941 4094 36309 7909 4094 36310 7877 4094 36311 7877 4094 36312 7845 4094 36313 7941 4094 36314 7845 4094 36315 7813 4094 36316 7941 4094 36317 7813 4094 36318 7781 4094 36319 7749 4094 36320 7749 4094 36321 7717 4094 36322 7685 4094 36323 7429 4094 36324 7397 4094 36325 7301 4094 36326 7397 4094 36327 7365 4094 36328 7301 4094 36329 7237 4094 36330 7205 4094 36331 7301 4094 36332 7205 4094 36333 7173 4094 36334 7301 4094 36335 7173 4094 36336 7141 4094 36337 7109 4094 36338 7109 4094 36339 7077 4094 36340 7045 4094 36341 6981 4094 36342 6949 4094 36343 7045 4094 36344 6949 4094 36345 6917 4094 36346 7045 4094 36347 6917 4094 36348 6885 4094 36349 6853 4094 36350 6853 4094 36351 6821 4094 36352 6917 4094 36353 6821 4094 36354 6789 4094 36355 6917 4094 36356 6341 4094 36357 6309 4094 36358 6405 4094 36359 6309 4094 36360 6277 4094 36361 6405 4094 36362 6277 4094 36363 6245 4094 36364 6149 4094 36365 6245 4094 36366 6213 4094 36367 6149 4094 36368 6085 4094 36369 6053 4094 36370 6149 4094 36371 6053 4094 36372 6021 4094 36373 6149 4094 36374 5957 4094 36375 5925 4094 36376 5893 4094 36377 5893 4094 36378 5861 4094 36379 5829 4094 36380 5829 4094 36381 5797 4094 36382 5893 4094 36383 5797 4094 36384 5765 4094 36385 5893 4094 36386 5765 4094 36387 5733 4094 36388 5701 4094 36389 5701 4094 36390 5669 4094 36391 5637 4094 36392 5381 4094 36393 5349 4094 36394 5253 4094 36395 5349 4094 36396 5317 4094 36397 5253 4094 36398 5189 4094 36399 5157 4094 36400 5253 4094 36401 5157 4094 36402 5125 4094 36403 5253 4094 36404 5125 4094 36405 5093 4094 36406 5061 4094 36407 5061 4094 36408 5029 4094 36409 4997 4094 36410 4933 4094 36411 4901 4094 36412 4997 4094 36413 4901 4094 36414 4869 4094 36415 4997 4094 36416 4869 4094 36417 4837 4094 36418 4805 4094 36419 4805 4094 36420 4773 4094 36421 4869 4094 36422 4773 4094 36423 4741 4094 36424 4869 4094 36425 4293 4094 36426 4261 4094 36427 4357 4094 36428 4261 4094 36429 4229 4094 36430 4357 4094 36431 4229 4094 36432 4197 4094 36433 4101 4094 36434 4197 4094 36435 4165 4094 36436 4101 4094 36437 4037 4094 36438 4005 4094 36439 4101 4094 36440 4005 4094 36441 3973 4094 36442 4101 4094 36443 3909 4094 36444 3877 4094 36445 3845 4094 36446 3845 4094 36447 3813 4094 36448 3781 4094 36449 3781 4094 36450 3749 4094 36451 3845 4094 36452 3749 4094 36453 3717 4094 36454 3845 4094 36455 3717 4094 36456 3685 4094 36457 3653 4094 36458 3653 4094 36459 3621 4094 36460 3589 4094 36461 3333 4094 36462 3301 4094 36463 3205 4094 36464 3301 4094 36465 3269 4094 36466 3205 4094 36467 3141 4094 36468 3109 4094 36469 3205 4094 36470 3109 4094 36471 3077 4094 36472 3205 4094 36473 3077 4094 36474 3045 4094 36475 3013 4094 36476 3013 4094 36477 2981 4094 36478 2949 4094 36479 2885 4094 36480 2853 4094 36481 2949 4094 36482 2853 4094 36483 2821 4094 36484 2949 4094 36485 2821 4094 36486 2789 4094 36487 2757 4094 36488 2757 4094 36489 2725 4094 36490 2821 4094 36491 2725 4094 36492 2693 4094 36493 2821 4094 36494 2245 4094 36495 2213 4094 36496 2309 4094 36497 2213 4094 36498 2181 4094 36499 2309 4094 36500 2181 4094 36501 2149 4094 36502 2053 4094 36503 2149 4094 36504 2117 4094 36505 2053 4094 36506 1989 4094 36507 1957 4094 36508 2053 4094 36509 1957 4094 36510 1925 4094 36511 2053 4094 36512 1861 4094 36513 1829 4094 36514 1797 4094 36515 1797 4094 36516 1765 4094 36517 1733 4094 36518 1733 4094 36519 1701 4094 36520 1797 4094 36521 1701 4094 36522 1669 4094 36523 1797 4094 36524 1669 4094 36525 1637 4094 36526 1605 4094 36527 1605 4094 36528 1573 4094 36529 1541 4094 36530 1285 4094 36531 1253 4094 36532 1157 4094 36533 1253 4094 36534 1221 4094 36535 1157 4094 36536 1093 4094 36537 1061 4094 36538 1157 4094 36539 1061 4094 36540 1029 4094 36541 1157 4094 36542 1029 4094 36543 997 4094 36544 965 4094 36545 965 4094 36546 933 4094 36547 901 4094 36548 837 4094 36549 805 4094 36550 901 4094 36551 805 4094 36552 773 4094 36553 901 4094 36554 773 4094 36555 741 4094 36556 709 4094 36557 709 4094 36558 677 4094 36559 773 4094 36560 677 4094 36561 645 4094 36562 773 4094 36563 197 4094 36564 165 4094 36565 261 4094 36566 165 4094 36567 133 4094 36568 261 4094 36569 133 4094 36570 101 4094 36571 5 4094 36572 101 4094 36573 69 4094 36574 5 4094 36575 8069 4094 36576 8005 4094 36577 5 4094 36578 8005 4094 36579 7941 4094 36580 5 4094 36581 7813 4094 36582 7749 4094 36583 7941 4094 36584 7749 4094 36585 7685 4094 36586 7941 4094 36587 7685 4094 36588 7621 4094 36589 7557 4094 36590 7557 4094 36591 7493 4094 36592 7429 4094 36593 7173 4094 36594 7109 4094 36595 7045 4094 36596 6789 4094 36597 6725 4094 36598 6661 4094 36599 6661 4094 36600 6597 4094 36601 6405 4094 36602 6597 4094 36603 6533 4094 36604 6405 4094 36605 6533 4094 36606 6469 4094 36607 6405 4094 36608 6021 4094 36609 5957 4094 36610 6149 4094 36611 5957 4094 36612 5893 4094 36613 6149 4094 36614 5765 4094 36615 5701 4094 36616 5893 4094 36617 5701 4094 36618 5637 4094 36619 5893 4094 36620 5637 4094 36621 5573 4094 36622 5509 4094 36623 5509 4094 36624 5445 4094 36625 5381 4094 36626 5125 4094 36627 5061 4094 36628 4997 4094 36629 4741 4094 36630 4677 4094 36631 4613 4094 36632 4613 4094 36633 4549 4094 36634 4357 4094 36635 4549 4094 36636 4485 4094 36637 4357 4094 36638 4485 4094 36639 4421 4094 36640 4357 4094 36641 3973 4094 36642 3909 4094 36643 4101 4094 36644 3909 4094 36645 3845 4094 36646 4101 4094 36647 3717 4094 36648 3653 4094 36649 3845 4094 36650 3653 4094 36651 3589 4094 36652 3845 4094 36653 3589 4094 36654 3525 4094 36655 3461 4094 36656 3461 4094 36657 3397 4094 36658 3333 4094 36659 3077 4094 36660 3013 4094 36661 2949 4094 36662 2693 4094 36663 2629 4094 36664 2565 4094 36665 2565 4094 36666 2501 4094 36667 2309 4094 36668 2501 4094 36669 2437 4094 36670 2309 4094 36671 2437 4094 36672 2373 4094 36673 2309 4094 36674 1925 4094 36675 1861 4094 36676 2053 4094 36677 1861 4094 36678 1797 4094 36679 2053 4094 36680 1669 4094 36681 1605 4094 36682 1797 4094 36683 1605 4094 36684 1541 4094 36685 1797 4094 36686 1541 4094 36687 1477 4094 36688 1413 4094 36689 1413 4094 36690 1349 4094 36691 1285 4094 36692 1029 4094 36693 965 4094 36694 901 4094 36695 645 4094 36696 581 4094 36697 517 4094 36698 517 4094 36699 453 4094 36700 261 4094 36701 453 4094 36702 389 4094 36703 261 4094 36704 389 4094 36705 325 4094 36706 261 4094 36707 7685 4094 36708 7557 4094 36709 7173 4094 36710 7557 4094 36711 7429 4094 36712 7173 4094 36713 7429 4094 36714 7301 4094 36715 7173 4094 36716 7173 4094 36717 7045 4094 36718 6917 4094 36719 6917 4094 36720 6789 4094 36721 7173 4094 36722 6789 4094 36723 6661 4094 36724 7173 4094 36725 6405 4094 36726 6277 4094 36727 6149 4094 36728 5637 4094 36729 5509 4094 36730 5125 4094 36731 5509 4094 36732 5381 4094 36733 5125 4094 36734 5381 4094 36735 5253 4094 36736 5125 4094 36737 5125 4094 36738 4997 4094 36739 4869 4094 36740 4869 4094 36741 4741 4094 36742 5125 4094 36743 4741 4094 36744 4613 4094 36745 5125 4094 36746 4357 4094 36747 4229 4094 36748 4101 4094 36749 3589 4094 36750 3461 4094 36751 3077 4094 36752 3461 4094 36753 3333 4094 36754 3077 4094 36755 3333 4094 36756 3205 4094 36757 3077 4094 36758 3077 4094 36759 2949 4094 36760 2821 4094 36761 2821 4094 36762 2693 4094 36763 3077 4094 36764 2693 4094 36765 2565 4094 36766 3077 4094 36767 2309 4094 36768 2181 4094 36769 2053 4094 36770 1541 4094 36771 1413 4094 36772 1029 4094 36773 1413 4094 36774 1285 4094 36775 1029 4094 36776 1285 4094 36777 1157 4094 36778 1029 4094 36779 1029 4094 36780 901 4094 36781 773 4094 36782 773 4094 36783 645 4094 36784 1029 4094 36785 645 4094 36786 517 4094 36787 1029 4094 36788 261 4094 36789 133 4094 36790 5 4094 36791 5 4094 36792 7941 4094 36793 7685 4094 36794 6661 4094 36795 6405 4094 36796 7173 4094 36797 6405 4094 36798 6149 4094 36799 7173 4094 36800 6149 6121 36801 5893 6121 36802 5637 6121 36803 4613 4094 36804 4357 4094 36805 5125 4094 36806 4357 4094 36807 4101 4094 36808 5125 4094 36809 4101 4094 36810 3845 4094 36811 3589 4094 36812 2565 4094 36813 2309 4094 36814 3077 4094 36815 2309 4094 36816 2053 4094 36817 3077 4094 36818 2053 6122 36819 1797 6122 36820 1541 6122 36821 517 4094 36822 261 4094 36823 1029 4094 36824 261 4094 36825 5 4094 36826 1029 4094 36827 5 4094 36828 7685 4094 36829 7173 4094 36830 6149 4094 36831 5637 4094 36832 5125 4094 36833 4101 4094 36834 3589 4094 36835 3077 4094 36836 2053 4094 36837 1541 4094 36838 1029 4094 36839 5 4094 36840 7173 4094 36841 6149 4094 36842 6149 4094 36843 5125 4094 36844 5 4094 36845 5125 4094 36846 4101 4094 36847 5 4094 36848 4101 4094 36849 3077 4094 36850 2053 4094 36851 2053 4094 36852 1029 4094 36853 4101 4094 36854 8189 6123 36855 8191 6123 36856 8190 6123 36857 8191 4096 36858 1 4096 36859 0 4096 36860 8190 4097 36861 0 4097 36862 2 4097 36863 2 4097 36864 4 4097 36865 6 4097 36866 6 4097 36867 8 4097 36868 10 4097 36869 10 4097 36870 12 4097 36871 6 4097 36872 12 4097 36873 14 4097 36874 6 4097 36875 14 4097 36876 16 4097 36877 18 4097 36878 18 4097 36879 20 4097 36880 22 4097 36881 22 4097 36882 24 4097 36883 26 4097 36884 26 4097 36885 28 4097 36886 22 4097 36887 28 4097 36888 30 4097 36889 22 4097 36890 30 4097 36891 32 4097 36892 38 4097 36893 32 4097 36894 34 4097 36895 38 4097 36896 34 4097 36897 36 4097 36898 38 4097 36899 38 4097 36900 40 4097 36901 46 4097 36902 40 4097 36903 42 4097 36904 46 4097 36905 42 4097 36906 44 4097 36907 46 4097 36908 46 4097 36909 48 4097 36910 54 4097 36911 48 4097 36912 50 4097 36913 54 4097 36914 50 4097 36915 52 4097 36916 54 4097 36917 54 4097 36918 56 4097 36919 58 4097 36920 58 4097 36921 60 4097 36922 62 4097 36923 62 4097 36924 64 4097 36925 70 4097 36926 64 4097 36927 66 4097 36928 70 4097 36929 66 4097 36930 68 4097 36931 70 4097 36932 70 4097 36933 72 4097 36934 74 4097 36935 74 4097 36936 76 4097 36937 78 4097 36938 78 4097 36939 80 4097 36940 86 4097 36941 80 4097 36942 82 4097 36943 86 4097 36944 82 4097 36945 84 4097 36946 86 4097 36947 86 4097 36948 88 4097 36949 94 4097 36950 88 4097 36951 90 4097 36952 94 4097 36953 90 4097 36954 92 4097 36955 94 4097 36956 94 4097 36957 96 4097 36958 98 4097 36959 98 4097 36960 100 4097 36961 102 4097 36962 102 4097 36963 104 4097 36964 110 4097 36965 104 4097 36966 106 4097 36967 110 4097 36968 106 4097 36969 108 4097 36970 110 4097 36971 110 4097 36972 112 4097 36973 114 4097 36974 114 4097 36975 116 4097 36976 118 4097 36977 118 4097 36978 120 4097 36979 126 4097 36980 120 4097 36981 122 4097 36982 126 4097 36983 122 4097 36984 124 4097 36985 126 4097 36986 126 4097 36987 128 4097 36988 130 4097 36989 130 4097 36990 132 4097 36991 126 4097 36992 132 4097 36993 134 4097 36994 126 4097 36995 134 4097 36996 136 4097 36997 138 4097 36998 138 4097 36999 140 4097 37000 142 4097 37001 142 4097 37002 144 4097 37003 150 4097 37004 144 4097 37005 146 4097 37006 150 4097 37007 146 4097 37008 148 4097 37009 150 4097 37010 150 4097 37011 152 4097 37012 158 4097 37013 152 4097 37014 154 4097 37015 158 4097 37016 154 4097 37017 156 4097 37018 158 4097 37019 158 4097 37020 160 4097 37021 162 4097 37022 162 4097 37023 164 4097 37024 158 4097 37025 164 4097 37026 166 4097 37027 158 4097 37028 166 4097 37029 168 4097 37030 170 4097 37031 170 4097 37032 172 4097 37033 166 4097 37034 172 4097 37035 174 4097 37036 166 4097 37037 174 4097 37038 176 4097 37039 178 4097 37040 178 4097 37041 180 4097 37042 182 4097 37043 182 4097 37044 184 4097 37045 190 4097 37046 184 4097 37047 186 4097 37048 190 4097 37049 186 4097 37050 188 4097 37051 190 4097 37052 190 4097 37053 192 4097 37054 194 4097 37055 194 4097 37056 196 4097 37057 198 4097 37058 198 4097 37059 200 4097 37060 206 4097 37061 200 4097 37062 202 4097 37063 206 4097 37064 202 4097 37065 204 4097 37066 206 4097 37067 206 4097 37068 208 4097 37069 210 4097 37070 210 4097 37071 212 4097 37072 214 4097 37073 214 4097 37074 216 4097 37075 218 4097 37076 218 4097 37077 220 4097 37078 222 4097 37079 222 4097 37080 224 4097 37081 226 4097 37082 226 4097 37083 228 4097 37084 222 4097 37085 228 4097 37086 230 4097 37087 222 4097 37088 230 4097 37089 232 4097 37090 238 4097 37091 232 4097 37092 234 4097 37093 238 4097 37094 234 4097 37095 236 4097 37096 238 4097 37097 238 4097 37098 240 4097 37099 246 4097 37100 240 4097 37101 242 4097 37102 246 4097 37103 242 4097 37104 244 4097 37105 246 4097 37106 246 4097 37107 248 4097 37108 250 4097 37109 250 4097 37110 252 4097 37111 254 4097 37112 254 4097 37113 256 4097 37114 258 4097 37115 258 4097 37116 260 4097 37117 262 4097 37118 262 4097 37119 264 4097 37120 266 4097 37121 266 4097 37122 268 4097 37123 262 4097 37124 268 4097 37125 270 4097 37126 262 4097 37127 270 4097 37128 272 4097 37129 274 4097 37130 274 4097 37131 276 4097 37132 278 4097 37133 278 4097 37134 280 4097 37135 282 4097 37136 282 4097 37137 284 4097 37138 286 4097 37139 286 4097 37140 288 4097 37141 290 4097 37142 290 4097 37143 292 4097 37144 294 4097 37145 294 4097 37146 296 4097 37147 302 4097 37148 296 4097 37149 298 4097 37150 302 4097 37151 298 4097 37152 300 4097 37153 302 4097 37154 302 4097 37155 304 4097 37156 306 4097 37157 306 4097 37158 308 4097 37159 310 4097 37160 310 4097 37161 312 4097 37162 314 4097 37163 314 4097 37164 316 4097 37165 318 4097 37166 318 4097 37167 320 4097 37168 322 4097 37169 322 4097 37170 324 4097 37171 326 4097 37172 326 4097 37173 328 4097 37174 334 4097 37175 328 4097 37176 330 4097 37177 334 4097 37178 330 4097 37179 332 4097 37180 334 4097 37181 334 4097 37182 336 4097 37183 338 4097 37184 338 4097 37185 340 4097 37186 334 4097 37187 340 4097 37188 342 4097 37189 334 4097 37190 342 4097 37191 344 4097 37192 346 4097 37193 346 4097 37194 348 4097 37195 350 4097 37196 350 4097 37197 352 4097 37198 354 4097 37199 354 4097 37200 356 4097 37201 358 4097 37202 358 4097 37203 360 4097 37204 362 4097 37205 362 4097 37206 364 4097 37207 366 4097 37208 366 4097 37209 368 4097 37210 370 4097 37211 370 4097 37212 372 4097 37213 374 4097 37214 374 4097 37215 376 4097 37216 382 4097 37217 376 4097 37218 378 4097 37219 382 4097 37220 378 4097 37221 380 4097 37222 382 4097 37223 382 4097 37224 384 4097 37225 386 4097 37226 386 4097 37227 388 4097 37228 390 4097 37229 390 4097 37230 392 4097 37231 394 4097 37232 394 4097 37233 396 4097 37234 398 4097 37235 398 4097 37236 400 4097 37237 406 4097 37238 400 4097 37239 402 4097 37240 406 4097 37241 402 4097 37242 404 4097 37243 406 4097 37244 406 4097 37245 408 4097 37246 410 4097 37247 410 4097 37248 412 4097 37249 414 4097 37250 414 4097 37251 416 4097 37252 422 4097 37253 416 4097 37254 418 4097 37255 422 4097 37256 418 4097 37257 420 4097 37258 422 4097 37259 422 4097 37260 424 4097 37261 430 4097 37262 424 4097 37263 426 4097 37264 430 4097 37265 426 4097 37266 428 4097 37267 430 4097 37268 430 4097 37269 432 4097 37270 434 4097 37271 434 4097 37272 436 4097 37273 438 4097 37274 438 4097 37275 440 4097 37276 446 4097 37277 440 4097 37278 442 4097 37279 446 4097 37280 442 4097 37281 444 4097 37282 446 4097 37283 446 4097 37284 448 4097 37285 450 4097 37286 450 4097 37287 452 4097 37288 454 4097 37289 454 4097 37290 456 4097 37291 462 4097 37292 456 4097 37293 458 4097 37294 462 4097 37295 458 4097 37296 460 4097 37297 462 4097 37298 462 4097 37299 464 4097 37300 466 4097 37301 466 4097 37302 468 4097 37303 462 4097 37304 468 4097 37305 470 4097 37306 462 4097 37307 470 4097 37308 472 4097 37309 474 4097 37310 474 4097 37311 476 4097 37312 478 4097 37313 478 4097 37314 480 4097 37315 482 4097 37316 482 4097 37317 484 4097 37318 486 4097 37319 486 4097 37320 488 4097 37321 490 4097 37322 490 4097 37323 492 4097 37324 494 4097 37325 494 4097 37326 496 4097 37327 498 4097 37328 498 4097 37329 500 4097 37330 494 4097 37331 500 4097 37332 502 4097 37333 494 4097 37334 502 4097 37335 504 4097 37336 506 4097 37337 506 4097 37338 508 4097 37339 510 4097 37340 510 4097 37341 512 4097 37342 514 4097 37343 514 4097 37344 516 4097 37345 518 4097 37346 518 4097 37347 520 4097 37348 522 4097 37349 522 4097 37350 524 4097 37351 518 4097 37352 524 4097 37353 526 4097 37354 518 4097 37355 526 4097 37356 528 4097 37357 530 4097 37358 530 4097 37359 532 4097 37360 526 4097 37361 532 4097 37362 534 4097 37363 526 4097 37364 534 4097 37365 536 4097 37366 538 4097 37367 538 4097 37368 540 4097 37369 534 4097 37370 540 4097 37371 542 4097 37372 534 4097 37373 542 4097 37374 544 4097 37375 550 4097 37376 544 4097 37377 546 4097 37378 550 4097 37379 546 4097 37380 548 4097 37381 550 4097 37382 550 4097 37383 552 4097 37384 554 4097 37385 554 4097 37386 556 4097 37387 550 4097 37388 556 4097 37389 558 4097 37390 550 4097 37391 558 4097 37392 560 4097 37393 562 4097 37394 562 4097 37395 564 4097 37396 566 4097 37397 566 4097 37398 568 4097 37399 570 4097 37400 570 4097 37401 572 4097 37402 574 4097 37403 574 4097 37404 576 4097 37405 578 4097 37406 578 4097 37407 580 4097 37408 582 4097 37409 582 4097 37410 584 4097 37411 586 4097 37412 586 4097 37413 588 4097 37414 590 4097 37415 590 4097 37416 592 4097 37417 594 4097 37418 594 4097 37419 596 4097 37420 590 4097 37421 596 4097 37422 598 4097 37423 590 4097 37424 598 4097 37425 600 4097 37426 602 4097 37427 602 4097 37428 604 4097 37429 598 4097 37430 604 4097 37431 606 4097 37432 598 4097 37433 606 4097 37434 608 4097 37435 610 4097 37436 610 4097 37437 612 4097 37438 614 4097 37439 614 4097 37440 616 4097 37441 618 4097 37442 618 4097 37443 620 4097 37444 622 4097 37445 622 4097 37446 624 4097 37447 626 4097 37448 626 4097 37449 628 4097 37450 630 4097 37451 630 4097 37452 632 4097 37453 634 4097 37454 634 4097 37455 636 4097 37456 630 4097 37457 636 4097 37458 638 4097 37459 630 4097 37460 638 4097 37461 640 4097 37462 646 4097 37463 640 4097 37464 642 4097 37465 646 4097 37466 642 4097 37467 644 4097 37468 646 4097 37469 646 4097 37470 648 4097 37471 650 4097 37472 650 4097 37473 652 4097 37474 646 4097 37475 652 4097 37476 654 4097 37477 646 4097 37478 654 4097 37479 656 4097 37480 658 4097 37481 658 4097 37482 660 4097 37483 662 4097 37484 662 4097 37485 664 4097 37486 666 4097 37487 666 4097 37488 668 4097 37489 670 4097 37490 670 4097 37491 672 4097 37492 678 4097 37493 672 4097 37494 674 4097 37495 678 4097 37496 674 4097 37497 676 4097 37498 678 4097 37499 678 4097 37500 680 4097 37501 686 4097 37502 680 4097 37503 682 4097 37504 686 4097 37505 682 4097 37506 684 4097 37507 686 4097 37508 686 4097 37509 688 4097 37510 694 4097 37511 688 4097 37512 690 4097 37513 694 4097 37514 690 4097 37515 692 4097 37516 694 4097 37517 694 4097 37518 696 4097 37519 698 4097 37520 698 4097 37521 700 4097 37522 702 4097 37523 702 4097 37524 704 4097 37525 706 4097 37526 706 4097 37527 708 4097 37528 710 4097 37529 710 4097 37530 712 4097 37531 714 4097 37532 714 4097 37533 716 4097 37534 710 4097 37535 716 4097 37536 718 4097 37537 710 4097 37538 718 4097 37539 720 4097 37540 722 4097 37541 722 4097 37542 724 4097 37543 726 4097 37544 726 4097 37545 728 4097 37546 730 4097 37547 730 4097 37548 732 4097 37549 734 4097 37550 734 4097 37551 736 4097 37552 738 4097 37553 738 4097 37554 740 4097 37555 742 4097 37556 742 4097 37557 744 4097 37558 746 4097 37559 746 4097 37560 748 4097 37561 742 4097 37562 748 4097 37563 750 4097 37564 742 4097 37565 750 4097 37566 752 4097 37567 758 4097 37568 752 4097 37569 754 4097 37570 758 4097 37571 754 4097 37572 756 4097 37573 758 4097 37574 758 4097 37575 760 4097 37576 766 4097 37577 760 4097 37578 762 4097 37579 766 4097 37580 762 4097 37581 764 4097 37582 766 4097 37583 766 4097 37584 768 4097 37585 770 4097 37586 770 4097 37587 772 4097 37588 766 4097 37589 772 4097 37590 774 4097 37591 766 4097 37592 774 4097 37593 776 4097 37594 782 4097 37595 776 4097 37596 778 4097 37597 782 4097 37598 778 4097 37599 780 4097 37600 782 4097 37601 782 4097 37602 784 4097 37603 786 4097 37604 786 4097 37605 788 4097 37606 782 4097 37607 788 4097 37608 790 4097 37609 782 4097 37610 790 4097 37611 792 4097 37612 794 4097 37613 794 4097 37614 796 4097 37615 798 4097 37616 798 4097 37617 800 4097 37618 802 4097 37619 802 4097 37620 804 4097 37621 798 4097 37622 804 4097 37623 806 4097 37624 798 4097 37625 806 4097 37626 808 4097 37627 810 4097 37628 810 4097 37629 812 4097 37630 814 4097 37631 814 4097 37632 816 4097 37633 818 4097 37634 818 4097 37635 820 4097 37636 814 4097 37637 820 4097 37638 822 4097 37639 814 4097 37640 822 4097 37641 824 4097 37642 826 4097 37643 826 4097 37644 828 4097 37645 822 4097 37646 828 4097 37647 830 4097 37648 822 4097 37649 830 4097 37650 832 4097 37651 834 4097 37652 834 4097 37653 836 4097 37654 838 4097 37655 838 4097 37656 840 4097 37657 842 4097 37658 842 4097 37659 844 4097 37660 838 4097 37661 844 4097 37662 846 4097 37663 838 4097 37664 846 4097 37665 848 4097 37666 850 4097 37667 850 4097 37668 852 4097 37669 846 4097 37670 852 4097 37671 854 4097 37672 846 4097 37673 854 4097 37674 856 4097 37675 858 4097 37676 858 4097 37677 860 4097 37678 854 4097 37679 860 4097 37680 862 4097 37681 854 4097 37682 862 4097 37683 864 4097 37684 866 4097 37685 866 4097 37686 868 4097 37687 870 4097 37688 870 4097 37689 872 4097 37690 874 4097 37691 874 4097 37692 876 4097 37693 870 4097 37694 876 4097 37695 878 4097 37696 870 4097 37697 878 4097 37698 880 4097 37699 882 4097 37700 882 4097 37701 884 4097 37702 886 4097 37703 886 4097 37704 888 4097 37705 890 4097 37706 890 4097 37707 892 4097 37708 886 4097 37709 892 4097 37710 894 4097 37711 886 4097 37712 894 4097 37713 896 4097 37714 898 4097 37715 898 4097 37716 900 4097 37717 894 4097 37718 900 4097 37719 902 4097 37720 894 4097 37721 902 4097 37722 904 4097 37723 906 4097 37724 906 4097 37725 908 4097 37726 910 4097 37727 910 4097 37728 912 4097 37729 918 4097 37730 912 4097 37731 914 4097 37732 918 4097 37733 914 4097 37734 916 4097 37735 918 4097 37736 918 4097 37737 920 4097 37738 922 4097 37739 922 4097 37740 924 4097 37741 926 4097 37742 926 4097 37743 928 4097 37744 930 4097 37745 930 4097 37746 932 4097 37747 934 4097 37748 934 4097 37749 936 4097 37750 938 4097 37751 938 4097 37752 940 4097 37753 934 4097 37754 940 4097 37755 942 4097 37756 934 4097 37757 942 4097 37758 944 4097 37759 946 4097 37760 946 4097 37761 948 4097 37762 950 4097 37763 950 4097 37764 952 4097 37765 954 4097 37766 954 4097 37767 956 4097 37768 958 4097 37769 958 4097 37770 960 4097 37771 962 4097 37772 962 4097 37773 964 4097 37774 958 4097 37775 964 4097 37776 966 4097 37777 958 4097 37778 966 4097 37779 968 4097 37780 970 4097 37781 970 4097 37782 972 4097 37783 974 4097 37784 974 4097 37785 976 4097 37786 978 4097 37787 978 4097 37788 980 4097 37789 982 4097 37790 982 4097 37791 984 4097 37792 986 4097 37793 986 4097 37794 988 4097 37795 982 4097 37796 988 4097 37797 990 4097 37798 982 4097 37799 990 4097 37800 992 4097 37801 994 4097 37802 994 4097 37803 996 4097 37804 998 4097 37805 998 4097 37806 1000 4097 37807 1006 4097 37808 1000 4097 37809 1002 4097 37810 1006 4097 37811 1002 4097 37812 1004 4097 37813 1006 4097 37814 1006 4097 37815 1008 4097 37816 1014 4097 37817 1008 4097 37818 1010 4097 37819 1014 4097 37820 1010 4097 37821 1012 4097 37822 1014 4097 37823 1014 4097 37824 1016 4097 37825 1018 4097 37826 1018 4097 37827 1020 4097 37828 1022 4097 37829 1022 4097 37830 1024 4097 37831 1026 4097 37832 1026 4097 37833 1028 4097 37834 1022 4097 37835 1028 4097 37836 1030 4097 37837 1022 4097 37838 1030 4097 37839 1032 4097 37840 1034 4097 37841 1034 4097 37842 1036 4097 37843 1038 4097 37844 1038 4097 37845 1040 4097 37846 1042 4097 37847 1042 4097 37848 1044 4097 37849 1046 4097 37850 1046 4097 37851 1048 4097 37852 1054 4097 37853 1048 4097 37854 1050 4097 37855 1054 4097 37856 1050 4097 37857 1052 4097 37858 1054 4097 37859 1054 4097 37860 1056 4097 37861 1058 4097 37862 1058 4097 37863 1060 4097 37864 1054 4097 37865 1060 4097 37866 1062 4097 37867 1054 4097 37868 1062 4097 37869 1064 4097 37870 1070 4097 37871 1064 4097 37872 1066 4097 37873 1070 4097 37874 1066 4097 37875 1068 4097 37876 1070 4097 37877 1070 4097 37878 1072 4097 37879 1074 4097 37880 1074 4097 37881 1076 4097 37882 1078 4097 37883 1078 4097 37884 1080 4097 37885 1082 4097 37886 1082 4097 37887 1084 4097 37888 1078 4097 37889 1084 4097 37890 1086 4097 37891 1078 4097 37892 1086 4097 37893 1088 4097 37894 1090 4097 37895 1090 4097 37896 1092 4097 37897 1094 4097 37898 1094 4097 37899 1096 4097 37900 1098 4097 37901 1098 4097 37902 1100 4097 37903 1102 4097 37904 1102 4097 37905 1104 4097 37906 1106 4097 37907 1106 4097 37908 1108 4097 37909 1102 4097 37910 1108 4097 37911 1110 4097 37912 1102 4097 37913 1110 4097 37914 1112 4097 37915 1114 4097 37916 1114 4097 37917 1116 4097 37918 1118 4097 37919 1118 4097 37920 1120 4097 37921 1122 4097 37922 1122 4097 37923 1124 4097 37924 1118 4097 37925 1124 4097 37926 1126 4097 37927 1118 4097 37928 1126 4097 37929 1128 4097 37930 1134 4097 37931 1128 4097 37932 1130 4097 37933 1134 4097 37934 1130 4097 37935 1132 4097 37936 1134 4097 37937 1134 4097 37938 1136 4097 37939 1142 4097 37940 1136 4097 37941 1138 4097 37942 1142 4097 37943 1138 4097 37944 1140 4097 37945 1142 4097 37946 1142 4097 37947 1144 4097 37948 1146 4097 37949 1146 4097 37950 1148 4097 37951 1142 4097 37952 1148 4097 37953 1150 4097 37954 1142 4097 37955 1150 4097 37956 1152 4097 37957 1154 4097 37958 1154 4097 37959 1156 4097 37960 1158 4097 37961 1158 4097 37962 1160 4097 37963 1166 4097 37964 1160 4097 37965 1162 4097 37966 1166 4097 37967 1162 4097 37968 1164 4097 37969 1166 4097 37970 1166 4097 37971 1168 4097 37972 1170 4097 37973 1170 4097 37974 1172 4097 37975 1166 4097 37976 1172 4097 37977 1174 4097 37978 1166 4097 37979 1174 4097 37980 1176 4097 37981 1178 4097 37982 1178 4097 37983 1180 4097 37984 1182 4097 37985 1182 4097 37986 1184 4097 37987 1186 4097 37988 1186 4097 37989 1188 4097 37990 1182 4097 37991 1188 4097 37992 1190 4097 37993 1182 4097 37994 1190 4097 37995 1192 4097 37996 1198 4097 37997 1192 4097 37998 1194 4097 37999 1198 4097 38000 1194 4097 38001 1196 4097 38002 1198 4097 38003 1198 4097 38004 1200 4097 38005 1202 4097 38006 1202 4097 38007 1204 4097 38008 1206 4097 38009 1206 4097 38010 1208 4097 38011 1214 4097 38012 1208 4097 38013 1210 4097 38014 1214 4097 38015 1210 4097 38016 1212 4097 38017 1214 4097 38018 1214 4097 38019 1216 4097 38020 1218 4097 38021 1218 4097 38022 1220 4097 38023 1222 4097 38024 1222 4097 38025 1224 4097 38026 1226 4097 38027 1226 4097 38028 1228 4097 38029 1222 4097 38030 1228 4097 38031 1230 4097 38032 1222 4097 38033 1230 4097 38034 1232 4097 38035 1234 4097 38036 1234 4097 38037 1236 4097 38038 1238 4097 38039 1238 4097 38040 1240 4097 38041 1242 4097 38042 1242 4097 38043 1244 4097 38044 1238 4097 38045 1244 4097 38046 1246 4097 38047 1238 4097 38048 1246 4097 38049 1248 4097 38050 1250 4097 38051 1250 4097 38052 1252 4097 38053 1246 4097 38054 1252 4097 38055 1254 4097 38056 1246 4097 38057 1254 4097 38058 1256 4097 38059 1258 4097 38060 1258 4097 38061 1260 4097 38062 1254 4097 38063 1260 4097 38064 1262 4097 38065 1254 4097 38066 1262 4097 38067 1264 4097 38068 1266 4097 38069 1266 4097 38070 1268 4097 38071 1270 4097 38072 1270 4097 38073 1272 4097 38074 1274 4097 38075 1274 4097 38076 1276 4097 38077 1270 4097 38078 1276 4097 38079 1278 4097 38080 1270 4097 38081 1278 4097 38082 1280 4097 38083 1286 4097 38084 1280 4097 38085 1282 4097 38086 1286 4097 38087 1282 4097 38088 1284 4097 38089 1286 4097 38090 1286 4097 38091 1288 4097 38092 1290 4097 38093 1290 4097 38094 1292 4097 38095 1294 4097 38096 1294 4097 38097 1296 4097 38098 1298 4097 38099 1298 4097 38100 1300 4097 38101 1294 4097 38102 1300 4097 38103 1302 4097 38104 1294 4097 38105 1302 4097 38106 1304 4097 38107 1306 4097 38108 1306 4097 38109 1308 4097 38110 1302 4097 38111 1308 4097 38112 1310 4097 38113 1302 4097 38114 1310 4097 38115 1312 4097 38116 1318 4097 38117 1312 4097 38118 1314 4097 38119 1318 4097 38120 1314 4097 38121 1316 4097 38122 1318 4097 38123 1318 4097 38124 1320 4097 38125 1326 4097 38126 1320 4097 38127 1322 4097 38128 1326 4097 38129 1322 4097 38130 1324 4097 38131 1326 4097 38132 1326 4097 38133 1328 4097 38134 1330 4097 38135 1330 4097 38136 1332 4097 38137 1326 4097 38138 1332 4097 38139 1334 4097 38140 1326 4097 38141 1334 4097 38142 1336 4097 38143 1338 4097 38144 1338 4097 38145 1340 4097 38146 1342 4097 38147 1342 4097 38148 1344 4097 38149 1350 4097 38150 1344 4097 38151 1346 4097 38152 1350 4097 38153 1346 4097 38154 1348 4097 38155 1350 4097 38156 1350 4097 38157 1352 4097 38158 1358 4097 38159 1352 4097 38160 1354 4097 38161 1358 4097 38162 1354 4097 38163 1356 4097 38164 1358 4097 38165 1358 4097 38166 1360 4097 38167 1362 4097 38168 1362 4097 38169 1364 4097 38170 1366 4097 38171 1366 4097 38172 1368 4097 38173 1374 4097 38174 1368 4097 38175 1370 4097 38176 1374 4097 38177 1370 4097 38178 1372 4097 38179 1374 4097 38180 1374 4097 38181 1376 4097 38182 1378 4097 38183 1378 4097 38184 1380 4097 38185 1382 4097 38186 1382 4097 38187 1384 4097 38188 1386 4097 38189 1386 4097 38190 1388 4097 38191 1390 4097 38192 1390 4097 38193 1392 4097 38194 1394 4097 38195 1394 4097 38196 1396 4097 38197 1398 4097 38198 1398 4097 38199 1400 4097 38200 1402 4097 38201 1402 4097 38202 1404 4097 38203 1406 4097 38204 1406 4097 38205 1408 4097 38206 1414 4097 38207 1408 4097 38208 1410 4097 38209 1414 4097 38210 1410 4097 38211 1412 4097 38212 1414 4097 38213 1414 4097 38214 1416 4097 38215 1418 4097 38216 1418 4097 38217 1420 4097 38218 1422 4097 38219 1422 4097 38220 1424 4097 38221 1426 4097 38222 1426 4097 38223 1428 4097 38224 1430 4097 38225 1430 4097 38226 1432 4097 38227 1434 4097 38228 1434 4097 38229 1436 4097 38230 1430 4097 38231 1436 4097 38232 1438 4097 38233 1430 4097 38234 1438 4097 38235 1440 4097 38236 1442 4097 38237 1442 4097 38238 1444 4097 38239 1438 4097 38240 1444 4097 38241 1446 4097 38242 1438 4097 38243 1446 4097 38244 1448 4097 38245 1450 4097 38246 1450 4097 38247 1452 4097 38248 1454 4097 38249 1454 4097 38250 1456 4097 38251 1458 4097 38252 1458 4097 38253 1460 4097 38254 1462 4097 38255 1462 4097 38256 1464 4097 38257 1466 4097 38258 1466 4097 38259 1468 4097 38260 1470 4097 38261 1470 4097 38262 1472 4097 38263 1474 4097 38264 1474 4097 38265 1476 4097 38266 1478 4097 38267 1478 4097 38268 1480 4097 38269 1482 4097 38270 1482 4097 38271 1484 4097 38272 1478 4097 38273 1484 4097 38274 1486 4097 38275 1478 4097 38276 1486 4097 38277 1488 4097 38278 1490 4097 38279 1490 4097 38280 1492 4097 38281 1486 4097 38282 1492 4097 38283 1494 4097 38284 1486 4097 38285 1494 4097 38286 1496 4097 38287 1498 4097 38288 1498 4097 38289 1500 4097 38290 1502 4097 38291 1502 4097 38292 1504 4097 38293 1510 4097 38294 1504 4097 38295 1506 4097 38296 1510 4097 38297 1506 4097 38298 1508 4097 38299 1510 4097 38300 1510 4097 38301 1512 4097 38302 1514 4097 38303 1514 4097 38304 1516 4097 38305 1518 4097 38306 1518 4097 38307 1520 4097 38308 1522 4097 38309 1522 4097 38310 1524 4097 38311 1518 4097 38312 1524 4097 38313 1526 4097 38314 1518 4097 38315 1526 4097 38316 1528 4097 38317 1530 4097 38318 1530 4097 38319 1532 4097 38320 1534 4097 38321 1534 4097 38322 1536 4097 38323 1542 4097 38324 1536 4097 38325 1538 4097 38326 1542 4097 38327 1538 4097 38328 1540 4097 38329 1542 4097 38330 1542 4097 38331 1544 4097 38332 1546 4097 38333 1546 4097 38334 1548 4097 38335 1542 4097 38336 1548 4097 38337 1550 4097 38338 1542 4097 38339 1550 4097 38340 1552 4097 38341 1554 4097 38342 1554 4097 38343 1556 4097 38344 1550 4097 38345 1556 4097 38346 1558 4097 38347 1550 4097 38348 1558 4097 38349 1560 4097 38350 1562 4097 38351 1562 4097 38352 1564 4097 38353 1566 4097 38354 1566 4097 38355 1568 4097 38356 1570 4097 38357 1570 4097 38358 1572 4097 38359 1566 4097 38360 1572 4097 38361 1574 4097 38362 1566 4097 38363 1574 4097 38364 1576 4097 38365 1578 4097 38366 1578 4097 38367 1580 4097 38368 1574 4097 38369 1580 4097 38370 1582 4097 38371 1574 4097 38372 1582 4097 38373 1584 4097 38374 1586 4097 38375 1586 4097 38376 1588 4097 38377 1590 4097 38378 1590 4097 38379 1592 4097 38380 1594 4097 38381 1594 4097 38382 1596 4097 38383 1590 4097 38384 1596 4097 38385 1598 4097 38386 1590 4097 38387 1598 4097 38388 1600 4097 38389 1602 4097 38390 1602 4097 38391 1604 4097 38392 1598 4097 38393 1604 4097 38394 1606 4097 38395 1598 4097 38396 1606 4097 38397 1608 4097 38398 1614 4097 38399 1608 4097 38400 1610 4097 38401 1614 4097 38402 1610 4097 38403 1612 4097 38404 1614 4097 38405 1614 4097 38406 1616 4097 38407 1618 4097 38408 1618 4097 38409 1620 4097 38410 1614 4097 38411 1620 4097 38412 1622 4097 38413 1614 4097 38414 1622 4097 38415 1624 4097 38416 1626 4097 38417 1626 4097 38418 1628 4097 38419 1630 4097 38420 1630 4097 38421 1632 4097 38422 1634 4097 38423 1634 4097 38424 1636 4097 38425 1638 4097 38426 1638 4097 38427 1640 4097 38428 1642 4097 38429 1642 4097 38430 1644 4097 38431 1638 4097 38432 1644 4097 38433 1646 4097 38434 1638 4097 38435 1646 4097 38436 1648 4097 38437 1654 4097 38438 1648 4097 38439 1650 4097 38440 1654 4097 38441 1650 4097 38442 1652 4097 38443 1654 4097 38444 1654 4097 38445 1656 4097 38446 1658 4097 38447 1658 4097 38448 1660 4097 38449 1662 4097 38450 1662 4097 38451 1664 4097 38452 1666 4097 38453 1666 4097 38454 1668 4097 38455 1670 4097 38456 1670 4097 38457 1672 4097 38458 1678 4097 38459 1672 4097 38460 1674 4097 38461 1678 4097 38462 1674 4097 38463 1676 4097 38464 1678 4097 38465 1678 4097 38466 1680 4097 38467 1682 4097 38468 1682 4097 38469 1684 4097 38470 1678 4097 38471 1684 4097 38472 1686 4097 38473 1678 4097 38474 1686 4097 38475 1688 4097 38476 1690 4097 38477 1690 4097 38478 1692 4097 38479 1686 4097 38480 1692 4097 38481 1694 4097 38482 1686 4097 38483 1694 4097 38484 1696 4097 38485 1698 4097 38486 1698 4097 38487 1700 4097 38488 1694 4097 38489 1700 4097 38490 1702 4097 38491 1694 4097 38492 1702 4097 38493 1704 4097 38494 1706 4097 38495 1706 4097 38496 1708 4097 38497 1702 4097 38498 1708 4097 38499 1710 4097 38500 1702 4097 38501 1710 4097 38502 1712 4097 38503 1714 4097 38504 1714 4097 38505 1716 4097 38506 1718 4097 38507 1718 4097 38508 1720 4097 38509 1726 4097 38510 1720 4097 38511 1722 4097 38512 1726 4097 38513 1722 4097 38514 1724 4097 38515 1726 4097 38516 1726 4097 38517 1728 4097 38518 1730 4097 38519 1730 4097 38520 1732 4097 38521 1734 4097 38522 1734 4097 38523 1736 4097 38524 1738 4097 38525 1738 4097 38526 1740 4097 38527 1742 4097 38528 1742 4097 38529 1744 4097 38530 1746 4097 38531 1746 4097 38532 1748 4097 38533 1750 4097 38534 1750 4097 38535 1752 4097 38536 1758 4097 38537 1752 4097 38538 1754 4097 38539 1758 4097 38540 1754 4097 38541 1756 4097 38542 1758 4097 38543 1758 4097 38544 1760 4097 38545 1766 4097 38546 1760 4097 38547 1762 4097 38548 1766 4097 38549 1762 4097 38550 1764 4097 38551 1766 4097 38552 1766 4097 38553 1768 4097 38554 1770 4097 38555 1770 4097 38556 1772 4097 38557 1774 4097 38558 1774 4097 38559 1776 4097 38560 1778 4097 38561 1778 4097 38562 1780 4097 38563 1774 4097 38564 1780 4097 38565 1782 4097 38566 1774 4097 38567 1782 4097 38568 1784 4097 38569 1786 4097 38570 1786 4097 38571 1788 4097 38572 1782 4097 38573 1788 4097 38574 1790 4097 38575 1782 4097 38576 1790 4097 38577 1792 4097 38578 1798 4097 38579 1792 4097 38580 1794 4097 38581 1798 4097 38582 1794 4097 38583 1796 4097 38584 1798 4097 38585 1798 4097 38586 1800 4097 38587 1802 4097 38588 1802 4097 38589 1804 4097 38590 1806 4097 38591 1806 4097 38592 1808 4097 38593 1810 4097 38594 1810 4097 38595 1812 4097 38596 1814 4097 38597 1814 4097 38598 1816 4097 38599 1818 4097 38600 1818 4097 38601 1820 4097 38602 1822 4097 38603 1822 4097 38604 1824 4097 38605 1826 4097 38606 1826 4097 38607 1828 4097 38608 1830 4097 38609 1830 4097 38610 1832 4097 38611 1834 4097 38612 1834 4097 38613 1836 4097 38614 1830 4097 38615 1836 4097 38616 1838 4097 38617 1830 4097 38618 1838 4097 38619 1840 4097 38620 1842 4097 38621 1842 4097 38622 1844 4097 38623 1846 4097 38624 1846 4097 38625 1848 4097 38626 1850 4097 38627 1850 4097 38628 1852 4097 38629 1846 4097 38630 1852 4097 38631 1854 4097 38632 1846 4097 38633 1854 4097 38634 1856 4097 38635 1858 4097 38636 1858 4097 38637 1860 4097 38638 1854 4097 38639 1860 4097 38640 1862 4097 38641 1854 4097 38642 1862 4097 38643 1864 4097 38644 1870 4097 38645 1864 4097 38646 1866 4097 38647 1870 4097 38648 1866 4097 38649 1868 4097 38650 1870 4097 38651 1870 4097 38652 1872 4097 38653 1874 4097 38654 1874 4097 38655 1876 4097 38656 1870 4097 38657 1876 4097 38658 1878 4097 38659 1870 4097 38660 1878 4097 38661 1880 4097 38662 1882 4097 38663 1882 4097 38664 1884 4097 38665 1878 4097 38666 1884 4097 38667 1886 4097 38668 1878 4097 38669 1886 4097 38670 1888 4097 38671 1890 4097 38672 1890 4097 38673 1892 4097 38674 1894 4097 38675 1894 4097 38676 1896 4097 38677 1898 4097 38678 1898 4097 38679 1900 4097 38680 1894 4097 38681 1900 4097 38682 1902 4097 38683 1894 4097 38684 1902 4097 38685 1904 4097 38686 1910 4097 38687 1904 4097 38688 1906 4097 38689 1910 4097 38690 1906 4097 38691 1908 4097 38692 1910 4097 38693 1910 4097 38694 1912 4097 38695 1914 4097 38696 1914 4097 38697 1916 4097 38698 1910 4097 38699 1916 4097 38700 1918 4097 38701 1910 4097 38702 1918 4097 38703 1920 4097 38704 1926 4097 38705 1920 4097 38706 1922 4097 38707 1926 4097 38708 1922 4097 38709 1924 4097 38710 1926 4097 38711 1926 4097 38712 1928 4097 38713 1934 4097 38714 1928 4097 38715 1930 4097 38716 1934 4097 38717 1930 4097 38718 1932 4097 38719 1934 4097 38720 1934 4097 38721 1936 4097 38722 1938 4097 38723 1938 4097 38724 1940 4097 38725 1934 4097 38726 1940 4097 38727 1942 4097 38728 1934 4097 38729 1942 4097 38730 1944 4097 38731 1946 4097 38732 1946 4097 38733 1948 4097 38734 1950 4097 38735 1950 4097 38736 1952 4097 38737 1954 4097 38738 1954 4097 38739 1956 4097 38740 1950 4097 38741 1956 4097 38742 1958 4097 38743 1950 4097 38744 1958 4097 38745 1960 4097 38746 1962 4097 38747 1962 4097 38748 1964 4097 38749 1966 4097 38750 1966 4097 38751 1968 4097 38752 1974 4097 38753 1968 4097 38754 1970 4097 38755 1974 4097 38756 1970 4097 38757 1972 4097 38758 1974 4097 38759 1974 4097 38760 1976 4097 38761 1978 4097 38762 1978 4097 38763 1980 4097 38764 1982 4097 38765 1982 4097 38766 1984 4097 38767 1990 4097 38768 1984 4097 38769 1986 4097 38770 1990 4097 38771 1986 4097 38772 1988 4097 38773 1990 4097 38774 1990 4097 38775 1992 4097 38776 1994 4097 38777 1994 4097 38778 1996 4097 38779 1990 4097 38780 1996 4097 38781 1998 4097 38782 1990 4097 38783 1998 4097 38784 2000 4097 38785 2006 4097 38786 2000 4097 38787 2002 4097 38788 2006 4097 38789 2002 4097 38790 2004 4097 38791 2006 4097 38792 2006 4097 38793 2008 4097 38794 2010 4097 38795 2010 4097 38796 2012 4097 38797 2006 4097 38798 2012 4097 38799 2014 4097 38800 2006 4097 38801 2014 4097 38802 2016 4097 38803 2018 4097 38804 2018 4097 38805 2020 4097 38806 2014 4097 38807 2020 4097 38808 2022 4097 38809 2014 4097 38810 2022 4097 38811 2024 4097 38812 2026 4097 38813 2026 4097 38814 2028 4097 38815 2022 4097 38816 2028 4097 38817 2030 4097 38818 2022 4097 38819 2030 4097 38820 2032 4097 38821 2034 4097 38822 2034 4097 38823 2036 4097 38824 2030 4097 38825 2036 4097 38826 2038 4097 38827 2030 4097 38828 2038 4097 38829 2040 4097 38830 2042 4097 38831 2042 4097 38832 2044 4097 38833 2046 4097 38834 2046 4097 38835 2048 4097 38836 2050 4097 38837 2050 4097 38838 2052 4097 38839 2054 4097 38840 2054 4097 38841 2056 4097 38842 2058 4097 38843 2058 4097 38844 2060 4097 38845 2054 4097 38846 2060 4097 38847 2062 4097 38848 2054 4097 38849 2062 4097 38850 2064 4097 38851 2066 4097 38852 2066 4097 38853 2068 4097 38854 2070 4097 38855 2070 4097 38856 2072 4097 38857 2074 4097 38858 2074 4097 38859 2076 4097 38860 2070 4097 38861 2076 4097 38862 2078 4097 38863 2070 4097 38864 2078 4097 38865 2080 4097 38866 2086 4097 38867 2080 4097 38868 2082 4097 38869 2086 4097 38870 2082 4097 38871 2084 4097 38872 2086 4097 38873 2086 4097 38874 2088 4097 38875 2094 4097 38876 2088 4097 38877 2090 4097 38878 2094 4097 38879 2090 4097 38880 2092 4097 38881 2094 4097 38882 2094 4097 38883 2096 4097 38884 2102 4097 38885 2096 4097 38886 2098 4097 38887 2102 4097 38888 2098 4097 38889 2100 4097 38890 2102 4097 38891 2102 4097 38892 2104 4097 38893 2106 4097 38894 2106 4097 38895 2108 4097 38896 2110 4097 38897 2110 4097 38898 2112 4097 38899 2118 4097 38900 2112 4097 38901 2114 4097 38902 2118 4097 38903 2114 4097 38904 2116 4097 38905 2118 4097 38906 2118 4097 38907 2120 4097 38908 2122 4097 38909 2122 4097 38910 2124 4097 38911 2126 4097 38912 2126 4097 38913 2128 4097 38914 2134 4097 38915 2128 4097 38916 2130 4097 38917 2134 4097 38918 2130 4097 38919 2132 4097 38920 2134 4097 38921 2134 4097 38922 2136 4097 38923 2142 4097 38924 2136 4097 38925 2138 4097 38926 2142 4097 38927 2138 4097 38928 2140 4097 38929 2142 4097 38930 2142 4097 38931 2144 4097 38932 2146 4097 38933 2146 4097 38934 2148 4097 38935 2150 4097 38936 2150 4097 38937 2152 4097 38938 2158 4097 38939 2152 4097 38940 2154 4097 38941 2158 4097 38942 2154 4097 38943 2156 4097 38944 2158 4097 38945 2158 4097 38946 2160 4097 38947 2162 4097 38948 2162 4097 38949 2164 4097 38950 2166 4097 38951 2166 4097 38952 2168 4097 38953 2174 4097 38954 2168 4097 38955 2170 4097 38956 2174 4097 38957 2170 4097 38958 2172 4097 38959 2174 4097 38960 2174 4097 38961 2176 4097 38962 2178 4097 38963 2178 4097 38964 2180 4097 38965 2174 4097 38966 2180 4097 38967 2182 4097 38968 2174 4097 38969 2182 4097 38970 2184 4097 38971 2186 4097 38972 2186 4097 38973 2188 4097 38974 2190 4097 38975 2190 4097 38976 2192 4097 38977 2198 4097 38978 2192 4097 38979 2194 4097 38980 2198 4097 38981 2194 4097 38982 2196 4097 38983 2198 4097 38984 2198 4097 38985 2200 4097 38986 2206 4097 38987 2200 4097 38988 2202 4097 38989 2206 4097 38990 2202 4097 38991 2204 4097 38992 2206 4097 38993 2206 4097 38994 2208 4097 38995 2210 4097 38996 2210 4097 38997 2212 4097 38998 2206 4097 38999 2212 4097 39000 2214 4097 39001 2206 4097 39002 2214 4097 39003 2216 4097 39004 2218 4097 39005 2218 4097 39006 2220 4097 39007 2214 4097 39008 2220 4097 39009 2222 4097 39010 2214 4097 39011 2222 4097 39012 2224 4097 39013 2226 4097 39014 2226 4097 39015 2228 4097 39016 2230 4097 39017 2230 4097 39018 2232 4097 39019 2238 4097 39020 2232 4097 39021 2234 4097 39022 2238 4097 39023 2234 4097 39024 2236 4097 39025 2238 4097 39026 2238 4097 39027 2240 4097 39028 2242 4097 39029 2242 4097 39030 2244 4097 39031 2246 4097 39032 2246 4097 39033 2248 4097 39034 2254 4097 39035 2248 4097 39036 2250 4097 39037 2254 4097 39038 2250 4097 39039 2252 4097 39040 2254 4097 39041 2254 4097 39042 2256 4097 39043 2258 4097 39044 2258 4097 39045 2260 4097 39046 2262 4097 39047 2262 4097 39048 2264 4097 39049 2266 4097 39050 2266 4097 39051 2268 4097 39052 2270 4097 39053 2270 4097 39054 2272 4097 39055 2274 4097 39056 2274 4097 39057 2276 4097 39058 2270 4097 39059 2276 4097 39060 2278 4097 39061 2270 4097 39062 2278 4097 39063 2280 4097 39064 2286 4097 39065 2280 4097 39066 2282 4097 39067 2286 4097 39068 2282 4097 39069 2284 4097 39070 2286 4097 39071 2286 4097 39072 2288 4097 39073 2294 4097 39074 2288 4097 39075 2290 4097 39076 2294 4097 39077 2290 4097 39078 2292 4097 39079 2294 4097 39080 2294 4097 39081 2296 4097 39082 2298 4097 39083 2298 4097 39084 2300 4097 39085 2302 4097 39086 2302 4097 39087 2304 4097 39088 2306 4097 39089 2306 4097 39090 2308 4097 39091 2310 4097 39092 2310 4097 39093 2312 4097 39094 2314 4097 39095 2314 4097 39096 2316 4097 39097 2310 4097 39098 2316 4097 39099 2318 4097 39100 2310 4097 39101 2318 4097 39102 2320 4097 39103 2322 4097 39104 2322 4097 39105 2324 4097 39106 2326 4097 39107 2326 4097 39108 2328 4097 39109 2330 4097 39110 2330 4097 39111 2332 4097 39112 2334 4097 39113 2334 4097 39114 2336 4097 39115 2338 4097 39116 2338 4097 39117 2340 4097 39118 2342 4097 39119 2342 4097 39120 2344 4097 39121 2350 4097 39122 2344 4097 39123 2346 4097 39124 2350 4097 39125 2346 4097 39126 2348 4097 39127 2350 4097 39128 2350 4097 39129 2352 4097 39130 2354 4097 39131 2354 4097 39132 2356 4097 39133 2358 4097 39134 2358 4097 39135 2360 4097 39136 2362 4097 39137 2362 4097 39138 2364 4097 39139 2366 4097 39140 2366 4097 39141 2368 4097 39142 2370 4097 39143 2370 4097 39144 2372 4097 39145 2374 4097 39146 2374 4097 39147 2376 4097 39148 2382 4097 39149 2376 4097 39150 2378 4097 39151 2382 4097 39152 2378 4097 39153 2380 4097 39154 2382 4097 39155 2382 4097 39156 2384 4097 39157 2386 4097 39158 2386 4097 39159 2388 4097 39160 2382 4097 39161 2388 4097 39162 2390 4097 39163 2382 4097 39164 2390 4097 39165 2392 4097 39166 2394 4097 39167 2394 4097 39168 2396 4097 39169 2398 4097 39170 2398 4097 39171 2400 4097 39172 2402 4097 39173 2402 4097 39174 2404 4097 39175 2406 4097 39176 2406 4097 39177 2408 4097 39178 2410 4097 39179 2410 4097 39180 2412 4097 39181 2414 4097 39182 2414 4097 39183 2416 4097 39184 2418 4097 39185 2418 4097 39186 2420 4097 39187 2422 4097 39188 2422 4097 39189 2424 4097 39190 2430 4097 39191 2424 4097 39192 2426 4097 39193 2430 4097 39194 2426 4097 39195 2428 4097 39196 2430 4097 39197 2430 4097 39198 2432 4097 39199 2434 4097 39200 2434 4097 39201 2436 4097 39202 2438 4097 39203 2438 4097 39204 2440 4097 39205 2442 4097 39206 2442 4097 39207 2444 4097 39208 2446 4097 39209 2446 4097 39210 2448 4097 39211 2454 4097 39212 2448 4097 39213 2450 4097 39214 2454 4097 39215 2450 4097 39216 2452 4097 39217 2454 4097 39218 2454 4097 39219 2456 4097 39220 2458 4097 39221 2458 4097 39222 2460 4097 39223 2462 4097 39224 2462 4097 39225 2464 4097 39226 2470 4097 39227 2464 4097 39228 2466 4097 39229 2470 4097 39230 2466 4097 39231 2468 4097 39232 2470 4097 39233 2470 4097 39234 2472 4097 39235 2478 4097 39236 2472 4097 39237 2474 4097 39238 2478 4097 39239 2474 4097 39240 2476 4097 39241 2478 4097 39242 2478 4097 39243 2480 4097 39244 2482 4097 39245 2482 4097 39246 2484 4097 39247 2486 4097 39248 2486 4097 39249 2488 4097 39250 2494 4097 39251 2488 4097 39252 2490 4097 39253 2494 4097 39254 2490 4097 39255 2492 4097 39256 2494 4097 39257 2494 4097 39258 2496 4097 39259 2498 4097 39260 2498 4097 39261 2500 4097 39262 2502 4097 39263 2502 4097 39264 2504 4097 39265 2510 4097 39266 2504 4097 39267 2506 4097 39268 2510 4097 39269 2506 4097 39270 2508 4097 39271 2510 4097 39272 2510 4097 39273 2512 4097 39274 2514 4097 39275 2514 4097 39276 2516 4097 39277 2510 4097 39278 2516 4097 39279 2518 4097 39280 2510 4097 39281 2518 4097 39282 2520 4097 39283 2522 4097 39284 2522 4097 39285 2524 4097 39286 2526 4097 39287 2526 4097 39288 2528 4097 39289 2530 4097 39290 2530 4097 39291 2532 4097 39292 2534 4097 39293 2534 4097 39294 2536 4097 39295 2538 4097 39296 2538 4097 39297 2540 4097 39298 2542 4097 39299 2542 4097 39300 2544 4097 39301 2546 4097 39302 2546 4097 39303 2548 4097 39304 2542 4097 39305 2548 4097 39306 2550 4097 39307 2542 4097 39308 2550 4097 39309 2552 4097 39310 2554 4097 39311 2554 4097 39312 2556 4097 39313 2558 4097 39314 2558 4097 39315 2560 4097 39316 2562 4097 39317 2562 4097 39318 2564 4097 39319 2566 4097 39320 2566 4097 39321 2568 4097 39322 2570 4097 39323 2570 4097 39324 2572 4097 39325 2566 4097 39326 2572 4097 39327 2574 4097 39328 2566 4097 39329 2574 4097 39330 2576 4097 39331 2578 4097 39332 2578 4097 39333 2580 4097 39334 2574 4097 39335 2580 4097 39336 2582 4097 39337 2574 4097 39338 2582 4097 39339 2584 4097 39340 2586 4097 39341 2586 4097 39342 2588 4097 39343 2582 4097 39344 2588 4097 39345 2590 4097 39346 2582 4097 39347 2590 4097 39348 2592 4097 39349 2598 4097 39350 2592 4097 39351 2594 4097 39352 2598 4097 39353 2594 4097 39354 2596 4097 39355 2598 4097 39356 2598 4097 39357 2600 4097 39358 2602 4097 39359 2602 4097 39360 2604 4097 39361 2598 4097 39362 2604 4097 39363 2606 4097 39364 2598 4097 39365 2606 4097 39366 2608 4097 39367 2610 4097 39368 2610 4097 39369 2612 4097 39370 2614 4097 39371 2614 4097 39372 2616 4097 39373 2618 4097 39374 2618 4097 39375 2620 4097 39376 2622 4097 39377 2622 4097 39378 2624 4097 39379 2626 4097 39380 2626 4097 39381 2628 4097 39382 2630 4097 39383 2630 4097 39384 2632 4097 39385 2634 4097 39386 2634 4097 39387 2636 4097 39388 2638 4097 39389 2638 4097 39390 2640 4097 39391 2642 4097 39392 2642 4097 39393 2644 4097 39394 2638 4097 39395 2644 4097 39396 2646 4097 39397 2638 4097 39398 2646 4097 39399 2648 4097 39400 2650 4097 39401 2650 4097 39402 2652 4097 39403 2646 4097 39404 2652 4097 39405 2654 4097 39406 2646 4097 39407 2654 4097 39408 2656 4097 39409 2658 4097 39410 2658 4097 39411 2660 4097 39412 2662 4097 39413 2662 4097 39414 2664 4097 39415 2666 4097 39416 2666 4097 39417 2668 4097 39418 2670 4097 39419 2670 4097 39420 2672 4097 39421 2674 4097 39422 2674 4097 39423 2676 4097 39424 2678 4097 39425 2678 4097 39426 2680 4097 39427 2682 4097 39428 2682 4097 39429 2684 4097 39430 2678 4097 39431 2684 4097 39432 2686 4097 39433 2678 4097 39434 2686 4097 39435 2688 4097 39436 2694 4097 39437 2688 4097 39438 2690 4097 39439 2694 4097 39440 2690 4097 39441 2692 4097 39442 2694 4097 39443 2694 4097 39444 2696 4097 39445 2698 4097 39446 2698 4097 39447 2700 4097 39448 2694 4097 39449 2700 4097 39450 2702 4097 39451 2694 4097 39452 2702 4097 39453 2704 4097 39454 2706 4097 39455 2706 4097 39456 2708 4097 39457 2710 4097 39458 2710 4097 39459 2712 4097 39460 2714 4097 39461 2714 4097 39462 2716 4097 39463 2718 4097 39464 2718 4097 39465 2720 4097 39466 2726 4097 39467 2720 4097 39468 2722 4097 39469 2726 4097 39470 2722 4097 39471 2724 4097 39472 2726 4097 39473 2726 4097 39474 2728 4097 39475 2734 4097 39476 2728 4097 39477 2730 4097 39478 2734 4097 39479 2730 4097 39480 2732 4097 39481 2734 4097 39482 2734 4097 39483 2736 4097 39484 2742 4097 39485 2736 4097 39486 2738 4097 39487 2742 4097 39488 2738 4097 39489 2740 4097 39490 2742 4097 39491 2742 4097 39492 2744 4097 39493 2746 4097 39494 2746 4097 39495 2748 4097 39496 2750 4097 39497 2750 4097 39498 2752 4097 39499 2754 4097 39500 2754 4097 39501 2756 4097 39502 2758 4097 39503 2758 4097 39504 2760 4097 39505 2762 4097 39506 2762 4097 39507 2764 4097 39508 2758 4097 39509 2764 4097 39510 2766 4097 39511 2758 4097 39512 2766 4097 39513 2768 4097 39514 2770 4097 39515 2770 4097 39516 2772 4097 39517 2774 4097 39518 2774 4097 39519 2776 4097 39520 2778 4097 39521 2778 4097 39522 2780 4097 39523 2782 4097 39524 2782 4097 39525 2784 4097 39526 2786 4097 39527 2786 4097 39528 2788 4097 39529 2790 4097 39530 2790 4097 39531 2792 4097 39532 2794 4097 39533 2794 4097 39534 2796 4097 39535 2790 4097 39536 2796 4097 39537 2798 4097 39538 2790 4097 39539 2798 4097 39540 2800 4097 39541 2806 4097 39542 2800 4097 39543 2802 4097 39544 2806 4097 39545 2802 4097 39546 2804 4097 39547 2806 4097 39548 2806 4097 39549 2808 4097 39550 2814 4097 39551 2808 4097 39552 2810 4097 39553 2814 4097 39554 2810 4097 39555 2812 4097 39556 2814 4097 39557 2814 4097 39558 2816 4097 39559 2818 4097 39560 2818 4097 39561 2820 4097 39562 2814 4097 39563 2820 4097 39564 2822 4097 39565 2814 4097 39566 2822 4097 39567 2824 4097 39568 2830 4097 39569 2824 4097 39570 2826 4097 39571 2830 4097 39572 2826 4097 39573 2828 4097 39574 2830 4097 39575 2830 4097 39576 2832 4097 39577 2834 4097 39578 2834 4097 39579 2836 4097 39580 2830 4097 39581 2836 4097 39582 2838 4097 39583 2830 4097 39584 2838 4097 39585 2840 4097 39586 2842 4097 39587 2842 4097 39588 2844 4097 39589 2846 4097 39590 2846 4097 39591 2848 4097 39592 2850 4097 39593 2850 4097 39594 2852 4097 39595 2846 4097 39596 2852 4097 39597 2854 4097 39598 2846 4097 39599 2854 4097 39600 2856 4097 39601 2858 4097 39602 2858 4097 39603 2860 4097 39604 2862 4097 39605 2862 4097 39606 2864 4097 39607 2866 4097 39608 2866 4097 39609 2868 4097 39610 2862 4097 39611 2868 4097 39612 2870 4097 39613 2862 4097 39614 2870 4097 39615 2872 4097 39616 2874 4097 39617 2874 4097 39618 2876 4097 39619 2870 4097 39620 2876 4097 39621 2878 4097 39622 2870 4097 39623 2878 4097 39624 2880 4097 39625 2882 4097 39626 2882 4097 39627 2884 4097 39628 2886 4097 39629 2886 4097 39630 2888 4097 39631 2890 4097 39632 2890 4097 39633 2892 4097 39634 2886 4097 39635 2892 4097 39636 2894 4097 39637 2886 4097 39638 2894 4097 39639 2896 4097 39640 2898 4097 39641 2898 4097 39642 2900 4097 39643 2894 4097 39644 2900 4097 39645 2902 4097 39646 2894 4097 39647 2902 4097 39648 2904 4097 39649 2906 4097 39650 2906 4097 39651 2908 4097 39652 2902 4097 39653 2908 4097 39654 2910 4097 39655 2902 4097 39656 2910 4097 39657 2912 4097 39658 2914 4097 39659 2914 4097 39660 2916 4097 39661 2918 4097 39662 2918 4097 39663 2920 4097 39664 2922 4097 39665 2922 4097 39666 2924 4097 39667 2918 4097 39668 2924 4097 39669 2926 4097 39670 2918 4097 39671 2926 4097 39672 2928 4097 39673 2930 4097 39674 2930 4097 39675 2932 4097 39676 2934 4097 39677 2934 4097 39678 2936 4097 39679 2938 4097 39680 2938 4097 39681 2940 4097 39682 2934 4097 39683 2940 4097 39684 2942 4097 39685 2934 4097 39686 2942 4097 39687 2944 4097 39688 2946 4097 39689 2946 4097 39690 2948 4097 39691 2942 4097 39692 2948 4097 39693 2950 4097 39694 2942 4097 39695 2950 4097 39696 2952 4097 39697 2954 4097 39698 2954 4097 39699 2956 4097 39700 2958 4097 39701 2958 4097 39702 2960 4097 39703 2966 4097 39704 2960 4097 39705 2962 4097 39706 2966 4097 39707 2962 4097 39708 2964 4097 39709 2966 4097 39710 2966 4097 39711 2968 4097 39712 2970 4097 39713 2970 4097 39714 2972 4097 39715 2974 4097 39716 2974 4097 39717 2976 4097 39718 2978 4097 39719 2978 4097 39720 2980 4097 39721 2982 4097 39722 2982 4097 39723 2984 4097 39724 2986 4097 39725 2986 4097 39726 2988 4097 39727 2982 4097 39728 2988 4097 39729 2990 4097 39730 2982 4097 39731 2990 4097 39732 2992 4097 39733 2994 4097 39734 2994 4097 39735 2996 4097 39736 2998 4097 39737 2998 4097 39738 3000 4097 39739 3002 4097 39740 3002 4097 39741 3004 4097 39742 3006 4097 39743 3006 4097 39744 3008 4097 39745 3010 4097 39746 3010 4097 39747 3012 4097 39748 3006 4097 39749 3012 4097 39750 3014 4097 39751 3006 4097 39752 3014 4097 39753 3016 4097 39754 3018 4097 39755 3018 4097 39756 3020 4097 39757 3022 4097 39758 3022 4097 39759 3024 4097 39760 3026 4097 39761 3026 4097 39762 3028 4097 39763 3030 4097 39764 3030 4097 39765 3032 4097 39766 3034 4097 39767 3034 4097 39768 3036 4097 39769 3030 4097 39770 3036 4097 39771 3038 4097 39772 3030 4097 39773 3038 4097 39774 3040 4097 39775 3042 4097 39776 3042 4097 39777 3044 4097 39778 3046 4097 39779 3046 4097 39780 3048 4097 39781 3054 4097 39782 3048 4097 39783 3050 4097 39784 3054 4097 39785 3050 4097 39786 3052 4097 39787 3054 4097 39788 3054 4097 39789 3056 4097 39790 3062 4097 39791 3056 4097 39792 3058 4097 39793 3062 4097 39794 3058 4097 39795 3060 4097 39796 3062 4097 39797 3062 4097 39798 3064 4097 39799 3066 4097 39800 3066 4097 39801 3068 4097 39802 3070 4097 39803 3070 4097 39804 3072 4097 39805 3074 4097 39806 3074 4097 39807 3076 4097 39808 3070 4097 39809 3076 4097 39810 3078 4097 39811 3070 4097 39812 3078 4097 39813 3080 4097 39814 3082 4097 39815 3082 4097 39816 3084 4097 39817 3086 4097 39818 3086 4097 39819 3088 4097 39820 3090 4097 39821 3090 4097 39822 3092 4097 39823 3094 4097 39824 3094 4097 39825 3096 4097 39826 3102 4097 39827 3096 4097 39828 3098 4097 39829 3102 4097 39830 3098 4097 39831 3100 4097 39832 3102 4097 39833 3102 4097 39834 3104 4097 39835 3106 4097 39836 3106 4097 39837 3108 4097 39838 3102 4097 39839 3108 4097 39840 3110 4097 39841 3102 4097 39842 3110 4097 39843 3112 4097 39844 3118 4097 39845 3112 4097 39846 3114 4097 39847 3118 4097 39848 3114 4097 39849 3116 4097 39850 3118 4097 39851 3118 4097 39852 3120 4097 39853 3122 4097 39854 3122 4097 39855 3124 4097 39856 3126 4097 39857 3126 4097 39858 3128 4097 39859 3130 4097 39860 3130 4097 39861 3132 4097 39862 3126 4097 39863 3132 4097 39864 3134 4097 39865 3126 4097 39866 3134 4097 39867 3136 4097 39868 3138 4097 39869 3138 4097 39870 3140 4097 39871 3142 4097 39872 3142 4097 39873 3144 4097 39874 3146 4097 39875 3146 4097 39876 3148 4097 39877 3150 4097 39878 3150 4097 39879 3152 4097 39880 3154 4097 39881 3154 4097 39882 3156 4097 39883 3150 4097 39884 3156 4097 39885 3158 4097 39886 3150 4097 39887 3158 4097 39888 3160 4097 39889 3162 4097 39890 3162 4097 39891 3164 4097 39892 3166 4097 39893 3166 4097 39894 3168 4097 39895 3170 4097 39896 3170 4097 39897 3172 4097 39898 3166 4097 39899 3172 4097 39900 3174 4097 39901 3166 4097 39902 3174 4097 39903 3176 4097 39904 3182 4097 39905 3176 4097 39906 3178 4097 39907 3182 4097 39908 3178 4097 39909 3180 4097 39910 3182 4097 39911 3182 4097 39912 3184 4097 39913 3190 4097 39914 3184 4097 39915 3186 4097 39916 3190 4097 39917 3186 4097 39918 3188 4097 39919 3190 4097 39920 3190 4097 39921 3192 4097 39922 3194 4097 39923 3194 4097 39924 3196 4097 39925 3190 4097 39926 3196 4097 39927 3198 4097 39928 3190 4097 39929 3198 4097 39930 3200 4097 39931 3202 4097 39932 3202 4097 39933 3204 4097 39934 3206 4097 39935 3206 4097 39936 3208 4097 39937 3214 4097 39938 3208 4097 39939 3210 4097 39940 3214 4097 39941 3210 4097 39942 3212 4097 39943 3214 4097 39944 3214 4097 39945 3216 4097 39946 3218 4097 39947 3218 4097 39948 3220 4097 39949 3214 4097 39950 3220 4097 39951 3222 4097 39952 3214 4097 39953 3222 4097 39954 3224 4097 39955 3226 4097 39956 3226 4097 39957 3228 4097 39958 3230 4097 39959 3230 4097 39960 3232 4097 39961 3234 4097 39962 3234 4097 39963 3236 4097 39964 3230 4097 39965 3236 4097 39966 3238 4097 39967 3230 4097 39968 3238 4097 39969 3240 4097 39970 3246 4097 39971 3240 4097 39972 3242 4097 39973 3246 4097 39974 3242 4097 39975 3244 4097 39976 3246 4097 39977 3246 4097 39978 3248 4097 39979 3250 4097 39980 3250 4097 39981 3252 4097 39982 3254 4097 39983 3254 4097 39984 3256 4097 39985 3262 4097 39986 3256 4097 39987 3258 4097 39988 3262 4097 39989 3258 4097 39990 3260 4097 39991 3262 4097 39992 3262 4097 39993 3264 4097 39994 3266 4097 39995 3266 4097 39996 3268 4097 39997 3270 4097 39998 3270 4097 39999 3272 4097 40000 3274 4097 40001 3274 4097 40002 3276 4097 40003 3270 4097 40004 3276 4097 40005 3278 4097 40006 3270 4097 40007 3278 4097 40008 3280 4097 40009 3282 4097 40010 3282 4097 40011 3284 4097 40012 3286 4097 40013 3286 4097 40014 3288 4097 40015 3290 4097 40016 3290 4097 40017 3292 4097 40018 3286 4097 40019 3292 4097 40020 3294 4097 40021 3286 4097 40022 3294 4097 40023 3296 4097 40024 3298 4097 40025 3298 4097 40026 3300 4097 40027 3294 4097 40028 3300 4097 40029 3302 4097 40030 3294 4097 40031 3302 4097 40032 3304 4097 40033 3306 4097 40034 3306 4097 40035 3308 4097 40036 3302 4097 40037 3308 4097 40038 3310 4097 40039 3302 4097 40040 3310 4097 40041 3312 4097 40042 3314 4097 40043 3314 4097 40044 3316 4097 40045 3318 4097 40046 3318 4097 40047 3320 4097 40048 3322 4097 40049 3322 4097 40050 3324 4097 40051 3318 4097 40052 3324 4097 40053 3326 4097 40054 3318 4097 40055 3326 4097 40056 3328 4097 40057 3334 4097 40058 3328 4097 40059 3330 4097 40060 3334 4097 40061 3330 4097 40062 3332 4097 40063 3334 4097 40064 3334 4097 40065 3336 4097 40066 3338 4097 40067 3338 4097 40068 3340 4097 40069 3342 4097 40070 3342 4097 40071 3344 4097 40072 3346 4097 40073 3346 4097 40074 3348 4097 40075 3342 4097 40076 3348 4097 40077 3350 4097 40078 3342 4097 40079 3350 4097 40080 3352 4097 40081 3354 4097 40082 3354 4097 40083 3356 4097 40084 3350 4097 40085 3356 4097 40086 3358 4097 40087 3350 4097 40088 3358 4097 40089 3360 4097 40090 3366 4097 40091 3360 4097 40092 3362 4097 40093 3366 4097 40094 3362 4097 40095 3364 4097 40096 3366 4097 40097 3366 4097 40098 3368 4097 40099 3374 4097 40100 3368 4097 40101 3370 4097 40102 3374 4097 40103 3370 4097 40104 3372 4097 40105 3374 4097 40106 3374 4097 40107 3376 4097 40108 3378 4097 40109 3378 4097 40110 3380 4097 40111 3374 4097 40112 3380 4097 40113 3382 4097 40114 3374 4097 40115 3382 4097 40116 3384 4097 40117 3386 4097 40118 3386 4097 40119 3388 4097 40120 3390 4097 40121 3390 4097 40122 3392 4097 40123 3398 4097 40124 3392 4097 40125 3394 4097 40126 3398 4097 40127 3394 4097 40128 3396 4097 40129 3398 4097 40130 3398 4097 40131 3400 4097 40132 3406 4097 40133 3400 4097 40134 3402 4097 40135 3406 4097 40136 3402 4097 40137 3404 4097 40138 3406 4097 40139 3406 4097 40140 3408 4097 40141 3410 4097 40142 3410 4097 40143 3412 4097 40144 3414 4097 40145 3414 4097 40146 3416 4097 40147 3422 4097 40148 3416 4097 40149 3418 4097 40150 3422 4097 40151 3418 4097 40152 3420 4097 40153 3422 4097 40154 3422 4097 40155 3424 4097 40156 3426 4097 40157 3426 4097 40158 3428 4097 40159 3430 4097 40160 3430 4097 40161 3432 4097 40162 3434 4097 40163 3434 4097 40164 3436 4097 40165 3438 4097 40166 3438 4097 40167 3440 4097 40168 3442 4097 40169 3442 4097 40170 3444 4097 40171 3446 4097 40172 3446 4097 40173 3448 4097 40174 3450 4097 40175 3450 4097 40176 3452 4097 40177 3454 4097 40178 3454 4097 40179 3456 4097 40180 3462 4097 40181 3456 4097 40182 3458 4097 40183 3462 4097 40184 3458 4097 40185 3460 4097 40186 3462 4097 40187 3462 4097 40188 3464 4097 40189 3466 4097 40190 3466 4097 40191 3468 4097 40192 3470 4097 40193 3470 4097 40194 3472 4097 40195 3474 4097 40196 3474 4097 40197 3476 4097 40198 3478 4097 40199 3478 4097 40200 3480 4097 40201 3482 4097 40202 3482 4097 40203 3484 4097 40204 3478 4097 40205 3484 4097 40206 3486 4097 40207 3478 4097 40208 3486 4097 40209 3488 4097 40210 3490 4097 40211 3490 4097 40212 3492 4097 40213 3486 4097 40214 3492 4097 40215 3494 4097 40216 3486 4097 40217 3494 4097 40218 3496 4097 40219 3498 4097 40220 3498 4097 40221 3500 4097 40222 3502 4097 40223 3502 4097 40224 3504 4097 40225 3506 4097 40226 3506 4097 40227 3508 4097 40228 3510 4097 40229 3510 4097 40230 3512 4097 40231 3514 4097 40232 3514 4097 40233 3516 4097 40234 3518 4097 40235 3518 4097 40236 3520 4097 40237 3522 4097 40238 3522 4097 40239 3524 4097 40240 3526 4097 40241 3526 4097 40242 3528 4097 40243 3530 4097 40244 3530 4097 40245 3532 4097 40246 3526 4097 40247 3532 4097 40248 3534 4097 40249 3526 4097 40250 3534 4097 40251 3536 4097 40252 3538 4097 40253 3538 4097 40254 3540 4097 40255 3534 4097 40256 3540 4097 40257 3542 4097 40258 3534 4097 40259 3542 4097 40260 3544 4097 40261 3546 4097 40262 3546 4097 40263 3548 4097 40264 3550 4097 40265 3550 4097 40266 3552 4097 40267 3558 4097 40268 3552 4097 40269 3554 4097 40270 3558 4097 40271 3554 4097 40272 3556 4097 40273 3558 4097 40274 3558 4097 40275 3560 4097 40276 3562 4097 40277 3562 4097 40278 3564 4097 40279 3566 4097 40280 3566 4097 40281 3568 4097 40282 3570 4097 40283 3570 4097 40284 3572 4097 40285 3566 4097 40286 3572 4097 40287 3574 4097 40288 3566 4097 40289 3574 4097 40290 3576 4097 40291 3578 4097 40292 3578 4097 40293 3580 4097 40294 3582 4097 40295 3582 4097 40296 3584 4097 40297 3590 4097 40298 3584 4097 40299 3586 4097 40300 3590 4097 40301 3586 4097 40302 3588 4097 40303 3590 4097 40304 3590 4097 40305 3592 4097 40306 3594 4097 40307 3594 4097 40308 3596 4097 40309 3590 4097 40310 3596 4097 40311 3598 4097 40312 3590 4097 40313 3598 4097 40314 3600 4097 40315 3602 4097 40316 3602 4097 40317 3604 4097 40318 3598 4097 40319 3604 4097 40320 3606 4097 40321 3598 4097 40322 3606 4097 40323 3608 4097 40324 3610 4097 40325 3610 4097 40326 3612 4097 40327 3614 4097 40328 3614 4097 40329 3616 4097 40330 3618 4097 40331 3618 4097 40332 3620 4097 40333 3614 4097 40334 3620 4097 40335 3622 4097 40336 3614 4097 40337 3622 4097 40338 3624 4097 40339 3626 4097 40340 3626 4097 40341 3628 4097 40342 3622 4097 40343 3628 4097 40344 3630 4097 40345 3622 4097 40346 3630 4097 40347 3632 4097 40348 3634 4097 40349 3634 4097 40350 3636 4097 40351 3638 4097 40352 3638 4097 40353 3640 4097 40354 3642 4097 40355 3642 4097 40356 3644 4097 40357 3638 4097 40358 3644 4097 40359 3646 4097 40360 3638 4097 40361 3646 4097 40362 3648 4097 40363 3650 4097 40364 3650 4097 40365 3652 4097 40366 3646 4097 40367 3652 4097 40368 3654 4097 40369 3646 4097 40370 3654 4097 40371 3656 4097 40372 3662 4097 40373 3656 4097 40374 3658 4097 40375 3662 4097 40376 3658 4097 40377 3660 4097 40378 3662 4097 40379 3662 4097 40380 3664 4097 40381 3666 4097 40382 3666 4097 40383 3668 4097 40384 3662 4097 40385 3668 4097 40386 3670 4097 40387 3662 4097 40388 3670 4097 40389 3672 4097 40390 3674 4097 40391 3674 4097 40392 3676 4097 40393 3678 4097 40394 3678 4097 40395 3680 4097 40396 3682 4097 40397 3682 4097 40398 3684 4097 40399 3686 4097 40400 3686 4097 40401 3688 4097 40402 3690 4097 40403 3690 4097 40404 3692 4097 40405 3686 4097 40406 3692 4097 40407 3694 4097 40408 3686 4097 40409 3694 4097 40410 3696 4097 40411 3702 4097 40412 3696 4097 40413 3698 4097 40414 3702 4097 40415 3698 4097 40416 3700 4097 40417 3702 4097 40418 3702 4097 40419 3704 4097 40420 3706 4097 40421 3706 4097 40422 3708 4097 40423 3710 4097 40424 3710 4097 40425 3712 4097 40426 3714 4097 40427 3714 4097 40428 3716 4097 40429 3718 4097 40430 3718 4097 40431 3720 4097 40432 3726 4097 40433 3720 4097 40434 3722 4097 40435 3726 4097 40436 3722 4097 40437 3724 4097 40438 3726 4097 40439 3726 4097 40440 3728 4097 40441 3730 4097 40442 3730 4097 40443 3732 4097 40444 3726 4097 40445 3732 4097 40446 3734 4097 40447 3726 4097 40448 3734 4097 40449 3736 4097 40450 3738 4097 40451 3738 4097 40452 3740 4097 40453 3734 4097 40454 3740 4097 40455 3742 4097 40456 3734 4097 40457 3742 4097 40458 3744 4097 40459 3746 4097 40460 3746 4097 40461 3748 4097 40462 3742 4097 40463 3748 4097 40464 3750 4097 40465 3742 4097 40466 3750 4097 40467 3752 4097 40468 3754 4097 40469 3754 4097 40470 3756 4097 40471 3750 4097 40472 3756 4097 40473 3758 4097 40474 3750 4097 40475 3758 4097 40476 3760 4097 40477 3762 4097 40478 3762 4097 40479 3764 4097 40480 3766 4097 40481 3766 4097 40482 3768 4097 40483 3774 4097 40484 3768 4097 40485 3770 4097 40486 3774 4097 40487 3770 4097 40488 3772 4097 40489 3774 4097 40490 3774 4097 40491 3776 4097 40492 3778 4097 40493 3778 4097 40494 3780 4097 40495 3782 4097 40496 3782 4097 40497 3784 4097 40498 3786 4097 40499 3786 4097 40500 3788 4097 40501 3790 4097 40502 3790 4097 40503 3792 4097 40504 3794 4097 40505 3794 4097 40506 3796 4097 40507 3798 4097 40508 3798 4097 40509 3800 4097 40510 3806 4097 40511 3800 4097 40512 3802 4097 40513 3806 4097 40514 3802 4097 40515 3804 4097 40516 3806 4097 40517 3806 4097 40518 3808 4097 40519 3814 4097 40520 3808 4097 40521 3810 4097 40522 3814 4097 40523 3810 4097 40524 3812 4097 40525 3814 4097 40526 3814 4097 40527 3816 4097 40528 3818 4097 40529 3818 4097 40530 3820 4097 40531 3822 4097 40532 3822 4097 40533 3824 4097 40534 3826 4097 40535 3826 4097 40536 3828 4097 40537 3822 4097 40538 3828 4097 40539 3830 4097 40540 3822 4097 40541 3830 4097 40542 3832 4097 40543 3834 4097 40544 3834 4097 40545 3836 4097 40546 3830 4097 40547 3836 4097 40548 3838 4097 40549 3830 4097 40550 3838 4097 40551 3840 4097 40552 3846 4097 40553 3840 4097 40554 3842 4097 40555 3846 4097 40556 3842 4097 40557 3844 4097 40558 3846 4097 40559 3846 4097 40560 3848 4097 40561 3850 4097 40562 3850 4097 40563 3852 4097 40564 3854 4097 40565 3854 4097 40566 3856 4097 40567 3858 4097 40568 3858 4097 40569 3860 4097 40570 3862 4097 40571 3862 4097 40572 3864 4097 40573 3866 4097 40574 3866 4097 40575 3868 4097 40576 3870 4097 40577 3870 4097 40578 3872 4097 40579 3874 4097 40580 3874 4097 40581 3876 4097 40582 3878 4097 40583 3878 4097 40584 3880 4097 40585 3882 4097 40586 3882 4097 40587 3884 4097 40588 3878 4097 40589 3884 4097 40590 3886 4097 40591 3878 4097 40592 3886 4097 40593 3888 4097 40594 3890 4097 40595 3890 4097 40596 3892 4097 40597 3894 4097 40598 3894 4097 40599 3896 4097 40600 3898 4097 40601 3898 4097 40602 3900 4097 40603 3894 4097 40604 3900 4097 40605 3902 4097 40606 3894 4097 40607 3902 4097 40608 3904 4097 40609 3906 4097 40610 3906 4097 40611 3908 4097 40612 3902 4097 40613 3908 4097 40614 3910 4097 40615 3902 4097 40616 3910 4097 40617 3912 4097 40618 3918 4097 40619 3912 4097 40620 3914 4097 40621 3918 4097 40622 3914 4097 40623 3916 4097 40624 3918 4097 40625 3918 4097 40626 3920 4097 40627 3922 4097 40628 3922 4097 40629 3924 4097 40630 3918 4097 40631 3924 4097 40632 3926 4097 40633 3918 4097 40634 3926 4097 40635 3928 4097 40636 3930 4097 40637 3930 4097 40638 3932 4097 40639 3926 4097 40640 3932 4097 40641 3934 4097 40642 3926 4097 40643 3934 4097 40644 3936 4097 40645 3938 4097 40646 3938 4097 40647 3940 4097 40648 3942 4097 40649 3942 4097 40650 3944 4097 40651 3946 4097 40652 3946 4097 40653 3948 4097 40654 3942 4097 40655 3948 4097 40656 3950 4097 40657 3942 4097 40658 3950 4097 40659 3952 4097 40660 3958 4097 40661 3952 4097 40662 3954 4097 40663 3958 4097 40664 3954 4097 40665 3956 4097 40666 3958 4097 40667 3958 4097 40668 3960 4097 40669 3962 4097 40670 3962 4097 40671 3964 4097 40672 3958 4097 40673 3964 4097 40674 3966 4097 40675 3958 4097 40676 3966 4097 40677 3968 4097 40678 3974 4097 40679 3968 4097 40680 3970 4097 40681 3974 4097 40682 3970 4097 40683 3972 4097 40684 3974 4097 40685 3974 4097 40686 3976 4097 40687 3982 4097 40688 3976 4097 40689 3978 4097 40690 3982 4097 40691 3978 4097 40692 3980 4097 40693 3982 4097 40694 3982 4097 40695 3984 4097 40696 3986 4097 40697 3986 4097 40698 3988 4097 40699 3982 4097 40700 3988 4097 40701 3990 4097 40702 3982 4097 40703 3990 4097 40704 3992 4097 40705 3994 4097 40706 3994 4097 40707 3996 4097 40708 3998 4097 40709 3998 4097 40710 4000 4097 40711 4002 4097 40712 4002 4097 40713 4004 4097 40714 3998 4097 40715 4004 4097 40716 4006 4097 40717 3998 4097 40718 4006 4097 40719 4008 4097 40720 4010 4097 40721 4010 4097 40722 4012 4097 40723 4014 4097 40724 4014 4097 40725 4016 4097 40726 4022 4097 40727 4016 4097 40728 4018 4097 40729 4022 4097 40730 4018 4097 40731 4020 4097 40732 4022 4097 40733 4022 4097 40734 4024 4097 40735 4026 4097 40736 4026 4097 40737 4028 4097 40738 4030 4097 40739 4030 4097 40740 4032 4097 40741 4038 4097 40742 4032 4097 40743 4034 4097 40744 4038 4097 40745 4034 4097 40746 4036 4097 40747 4038 4097 40748 4038 4097 40749 4040 4097 40750 4042 4097 40751 4042 4097 40752 4044 4097 40753 4038 4097 40754 4044 4097 40755 4046 4097 40756 4038 4097 40757 4046 4097 40758 4048 4097 40759 4054 4097 40760 4048 4097 40761 4050 4097 40762 4054 4097 40763 4050 4097 40764 4052 4097 40765 4054 4097 40766 4054 4097 40767 4056 4097 40768 4058 4097 40769 4058 4097 40770 4060 4097 40771 4054 4097 40772 4060 4097 40773 4062 4097 40774 4054 4097 40775 4062 4097 40776 4064 4097 40777 4066 4097 40778 4066 4097 40779 4068 4097 40780 4062 4097 40781 4068 4097 40782 4070 4097 40783 4062 4097 40784 4070 4097 40785 4072 4097 40786 4074 4097 40787 4074 4097 40788 4076 4097 40789 4070 4097 40790 4076 4097 40791 4078 4097 40792 4070 4097 40793 4078 4097 40794 4080 4097 40795 4082 4097 40796 4082 4097 40797 4084 4097 40798 4078 4097 40799 4084 4097 40800 4086 4097 40801 4078 4097 40802 4086 4097 40803 4088 4097 40804 4090 4097 40805 4090 4097 40806 4092 4097 40807 4094 4097 40808 4094 4097 40809 4096 4097 40810 4098 4097 40811 4098 4097 40812 4100 4097 40813 4102 4097 40814 4102 4097 40815 4104 4097 40816 4106 4097 40817 4106 4097 40818 4108 4097 40819 4102 4097 40820 4108 4097 40821 4110 4097 40822 4102 4097 40823 4110 4097 40824 4112 4097 40825 4114 4097 40826 4114 4097 40827 4116 4097 40828 4118 4097 40829 4118 4097 40830 4120 4097 40831 4122 4097 40832 4122 4097 40833 4124 4097 40834 4118 4097 40835 4124 4097 40836 4126 4097 40837 4118 4097 40838 4126 4097 40839 4128 4097 40840 4134 4097 40841 4128 4097 40842 4130 4097 40843 4134 4097 40844 4130 4097 40845 4132 4097 40846 4134 4097 40847 4134 4097 40848 4136 4097 40849 4142 4097 40850 4136 4097 40851 4138 4097 40852 4142 4097 40853 4138 4097 40854 4140 4097 40855 4142 4097 40856 4142 4097 40857 4144 4097 40858 4150 4097 40859 4144 4097 40860 4146 4097 40861 4150 4097 40862 4146 4097 40863 4148 4097 40864 4150 4097 40865 4150 4097 40866 4152 4097 40867 4154 4097 40868 4154 4097 40869 4156 4097 40870 4158 4097 40871 4158 4097 40872 4160 4097 40873 4166 4097 40874 4160 4097 40875 4162 4097 40876 4166 4097 40877 4162 4097 40878 4164 4097 40879 4166 4097 40880 4166 4097 40881 4168 4097 40882 4170 4097 40883 4170 4097 40884 4172 4097 40885 4174 4097 40886 4174 4097 40887 4176 4097 40888 4182 4097 40889 4176 4097 40890 4178 4097 40891 4182 4097 40892 4178 4097 40893 4180 4097 40894 4182 4097 40895 4182 4097 40896 4184 4097 40897 4190 4097 40898 4184 4097 40899 4186 4097 40900 4190 4097 40901 4186 4097 40902 4188 4097 40903 4190 4097 40904 4190 4097 40905 4192 4097 40906 4194 4097 40907 4194 4097 40908 4196 4097 40909 4198 4097 40910 4198 4097 40911 4200 4097 40912 4206 4097 40913 4200 4097 40914 4202 4097 40915 4206 4097 40916 4202 4097 40917 4204 4097 40918 4206 4097 40919 4206 4097 40920 4208 4097 40921 4210 4097 40922 4210 4097 40923 4212 4097 40924 4214 4097 40925 4214 4097 40926 4216 4097 40927 4222 4097 40928 4216 4097 40929 4218 4097 40930 4222 4097 40931 4218 4097 40932 4220 4097 40933 4222 4097 40934 4222 4097 40935 4224 4097 40936 4226 4097 40937 4226 4097 40938 4228 4097 40939 4222 4097 40940 4228 4097 40941 4230 4097 40942 4222 4097 40943 4230 4097 40944 4232 4097 40945 4234 4097 40946 4234 4097 40947 4236 4097 40948 4238 4097 40949 4238 4097 40950 4240 4097 40951 4246 4097 40952 4240 4097 40953 4242 4097 40954 4246 4097 40955 4242 4097 40956 4244 4097 40957 4246 4097 40958 4246 4097 40959 4248 4097 40960 4254 4097 40961 4248 4097 40962 4250 4097 40963 4254 4097 40964 4250 4097 40965 4252 4097 40966 4254 4097 40967 4254 4097 40968 4256 4097 40969 4258 4097 40970 4258 4097 40971 4260 4097 40972 4254 4097 40973 4260 4097 40974 4262 4097 40975 4254 4097 40976 4262 4097 40977 4264 4097 40978 4266 4097 40979 4266 4097 40980 4268 4097 40981 4262 4097 40982 4268 4097 40983 4270 4097 40984 4262 4097 40985 4270 4097 40986 4272 4097 40987 4274 4097 40988 4274 4097 40989 4276 4097 40990 4278 4097 40991 4278 4097 40992 4280 4097 40993 4286 4097 40994 4280 4097 40995 4282 4097 40996 4286 4097 40997 4282 4097 40998 4284 4097 40999 4286 4097 41000 4286 4097 41001 4288 4097 41002 4290 4097 41003 4290 4097 41004 4292 4097 41005 4294 4097 41006 4294 4097 41007 4296 4097 41008 4302 4097 41009 4296 4097 41010 4298 4097 41011 4302 4097 41012 4298 4097 41013 4300 4097 41014 4302 4097 41015 4302 4097 41016 4304 4097 41017 4306 4097 41018 4306 4097 41019 4308 4097 41020 4310 4097 41021 4310 4097 41022 4312 4097 41023 4314 4097 41024 4314 4097 41025 4316 4097 41026 4318 4097 41027 4318 4097 41028 4320 4097 41029 4322 4097 41030 4322 4097 41031 4324 4097 41032 4318 4097 41033 4324 4097 41034 4326 4097 41035 4318 4097 41036 4326 4097 41037 4328 4097 41038 4334 4097 41039 4328 4097 41040 4330 4097 41041 4334 4097 41042 4330 4097 41043 4332 4097 41044 4334 4097 41045 4334 4097 41046 4336 4097 41047 4342 4097 41048 4336 4097 41049 4338 4097 41050 4342 4097 41051 4338 4097 41052 4340 4097 41053 4342 4097 41054 4342 4097 41055 4344 4097 41056 4346 4097 41057 4346 4097 41058 4348 4097 41059 4350 4097 41060 4350 4097 41061 4352 4097 41062 4354 4097 41063 4354 4097 41064 4356 4097 41065 4358 4097 41066 4358 4097 41067 4360 4097 41068 4362 4097 41069 4362 4097 41070 4364 4097 41071 4358 4097 41072 4364 4097 41073 4366 4097 41074 4358 4097 41075 4366 4097 41076 4368 4097 41077 4370 4097 41078 4370 4097 41079 4372 4097 41080 4374 4097 41081 4374 4097 41082 4376 4097 41083 4378 4097 41084 4378 4097 41085 4380 4097 41086 4382 4097 41087 4382 4097 41088 4384 4097 41089 4386 4097 41090 4386 4097 41091 4388 4097 41092 4390 4097 41093 4390 4097 41094 4392 4097 41095 4398 4097 41096 4392 4097 41097 4394 4097 41098 4398 4097 41099 4394 4097 41100 4396 4097 41101 4398 4097 41102 4398 4097 41103 4400 4097 41104 4402 4097 41105 4402 4097 41106 4404 4097 41107 4406 4097 41108 4406 4097 41109 4408 4097 41110 4410 4097 41111 4410 4097 41112 4412 4097 41113 4414 4097 41114 4414 4097 41115 4416 4097 41116 4418 4097 41117 4418 4097 41118 4420 4097 41119 4422 4097 41120 4422 4097 41121 4424 4097 41122 4430 4097 41123 4424 4097 41124 4426 4097 41125 4430 4097 41126 4426 4097 41127 4428 4097 41128 4430 4097 41129 4430 4097 41130 4432 4097 41131 4434 4097 41132 4434 4097 41133 4436 4097 41134 4430 4097 41135 4436 4097 41136 4438 4097 41137 4430 4097 41138 4438 4097 41139 4440 4097 41140 4442 4097 41141 4442 4097 41142 4444 4097 41143 4446 4097 41144 4446 4097 41145 4448 4097 41146 4450 4097 41147 4450 4097 41148 4452 4097 41149 4454 4097 41150 4454 4097 41151 4456 4097 41152 4458 4097 41153 4458 4097 41154 4460 4097 41155 4462 4097 41156 4462 4097 41157 4464 4097 41158 4466 4097 41159 4466 4097 41160 4468 4097 41161 4470 4097 41162 4470 4097 41163 4472 4097 41164 4478 4097 41165 4472 4097 41166 4474 4097 41167 4478 4097 41168 4474 4097 41169 4476 4097 41170 4478 4097 41171 4478 4097 41172 4480 4097 41173 4482 4097 41174 4482 4097 41175 4484 4097 41176 4486 4097 41177 4486 4097 41178 4488 4097 41179 4490 4097 41180 4490 4097 41181 4492 4097 41182 4494 4097 41183 4494 4097 41184 4496 4097 41185 4502 4097 41186 4496 4097 41187 4498 4097 41188 4502 4097 41189 4498 4097 41190 4500 4097 41191 4502 4097 41192 4502 4097 41193 4504 4097 41194 4506 4097 41195 4506 4097 41196 4508 4097 41197 4510 4097 41198 4510 4097 41199 4512 4097 41200 4518 4097 41201 4512 4097 41202 4514 4097 41203 4518 4097 41204 4514 4097 41205 4516 4097 41206 4518 4097 41207 4518 4097 41208 4520 4097 41209 4526 4097 41210 4520 4097 41211 4522 4097 41212 4526 4097 41213 4522 4097 41214 4524 4097 41215 4526 4097 41216 4526 4097 41217 4528 4097 41218 4530 4097 41219 4530 4097 41220 4532 4097 41221 4534 4097 41222 4534 4097 41223 4536 4097 41224 4542 4097 41225 4536 4097 41226 4538 4097 41227 4542 4097 41228 4538 4097 41229 4540 4097 41230 4542 4097 41231 4542 4097 41232 4544 4097 41233 4546 4097 41234 4546 4097 41235 4548 4097 41236 4550 4097 41237 4550 4097 41238 4552 4097 41239 4558 4097 41240 4552 4097 41241 4554 4097 41242 4558 4097 41243 4554 4097 41244 4556 4097 41245 4558 4097 41246 4558 4097 41247 4560 4097 41248 4562 4097 41249 4562 4097 41250 4564 4097 41251 4558 4097 41252 4564 4097 41253 4566 4097 41254 4558 4097 41255 4566 4097 41256 4568 4097 41257 4570 4097 41258 4570 4097 41259 4572 4097 41260 4574 4097 41261 4574 4097 41262 4576 4097 41263 4578 4097 41264 4578 4097 41265 4580 4097 41266 4582 4097 41267 4582 4097 41268 4584 4097 41269 4586 4097 41270 4586 4097 41271 4588 4097 41272 4590 4097 41273 4590 4097 41274 4592 4097 41275 4594 4097 41276 4594 4097 41277 4596 4097 41278 4590 4097 41279 4596 4097 41280 4598 4097 41281 4590 4097 41282 4598 4097 41283 4600 4097 41284 4602 4097 41285 4602 4097 41286 4604 4097 41287 4606 4097 41288 4606 4097 41289 4608 4097 41290 4610 4097 41291 4610 4097 41292 4612 4097 41293 4614 4097 41294 4614 4097 41295 4616 4097 41296 4618 4097 41297 4618 4097 41298 4620 4097 41299 4614 4097 41300 4620 4097 41301 4622 4097 41302 4614 4097 41303 4622 4097 41304 4624 4097 41305 4626 4097 41306 4626 4097 41307 4628 4097 41308 4622 4097 41309 4628 4097 41310 4630 4097 41311 4622 4097 41312 4630 4097 41313 4632 4097 41314 4634 4097 41315 4634 4097 41316 4636 4097 41317 4630 4097 41318 4636 4097 41319 4638 4097 41320 4630 4097 41321 4638 4097 41322 4640 4097 41323 4646 4097 41324 4640 4097 41325 4642 4097 41326 4646 4097 41327 4642 4097 41328 4644 4097 41329 4646 4097 41330 4646 4097 41331 4648 4097 41332 4650 4097 41333 4650 4097 41334 4652 4097 41335 4646 4097 41336 4652 4097 41337 4654 4097 41338 4646 4097 41339 4654 4097 41340 4656 4097 41341 4658 4097 41342 4658 4097 41343 4660 4097 41344 4662 4097 41345 4662 4097 41346 4664 4097 41347 4666 4097 41348 4666 4097 41349 4668 4097 41350 4670 4097 41351 4670 4097 41352 4672 4097 41353 4674 4097 41354 4674 4097 41355 4676 4097 41356 4678 4097 41357 4678 4097 41358 4680 4097 41359 4682 4097 41360 4682 4097 41361 4684 4097 41362 4686 4097 41363 4686 4097 41364 4688 4097 41365 4690 4097 41366 4690 4097 41367 4692 4097 41368 4686 4097 41369 4692 4097 41370 4694 4097 41371 4686 4097 41372 4694 4097 41373 4696 4097 41374 4698 4097 41375 4698 4097 41376 4700 4097 41377 4694 4097 41378 4700 4097 41379 4702 4097 41380 4694 4097 41381 4702 4097 41382 4704 4097 41383 4706 4097 41384 4706 4097 41385 4708 4097 41386 4710 4097 41387 4710 4097 41388 4712 4097 41389 4714 4097 41390 4714 4097 41391 4716 4097 41392 4718 4097 41393 4718 4097 41394 4720 4097 41395 4722 4097 41396 4722 4097 41397 4724 4097 41398 4726 4097 41399 4726 4097 41400 4728 4097 41401 4730 4097 41402 4730 4097 41403 4732 4097 41404 4726 4097 41405 4732 4097 41406 4734 4097 41407 4726 4097 41408 4734 4097 41409 4736 4097 41410 4742 4097 41411 4736 4097 41412 4738 4097 41413 4742 4097 41414 4738 4097 41415 4740 4097 41416 4742 4097 41417 4742 4097 41418 4744 4097 41419 4746 4097 41420 4746 4097 41421 4748 4097 41422 4742 4097 41423 4748 4097 41424 4750 4097 41425 4742 4097 41426 4750 4097 41427 4752 4097 41428 4754 4097 41429 4754 4097 41430 4756 4097 41431 4758 4097 41432 4758 4097 41433 4760 4097 41434 4762 4097 41435 4762 4097 41436 4764 4097 41437 4766 4097 41438 4766 4097 41439 4768 4097 41440 4774 4097 41441 4768 4097 41442 4770 4097 41443 4774 4097 41444 4770 4097 41445 4772 4097 41446 4774 4097 41447 4774 4097 41448 4776 4097 41449 4782 4097 41450 4776 4097 41451 4778 4097 41452 4782 4097 41453 4778 4097 41454 4780 4097 41455 4782 4097 41456 4782 4097 41457 4784 4097 41458 4790 4097 41459 4784 4097 41460 4786 4097 41461 4790 4097 41462 4786 4097 41463 4788 4097 41464 4790 4097 41465 4790 4097 41466 4792 4097 41467 4794 4097 41468 4794 4097 41469 4796 4097 41470 4798 4097 41471 4798 4097 41472 4800 4097 41473 4802 4097 41474 4802 4097 41475 4804 4097 41476 4806 4097 41477 4806 4097 41478 4808 4097 41479 4810 4097 41480 4810 4097 41481 4812 4097 41482 4806 4097 41483 4812 4097 41484 4814 4097 41485 4806 4097 41486 4814 4097 41487 4816 4097 41488 4818 4097 41489 4818 4097 41490 4820 4097 41491 4822 4097 41492 4822 4097 41493 4824 4097 41494 4826 4097 41495 4826 4097 41496 4828 4097 41497 4830 4097 41498 4830 4097 41499 4832 4097 41500 4834 4097 41501 4834 4097 41502 4836 4097 41503 4838 4097 41504 4838 4097 41505 4840 4097 41506 4842 4097 41507 4842 4097 41508 4844 4097 41509 4838 4097 41510 4844 4097 41511 4846 4097 41512 4838 4097 41513 4846 4097 41514 4848 4097 41515 4854 4097 41516 4848 4097 41517 4850 4097 41518 4854 4097 41519 4850 4097 41520 4852 4097 41521 4854 4097 41522 4854 4097 41523 4856 4097 41524 4862 4097 41525 4856 4097 41526 4858 4097 41527 4862 4097 41528 4858 4097 41529 4860 4097 41530 4862 4097 41531 4862 4097 41532 4864 4097 41533 4866 4097 41534 4866 4097 41535 4868 4097 41536 4862 4097 41537 4868 4097 41538 4870 4097 41539 4862 4097 41540 4870 4097 41541 4872 4097 41542 4878 4097 41543 4872 4097 41544 4874 4097 41545 4878 4097 41546 4874 4097 41547 4876 4097 41548 4878 4097 41549 4878 4097 41550 4880 4097 41551 4882 4097 41552 4882 4097 41553 4884 4097 41554 4878 4097 41555 4884 4097 41556 4886 4097 41557 4878 4097 41558 4886 4097 41559 4888 4097 41560 4890 4097 41561 4890 4097 41562 4892 4097 41563 4894 4097 41564 4894 4097 41565 4896 4097 41566 4898 4097 41567 4898 4097 41568 4900 4097 41569 4894 4097 41570 4900 4097 41571 4902 4097 41572 4894 4097 41573 4902 4097 41574 4904 4097 41575 4906 4097 41576 4906 4097 41577 4908 4097 41578 4910 4097 41579 4910 4097 41580 4912 4097 41581 4914 4097 41582 4914 4097 41583 4916 4097 41584 4910 4097 41585 4916 4097 41586 4918 4097 41587 4910 4097 41588 4918 4097 41589 4920 4097 41590 4922 4097 41591 4922 4097 41592 4924 4097 41593 4918 4097 41594 4924 4097 41595 4926 4097 41596 4918 4097 41597 4926 4097 41598 4928 4097 41599 4930 4097 41600 4930 4097 41601 4932 4097 41602 4934 4097 41603 4934 4097 41604 4936 4097 41605 4938 4097 41606 4938 4097 41607 4940 4097 41608 4934 4097 41609 4940 4097 41610 4942 4097 41611 4934 4097 41612 4942 4097 41613 4944 4097 41614 4946 4097 41615 4946 4097 41616 4948 4097 41617 4942 4097 41618 4948 4097 41619 4950 4097 41620 4942 4097 41621 4950 4097 41622 4952 4097 41623 4954 4097 41624 4954 4097 41625 4956 4097 41626 4950 4097 41627 4956 4097 41628 4958 4097 41629 4950 4097 41630 4958 4097 41631 4960 4097 41632 4962 4097 41633 4962 4097 41634 4964 4097 41635 4966 4097 41636 4966 4097 41637 4968 4097 41638 4970 4097 41639 4970 4097 41640 4972 4097 41641 4966 4097 41642 4972 4097 41643 4974 4097 41644 4966 4097 41645 4974 4097 41646 4976 4097 41647 4978 4097 41648 4978 4097 41649 4980 4097 41650 4982 4097 41651 4982 4097 41652 4984 4097 41653 4986 4097 41654 4986 4097 41655 4988 4097 41656 4982 4097 41657 4988 4097 41658 4990 4097 41659 4982 4097 41660 4990 4097 41661 4992 4097 41662 4994 4097 41663 4994 4097 41664 4996 4097 41665 4990 4097 41666 4996 4097 41667 4998 4097 41668 4990 4097 41669 4998 4097 41670 5000 4097 41671 5002 4097 41672 5002 4097 41673 5004 4097 41674 5006 4097 41675 5006 4097 41676 5008 4097 41677 5014 4097 41678 5008 4097 41679 5010 4097 41680 5014 4097 41681 5010 4097 41682 5012 4097 41683 5014 4097 41684 5014 4097 41685 5016 4097 41686 5018 4097 41687 5018 4097 41688 5020 4097 41689 5022 4097 41690 5022 4097 41691 5024 4097 41692 5026 4097 41693 5026 4097 41694 5028 4097 41695 5030 4097 41696 5030 4097 41697 5032 4097 41698 5034 4097 41699 5034 4097 41700 5036 4097 41701 5030 4097 41702 5036 4097 41703 5038 4097 41704 5030 4097 41705 5038 4097 41706 5040 4097 41707 5042 4097 41708 5042 4097 41709 5044 4097 41710 5046 4097 41711 5046 4097 41712 5048 4097 41713 5050 4097 41714 5050 4097 41715 5052 4097 41716 5054 4097 41717 5054 4097 41718 5056 4097 41719 5058 4097 41720 5058 4097 41721 5060 4097 41722 5054 4097 41723 5060 4097 41724 5062 4097 41725 5054 4097 41726 5062 4097 41727 5064 4097 41728 5066 4097 41729 5066 4097 41730 5068 4097 41731 5070 4097 41732 5070 4097 41733 5072 4097 41734 5074 4097 41735 5074 4097 41736 5076 4097 41737 5078 4097 41738 5078 4097 41739 5080 4097 41740 5082 4097 41741 5082 4097 41742 5084 4097 41743 5078 4097 41744 5084 4097 41745 5086 4097 41746 5078 4097 41747 5086 4097 41748 5088 4097 41749 5090 4097 41750 5090 4097 41751 5092 4097 41752 5094 4097 41753 5094 4097 41754 5096 4097 41755 5102 4097 41756 5096 4097 41757 5098 4097 41758 5102 4097 41759 5098 4097 41760 5100 4097 41761 5102 4097 41762 5102 4097 41763 5104 4097 41764 5110 4097 41765 5104 4097 41766 5106 4097 41767 5110 4097 41768 5106 4097 41769 5108 4097 41770 5110 4097 41771 5110 4097 41772 5112 4097 41773 5114 4097 41774 5114 4097 41775 5116 4097 41776 5118 4097 41777 5118 4097 41778 5120 4097 41779 5122 4097 41780 5122 4097 41781 5124 4097 41782 5118 4097 41783 5124 4097 41784 5126 4097 41785 5118 4097 41786 5126 4097 41787 5128 4097 41788 5130 4097 41789 5130 4097 41790 5132 4097 41791 5134 4097 41792 5134 4097 41793 5136 4097 41794 5138 4097 41795 5138 4097 41796 5140 4097 41797 5142 4097 41798 5142 4097 41799 5144 4097 41800 5150 4097 41801 5144 4097 41802 5146 4097 41803 5150 4097 41804 5146 4097 41805 5148 4097 41806 5150 4097 41807 5150 4097 41808 5152 4097 41809 5154 4097 41810 5154 4097 41811 5156 4097 41812 5150 4097 41813 5156 4097 41814 5158 4097 41815 5150 4097 41816 5158 4097 41817 5160 4097 41818 5166 4097 41819 5160 4097 41820 5162 4097 41821 5166 4097 41822 5162 4097 41823 5164 4097 41824 5166 4097 41825 5166 4097 41826 5168 4097 41827 5170 4097 41828 5170 4097 41829 5172 4097 41830 5174 4097 41831 5174 4097 41832 5176 4097 41833 5178 4097 41834 5178 4097 41835 5180 4097 41836 5174 4097 41837 5180 4097 41838 5182 4097 41839 5174 4097 41840 5182 4097 41841 5184 4097 41842 5186 4097 41843 5186 4097 41844 5188 4097 41845 5190 4097 41846 5190 4097 41847 5192 4097 41848 5194 4097 41849 5194 4097 41850 5196 4097 41851 5198 4097 41852 5198 4097 41853 5200 4097 41854 5202 4097 41855 5202 4097 41856 5204 4097 41857 5198 4097 41858 5204 4097 41859 5206 4097 41860 5198 4097 41861 5206 4097 41862 5208 4097 41863 5210 4097 41864 5210 4097 41865 5212 4097 41866 5214 4097 41867 5214 4097 41868 5216 4097 41869 5218 4097 41870 5218 4097 41871 5220 4097 41872 5214 4097 41873 5220 4097 41874 5222 4097 41875 5214 4097 41876 5222 4097 41877 5224 4097 41878 5230 4097 41879 5224 4097 41880 5226 4097 41881 5230 4097 41882 5226 4097 41883 5228 4097 41884 5230 4097 41885 5230 4097 41886 5232 4097 41887 5238 4097 41888 5232 4097 41889 5234 4097 41890 5238 4097 41891 5234 4097 41892 5236 4097 41893 5238 4097 41894 5238 4097 41895 5240 4097 41896 5242 4097 41897 5242 4097 41898 5244 4097 41899 5238 4097 41900 5244 4097 41901 5246 4097 41902 5238 4097 41903 5246 4097 41904 5248 4097 41905 5250 4097 41906 5250 4097 41907 5252 4097 41908 5254 4097 41909 5254 4097 41910 5256 4097 41911 5262 4097 41912 5256 4097 41913 5258 4097 41914 5262 4097 41915 5258 4097 41916 5260 4097 41917 5262 4097 41918 5262 4097 41919 5264 4097 41920 5266 4097 41921 5266 4097 41922 5268 4097 41923 5262 4097 41924 5268 4097 41925 5270 4097 41926 5262 4097 41927 5270 4097 41928 5272 4097 41929 5274 4097 41930 5274 4097 41931 5276 4097 41932 5278 4097 41933 5278 4097 41934 5280 4097 41935 5282 4097 41936 5282 4097 41937 5284 4097 41938 5278 4097 41939 5284 4097 41940 5286 4097 41941 5278 4097 41942 5286 4097 41943 5288 4097 41944 5294 4097 41945 5288 4097 41946 5290 4097 41947 5294 4097 41948 5290 4097 41949 5292 4097 41950 5294 4097 41951 5294 4097 41952 5296 4097 41953 5298 4097 41954 5298 4097 41955 5300 4097 41956 5302 4097 41957 5302 4097 41958 5304 4097 41959 5310 4097 41960 5304 4097 41961 5306 4097 41962 5310 4097 41963 5306 4097 41964 5308 4097 41965 5310 4097 41966 5310 4097 41967 5312 4097 41968 5314 4097 41969 5314 4097 41970 5316 4097 41971 5318 4097 41972 5318 4097 41973 5320 4097 41974 5322 4097 41975 5322 4097 41976 5324 4097 41977 5318 4097 41978 5324 4097 41979 5326 4097 41980 5318 4097 41981 5326 4097 41982 5328 4097 41983 5330 4097 41984 5330 4097 41985 5332 4097 41986 5334 4097 41987 5334 4097 41988 5336 4097 41989 5338 4097 41990 5338 4097 41991 5340 4097 41992 5334 4097 41993 5340 4097 41994 5342 4097 41995 5334 4097 41996 5342 4097 41997 5344 4097 41998 5346 4097 41999 5346 4097 42000 5348 4097 42001 5342 4097 42002 5348 4097 42003 5350 4097 42004 5342 4097 42005 5350 4097 42006 5352 4097 42007 5354 4097 42008 5354 4097 42009 5356 4097 42010 5350 4097 42011 5356 4097 42012 5358 4097 42013 5350 4097 42014 5358 4097 42015 5360 4097 42016 5362 4097 42017 5362 4097 42018 5364 4097 42019 5366 4097 42020 5366 4097 42021 5368 4097 42022 5370 4097 42023 5370 4097 42024 5372 4097 42025 5366 4097 42026 5372 4097 42027 5374 4097 42028 5366 4097 42029 5374 4097 42030 5376 4097 42031 5382 4097 42032 5376 4097 42033 5378 4097 42034 5382 4097 42035 5378 4097 42036 5380 4097 42037 5382 4097 42038 5382 4097 42039 5384 4097 42040 5386 4097 42041 5386 4097 42042 5388 4097 42043 5390 4097 42044 5390 4097 42045 5392 4097 42046 5394 4097 42047 5394 4097 42048 5396 4097 42049 5390 4097 42050 5396 4097 42051 5398 4097 42052 5390 4097 42053 5398 4097 42054 5400 4097 42055 5402 4097 42056 5402 4097 42057 5404 4097 42058 5398 4097 42059 5404 4097 42060 5406 4097 42061 5398 4097 42062 5406 4097 42063 5408 4097 42064 5414 4097 42065 5408 4097 42066 5410 4097 42067 5414 4097 42068 5410 4097 42069 5412 4097 42070 5414 4097 42071 5414 4097 42072 5416 4097 42073 5422 4097 42074 5416 4097 42075 5418 4097 42076 5422 4097 42077 5418 4097 42078 5420 4097 42079 5422 4097 42080 5422 4097 42081 5424 4097 42082 5426 4097 42083 5426 4097 42084 5428 4097 42085 5422 4097 42086 5428 4097 42087 5430 4097 42088 5422 4097 42089 5430 4097 42090 5432 4097 42091 5434 4097 42092 5434 4097 42093 5436 4097 42094 5438 4097 42095 5438 4097 42096 5440 4097 42097 5446 4097 42098 5440 4097 42099 5442 4097 42100 5446 4097 42101 5442 4097 42102 5444 4097 42103 5446 4097 42104 5446 4097 42105 5448 4097 42106 5454 4097 42107 5448 4097 42108 5450 4097 42109 5454 4097 42110 5450 4097 42111 5452 4097 42112 5454 4097 42113 5454 4097 42114 5456 4097 42115 5458 4097 42116 5458 4097 42117 5460 4097 42118 5462 4097 42119 5462 4097 42120 5464 4097 42121 5470 4097 42122 5464 4097 42123 5466 4097 42124 5470 4097 42125 5466 4097 42126 5468 4097 42127 5470 4097 42128 5470 4097 42129 5472 4097 42130 5474 4097 42131 5474 4097 42132 5476 4097 42133 5478 4097 42134 5478 4097 42135 5480 4097 42136 5482 4097 42137 5482 4097 42138 5484 4097 42139 5486 4097 42140 5486 4097 42141 5488 4097 42142 5490 4097 42143 5490 4097 42144 5492 4097 42145 5494 4097 42146 5494 4097 42147 5496 4097 42148 5498 4097 42149 5498 4097 42150 5500 4097 42151 5502 4097 42152 5502 4097 42153 5504 4097 42154 5510 4097 42155 5504 4097 42156 5506 4097 42157 5510 4097 42158 5506 4097 42159 5508 4097 42160 5510 4097 42161 5510 4097 42162 5512 4097 42163 5514 4097 42164 5514 4097 42165 5516 4097 42166 5518 4097 42167 5518 4097 42168 5520 4097 42169 5522 4097 42170 5522 4097 42171 5524 4097 42172 5526 4097 42173 5526 4097 42174 5528 4097 42175 5530 4097 42176 5530 4097 42177 5532 4097 42178 5526 4097 42179 5532 4097 42180 5534 4097 42181 5526 4097 42182 5534 4097 42183 5536 4097 42184 5538 4097 42185 5538 4097 42186 5540 4097 42187 5534 4097 42188 5540 4097 42189 5542 4097 42190 5534 4097 42191 5542 4097 42192 5544 4097 42193 5546 4097 42194 5546 4097 42195 5548 4097 42196 5550 4097 42197 5550 4097 42198 5552 4097 42199 5554 4097 42200 5554 4097 42201 5556 4097 42202 5558 4097 42203 5558 4097 42204 5560 4097 42205 5562 4097 42206 5562 4097 42207 5564 4097 42208 5566 4097 42209 5566 4097 42210 5568 4097 42211 5570 4097 42212 5570 4097 42213 5572 4097 42214 5574 4097 42215 5574 4097 42216 5576 4097 42217 5578 4097 42218 5578 4097 42219 5580 4097 42220 5574 4097 42221 5580 4097 42222 5582 4097 42223 5574 4097 42224 5582 4097 42225 5584 4097 42226 5586 4097 42227 5586 4097 42228 5588 4097 42229 5582 4097 42230 5588 4097 42231 5590 4097 42232 5582 4097 42233 5590 4097 42234 5592 4097 42235 5594 4097 42236 5594 4097 42237 5596 4097 42238 5598 4097 42239 5598 4097 42240 5600 4097 42241 5606 4097 42242 5600 4097 42243 5602 4097 42244 5606 4097 42245 5602 4097 42246 5604 4097 42247 5606 4097 42248 5606 4097 42249 5608 4097 42250 5610 4097 42251 5610 4097 42252 5612 4097 42253 5614 4097 42254 5614 4097 42255 5616 4097 42256 5618 4097 42257 5618 4097 42258 5620 4097 42259 5614 4097 42260 5620 4097 42261 5622 4097 42262 5614 4097 42263 5622 4097 42264 5624 4097 42265 5626 4097 42266 5626 4097 42267 5628 4097 42268 5630 4097 42269 5630 4097 42270 5632 4097 42271 5638 4097 42272 5632 4097 42273 5634 4097 42274 5638 4097 42275 5634 4097 42276 5636 4097 42277 5638 4097 42278 5638 4097 42279 5640 4097 42280 5642 4097 42281 5642 4097 42282 5644 4097 42283 5638 4097 42284 5644 4097 42285 5646 4097 42286 5638 4097 42287 5646 4097 42288 5648 4097 42289 5650 4097 42290 5650 4097 42291 5652 4097 42292 5646 4097 42293 5652 4097 42294 5654 4097 42295 5646 4097 42296 5654 4097 42297 5656 4097 42298 5658 4097 42299 5658 4097 42300 5660 4097 42301 5662 4097 42302 5662 4097 42303 5664 4097 42304 5666 4097 42305 5666 4097 42306 5668 4097 42307 5662 4097 42308 5668 4097 42309 5670 4097 42310 5662 4097 42311 5670 4097 42312 5672 4097 42313 5674 4097 42314 5674 4097 42315 5676 4097 42316 5670 4097 42317 5676 4097 42318 5678 4097 42319 5670 4097 42320 5678 4097 42321 5680 4097 42322 5682 4097 42323 5682 4097 42324 5684 4097 42325 5686 4097 42326 5686 4097 42327 5688 4097 42328 5690 4097 42329 5690 4097 42330 5692 4097 42331 5686 4097 42332 5692 4097 42333 5694 4097 42334 5686 4097 42335 5694 4097 42336 5696 4097 42337 5698 4097 42338 5698 4097 42339 5700 4097 42340 5694 4097 42341 5700 4097 42342 5702 4097 42343 5694 4097 42344 5702 4097 42345 5704 4097 42346 5710 4097 42347 5704 4097 42348 5706 4097 42349 5710 4097 42350 5706 4097 42351 5708 4097 42352 5710 4097 42353 5710 4097 42354 5712 4097 42355 5714 4097 42356 5714 4097 42357 5716 4097 42358 5710 4097 42359 5716 4097 42360 5718 4097 42361 5710 4097 42362 5718 4097 42363 5720 4097 42364 5722 4097 42365 5722 4097 42366 5724 4097 42367 5726 4097 42368 5726 4097 42369 5728 4097 42370 5730 4097 42371 5730 4097 42372 5732 4097 42373 5734 4097 42374 5734 4097 42375 5736 4097 42376 5738 4097 42377 5738 4097 42378 5740 4097 42379 5734 4097 42380 5740 4097 42381 5742 4097 42382 5734 4097 42383 5742 4097 42384 5744 4097 42385 5750 4097 42386 5744 4097 42387 5746 4097 42388 5750 4097 42389 5746 4097 42390 5748 4097 42391 5750 4097 42392 5750 4097 42393 5752 4097 42394 5754 4097 42395 5754 4097 42396 5756 4097 42397 5758 4097 42398 5758 4097 42399 5760 4097 42400 5762 4097 42401 5762 4097 42402 5764 4097 42403 5766 4097 42404 5766 4097 42405 5768 4097 42406 5774 4097 42407 5768 4097 42408 5770 4097 42409 5774 4097 42410 5770 4097 42411 5772 4097 42412 5774 4097 42413 5774 4097 42414 5776 4097 42415 5778 4097 42416 5778 4097 42417 5780 4097 42418 5774 4097 42419 5780 4097 42420 5782 4097 42421 5774 4097 42422 5782 4097 42423 5784 4097 42424 5786 4097 42425 5786 4097 42426 5788 4097 42427 5782 4097 42428 5788 4097 42429 5790 4097 42430 5782 4097 42431 5790 4097 42432 5792 4097 42433 5794 4097 42434 5794 4097 42435 5796 4097 42436 5790 4097 42437 5796 4097 42438 5798 4097 42439 5790 4097 42440 5798 4097 42441 5800 4097 42442 5802 4097 42443 5802 4097 42444 5804 4097 42445 5798 4097 42446 5804 4097 42447 5806 4097 42448 5798 4097 42449 5806 4097 42450 5808 4097 42451 5810 4097 42452 5810 4097 42453 5812 4097 42454 5814 4097 42455 5814 4097 42456 5816 4097 42457 5822 4097 42458 5816 4097 42459 5818 4097 42460 5822 4097 42461 5818 4097 42462 5820 4097 42463 5822 4097 42464 5822 4097 42465 5824 4097 42466 5826 4097 42467 5826 4097 42468 5828 4097 42469 5830 4097 42470 5830 4097 42471 5832 4097 42472 5834 4097 42473 5834 4097 42474 5836 4097 42475 5838 4097 42476 5838 4097 42477 5840 4097 42478 5842 4097 42479 5842 4097 42480 5844 4097 42481 5846 4097 42482 5846 4097 42483 5848 4097 42484 5854 4097 42485 5848 4097 42486 5850 4097 42487 5854 4097 42488 5850 4097 42489 5852 4097 42490 5854 4097 42491 5854 4097 42492 5856 4097 42493 5862 4097 42494 5856 4097 42495 5858 4097 42496 5862 4097 42497 5858 4097 42498 5860 4097 42499 5862 4097 42500 5862 4097 42501 5864 4097 42502 5866 4097 42503 5866 4097 42504 5868 4097 42505 5870 4097 42506 5870 4097 42507 5872 4097 42508 5874 4097 42509 5874 4097 42510 5876 4097 42511 5870 4097 42512 5876 4097 42513 5878 4097 42514 5870 4097 42515 5878 4097 42516 5880 4097 42517 5882 4097 42518 5882 4097 42519 5884 4097 42520 5878 4097 42521 5884 4097 42522 5886 4097 42523 5878 4097 42524 5886 4097 42525 5888 4097 42526 5894 4097 42527 5888 4097 42528 5890 4097 42529 5894 4097 42530 5890 4097 42531 5892 4097 42532 5894 4097 42533 5894 4097 42534 5896 4097 42535 5898 4097 42536 5898 4097 42537 5900 4097 42538 5902 4097 42539 5902 4097 42540 5904 4097 42541 5906 4097 42542 5906 4097 42543 5908 4097 42544 5910 4097 42545 5910 4097 42546 5912 4097 42547 5914 4097 42548 5914 4097 42549 5916 4097 42550 5918 4097 42551 5918 4097 42552 5920 4097 42553 5922 4097 42554 5922 4097 42555 5924 4097 42556 5926 4097 42557 5926 4097 42558 5928 4097 42559 5930 4097 42560 5930 4097 42561 5932 4097 42562 5926 4097 42563 5932 4097 42564 5934 4097 42565 5926 4097 42566 5934 4097 42567 5936 4097 42568 5938 4097 42569 5938 4097 42570 5940 4097 42571 5942 4097 42572 5942 4097 42573 5944 4097 42574 5946 4097 42575 5946 4097 42576 5948 4097 42577 5942 4097 42578 5948 4097 42579 5950 4097 42580 5942 4097 42581 5950 4097 42582 5952 4097 42583 5954 4097 42584 5954 4097 42585 5956 4097 42586 5950 4097 42587 5956 4097 42588 5958 4097 42589 5950 4097 42590 5958 4097 42591 5960 4097 42592 5966 4097 42593 5960 4097 42594 5962 4097 42595 5966 4097 42596 5962 4097 42597 5964 4097 42598 5966 4097 42599 5966 4097 42600 5968 4097 42601 5970 4097 42602 5970 4097 42603 5972 4097 42604 5966 4097 42605 5972 4097 42606 5974 4097 42607 5966 4097 42608 5974 4097 42609 5976 4097 42610 5978 4097 42611 5978 4097 42612 5980 4097 42613 5974 4097 42614 5980 4097 42615 5982 4097 42616 5974 4097 42617 5982 4097 42618 5984 4097 42619 5986 4097 42620 5986 4097 42621 5988 4097 42622 5990 4097 42623 5990 4097 42624 5992 4097 42625 5994 4097 42626 5994 4097 42627 5996 4097 42628 5990 4097 42629 5996 4097 42630 5998 4097 42631 5990 4097 42632 5998 4097 42633 6000 4097 42634 6006 4097 42635 6000 4097 42636 6002 4097 42637 6006 4097 42638 6002 4097 42639 6004 4097 42640 6006 4097 42641 6006 4097 42642 6008 4097 42643 6010 4097 42644 6010 4097 42645 6012 4097 42646 6006 4097 42647 6012 4097 42648 6014 4097 42649 6006 4097 42650 6014 4097 42651 6016 4097 42652 6022 4097 42653 6016 4097 42654 6018 4097 42655 6022 4097 42656 6018 4097 42657 6020 4097 42658 6022 4097 42659 6022 4097 42660 6024 4097 42661 6030 4097 42662 6024 4097 42663 6026 4097 42664 6030 4097 42665 6026 4097 42666 6028 4097 42667 6030 4097 42668 6030 4097 42669 6032 4097 42670 6034 4097 42671 6034 4097 42672 6036 4097 42673 6030 4097 42674 6036 4097 42675 6038 4097 42676 6030 4097 42677 6038 4097 42678 6040 4097 42679 6042 4097 42680 6042 4097 42681 6044 4097 42682 6046 4097 42683 6046 4097 42684 6048 4097 42685 6050 4097 42686 6050 4097 42687 6052 4097 42688 6046 4097 42689 6052 4097 42690 6054 4097 42691 6046 4097 42692 6054 4097 42693 6056 4097 42694 6058 4097 42695 6058 4097 42696 6060 4097 42697 6062 4097 42698 6062 4097 42699 6064 4097 42700 6070 4097 42701 6064 4097 42702 6066 4097 42703 6070 4097 42704 6066 4097 42705 6068 4097 42706 6070 4097 42707 6070 4097 42708 6072 4097 42709 6074 4097 42710 6074 4097 42711 6076 4097 42712 6078 4097 42713 6078 4097 42714 6080 4097 42715 6086 4097 42716 6080 4097 42717 6082 4097 42718 6086 4097 42719 6082 4097 42720 6084 4097 42721 6086 4097 42722 6086 4097 42723 6088 4097 42724 6090 4097 42725 6090 4097 42726 6092 4097 42727 6086 4097 42728 6092 4097 42729 6094 4097 42730 6086 4097 42731 6094 4097 42732 6096 4097 42733 6102 4097 42734 6096 4097 42735 6098 4097 42736 6102 4097 42737 6098 4097 42738 6100 4097 42739 6102 4097 42740 6102 4097 42741 6104 4097 42742 6106 4097 42743 6106 4097 42744 6108 4097 42745 6102 4097 42746 6108 4097 42747 6110 4097 42748 6102 4097 42749 6110 4097 42750 6112 4097 42751 6114 4097 42752 6114 4097 42753 6116 4097 42754 6110 4097 42755 6116 4097 42756 6118 4097 42757 6110 4097 42758 6118 4097 42759 6120 4097 42760 6122 4097 42761 6122 4097 42762 6124 4097 42763 6118 4097 42764 6124 4097 42765 6126 4097 42766 6118 4097 42767 6126 4097 42768 6128 4097 42769 6130 4097 42770 6130 4097 42771 6132 4097 42772 6126 4097 42773 6132 4097 42774 6134 4097 42775 6126 4097 42776 6134 4097 42777 6136 4097 42778 6138 4097 42779 6138 4097 42780 6140 4097 42781 6142 4097 42782 6142 4097 42783 6144 4097 42784 6146 4097 42785 6146 4097 42786 6148 4097 42787 6150 4097 42788 6150 4097 42789 6152 4097 42790 6154 4097 42791 6154 4097 42792 6156 4097 42793 6150 4097 42794 6156 4097 42795 6158 4097 42796 6150 4097 42797 6158 4097 42798 6160 4097 42799 6162 4097 42800 6162 4097 42801 6164 4097 42802 6166 4097 42803 6166 4097 42804 6168 4097 42805 6170 4097 42806 6170 4097 42807 6172 4097 42808 6166 4097 42809 6172 4097 42810 6174 4097 42811 6166 4097 42812 6174 4097 42813 6176 4097 42814 6182 4097 42815 6176 4097 42816 6178 4097 42817 6182 4097 42818 6178 4097 42819 6180 4097 42820 6182 4097 42821 6182 4097 42822 6184 4097 42823 6190 4097 42824 6184 4097 42825 6186 4097 42826 6190 4097 42827 6186 4097 42828 6188 4097 42829 6190 4097 42830 6190 4097 42831 6192 4097 42832 6198 4097 42833 6192 4097 42834 6194 4097 42835 6198 4097 42836 6194 4097 42837 6196 4097 42838 6198 4097 42839 6198 4097 42840 6200 4097 42841 6202 4097 42842 6202 4097 42843 6204 4097 42844 6206 4097 42845 6206 4097 42846 6208 4097 42847 6214 4097 42848 6208 4097 42849 6210 4097 42850 6214 4097 42851 6210 4097 42852 6212 4097 42853 6214 4097 42854 6214 4097 42855 6216 4097 42856 6218 4097 42857 6218 4097 42858 6220 4097 42859 6222 4097 42860 6222 4097 42861 6224 4097 42862 6230 4097 42863 6224 4097 42864 6226 4097 42865 6230 4097 42866 6226 4097 42867 6228 4097 42868 6230 4097 42869 6230 4097 42870 6232 4097 42871 6238 4097 42872 6232 4097 42873 6234 4097 42874 6238 4097 42875 6234 4097 42876 6236 4097 42877 6238 4097 42878 6238 4097 42879 6240 4097 42880 6242 4097 42881 6242 4097 42882 6244 4097 42883 6246 4097 42884 6246 4097 42885 6248 4097 42886 6254 4097 42887 6248 4097 42888 6250 4097 42889 6254 4097 42890 6250 4097 42891 6252 4097 42892 6254 4097 42893 6254 4097 42894 6256 4097 42895 6258 4097 42896 6258 4097 42897 6260 4097 42898 6262 4097 42899 6262 4097 42900 6264 4097 42901 6270 4097 42902 6264 4097 42903 6266 4097 42904 6270 4097 42905 6266 4097 42906 6268 4097 42907 6270 4097 42908 6270 4097 42909 6272 4097 42910 6274 4097 42911 6274 4097 42912 6276 4097 42913 6270 4097 42914 6276 4097 42915 6278 4097 42916 6270 4097 42917 6278 4097 42918 6280 4097 42919 6282 4097 42920 6282 4097 42921 6284 4097 42922 6286 4097 42923 6286 4097 42924 6288 4097 42925 6294 4097 42926 6288 4097 42927 6290 4097 42928 6294 4097 42929 6290 4097 42930 6292 4097 42931 6294 4097 42932 6294 4097 42933 6296 4097 42934 6302 4097 42935 6296 4097 42936 6298 4097 42937 6302 4097 42938 6298 4097 42939 6300 4097 42940 6302 4097 42941 6302 4097 42942 6304 4097 42943 6306 4097 42944 6306 4097 42945 6308 4097 42946 6302 4097 42947 6308 4097 42948 6310 4097 42949 6302 4097 42950 6310 4097 42951 6312 4097 42952 6314 4097 42953 6314 4097 42954 6316 4097 42955 6310 4097 42956 6316 4097 42957 6318 4097 42958 6310 4097 42959 6318 4097 42960 6320 4097 42961 6322 4097 42962 6322 4097 42963 6324 4097 42964 6326 4097 42965 6326 4097 42966 6328 4097 42967 6334 4097 42968 6328 4097 42969 6330 4097 42970 6334 4097 42971 6330 4097 42972 6332 4097 42973 6334 4097 42974 6334 4097 42975 6336 4097 42976 6338 4097 42977 6338 4097 42978 6340 4097 42979 6342 4097 42980 6342 4097 42981 6344 4097 42982 6350 4097 42983 6344 4097 42984 6346 4097 42985 6350 4097 42986 6346 4097 42987 6348 4097 42988 6350 4097 42989 6350 4097 42990 6352 4097 42991 6354 4097 42992 6354 4097 42993 6356 4097 42994 6358 4097 42995 6358 4097 42996 6360 4097 42997 6362 4097 42998 6362 4097 42999 6364 4097 43000 6366 4097 43001 6366 4097 43002 6368 4097 43003 6370 4097 43004 6370 4097 43005 6372 4097 43006 6366 4097 43007 6372 4097 43008 6374 4097 43009 6366 4097 43010 6374 4097 43011 6376 4097 43012 6382 4097 43013 6376 4097 43014 6378 4097 43015 6382 4097 43016 6378 4097 43017 6380 4097 43018 6382 4097 43019 6382 4097 43020 6384 4097 43021 6390 4097 43022 6384 4097 43023 6386 4097 43024 6390 4097 43025 6386 4097 43026 6388 4097 43027 6390 4097 43028 6390 4097 43029 6392 4097 43030 6394 4097 43031 6394 4097 43032 6396 4097 43033 6398 4097 43034 6398 4097 43035 6400 4097 43036 6402 4097 43037 6402 4097 43038 6404 4097 43039 6406 4097 43040 6406 4097 43041 6408 4097 43042 6410 4097 43043 6410 4097 43044 6412 4097 43045 6406 4097 43046 6412 4097 43047 6414 4097 43048 6406 4097 43049 6414 4097 43050 6416 4097 43051 6418 4097 43052 6418 4097 43053 6420 4097 43054 6422 4097 43055 6422 4097 43056 6424 4097 43057 6426 4097 43058 6426 4097 43059 6428 4097 43060 6430 4097 43061 6430 4097 43062 6432 4097 43063 6434 4097 43064 6434 4097 43065 6436 4097 43066 6438 4097 43067 6438 4097 43068 6440 4097 43069 6446 4097 43070 6440 4097 43071 6442 4097 43072 6446 4097 43073 6442 4097 43074 6444 4097 43075 6446 4097 43076 6446 4097 43077 6448 4097 43078 6450 4097 43079 6450 4097 43080 6452 4097 43081 6454 4097 43082 6454 4097 43083 6456 4097 43084 6458 4097 43085 6458 4097 43086 6460 4097 43087 6462 4097 43088 6462 4097 43089 6464 4097 43090 6466 4097 43091 6466 4097 43092 6468 4097 43093 6470 4097 43094 6470 4097 43095 6472 4097 43096 6478 4097 43097 6472 4097 43098 6474 4097 43099 6478 4097 43100 6474 4097 43101 6476 4097 43102 6478 4097 43103 6478 4097 43104 6480 4097 43105 6482 4097 43106 6482 4097 43107 6484 4097 43108 6478 4097 43109 6484 4097 43110 6486 4097 43111 6478 4097 43112 6486 4097 43113 6488 4097 43114 6490 4097 43115 6490 4097 43116 6492 4097 43117 6494 4097 43118 6494 4097 43119 6496 4097 43120 6498 4097 43121 6498 4097 43122 6500 4097 43123 6502 4097 43124 6502 4097 43125 6504 4097 43126 6506 4097 43127 6506 4097 43128 6508 4097 43129 6510 4097 43130 6510 4097 43131 6512 4097 43132 6514 4097 43133 6514 4097 43134 6516 4097 43135 6518 4097 43136 6518 4097 43137 6520 4097 43138 6526 4097 43139 6520 4097 43140 6522 4097 43141 6526 4097 43142 6522 4097 43143 6524 4097 43144 6526 4097 43145 6526 4097 43146 6528 4097 43147 6530 4097 43148 6530 4097 43149 6532 4097 43150 6534 4097 43151 6534 4097 43152 6536 4097 43153 6538 4097 43154 6538 4097 43155 6540 4097 43156 6542 4097 43157 6542 4097 43158 6544 4097 43159 6550 4097 43160 6544 4097 43161 6546 4097 43162 6550 4097 43163 6546 4097 43164 6548 4097 43165 6550 4097 43166 6550 4097 43167 6552 4097 43168 6554 4097 43169 6554 4097 43170 6556 4097 43171 6558 4097 43172 6558 4097 43173 6560 4097 43174 6566 4097 43175 6560 4097 43176 6562 4097 43177 6566 4097 43178 6562 4097 43179 6564 4097 43180 6566 4097 43181 6566 4097 43182 6568 4097 43183 6574 4097 43184 6568 4097 43185 6570 4097 43186 6574 4097 43187 6570 4097 43188 6572 4097 43189 6574 4097 43190 6574 4097 43191 6576 4097 43192 6578 4097 43193 6578 4097 43194 6580 4097 43195 6582 4097 43196 6582 4097 43197 6584 4097 43198 6590 4097 43199 6584 4097 43200 6586 4097 43201 6590 4097 43202 6586 4097 43203 6588 4097 43204 6590 4097 43205 6590 4097 43206 6592 4097 43207 6594 4097 43208 6594 4097 43209 6596 4097 43210 6598 4097 43211 6598 4097 43212 6600 4097 43213 6606 4097 43214 6600 4097 43215 6602 4097 43216 6606 4097 43217 6602 4097 43218 6604 4097 43219 6606 4097 43220 6606 4097 43221 6608 4097 43222 6610 4097 43223 6610 4097 43224 6612 4097 43225 6606 4097 43226 6612 4097 43227 6614 4097 43228 6606 4097 43229 6614 4097 43230 6616 4097 43231 6618 4097 43232 6618 4097 43233 6620 4097 43234 6622 4097 43235 6622 4097 43236 6624 4097 43237 6626 4097 43238 6626 4097 43239 6628 4097 43240 6630 4097 43241 6630 4097 43242 6632 4097 43243 6634 4097 43244 6634 4097 43245 6636 4097 43246 6638 4097 43247 6638 4097 43248 6640 4097 43249 6642 4097 43250 6642 4097 43251 6644 4097 43252 6638 4097 43253 6644 4097 43254 6646 4097 43255 6638 4097 43256 6646 4097 43257 6648 4097 43258 6650 4097 43259 6650 4097 43260 6652 4097 43261 6654 4097 43262 6654 4097 43263 6656 4097 43264 6658 4097 43265 6658 4097 43266 6660 4097 43267 6662 4097 43268 6662 4097 43269 6664 4097 43270 6666 4097 43271 6666 4097 43272 6668 4097 43273 6662 4097 43274 6668 4097 43275 6670 4097 43276 6662 4097 43277 6670 4097 43278 6672 4097 43279 6674 4097 43280 6674 4097 43281 6676 4097 43282 6670 4097 43283 6676 4097 43284 6678 4097 43285 6670 4097 43286 6678 4097 43287 6680 4097 43288 6682 4097 43289 6682 4097 43290 6684 4097 43291 6678 4097 43292 6684 4097 43293 6686 4097 43294 6678 4097 43295 6686 4097 43296 6688 4097 43297 6694 4097 43298 6688 4097 43299 6690 4097 43300 6694 4097 43301 6690 4097 43302 6692 4097 43303 6694 4097 43304 6694 4097 43305 6696 4097 43306 6698 4097 43307 6698 4097 43308 6700 4097 43309 6694 4097 43310 6700 4097 43311 6702 4097 43312 6694 4097 43313 6702 4097 43314 6704 4097 43315 6706 4097 43316 6706 4097 43317 6708 4097 43318 6710 4097 43319 6710 4097 43320 6712 4097 43321 6714 4097 43322 6714 4097 43323 6716 4097 43324 6718 4097 43325 6718 4097 43326 6720 4097 43327 6722 4097 43328 6722 4097 43329 6724 4097 43330 6726 4097 43331 6726 4097 43332 6728 4097 43333 6730 4097 43334 6730 4097 43335 6732 4097 43336 6734 4097 43337 6734 4097 43338 6736 4097 43339 6738 4097 43340 6738 4097 43341 6740 4097 43342 6734 4097 43343 6740 4097 43344 6742 4097 43345 6734 4097 43346 6742 4097 43347 6744 4097 43348 6746 4097 43349 6746 4097 43350 6748 4097 43351 6742 4097 43352 6748 4097 43353 6750 4097 43354 6742 4097 43355 6750 4097 43356 6752 4097 43357 6754 4097 43358 6754 4097 43359 6756 4097 43360 6758 4097 43361 6758 4097 43362 6760 4097 43363 6762 4097 43364 6762 4097 43365 6764 4097 43366 6766 4097 43367 6766 4097 43368 6768 4097 43369 6770 4097 43370 6770 4097 43371 6772 4097 43372 6774 4097 43373 6774 4097 43374 6776 4097 43375 6778 4097 43376 6778 4097 43377 6780 4097 43378 6774 4097 43379 6780 4097 43380 6782 4097 43381 6774 4097 43382 6782 4097 43383 6784 4097 43384 6790 4097 43385 6784 4097 43386 6786 4097 43387 6790 4097 43388 6786 4097 43389 6788 4097 43390 6790 4097 43391 6790 4097 43392 6792 4097 43393 6794 4097 43394 6794 4097 43395 6796 4097 43396 6790 4097 43397 6796 4097 43398 6798 4097 43399 6790 4097 43400 6798 4097 43401 6800 4097 43402 6802 4097 43403 6802 4097 43404 6804 4097 43405 6806 4097 43406 6806 4097 43407 6808 4097 43408 6810 4097 43409 6810 4097 43410 6812 4097 43411 6814 4097 43412 6814 4097 43413 6816 4097 43414 6822 4097 43415 6816 4097 43416 6818 4097 43417 6822 4097 43418 6818 4097 43419 6820 4097 43420 6822 4097 43421 6822 4097 43422 6824 4097 43423 6830 4097 43424 6824 4097 43425 6826 4097 43426 6830 4097 43427 6826 4097 43428 6828 4097 43429 6830 4097 43430 6830 4097 43431 6832 4097 43432 6838 4097 43433 6832 4097 43434 6834 4097 43435 6838 4097 43436 6834 4097 43437 6836 4097 43438 6838 4097 43439 6838 4097 43440 6840 4097 43441 6842 4097 43442 6842 4097 43443 6844 4097 43444 6846 4097 43445 6846 4097 43446 6848 4097 43447 6850 4097 43448 6850 4097 43449 6852 4097 43450 6854 4097 43451 6854 4097 43452 6856 4097 43453 6858 4097 43454 6858 4097 43455 6860 4097 43456 6854 4097 43457 6860 4097 43458 6862 4097 43459 6854 4097 43460 6862 4097 43461 6864 4097 43462 6866 4097 43463 6866 4097 43464 6868 4097 43465 6870 4097 43466 6870 4097 43467 6872 4097 43468 6874 4097 43469 6874 4097 43470 6876 4097 43471 6878 4097 43472 6878 4097 43473 6880 4097 43474 6882 4097 43475 6882 4097 43476 6884 4097 43477 6886 4097 43478 6886 4097 43479 6888 4097 43480 6890 4097 43481 6890 4097 43482 6892 4097 43483 6886 4097 43484 6892 4097 43485 6894 4097 43486 6886 4097 43487 6894 4097 43488 6896 4097 43489 6902 4097 43490 6896 4097 43491 6898 4097 43492 6902 4097 43493 6898 4097 43494 6900 4097 43495 6902 4097 43496 6902 4097 43497 6904 4097 43498 6910 4097 43499 6904 4097 43500 6906 4097 43501 6910 4097 43502 6906 4097 43503 6908 4097 43504 6910 4097 43505 6910 4097 43506 6912 4097 43507 6914 4097 43508 6914 4097 43509 6916 4097 43510 6910 4097 43511 6916 4097 43512 6918 4097 43513 6910 4097 43514 6918 4097 43515 6920 4097 43516 6926 4097 43517 6920 4097 43518 6922 4097 43519 6926 4097 43520 6922 4097 43521 6924 4097 43522 6926 4097 43523 6926 4097 43524 6928 4097 43525 6930 4097 43526 6930 4097 43527 6932 4097 43528 6926 4097 43529 6932 4097 43530 6934 4097 43531 6926 4097 43532 6934 4097 43533 6936 4097 43534 6938 4097 43535 6938 4097 43536 6940 4097 43537 6942 4097 43538 6942 4097 43539 6944 4097 43540 6946 4097 43541 6946 4097 43542 6948 4097 43543 6942 4097 43544 6948 4097 43545 6950 4097 43546 6942 4097 43547 6950 4097 43548 6952 4097 43549 6954 4097 43550 6954 4097 43551 6956 4097 43552 6958 4097 43553 6958 4097 43554 6960 4097 43555 6962 4097 43556 6962 4097 43557 6964 4097 43558 6958 4097 43559 6964 4097 43560 6966 4097 43561 6958 4097 43562 6966 4097 43563 6968 4097 43564 6970 4097 43565 6970 4097 43566 6972 4097 43567 6966 4097 43568 6972 4097 43569 6974 4097 43570 6966 4097 43571 6974 4097 43572 6976 4097 43573 6978 4097 43574 6978 4097 43575 6980 4097 43576 6982 4097 43577 6982 4097 43578 6984 4097 43579 6986 4097 43580 6986 4097 43581 6988 4097 43582 6982 4097 43583 6988 4097 43584 6990 4097 43585 6982 4097 43586 6990 4097 43587 6992 4097 43588 6994 4097 43589 6994 4097 43590 6996 4097 43591 6990 4097 43592 6996 4097 43593 6998 4097 43594 6990 4097 43595 6998 4097 43596 7000 4097 43597 7002 4097 43598 7002 4097 43599 7004 4097 43600 6998 4097 43601 7004 4097 43602 7006 4097 43603 6998 4097 43604 7006 4097 43605 7008 4097 43606 7010 4097 43607 7010 4097 43608 7012 4097 43609 7014 4097 43610 7014 4097 43611 7016 4097 43612 7018 4097 43613 7018 4097 43614 7020 4097 43615 7014 4097 43616 7020 4097 43617 7022 4097 43618 7014 4097 43619 7022 4097 43620 7024 4097 43621 7026 4097 43622 7026 4097 43623 7028 4097 43624 7030 4097 43625 7030 4097 43626 7032 4097 43627 7034 4097 43628 7034 4097 43629 7036 4097 43630 7030 4097 43631 7036 4097 43632 7038 4097 43633 7030 4097 43634 7038 4097 43635 7040 4097 43636 7042 4097 43637 7042 4097 43638 7044 4097 43639 7038 4097 43640 7044 4097 43641 7046 4097 43642 7038 4097 43643 7046 4097 43644 7048 4097 43645 7050 4097 43646 7050 4097 43647 7052 4097 43648 7054 4097 43649 7054 4097 43650 7056 4097 43651 7062 4097 43652 7056 4097 43653 7058 4097 43654 7062 4097 43655 7058 4097 43656 7060 4097 43657 7062 4097 43658 7062 4097 43659 7064 4097 43660 7066 4097 43661 7066 4097 43662 7068 4097 43663 7070 4097 43664 7070 4097 43665 7072 4097 43666 7074 4097 43667 7074 4097 43668 7076 4097 43669 7078 4097 43670 7078 4097 43671 7080 4097 43672 7082 4097 43673 7082 4097 43674 7084 4097 43675 7078 4097 43676 7084 4097 43677 7086 4097 43678 7078 4097 43679 7086 4097 43680 7088 4097 43681 7090 4097 43682 7090 4097 43683 7092 4097 43684 7094 4097 43685 7094 4097 43686 7096 4097 43687 7098 4097 43688 7098 4097 43689 7100 4097 43690 7102 4097 43691 7102 4097 43692 7104 4097 43693 7106 4097 43694 7106 4097 43695 7108 4097 43696 7102 4097 43697 7108 4097 43698 7110 4097 43699 7102 4097 43700 7110 4097 43701 7112 4097 43702 7114 4097 43703 7114 4097 43704 7116 4097 43705 7118 4097 43706 7118 4097 43707 7120 4097 43708 7122 4097 43709 7122 4097 43710 7124 4097 43711 7126 4097 43712 7126 4097 43713 7128 4097 43714 7130 4097 43715 7130 4097 43716 7132 4097 43717 7126 4097 43718 7132 4097 43719 7134 4097 43720 7126 4097 43721 7134 4097 43722 7136 4097 43723 7138 4097 43724 7138 4097 43725 7140 4097 43726 7142 4097 43727 7142 4097 43728 7144 4097 43729 7150 4097 43730 7144 4097 43731 7146 4097 43732 7150 4097 43733 7146 4097 43734 7148 4097 43735 7150 4097 43736 7150 4097 43737 7152 4097 43738 7158 4097 43739 7152 4097 43740 7154 4097 43741 7158 4097 43742 7154 4097 43743 7156 4097 43744 7158 4097 43745 7158 4097 43746 7160 4097 43747 7162 4097 43748 7162 4097 43749 7164 4097 43750 7166 4097 43751 7166 4097 43752 7168 4097 43753 7170 4097 43754 7170 4097 43755 7172 4097 43756 7166 4097 43757 7172 4097 43758 7174 4097 43759 7166 4097 43760 7174 4097 43761 7176 4097 43762 7178 4097 43763 7178 4097 43764 7180 4097 43765 7182 4097 43766 7182 4097 43767 7184 4097 43768 7186 4097 43769 7186 4097 43770 7188 4097 43771 7190 4097 43772 7190 4097 43773 7192 4097 43774 7198 4097 43775 7192 4097 43776 7194 4097 43777 7198 4097 43778 7194 4097 43779 7196 4097 43780 7198 4097 43781 7198 4097 43782 7200 4097 43783 7202 4097 43784 7202 4097 43785 7204 4097 43786 7198 4097 43787 7204 4097 43788 7206 4097 43789 7198 4097 43790 7206 4097 43791 7208 4097 43792 7214 4097 43793 7208 4097 43794 7210 4097 43795 7214 4097 43796 7210 4097 43797 7212 4097 43798 7214 4097 43799 7214 4097 43800 7216 4097 43801 7218 4097 43802 7218 4097 43803 7220 4097 43804 7222 4097 43805 7222 4097 43806 7224 4097 43807 7226 4097 43808 7226 4097 43809 7228 4097 43810 7222 4097 43811 7228 4097 43812 7230 4097 43813 7222 4097 43814 7230 4097 43815 7232 4097 43816 7234 4097 43817 7234 4097 43818 7236 4097 43819 7238 4097 43820 7238 4097 43821 7240 4097 43822 7242 4097 43823 7242 4097 43824 7244 4097 43825 7246 4097 43826 7246 4097 43827 7248 4097 43828 7250 4097 43829 7250 4097 43830 7252 4097 43831 7246 4097 43832 7252 4097 43833 7254 4097 43834 7246 4097 43835 7254 4097 43836 7256 4097 43837 7258 4097 43838 7258 4097 43839 7260 4097 43840 7262 4097 43841 7262 4097 43842 7264 4097 43843 7266 4097 43844 7266 4097 43845 7268 4097 43846 7262 4097 43847 7268 4097 43848 7270 4097 43849 7262 4097 43850 7270 4097 43851 7272 4097 43852 7278 4097 43853 7272 4097 43854 7274 4097 43855 7278 4097 43856 7274 4097 43857 7276 4097 43858 7278 4097 43859 7278 4097 43860 7280 4097 43861 7286 4097 43862 7280 4097 43863 7282 4097 43864 7286 4097 43865 7282 4097 43866 7284 4097 43867 7286 4097 43868 7286 4097 43869 7288 4097 43870 7290 4097 43871 7290 4097 43872 7292 4097 43873 7286 4097 43874 7292 4097 43875 7294 4097 43876 7286 4097 43877 7294 4097 43878 7296 4097 43879 7298 4097 43880 7298 4097 43881 7300 4097 43882 7302 4097 43883 7302 4097 43884 7304 4097 43885 7310 4097 43886 7304 4097 43887 7306 4097 43888 7310 4097 43889 7306 4097 43890 7308 4097 43891 7310 4097 43892 7310 4097 43893 7312 4097 43894 7314 4097 43895 7314 4097 43896 7316 4097 43897 7310 4097 43898 7316 4097 43899 7318 4097 43900 7310 4097 43901 7318 4097 43902 7320 4097 43903 7322 4097 43904 7322 4097 43905 7324 4097 43906 7326 4097 43907 7326 4097 43908 7328 4097 43909 7330 4097 43910 7330 4097 43911 7332 4097 43912 7326 4097 43913 7332 4097 43914 7334 4097 43915 7326 4097 43916 7334 4097 43917 7336 4097 43918 7342 4097 43919 7336 4097 43920 7338 4097 43921 7342 4097 43922 7338 4097 43923 7340 4097 43924 7342 4097 43925 7342 4097 43926 7344 4097 43927 7346 4097 43928 7346 4097 43929 7348 4097 43930 7350 4097 43931 7350 4097 43932 7352 4097 43933 7358 4097 43934 7352 4097 43935 7354 4097 43936 7358 4097 43937 7354 4097 43938 7356 4097 43939 7358 4097 43940 7358 4097 43941 7360 4097 43942 7362 4097 43943 7362 4097 43944 7364 4097 43945 7366 4097 43946 7366 4097 43947 7368 4097 43948 7370 4097 43949 7370 4097 43950 7372 4097 43951 7366 4097 43952 7372 4097 43953 7374 4097 43954 7366 4097 43955 7374 4097 43956 7376 4097 43957 7378 4097 43958 7378 4097 43959 7380 4097 43960 7382 4097 43961 7382 4097 43962 7384 4097 43963 7386 4097 43964 7386 4097 43965 7388 4097 43966 7382 4097 43967 7388 4097 43968 7390 4097 43969 7382 4097 43970 7390 4097 43971 7392 4097 43972 7394 4097 43973 7394 4097 43974 7396 4097 43975 7390 4097 43976 7396 4097 43977 7398 4097 43978 7390 4097 43979 7398 4097 43980 7400 4097 43981 7402 4097 43982 7402 4097 43983 7404 4097 43984 7398 4097 43985 7404 4097 43986 7406 4097 43987 7398 4097 43988 7406 4097 43989 7408 4097 43990 7410 4097 43991 7410 4097 43992 7412 4097 43993 7414 4097 43994 7414 4097 43995 7416 4097 43996 7418 4097 43997 7418 4097 43998 7420 4097 43999 7414 4097 44000 7420 4097 44001 7422 4097 44002 7414 4097 44003 7422 4097 44004 7424 4097 44005 7430 4097 44006 7424 4097 44007 7426 4097 44008 7430 4097 44009 7426 4097 44010 7428 4097 44011 7430 4097 44012 7430 4097 44013 7432 4097 44014 7434 4097 44015 7434 4097 44016 7436 4097 44017 7438 4097 44018 7438 4097 44019 7440 4097 44020 7442 4097 44021 7442 4097 44022 7444 4097 44023 7438 4097 44024 7444 4097 44025 7446 4097 44026 7438 4097 44027 7446 4097 44028 7448 4097 44029 7450 4097 44030 7450 4097 44031 7452 4097 44032 7446 4097 44033 7452 4097 44034 7454 4097 44035 7446 4097 44036 7454 4097 44037 7456 4097 44038 7462 4097 44039 7456 4097 44040 7458 4097 44041 7462 4097 44042 7458 4097 44043 7460 4097 44044 7462 4097 44045 7462 4097 44046 7464 4097 44047 7470 4097 44048 7464 4097 44049 7466 4097 44050 7470 4097 44051 7466 4097 44052 7468 4097 44053 7470 4097 44054 7470 4097 44055 7472 4097 44056 7474 4097 44057 7474 4097 44058 7476 4097 44059 7470 4097 44060 7476 4097 44061 7478 4097 44062 7470 4097 44063 7478 4097 44064 7480 4097 44065 7482 4097 44066 7482 4097 44067 7484 4097 44068 7486 4097 44069 7486 4097 44070 7488 4097 44071 7494 4097 44072 7488 4097 44073 7490 4097 44074 7494 4097 44075 7490 4097 44076 7492 4097 44077 7494 4097 44078 7494 4097 44079 7496 4097 44080 7502 4097 44081 7496 4097 44082 7498 4097 44083 7502 4097 44084 7498 4097 44085 7500 4097 44086 7502 4097 44087 7502 4097 44088 7504 4097 44089 7506 4097 44090 7506 4097 44091 7508 4097 44092 7510 4097 44093 7510 4097 44094 7512 4097 44095 7518 4097 44096 7512 4097 44097 7514 4097 44098 7518 4097 44099 7514 4097 44100 7516 4097 44101 7518 4097 44102 7518 4097 44103 7520 4097 44104 7522 4097 44105 7522 4097 44106 7524 4097 44107 7526 4097 44108 7526 4097 44109 7528 4097 44110 7530 4097 44111 7530 4097 44112 7532 4097 44113 7534 4097 44114 7534 4097 44115 7536 4097 44116 7538 4097 44117 7538 4097 44118 7540 4097 44119 7542 4097 44120 7542 4097 44121 7544 4097 44122 7546 4097 44123 7546 4097 44124 7548 4097 44125 7550 4097 44126 7550 4097 44127 7552 4097 44128 7558 4097 44129 7552 4097 44130 7554 4097 44131 7558 4097 44132 7554 4097 44133 7556 4097 44134 7558 4097 44135 7558 4097 44136 7560 4097 44137 7562 4097 44138 7562 4097 44139 7564 4097 44140 7566 4097 44141 7566 4097 44142 7568 4097 44143 7570 4097 44144 7570 4097 44145 7572 4097 44146 7574 4097 44147 7574 4097 44148 7576 4097 44149 7578 4097 44150 7578 4097 44151 7580 4097 44152 7574 4097 44153 7580 4097 44154 7582 4097 44155 7574 4097 44156 7582 4097 44157 7584 4097 44158 7586 4097 44159 7586 4097 44160 7588 4097 44161 7582 4097 44162 7588 4097 44163 7590 4097 44164 7582 4097 44165 7590 4097 44166 7592 4097 44167 7594 4097 44168 7594 4097 44169 7596 4097 44170 7598 4097 44171 7598 4097 44172 7600 4097 44173 7602 4097 44174 7602 4097 44175 7604 4097 44176 7606 4097 44177 7606 4097 44178 7608 4097 44179 7610 4097 44180 7610 4097 44181 7612 4097 44182 7614 4097 44183 7614 4097 44184 7616 4097 44185 7618 4097 44186 7618 4097 44187 7620 4097 44188 7622 4097 44189 7622 4097 44190 7624 4097 44191 7626 4097 44192 7626 4097 44193 7628 4097 44194 7622 4097 44195 7628 4097 44196 7630 4097 44197 7622 4097 44198 7630 4097 44199 7632 4097 44200 7634 4097 44201 7634 4097 44202 7636 4097 44203 7630 4097 44204 7636 4097 44205 7638 4097 44206 7630 4097 44207 7638 4097 44208 7640 4097 44209 7642 4097 44210 7642 4097 44211 7644 4097 44212 7646 4097 44213 7646 4097 44214 7648 4097 44215 7654 4097 44216 7648 4097 44217 7650 4097 44218 7654 4097 44219 7650 4097 44220 7652 4097 44221 7654 4097 44222 7654 4097 44223 7656 4097 44224 7658 4097 44225 7658 4097 44226 7660 4097 44227 7662 4097 44228 7662 4097 44229 7664 4097 44230 7666 4097 44231 7666 4097 44232 7668 4097 44233 7662 4097 44234 7668 4097 44235 7670 4097 44236 7662 4097 44237 7670 4097 44238 7672 4097 44239 7674 4097 44240 7674 4097 44241 7676 4097 44242 7678 4097 44243 7678 4097 44244 7680 4097 44245 7686 4097 44246 7680 4097 44247 7682 4097 44248 7686 4097 44249 7682 4097 44250 7684 4097 44251 7686 4097 44252 7686 4097 44253 7688 4097 44254 7690 4097 44255 7690 4097 44256 7692 4097 44257 7686 4097 44258 7692 4097 44259 7694 4097 44260 7686 4097 44261 7694 4097 44262 7696 4097 44263 7698 4097 44264 7698 4097 44265 7700 4097 44266 7694 4097 44267 7700 4097 44268 7702 4097 44269 7694 4097 44270 7702 4097 44271 7704 4097 44272 7706 4097 44273 7706 4097 44274 7708 4097 44275 7710 4097 44276 7710 4097 44277 7712 4097 44278 7714 4097 44279 7714 4097 44280 7716 4097 44281 7710 4097 44282 7716 4097 44283 7718 4097 44284 7710 4097 44285 7718 4097 44286 7720 4097 44287 7722 4097 44288 7722 4097 44289 7724 4097 44290 7718 4097 44291 7724 4097 44292 7726 4097 44293 7718 4097 44294 7726 4097 44295 7728 4097 44296 7730 4097 44297 7730 4097 44298 7732 4097 44299 7734 4097 44300 7734 4097 44301 7736 4097 44302 7738 4097 44303 7738 4097 44304 7740 4097 44305 7734 4097 44306 7740 4097 44307 7742 4097 44308 7734 4097 44309 7742 4097 44310 7744 4097 44311 7746 4097 44312 7746 4097 44313 7748 4097 44314 7742 4097 44315 7748 4097 44316 7750 4097 44317 7742 4097 44318 7750 4097 44319 7752 4097 44320 7758 4097 44321 7752 4097 44322 7754 4097 44323 7758 4097 44324 7754 4097 44325 7756 4097 44326 7758 4097 44327 7758 4097 44328 7760 4097 44329 7762 4097 44330 7762 4097 44331 7764 4097 44332 7758 4097 44333 7764 4097 44334 7766 4097 44335 7758 4097 44336 7766 4097 44337 7768 4097 44338 7770 4097 44339 7770 4097 44340 7772 4097 44341 7774 4097 44342 7774 4097 44343 7776 4097 44344 7778 4097 44345 7778 4097 44346 7780 4097 44347 7782 4097 44348 7782 4097 44349 7784 4097 44350 7786 4097 44351 7786 4097 44352 7788 4097 44353 7782 4097 44354 7788 4097 44355 7790 4097 44356 7782 4097 44357 7790 4097 44358 7792 4097 44359 7798 4097 44360 7792 4097 44361 7794 4097 44362 7798 4097 44363 7794 4097 44364 7796 4097 44365 7798 4097 44366 7798 4097 44367 7800 4097 44368 7802 4097 44369 7802 4097 44370 7804 4097 44371 7806 4097 44372 7806 4097 44373 7808 4097 44374 7810 4097 44375 7810 4097 44376 7812 4097 44377 7814 4097 44378 7814 4097 44379 7816 4097 44380 7822 4097 44381 7816 4097 44382 7818 4097 44383 7822 4097 44384 7818 4097 44385 7820 4097 44386 7822 4097 44387 7822 4097 44388 7824 4097 44389 7826 4097 44390 7826 4097 44391 7828 4097 44392 7822 4097 44393 7828 4097 44394 7830 4097 44395 7822 4097 44396 7830 4097 44397 7832 4097 44398 7834 4097 44399 7834 4097 44400 7836 4097 44401 7830 4097 44402 7836 4097 44403 7838 4097 44404 7830 4097 44405 7838 4097 44406 7840 4097 44407 7842 4097 44408 7842 4097 44409 7844 4097 44410 7838 4097 44411 7844 4097 44412 7846 4097 44413 7838 4097 44414 7846 4097 44415 7848 4097 44416 7850 4097 44417 7850 4097 44418 7852 4097 44419 7846 4097 44420 7852 4097 44421 7854 4097 44422 7846 4097 44423 7854 4097 44424 7856 4097 44425 7858 4097 44426 7858 4097 44427 7860 4097 44428 7862 4097 44429 7862 4097 44430 7864 4097 44431 7870 4097 44432 7864 4097 44433 7866 4097 44434 7870 4097 44435 7866 4097 44436 7868 4097 44437 7870 4097 44438 7870 4097 44439 7872 4097 44440 7874 4097 44441 7874 4097 44442 7876 4097 44443 7878 4097 44444 7878 4097 44445 7880 4097 44446 7882 4097 44447 7882 4097 44448 7884 4097 44449 7886 4097 44450 7886 4097 44451 7888 4097 44452 7890 4097 44453 7890 4097 44454 7892 4097 44455 7894 4097 44456 7894 4097 44457 7896 4097 44458 7902 4097 44459 7896 4097 44460 7898 4097 44461 7902 4097 44462 7898 4097 44463 7900 4097 44464 7902 4097 44465 7902 4097 44466 7904 4097 44467 7910 4097 44468 7904 4097 44469 7906 4097 44470 7910 4097 44471 7906 4097 44472 7908 4097 44473 7910 4097 44474 7910 4097 44475 7912 4097 44476 7914 4097 44477 7914 4097 44478 7916 4097 44479 7918 4097 44480 7918 4097 44481 7920 4097 44482 7922 4097 44483 7922 4097 44484 7924 4097 44485 7918 4097 44486 7924 4097 44487 7926 4097 44488 7918 4097 44489 7926 4097 44490 7928 4097 44491 7930 4097 44492 7930 4097 44493 7932 4097 44494 7926 4097 44495 7932 4097 44496 7934 4097 44497 7926 4097 44498 7934 4097 44499 7936 4097 44500 7942 4097 44501 7936 4097 44502 7938 4097 44503 7942 4097 44504 7938 4097 44505 7940 4097 44506 7942 4097 44507 7942 4097 44508 7944 4097 44509 7946 4097 44510 7946 4097 44511 7948 4097 44512 7950 4097 44513 7950 4097 44514 7952 4097 44515 7954 4097 44516 7954 4097 44517 7956 4097 44518 7958 4097 44519 7958 4097 44520 7960 4097 44521 7962 4097 44522 7962 4097 44523 7964 4097 44524 7966 4097 44525 7966 4097 44526 7968 4097 44527 7970 4097 44528 7970 4097 44529 7972 4097 44530 7974 4097 44531 7974 4097 44532 7976 4097 44533 7978 4097 44534 7978 4097 44535 7980 4097 44536 7974 4097 44537 7980 4097 44538 7982 4097 44539 7974 4097 44540 7982 4097 44541 7984 4097 44542 7986 4097 44543 7986 4097 44544 7988 4097 44545 7990 4097 44546 7990 4097 44547 7992 4097 44548 7994 4097 44549 7994 4097 44550 7996 4097 44551 7990 4097 44552 7996 4097 44553 7998 4097 44554 7990 4097 44555 7998 4097 44556 8000 4097 44557 8002 4097 44558 8002 4097 44559 8004 4097 44560 7998 4097 44561 8004 4097 44562 8006 4097 44563 7998 4097 44564 8006 4097 44565 8008 4097 44566 8014 4097 44567 8008 4097 44568 8010 4097 44569 8014 4097 44570 8010 4097 44571 8012 4097 44572 8014 4097 44573 8014 4097 44574 8016 4097 44575 8018 4097 44576 8018 4097 44577 8020 4097 44578 8014 4097 44579 8020 4097 44580 8022 4097 44581 8014 4097 44582 8022 4097 44583 8024 4097 44584 8026 4097 44585 8026 4097 44586 8028 4097 44587 8022 4097 44588 8028 4097 44589 8030 4097 44590 8022 4097 44591 8030 4097 44592 8032 4097 44593 8034 4097 44594 8034 4097 44595 8036 4097 44596 8038 4097 44597 8038 4097 44598 8040 4097 44599 8042 4097 44600 8042 4097 44601 8044 4097 44602 8038 4097 44603 8044 4097 44604 8046 4097 44605 8038 4097 44606 8046 4097 44607 8048 4097 44608 8054 4097 44609 8048 4097 44610 8050 4097 44611 8054 4097 44612 8050 4097 44613 8052 4097 44614 8054 4097 44615 8054 4097 44616 8056 4097 44617 8058 4097 44618 8058 4097 44619 8060 4097 44620 8054 4097 44621 8060 4097 44622 8062 4097 44623 8054 4097 44624 8062 4097 44625 8064 4097 44626 8070 4097 44627 8064 4097 44628 8066 4097 44629 8070 4097 44630 8066 4097 44631 8068 4097 44632 8070 4097 44633 8070 4097 44634 8072 4097 44635 8078 4097 44636 8072 4097 44637 8074 4097 44638 8078 4097 44639 8074 4097 44640 8076 4097 44641 8078 4097 44642 8078 4097 44643 8080 4097 44644 8082 4097 44645 8082 4097 44646 8084 4097 44647 8078 4097 44648 8084 4097 44649 8086 4097 44650 8078 4097 44651 8086 4097 44652 8088 4097 44653 8090 4097 44654 8090 4097 44655 8092 4097 44656 8094 4097 44657 8094 4097 44658 8096 4097 44659 8098 4097 44660 8098 4097 44661 8100 4097 44662 8094 4097 44663 8100 4097 44664 8102 4097 44665 8094 4097 44666 8102 4097 44667 8104 4097 44668 8106 4097 44669 8106 4097 44670 8108 4097 44671 8110 4097 44672 8110 4097 44673 8112 4097 44674 8118 4097 44675 8112 4097 44676 8114 4097 44677 8118 4097 44678 8114 4097 44679 8116 4097 44680 8118 4097 44681 8118 4097 44682 8120 4097 44683 8122 4097 44684 8122 4097 44685 8124 4097 44686 8126 4097 44687 8126 4097 44688 8128 4097 44689 8134 4097 44690 8128 4097 44691 8130 4097 44692 8134 4097 44693 8130 4097 44694 8132 4097 44695 8134 4097 44696 8134 4097 44697 8136 4097 44698 8138 4097 44699 8138 4097 44700 8140 4097 44701 8134 4097 44702 8140 4097 44703 8142 4097 44704 8134 4097 44705 8142 4097 44706 8144 4097 44707 8150 4097 44708 8144 4097 44709 8146 4097 44710 8150 4097 44711 8146 4097 44712 8148 4097 44713 8150 4097 44714 8150 4097 44715 8152 4097 44716 8154 4097 44717 8154 4097 44718 8156 4097 44719 8150 4097 44720 8156 4097 44721 8158 4097 44722 8150 4097 44723 8158 4097 44724 8160 4097 44725 8162 4097 44726 8162 4097 44727 8164 4097 44728 8158 4097 44729 8164 4097 44730 8166 4097 44731 8158 4097 44732 8166 4097 44733 8168 4097 44734 8170 4097 44735 8170 4097 44736 8172 4097 44737 8166 4097 44738 8172 4097 44739 8174 4097 44740 8166 4097 44741 8174 4097 44742 8176 4097 44743 8178 4097 44744 8178 4097 44745 8180 4097 44746 8174 4097 44747 8180 4097 44748 8182 4097 44749 8174 4097 44750 8182 4097 44751 8184 4097 44752 8186 4097 44753 8186 4097 44754 8188 4097 44755 8190 4097 44756 8190 4097 44757 2 4097 44758 6 4097 44759 14 4097 44760 18 4097 44761 30 4097 44762 18 4097 44763 22 4097 44764 30 4097 44765 54 4097 44766 58 4097 44767 62 4097 44768 70 4097 44769 74 4097 44770 62 4097 44771 74 4097 44772 78 4097 44773 62 4097 44774 94 4097 44775 98 4097 44776 110 4097 44777 98 4097 44778 102 4097 44779 110 4097 44780 110 4097 44781 114 4097 44782 126 4097 44783 114 4097 44784 118 4097 44785 126 4097 44786 134 4097 44787 138 4097 44788 126 4097 44789 138 4097 44790 142 4097 44791 126 4097 44792 174 4097 44793 178 4097 44794 190 4097 44795 178 4097 44796 182 4097 44797 190 4097 44798 190 4097 44799 194 4097 44800 206 4097 44801 194 4097 44802 198 4097 44803 206 4097 44804 206 4097 44805 210 4097 44806 222 4097 44807 210 4097 44808 214 4097 44809 222 4097 44810 214 4097 44811 218 4097 44812 222 4097 44813 246 4097 44814 250 4097 44815 254 4097 44816 254 4097 44817 258 4097 44818 270 4097 44819 258 4097 44820 262 4097 44821 270 4097 44822 270 4097 44823 274 4097 44824 278 4097 44825 278 4097 44826 282 4097 44827 286 4097 44828 286 4097 44829 290 4097 44830 302 4097 44831 290 4097 44832 294 4097 44833 302 4097 44834 302 4097 44835 306 4097 44836 310 4097 44837 310 4097 44838 314 4097 44839 318 4097 44840 318 4097 44841 322 4097 44842 334 4097 44843 322 4097 44844 326 4097 44845 334 4097 44846 342 4097 44847 346 4097 44848 334 4097 44849 346 4097 44850 350 4097 44851 334 4097 44852 350 4097 44853 354 4097 44854 358 4097 44855 358 4097 44856 362 4097 44857 350 4097 44858 362 4097 44859 366 4097 44860 350 4097 44861 366 4097 44862 370 4097 44863 382 4097 44864 370 4097 44865 374 4097 44866 382 4097 44867 382 4097 44868 386 4097 44869 390 4097 44870 390 4097 44871 394 4097 44872 398 4097 44873 406 4097 44874 410 4097 44875 398 4097 44876 410 4097 44877 414 4097 44878 398 4097 44879 430 4097 44880 434 4097 44881 446 4097 44882 434 4097 44883 438 4097 44884 446 4097 44885 446 4097 44886 450 4097 44887 462 4097 44888 450 4097 44889 454 4097 44890 462 4097 44891 470 4097 44892 474 4097 44893 462 4097 44894 474 4097 44895 478 4097 44896 462 4097 44897 478 4097 44898 482 4097 44899 486 4097 44900 486 4097 44901 490 4097 44902 494 4097 44903 502 4097 44904 506 4097 44905 494 4097 44906 506 4097 44907 510 4097 44908 494 4097 44909 510 4097 44910 514 4097 44911 526 4097 44912 514 4097 44913 518 4097 44914 526 4097 44915 558 4097 44916 562 4097 44917 574 4097 44918 562 4097 44919 566 4097 44920 574 4097 44921 566 4097 44922 570 4097 44923 574 4097 44924 574 4097 44925 578 4097 44926 582 4097 44927 582 4097 44928 586 4097 44929 590 4097 44930 606 4097 44931 610 4097 44932 622 4097 44933 610 4097 44934 614 4097 44935 622 4097 44936 614 4097 44937 618 4097 44938 622 4097 44939 622 4097 44940 626 4097 44941 630 4097 44942 654 4097 44943 658 4097 44944 670 4097 44945 658 4097 44946 662 4097 44947 670 4097 44948 662 4097 44949 666 4097 44950 670 4097 44951 694 4097 44952 698 4097 44953 686 4097 44954 698 4097 44955 702 4097 44956 686 4097 44957 702 4097 44958 706 4097 44959 710 4097 44960 718 4097 44961 722 4097 44962 726 4097 44963 726 4097 44964 730 4097 44965 718 4097 44966 730 4097 44967 734 4097 44968 718 4097 44969 734 4097 44970 738 4097 44971 750 4097 44972 738 4097 44973 742 4097 44974 750 4097 44975 790 4097 44976 794 4097 44977 782 4097 44978 794 4097 44979 798 4097 44980 782 4097 44981 806 4097 44982 810 4097 44983 798 4097 44984 810 4097 44985 814 4097 44986 798 4097 44987 830 4097 44988 834 4097 44989 846 4097 44990 834 4097 44991 838 4097 44992 846 4097 44993 862 4097 44994 866 4097 44995 878 4097 44996 866 4097 44997 870 4097 44998 878 4097 44999 878 4097 45000 882 4097 45001 894 4097 45002 882 4097 45003 886 4097 45004 894 4097 45005 902 4097 45006 906 4097 45007 894 4097 45008 906 4097 45009 910 4097 45010 894 4097 45011 918 4097 45012 922 4097 45013 910 4097 45014 922 4097 45015 926 4097 45016 910 4097 45017 926 4097 45018 930 4097 45019 942 4097 45020 930 4097 45021 934 4097 45022 942 4097 45023 942 4097 45024 946 4097 45025 950 4097 45026 950 4097 45027 954 4097 45028 958 4097 45029 966 4097 45030 970 4097 45031 958 4097 45032 970 4097 45033 974 4097 45034 958 4097 45035 974 4097 45036 978 4097 45037 982 4097 45038 990 4097 45039 994 4097 45040 1006 4097 45041 994 4097 45042 998 4097 45043 1006 4097 45044 1014 4097 45045 1018 4097 45046 1006 4097 45047 1018 4097 45048 1022 4097 45049 1006 4097 45050 1030 4097 45051 1034 4097 45052 1038 4097 45053 1038 4097 45054 1042 4097 45055 1054 4097 45056 1042 4097 45057 1046 4097 45058 1054 4097 45059 1070 4097 45060 1074 4097 45061 1086 4097 45062 1074 4097 45063 1078 4097 45064 1086 4097 45065 1086 4097 45066 1090 4097 45067 1094 4097 45068 1094 4097 45069 1098 4097 45070 1102 4097 45071 1110 4097 45072 1114 4097 45073 1118 4097 45074 1150 4097 45075 1154 4097 45076 1166 4097 45077 1154 4097 45078 1158 4097 45079 1166 4097 45080 1174 4097 45081 1178 4097 45082 1166 4097 45083 1178 4097 45084 1182 4097 45085 1166 4097 45086 1198 4097 45087 1202 4097 45088 1214 4097 45089 1202 4097 45090 1206 4097 45091 1214 4097 45092 1214 4097 45093 1218 4097 45094 1230 4097 45095 1218 4097 45096 1222 4097 45097 1230 4097 45098 1230 4097 45099 1234 4097 45100 1238 4097 45101 1262 4097 45102 1266 4097 45103 1278 4097 45104 1266 4097 45105 1270 4097 45106 1278 4097 45107 1286 4097 45108 1290 4097 45109 1278 4097 45110 1290 4097 45111 1294 4097 45112 1278 4097 45113 1334 4097 45114 1338 4097 45115 1326 4097 45116 1338 4097 45117 1342 4097 45118 1326 4097 45119 1358 4097 45120 1362 4097 45121 1374 4097 45122 1362 4097 45123 1366 4097 45124 1374 4097 45125 1374 4097 45126 1378 4097 45127 1390 4097 45128 1378 4097 45129 1382 4097 45130 1390 4097 45131 1382 4097 45132 1386 4097 45133 1390 4097 45134 1390 4097 45135 1394 4097 45136 1398 4097 45137 1398 4097 45138 1402 4097 45139 1390 4097 45140 1402 4097 45141 1406 4097 45142 1390 4097 45143 1414 4097 45144 1418 4097 45145 1422 4097 45146 1422 4097 45147 1426 4097 45148 1438 4097 45149 1426 4097 45150 1430 4097 45151 1438 4097 45152 1446 4097 45153 1450 4097 45154 1438 4097 45155 1450 4097 45156 1454 4097 45157 1438 4097 45158 1454 4097 45159 1458 4097 45160 1462 4097 45161 1462 4097 45162 1466 4097 45163 1470 4097 45164 1470 4097 45165 1474 4097 45166 1478 4097 45167 1494 4097 45168 1498 4097 45169 1486 4097 45170 1498 4097 45171 1502 4097 45172 1486 4097 45173 1510 4097 45174 1514 4097 45175 1502 4097 45176 1514 4097 45177 1518 4097 45178 1502 4097 45179 1526 4097 45180 1530 4097 45181 1534 4097 45182 1558 4097 45183 1562 4097 45184 1566 4097 45185 1582 4097 45186 1586 4097 45187 1598 4097 45188 1586 4097 45189 1590 4097 45190 1598 4097 45191 1622 4097 45192 1626 4097 45193 1614 4097 45194 1626 4097 45195 1630 4097 45196 1614 4097 45197 1630 4097 45198 1634 4097 45199 1646 4097 45200 1634 4097 45201 1638 4097 45202 1646 4097 45203 1654 4097 45204 1658 4097 45205 1646 4097 45206 1658 4097 45207 1662 4097 45208 1646 4097 45209 1662 4097 45210 1666 4097 45211 1670 4097 45212 1710 4097 45213 1714 4097 45214 1726 4097 45215 1714 4097 45216 1718 4097 45217 1726 4097 45218 1726 4097 45219 1730 4097 45220 1734 4097 45221 1734 4097 45222 1738 4097 45223 1742 4097 45224 1742 4097 45225 1746 4097 45226 1750 4097 45227 1766 4097 45228 1770 4097 45229 1758 4097 45230 1770 4097 45231 1774 4097 45232 1758 4097 45233 1798 4097 45234 1802 4097 45235 1790 4097 45236 1802 4097 45237 1806 4097 45238 1790 4097 45239 1806 4097 45240 1810 4097 45241 1814 4097 45242 1814 4097 45243 1818 4097 45244 1806 4097 45245 1818 4097 45246 1822 4097 45247 1806 4097 45248 1822 4097 45249 1826 4097 45250 1838 4097 45251 1826 4097 45252 1830 4097 45253 1838 4097 45254 1838 4097 45255 1842 4097 45256 1854 4097 45257 1842 4097 45258 1846 4097 45259 1854 4097 45260 1886 4097 45261 1890 4097 45262 1894 4097 45263 1942 4097 45264 1946 4097 45265 1934 4097 45266 1946 4097 45267 1950 4097 45268 1934 4097 45269 1958 4097 45270 1962 4097 45271 1950 4097 45272 1962 4097 45273 1966 4097 45274 1950 4097 45275 1974 4097 45276 1978 4097 45277 1966 4097 45278 1978 4097 45279 1982 4097 45280 1966 4097 45281 2038 4097 45282 2042 4097 45283 2030 4097 45284 2042 4097 45285 2046 4097 45286 2030 4097 45287 2046 6124 45288 2050 6124 45289 2054 6124 45290 2062 4097 45291 2066 4097 45292 2078 4097 45293 2066 4097 45294 2070 4097 45295 2078 4097 45296 2102 4097 45297 2106 4097 45298 2110 4097 45299 2118 4097 45300 2122 4097 45301 2110 4097 45302 2122 4097 45303 2126 4097 45304 2110 4097 45305 2142 4097 45306 2146 4097 45307 2158 4097 45308 2146 4097 45309 2150 4097 45310 2158 4097 45311 2158 4097 45312 2162 4097 45313 2174 4097 45314 2162 4097 45315 2166 4097 45316 2174 4097 45317 2182 4097 45318 2186 4097 45319 2174 4097 45320 2186 4097 45321 2190 4097 45322 2174 4097 45323 2222 4097 45324 2226 4097 45325 2238 4097 45326 2226 4097 45327 2230 4097 45328 2238 4097 45329 2238 4097 45330 2242 4097 45331 2254 4097 45332 2242 4097 45333 2246 4097 45334 2254 4097 45335 2254 4097 45336 2258 4097 45337 2270 4097 45338 2258 4097 45339 2262 4097 45340 2270 4097 45341 2262 4097 45342 2266 4097 45343 2270 4097 45344 2294 4097 45345 2298 4097 45346 2302 4097 45347 2302 4097 45348 2306 4097 45349 2318 4097 45350 2306 4097 45351 2310 4097 45352 2318 4097 45353 2318 4097 45354 2322 4097 45355 2326 4097 45356 2326 4097 45357 2330 4097 45358 2334 4097 45359 2334 4097 45360 2338 4097 45361 2350 4097 45362 2338 4097 45363 2342 4097 45364 2350 4097 45365 2350 4097 45366 2354 4097 45367 2358 4097 45368 2358 4097 45369 2362 4097 45370 2366 4097 45371 2366 4097 45372 2370 4097 45373 2382 4097 45374 2370 4097 45375 2374 4097 45376 2382 4097 45377 2390 4097 45378 2394 4097 45379 2382 4097 45380 2394 4097 45381 2398 4097 45382 2382 4097 45383 2398 4097 45384 2402 4097 45385 2406 4097 45386 2406 4097 45387 2410 4097 45388 2398 4097 45389 2410 4097 45390 2414 4097 45391 2398 4097 45392 2414 4097 45393 2418 4097 45394 2430 4097 45395 2418 4097 45396 2422 4097 45397 2430 4097 45398 2430 4097 45399 2434 4097 45400 2438 4097 45401 2438 4097 45402 2442 4097 45403 2446 4097 45404 2454 4097 45405 2458 4097 45406 2446 4097 45407 2458 4097 45408 2462 4097 45409 2446 4097 45410 2478 4097 45411 2482 4097 45412 2494 4097 45413 2482 4097 45414 2486 4097 45415 2494 4097 45416 2494 4097 45417 2498 4097 45418 2510 4097 45419 2498 4097 45420 2502 4097 45421 2510 4097 45422 2518 4097 45423 2522 4097 45424 2510 4097 45425 2522 4097 45426 2526 4097 45427 2510 4097 45428 2526 4097 45429 2530 4097 45430 2534 4097 45431 2534 4097 45432 2538 4097 45433 2542 4097 45434 2550 4097 45435 2554 4097 45436 2542 4097 45437 2554 4097 45438 2558 4097 45439 2542 4097 45440 2558 4097 45441 2562 4097 45442 2574 4097 45443 2562 4097 45444 2566 4097 45445 2574 4097 45446 2606 4097 45447 2610 4097 45448 2622 4097 45449 2610 4097 45450 2614 4097 45451 2622 4097 45452 2614 4097 45453 2618 4097 45454 2622 4097 45455 2622 4097 45456 2626 4097 45457 2630 4097 45458 2630 4097 45459 2634 4097 45460 2638 4097 45461 2654 4097 45462 2658 4097 45463 2670 4097 45464 2658 4097 45465 2662 4097 45466 2670 4097 45467 2662 4097 45468 2666 4097 45469 2670 4097 45470 2670 4097 45471 2674 4097 45472 2678 4097 45473 2702 4097 45474 2706 4097 45475 2718 4097 45476 2706 4097 45477 2710 4097 45478 2718 4097 45479 2710 4097 45480 2714 4097 45481 2718 4097 45482 2742 4097 45483 2746 4097 45484 2734 4097 45485 2746 4097 45486 2750 4097 45487 2734 4097 45488 2750 4097 45489 2754 4097 45490 2758 4097 45491 2766 4097 45492 2770 4097 45493 2774 4097 45494 2774 4097 45495 2778 4097 45496 2766 4097 45497 2778 4097 45498 2782 4097 45499 2766 4097 45500 2782 4097 45501 2786 4097 45502 2798 4097 45503 2786 4097 45504 2790 4097 45505 2798 4097 45506 2838 4097 45507 2842 4097 45508 2830 4097 45509 2842 4097 45510 2846 4097 45511 2830 4097 45512 2854 4097 45513 2858 4097 45514 2846 4097 45515 2858 4097 45516 2862 4097 45517 2846 4097 45518 2878 4097 45519 2882 4097 45520 2894 4097 45521 2882 4097 45522 2886 4097 45523 2894 4097 45524 2910 4097 45525 2914 4097 45526 2926 4097 45527 2914 4097 45528 2918 4097 45529 2926 4097 45530 2926 4097 45531 2930 4097 45532 2942 4097 45533 2930 4097 45534 2934 4097 45535 2942 4097 45536 2950 4097 45537 2954 4097 45538 2942 4097 45539 2954 4097 45540 2958 4097 45541 2942 4097 45542 2966 4097 45543 2970 4097 45544 2958 4097 45545 2970 4097 45546 2974 4097 45547 2958 4097 45548 2974 4097 45549 2978 4097 45550 2990 4097 45551 2978 4097 45552 2982 4097 45553 2990 4097 45554 2990 4097 45555 2994 4097 45556 2998 4097 45557 2998 4097 45558 3002 4097 45559 3006 4097 45560 3014 4097 45561 3018 4097 45562 3006 4097 45563 3018 4097 45564 3022 4097 45565 3006 4097 45566 3022 4097 45567 3026 4097 45568 3030 4097 45569 3038 4097 45570 3042 4097 45571 3054 4097 45572 3042 4097 45573 3046 4097 45574 3054 4097 45575 3062 4097 45576 3066 4097 45577 3054 4097 45578 3066 4097 45579 3070 4097 45580 3054 4097 45581 3078 4097 45582 3082 4097 45583 3086 4097 45584 3086 4097 45585 3090 4097 45586 3102 4097 45587 3090 4097 45588 3094 4097 45589 3102 4097 45590 3118 4097 45591 3122 4097 45592 3134 4097 45593 3122 4097 45594 3126 4097 45595 3134 4097 45596 3134 4097 45597 3138 4097 45598 3142 4097 45599 3142 4097 45600 3146 4097 45601 3150 4097 45602 3158 4097 45603 3162 4097 45604 3166 4097 45605 3198 4097 45606 3202 4097 45607 3214 4097 45608 3202 4097 45609 3206 4097 45610 3214 4097 45611 3222 4097 45612 3226 4097 45613 3214 4097 45614 3226 4097 45615 3230 4097 45616 3214 4097 45617 3246 4097 45618 3250 4097 45619 3262 4097 45620 3250 4097 45621 3254 4097 45622 3262 4097 45623 3262 4097 45624 3266 4097 45625 3278 4097 45626 3266 4097 45627 3270 4097 45628 3278 4097 45629 3278 4097 45630 3282 4097 45631 3286 4097 45632 3310 4097 45633 3314 4097 45634 3326 4097 45635 3314 4097 45636 3318 4097 45637 3326 4097 45638 3334 4097 45639 3338 4097 45640 3326 4097 45641 3338 4097 45642 3342 4097 45643 3326 4097 45644 3382 4097 45645 3386 4097 45646 3374 4097 45647 3386 4097 45648 3390 4097 45649 3374 4097 45650 3406 4097 45651 3410 4097 45652 3422 4097 45653 3410 4097 45654 3414 4097 45655 3422 4097 45656 3422 4097 45657 3426 4097 45658 3438 4097 45659 3426 4097 45660 3430 4097 45661 3438 4097 45662 3430 4097 45663 3434 4097 45664 3438 4097 45665 3438 4097 45666 3442 4097 45667 3446 4097 45668 3446 4097 45669 3450 4097 45670 3438 4097 45671 3450 4097 45672 3454 4097 45673 3438 4097 45674 3462 4097 45675 3466 4097 45676 3470 4097 45677 3470 4097 45678 3474 4097 45679 3486 4097 45680 3474 4097 45681 3478 4097 45682 3486 4097 45683 3494 4097 45684 3498 4097 45685 3486 4097 45686 3498 4097 45687 3502 4097 45688 3486 4097 45689 3502 4097 45690 3506 4097 45691 3510 4097 45692 3510 4097 45693 3514 4097 45694 3518 4097 45695 3518 4097 45696 3522 4097 45697 3526 4097 45698 3542 4097 45699 3546 4097 45700 3534 4097 45701 3546 4097 45702 3550 4097 45703 3534 4097 45704 3558 4097 45705 3562 4097 45706 3550 4097 45707 3562 4097 45708 3566 4097 45709 3550 4097 45710 3574 4097 45711 3578 4097 45712 3582 4097 45713 3606 4097 45714 3610 4097 45715 3614 4097 45716 3630 4097 45717 3634 4097 45718 3646 4097 45719 3634 4097 45720 3638 4097 45721 3646 4097 45722 3670 4097 45723 3674 4097 45724 3662 4097 45725 3674 4097 45726 3678 4097 45727 3662 4097 45728 3678 4097 45729 3682 4097 45730 3694 4097 45731 3682 4097 45732 3686 4097 45733 3694 4097 45734 3702 4097 45735 3706 4097 45736 3694 4097 45737 3706 4097 45738 3710 4097 45739 3694 4097 45740 3710 4097 45741 3714 4097 45742 3718 4097 45743 3758 4097 45744 3762 4097 45745 3774 4097 45746 3762 4097 45747 3766 4097 45748 3774 4097 45749 3774 4097 45750 3778 4097 45751 3782 4097 45752 3782 4097 45753 3786 4097 45754 3790 4097 45755 3790 4097 45756 3794 4097 45757 3798 4097 45758 3814 4097 45759 3818 4097 45760 3806 4097 45761 3818 4097 45762 3822 4097 45763 3806 4097 45764 3846 4097 45765 3850 4097 45766 3838 4097 45767 3850 4097 45768 3854 4097 45769 3838 4097 45770 3854 4097 45771 3858 4097 45772 3862 4097 45773 3862 4097 45774 3866 4097 45775 3854 4097 45776 3866 4097 45777 3870 4097 45778 3854 4097 45779 3870 4097 45780 3874 4097 45781 3886 4097 45782 3874 4097 45783 3878 4097 45784 3886 4097 45785 3886 4097 45786 3890 4097 45787 3902 4097 45788 3890 4097 45789 3894 4097 45790 3902 4097 45791 3934 4097 45792 3938 4097 45793 3942 4097 45794 3990 4097 45795 3994 4097 45796 3982 4097 45797 3994 4097 45798 3998 4097 45799 3982 4097 45800 4006 4097 45801 4010 4097 45802 3998 4097 45803 4010 4097 45804 4014 4097 45805 3998 4097 45806 4022 4097 45807 4026 4097 45808 4014 4097 45809 4026 4097 45810 4030 4097 45811 4014 4097 45812 4086 4097 45813 4090 4097 45814 4078 4097 45815 4090 4097 45816 4094 4097 45817 4078 4097 45818 4094 4097 45819 4098 4097 45820 4102 4097 45821 4110 4097 45822 4114 4097 45823 4126 4097 45824 4114 4097 45825 4118 4097 45826 4126 4097 45827 4150 4097 45828 4154 4097 45829 4158 4097 45830 4166 4097 45831 4170 4097 45832 4158 4097 45833 4170 4097 45834 4174 4097 45835 4158 4097 45836 4190 4097 45837 4194 4097 45838 4206 4097 45839 4194 4097 45840 4198 4097 45841 4206 4097 45842 4206 4097 45843 4210 4097 45844 4222 4097 45845 4210 4097 45846 4214 4097 45847 4222 4097 45848 4230 4097 45849 4234 4097 45850 4222 4097 45851 4234 4097 45852 4238 4097 45853 4222 4097 45854 4270 4097 45855 4274 4097 45856 4286 4097 45857 4274 4097 45858 4278 4097 45859 4286 4097 45860 4286 4097 45861 4290 4097 45862 4302 4097 45863 4290 4097 45864 4294 4097 45865 4302 4097 45866 4302 4097 45867 4306 4097 45868 4318 4097 45869 4306 4097 45870 4310 4097 45871 4318 4097 45872 4310 4097 45873 4314 4097 45874 4318 4097 45875 4342 4097 45876 4346 4097 45877 4350 4097 45878 4350 4097 45879 4354 4097 45880 4366 4097 45881 4354 4097 45882 4358 4097 45883 4366 4097 45884 4366 4097 45885 4370 4097 45886 4374 4097 45887 4374 4097 45888 4378 4097 45889 4382 4097 45890 4382 4097 45891 4386 4097 45892 4398 4097 45893 4386 4097 45894 4390 4097 45895 4398 4097 45896 4398 4097 45897 4402 4097 45898 4406 4097 45899 4406 4097 45900 4410 4097 45901 4414 4097 45902 4414 4097 45903 4418 4097 45904 4430 4097 45905 4418 4097 45906 4422 4097 45907 4430 4097 45908 4438 4097 45909 4442 4097 45910 4430 4097 45911 4442 4097 45912 4446 4097 45913 4430 4097 45914 4446 4097 45915 4450 4097 45916 4454 4097 45917 4454 4097 45918 4458 4097 45919 4446 4097 45920 4458 4097 45921 4462 4097 45922 4446 4097 45923 4462 4097 45924 4466 4097 45925 4478 4097 45926 4466 4097 45927 4470 4097 45928 4478 4097 45929 4478 4097 45930 4482 4097 45931 4486 4097 45932 4486 4097 45933 4490 4097 45934 4494 4097 45935 4502 4097 45936 4506 4097 45937 4494 4097 45938 4506 4097 45939 4510 4097 45940 4494 4097 45941 4526 4097 45942 4530 4097 45943 4542 4097 45944 4530 4097 45945 4534 4097 45946 4542 4097 45947 4542 4097 45948 4546 4097 45949 4558 4097 45950 4546 4097 45951 4550 4097 45952 4558 4097 45953 4566 4097 45954 4570 4097 45955 4558 4097 45956 4570 4097 45957 4574 4097 45958 4558 4097 45959 4574 4097 45960 4578 4097 45961 4582 4097 45962 4582 4097 45963 4586 4097 45964 4590 4097 45965 4598 4097 45966 4602 4097 45967 4590 4097 45968 4602 4097 45969 4606 4097 45970 4590 4097 45971 4606 4097 45972 4610 4097 45973 4622 4097 45974 4610 4097 45975 4614 4097 45976 4622 4097 45977 4654 4097 45978 4658 4097 45979 4670 4097 45980 4658 4097 45981 4662 4097 45982 4670 4097 45983 4662 4097 45984 4666 4097 45985 4670 4097 45986 4670 4097 45987 4674 4097 45988 4678 4097 45989 4678 4097 45990 4682 4097 45991 4686 4097 45992 4702 4097 45993 4706 4097 45994 4718 4097 45995 4706 4097 45996 4710 4097 45997 4718 4097 45998 4710 4097 45999 4714 4097 46000 4718 4097 46001 4718 4097 46002 4722 4097 46003 4726 4097 46004 4750 4097 46005 4754 4097 46006 4766 4097 46007 4754 4097 46008 4758 4097 46009 4766 4097 46010 4758 4097 46011 4762 4097 46012 4766 4097 46013 4790 4097 46014 4794 4097 46015 4782 4097 46016 4794 4097 46017 4798 4097 46018 4782 4097 46019 4798 4097 46020 4802 4097 46021 4806 4097 46022 4814 4097 46023 4818 4097 46024 4822 4097 46025 4822 4097 46026 4826 4097 46027 4814 4097 46028 4826 4097 46029 4830 4097 46030 4814 4097 46031 4830 4097 46032 4834 4097 46033 4846 4097 46034 4834 4097 46035 4838 4097 46036 4846 4097 46037 4886 4097 46038 4890 4097 46039 4878 4097 46040 4890 4097 46041 4894 4097 46042 4878 4097 46043 4902 4097 46044 4906 4097 46045 4894 4097 46046 4906 4097 46047 4910 4097 46048 4894 4097 46049 4926 4097 46050 4930 4097 46051 4942 4097 46052 4930 4097 46053 4934 4097 46054 4942 4097 46055 4958 4097 46056 4962 4097 46057 4974 4097 46058 4962 4097 46059 4966 4097 46060 4974 4097 46061 4974 4097 46062 4978 4097 46063 4990 4097 46064 4978 4097 46065 4982 4097 46066 4990 4097 46067 4998 4097 46068 5002 4097 46069 4990 4097 46070 5002 4097 46071 5006 4097 46072 4990 4097 46073 5014 4097 46074 5018 4097 46075 5006 4097 46076 5018 4097 46077 5022 4097 46078 5006 4097 46079 5022 4097 46080 5026 4097 46081 5038 4097 46082 5026 4097 46083 5030 4097 46084 5038 4097 46085 5038 4097 46086 5042 4097 46087 5046 4097 46088 5046 4097 46089 5050 4097 46090 5054 4097 46091 5062 4097 46092 5066 4097 46093 5054 4097 46094 5066 4097 46095 5070 4097 46096 5054 4097 46097 5070 4097 46098 5074 4097 46099 5078 4097 46100 5086 4097 46101 5090 4097 46102 5102 4097 46103 5090 4097 46104 5094 4097 46105 5102 4097 46106 5110 4097 46107 5114 4097 46108 5102 4097 46109 5114 4097 46110 5118 4097 46111 5102 4097 46112 5126 4097 46113 5130 4097 46114 5134 4097 46115 5134 4097 46116 5138 4097 46117 5150 4097 46118 5138 4097 46119 5142 4097 46120 5150 4097 46121 5166 4097 46122 5170 4097 46123 5182 4097 46124 5170 4097 46125 5174 4097 46126 5182 4097 46127 5182 4097 46128 5186 4097 46129 5190 4097 46130 5190 4097 46131 5194 4097 46132 5198 4097 46133 5206 4097 46134 5210 4097 46135 5214 4097 46136 5246 4097 46137 5250 4097 46138 5262 4097 46139 5250 4097 46140 5254 4097 46141 5262 4097 46142 5270 4097 46143 5274 4097 46144 5262 4097 46145 5274 4097 46146 5278 4097 46147 5262 4097 46148 5294 4097 46149 5298 4097 46150 5310 4097 46151 5298 4097 46152 5302 4097 46153 5310 4097 46154 5310 4097 46155 5314 4097 46156 5326 4097 46157 5314 4097 46158 5318 4097 46159 5326 4097 46160 5326 4097 46161 5330 4097 46162 5334 4097 46163 5358 4097 46164 5362 4097 46165 5374 4097 46166 5362 4097 46167 5366 4097 46168 5374 4097 46169 5382 4097 46170 5386 4097 46171 5374 4097 46172 5386 4097 46173 5390 4097 46174 5374 4097 46175 5430 4097 46176 5434 4097 46177 5422 4097 46178 5434 4097 46179 5438 4097 46180 5422 4097 46181 5454 4097 46182 5458 4097 46183 5470 4097 46184 5458 4097 46185 5462 4097 46186 5470 4097 46187 5470 4097 46188 5474 4097 46189 5486 4097 46190 5474 4097 46191 5478 4097 46192 5486 4097 46193 5478 4097 46194 5482 4097 46195 5486 4097 46196 5486 4097 46197 5490 4097 46198 5494 4097 46199 5494 4097 46200 5498 4097 46201 5486 4097 46202 5498 4097 46203 5502 4097 46204 5486 4097 46205 5510 4097 46206 5514 4097 46207 5518 4097 46208 5518 4097 46209 5522 4097 46210 5534 4097 46211 5522 4097 46212 5526 4097 46213 5534 4097 46214 5542 4097 46215 5546 4097 46216 5534 4097 46217 5546 4097 46218 5550 4097 46219 5534 4097 46220 5550 4097 46221 5554 4097 46222 5558 4097 46223 5558 4097 46224 5562 4097 46225 5566 4097 46226 5566 4097 46227 5570 4097 46228 5574 4097 46229 5590 4097 46230 5594 4097 46231 5582 4097 46232 5594 4097 46233 5598 4097 46234 5582 4097 46235 5606 4097 46236 5610 4097 46237 5598 4097 46238 5610 4097 46239 5614 4097 46240 5598 4097 46241 5622 4097 46242 5626 4097 46243 5630 4097 46244 5654 4097 46245 5658 4097 46246 5662 4097 46247 5678 4097 46248 5682 4097 46249 5694 4097 46250 5682 4097 46251 5686 4097 46252 5694 4097 46253 5718 4097 46254 5722 4097 46255 5710 4097 46256 5722 4097 46257 5726 4097 46258 5710 4097 46259 5726 4097 46260 5730 4097 46261 5742 4097 46262 5730 4097 46263 5734 4097 46264 5742 4097 46265 5750 4097 46266 5754 4097 46267 5742 4097 46268 5754 4097 46269 5758 4097 46270 5742 4097 46271 5758 4097 46272 5762 4097 46273 5766 4097 46274 5806 4097 46275 5810 4097 46276 5822 4097 46277 5810 4097 46278 5814 4097 46279 5822 4097 46280 5822 4097 46281 5826 4097 46282 5830 4097 46283 5830 4097 46284 5834 4097 46285 5838 4097 46286 5838 4097 46287 5842 4097 46288 5846 4097 46289 5862 4097 46290 5866 4097 46291 5854 4097 46292 5866 4097 46293 5870 4097 46294 5854 4097 46295 5894 4097 46296 5898 4097 46297 5886 4097 46298 5898 4097 46299 5902 4097 46300 5886 4097 46301 5902 4097 46302 5906 4097 46303 5910 4097 46304 5910 4097 46305 5914 4097 46306 5902 4097 46307 5914 4097 46308 5918 4097 46309 5902 4097 46310 5918 4097 46311 5922 4097 46312 5934 4097 46313 5922 4097 46314 5926 4097 46315 5934 4097 46316 5934 4097 46317 5938 4097 46318 5950 4097 46319 5938 4097 46320 5942 4097 46321 5950 4097 46322 5982 4097 46323 5986 4097 46324 5990 4097 46325 6038 4097 46326 6042 4097 46327 6030 4097 46328 6042 4097 46329 6046 4097 46330 6030 4097 46331 6054 4097 46332 6058 4097 46333 6046 4097 46334 6058 4097 46335 6062 4097 46336 6046 4097 46337 6070 4097 46338 6074 4097 46339 6062 4097 46340 6074 4097 46341 6078 4097 46342 6062 4097 46343 6134 4097 46344 6138 4097 46345 6126 4097 46346 6138 4097 46347 6142 4097 46348 6126 4097 46349 6142 6125 46350 6146 6125 46351 6150 6125 46352 6158 4097 46353 6162 4097 46354 6174 4097 46355 6162 4097 46356 6166 4097 46357 6174 4097 46358 6198 4097 46359 6202 4097 46360 6206 4097 46361 6214 4097 46362 6218 4097 46363 6206 4097 46364 6218 4097 46365 6222 4097 46366 6206 4097 46367 6238 4097 46368 6242 4097 46369 6254 4097 46370 6242 4097 46371 6246 4097 46372 6254 4097 46373 6254 4097 46374 6258 4097 46375 6270 4097 46376 6258 4097 46377 6262 4097 46378 6270 4097 46379 6278 4097 46380 6282 4097 46381 6270 4097 46382 6282 4097 46383 6286 4097 46384 6270 4097 46385 6318 4097 46386 6322 4097 46387 6334 4097 46388 6322 4097 46389 6326 4097 46390 6334 4097 46391 6334 4097 46392 6338 4097 46393 6350 4097 46394 6338 4097 46395 6342 4097 46396 6350 4097 46397 6350 4097 46398 6354 4097 46399 6366 4097 46400 6354 4097 46401 6358 4097 46402 6366 4097 46403 6358 4097 46404 6362 4097 46405 6366 4097 46406 6390 4097 46407 6394 4097 46408 6398 4097 46409 6398 4097 46410 6402 4097 46411 6414 4097 46412 6402 4097 46413 6406 4097 46414 6414 4097 46415 6414 4097 46416 6418 4097 46417 6422 4097 46418 6422 4097 46419 6426 4097 46420 6430 4097 46421 6430 4097 46422 6434 4097 46423 6446 4097 46424 6434 4097 46425 6438 4097 46426 6446 4097 46427 6446 4097 46428 6450 4097 46429 6454 4097 46430 6454 4097 46431 6458 4097 46432 6462 4097 46433 6462 4097 46434 6466 4097 46435 6478 4097 46436 6466 4097 46437 6470 4097 46438 6478 4097 46439 6486 4097 46440 6490 4097 46441 6478 4097 46442 6490 4097 46443 6494 4097 46444 6478 4097 46445 6494 4097 46446 6498 4097 46447 6502 4097 46448 6502 4097 46449 6506 4097 46450 6494 4097 46451 6506 4097 46452 6510 4097 46453 6494 4097 46454 6510 4097 46455 6514 4097 46456 6526 4097 46457 6514 4097 46458 6518 4097 46459 6526 4097 46460 6526 4097 46461 6530 4097 46462 6534 4097 46463 6534 4097 46464 6538 4097 46465 6542 4097 46466 6550 4097 46467 6554 4097 46468 6542 4097 46469 6554 4097 46470 6558 4097 46471 6542 4097 46472 6574 4097 46473 6578 4097 46474 6590 4097 46475 6578 4097 46476 6582 4097 46477 6590 4097 46478 6590 4097 46479 6594 4097 46480 6606 4097 46481 6594 4097 46482 6598 4097 46483 6606 4097 46484 6614 4097 46485 6618 4097 46486 6606 4097 46487 6618 4097 46488 6622 4097 46489 6606 4097 46490 6622 4097 46491 6626 4097 46492 6630 4097 46493 6630 4097 46494 6634 4097 46495 6638 4097 46496 6646 4097 46497 6650 4097 46498 6638 4097 46499 6650 4097 46500 6654 4097 46501 6638 4097 46502 6654 4097 46503 6658 4097 46504 6670 4097 46505 6658 4097 46506 6662 4097 46507 6670 4097 46508 6702 4097 46509 6706 4097 46510 6718 4097 46511 6706 4097 46512 6710 4097 46513 6718 4097 46514 6710 4097 46515 6714 4097 46516 6718 4097 46517 6718 4097 46518 6722 4097 46519 6726 4097 46520 6726 4097 46521 6730 4097 46522 6734 4097 46523 6750 4097 46524 6754 4097 46525 6766 4097 46526 6754 4097 46527 6758 4097 46528 6766 4097 46529 6758 4097 46530 6762 4097 46531 6766 4097 46532 6766 4097 46533 6770 4097 46534 6774 4097 46535 6798 4097 46536 6802 4097 46537 6814 4097 46538 6802 4097 46539 6806 4097 46540 6814 4097 46541 6806 4097 46542 6810 4097 46543 6814 4097 46544 6838 4097 46545 6842 4097 46546 6830 4097 46547 6842 4097 46548 6846 4097 46549 6830 4097 46550 6846 4097 46551 6850 4097 46552 6854 4097 46553 6862 4097 46554 6866 4097 46555 6870 4097 46556 6870 4097 46557 6874 4097 46558 6862 4097 46559 6874 4097 46560 6878 4097 46561 6862 4097 46562 6878 4097 46563 6882 4097 46564 6894 4097 46565 6882 4097 46566 6886 4097 46567 6894 4097 46568 6934 4097 46569 6938 4097 46570 6926 4097 46571 6938 4097 46572 6942 4097 46573 6926 4097 46574 6950 4097 46575 6954 4097 46576 6942 4097 46577 6954 4097 46578 6958 4097 46579 6942 4097 46580 6974 4097 46581 6978 4097 46582 6990 4097 46583 6978 4097 46584 6982 4097 46585 6990 4097 46586 7006 4097 46587 7010 4097 46588 7022 4097 46589 7010 4097 46590 7014 4097 46591 7022 4097 46592 7022 4097 46593 7026 4097 46594 7038 4097 46595 7026 4097 46596 7030 4097 46597 7038 4097 46598 7046 4097 46599 7050 4097 46600 7038 4097 46601 7050 4097 46602 7054 4097 46603 7038 4097 46604 7062 4097 46605 7066 4097 46606 7054 4097 46607 7066 4097 46608 7070 4097 46609 7054 4097 46610 7070 4097 46611 7074 4097 46612 7086 4097 46613 7074 4097 46614 7078 4097 46615 7086 4097 46616 7086 4097 46617 7090 4097 46618 7094 4097 46619 7094 4097 46620 7098 4097 46621 7102 4097 46622 7110 4097 46623 7114 4097 46624 7102 4097 46625 7114 4097 46626 7118 4097 46627 7102 4097 46628 7118 4097 46629 7122 4097 46630 7126 4097 46631 7134 4097 46632 7138 4097 46633 7150 4097 46634 7138 4097 46635 7142 4097 46636 7150 4097 46637 7158 4097 46638 7162 4097 46639 7150 4097 46640 7162 4097 46641 7166 4097 46642 7150 4097 46643 7174 4097 46644 7178 4097 46645 7182 4097 46646 7182 4097 46647 7186 4097 46648 7198 4097 46649 7186 4097 46650 7190 4097 46651 7198 4097 46652 7214 4097 46653 7218 4097 46654 7230 4097 46655 7218 4097 46656 7222 4097 46657 7230 4097 46658 7230 4097 46659 7234 4097 46660 7238 4097 46661 7238 4097 46662 7242 4097 46663 7246 4097 46664 7254 4097 46665 7258 4097 46666 7262 4097 46667 7294 4097 46668 7298 4097 46669 7310 4097 46670 7298 4097 46671 7302 4097 46672 7310 4097 46673 7318 4097 46674 7322 4097 46675 7310 4097 46676 7322 4097 46677 7326 4097 46678 7310 4097 46679 7342 4097 46680 7346 4097 46681 7358 4097 46682 7346 4097 46683 7350 4097 46684 7358 4097 46685 7358 4097 46686 7362 4097 46687 7374 4097 46688 7362 4097 46689 7366 4097 46690 7374 4097 46691 7374 4097 46692 7378 4097 46693 7382 4097 46694 7406 4097 46695 7410 4097 46696 7422 4097 46697 7410 4097 46698 7414 4097 46699 7422 4097 46700 7430 4097 46701 7434 4097 46702 7422 4097 46703 7434 4097 46704 7438 4097 46705 7422 4097 46706 7478 4097 46707 7482 4097 46708 7470 4097 46709 7482 4097 46710 7486 4097 46711 7470 4097 46712 7502 4097 46713 7506 4097 46714 7518 4097 46715 7506 4097 46716 7510 4097 46717 7518 4097 46718 7518 4097 46719 7522 4097 46720 7534 4097 46721 7522 4097 46722 7526 4097 46723 7534 4097 46724 7526 4097 46725 7530 4097 46726 7534 4097 46727 7534 4097 46728 7538 4097 46729 7542 4097 46730 7542 4097 46731 7546 4097 46732 7534 4097 46733 7546 4097 46734 7550 4097 46735 7534 4097 46736 7558 4097 46737 7562 4097 46738 7566 4097 46739 7566 4097 46740 7570 4097 46741 7582 4097 46742 7570 4097 46743 7574 4097 46744 7582 4097 46745 7590 4097 46746 7594 4097 46747 7582 4097 46748 7594 4097 46749 7598 4097 46750 7582 4097 46751 7598 4097 46752 7602 4097 46753 7606 4097 46754 7606 4097 46755 7610 4097 46756 7614 4097 46757 7614 4097 46758 7618 4097 46759 7622 4097 46760 7638 4097 46761 7642 4097 46762 7630 4097 46763 7642 4097 46764 7646 4097 46765 7630 4097 46766 7654 4097 46767 7658 4097 46768 7646 4097 46769 7658 4097 46770 7662 4097 46771 7646 4097 46772 7670 4097 46773 7674 4097 46774 7678 4097 46775 7702 4097 46776 7706 4097 46777 7710 4097 46778 7726 4097 46779 7730 4097 46780 7742 4097 46781 7730 4097 46782 7734 4097 46783 7742 4097 46784 7766 4097 46785 7770 4097 46786 7758 4097 46787 7770 4097 46788 7774 4097 46789 7758 4097 46790 7774 4097 46791 7778 4097 46792 7790 4097 46793 7778 4097 46794 7782 4097 46795 7790 4097 46796 7798 4097 46797 7802 4097 46798 7790 4097 46799 7802 4097 46800 7806 4097 46801 7790 4097 46802 7806 4097 46803 7810 4097 46804 7814 4097 46805 7854 4097 46806 7858 4097 46807 7870 4097 46808 7858 4097 46809 7862 4097 46810 7870 4097 46811 7870 4097 46812 7874 4097 46813 7878 4097 46814 7878 4097 46815 7882 4097 46816 7886 4097 46817 7886 4097 46818 7890 4097 46819 7894 4097 46820 7910 4097 46821 7914 4097 46822 7902 4097 46823 7914 4097 46824 7918 4097 46825 7902 4097 46826 7942 4097 46827 7946 4097 46828 7934 4097 46829 7946 4097 46830 7950 4097 46831 7934 4097 46832 7950 4097 46833 7954 4097 46834 7958 4097 46835 7958 4097 46836 7962 4097 46837 7950 4097 46838 7962 4097 46839 7966 4097 46840 7950 4097 46841 7966 4097 46842 7970 4097 46843 7982 4097 46844 7970 4097 46845 7974 4097 46846 7982 4097 46847 7982 4097 46848 7986 4097 46849 7998 4097 46850 7986 4097 46851 7990 4097 46852 7998 4097 46853 8030 4097 46854 8034 4097 46855 8038 4097 46856 8086 4097 46857 8090 4097 46858 8078 4097 46859 8090 4097 46860 8094 4097 46861 8078 4097 46862 8102 4097 46863 8106 4097 46864 8094 4097 46865 8106 4097 46866 8110 4097 46867 8094 4097 46868 8118 4097 46869 8122 4097 46870 8110 4097 46871 8122 4097 46872 8126 4097 46873 8110 4097 46874 8182 4097 46875 8186 4097 46876 8174 4097 46877 8186 4097 46878 8190 4097 46879 8174 4097 46880 8190 4097 46881 6 4097 46882 30 4097 46883 6 4097 46884 14 4097 46885 30 4097 46886 30 4097 46887 38 4097 46888 46 4097 46889 46 4097 46890 54 4097 46891 62 4097 46892 78 4097 46893 86 4097 46894 62 4097 46895 86 4097 46896 94 4097 46897 62 4097 46898 142 4097 46899 150 4097 46900 126 4097 46901 150 4097 46902 158 4097 46903 126 4097 46904 158 4097 46905 166 4097 46906 190 4097 46907 166 4097 46908 174 4097 46909 190 4097 46910 222 4097 46911 230 4097 46912 238 4097 46913 238 4097 46914 246 4097 46915 222 4097 46916 246 4097 46917 254 4097 46918 222 4097 46919 270 4097 46920 278 4097 46921 254 4097 46922 278 4097 46923 286 4097 46924 254 4097 46925 302 4097 46926 310 4097 46927 286 4097 46928 310 4097 46929 318 4097 46930 286 4097 46931 382 4097 46932 390 4097 46933 414 4097 46934 390 4097 46935 398 4097 46936 414 4097 46937 414 4097 46938 422 4097 46939 430 4097 46940 478 4097 46941 486 4097 46942 510 4097 46943 486 4097 46944 494 4097 46945 510 4097 46946 526 4097 46947 534 4097 46948 542 4097 46949 542 4097 46950 550 4097 46951 574 4097 46952 550 4097 46953 558 4097 46954 574 4097 46955 574 4097 46956 582 4097 46957 590 4097 46958 590 4097 46959 598 4097 46960 574 4097 46961 598 4097 46962 606 4097 46963 574 4097 46964 622 4097 46965 630 4097 46966 638 4097 46967 638 4097 46968 646 4097 46969 670 4097 46970 646 4097 46971 654 4097 46972 670 4097 46973 670 4097 46974 678 4097 46975 686 4097 46976 702 4097 46977 710 4097 46978 734 4097 46979 710 4097 46980 718 4097 46981 734 4097 46982 750 4097 46983 758 4097 46984 734 4097 46985 758 4097 46986 766 4097 46987 734 4097 46988 766 4097 46989 774 4097 46990 782 4097 46991 814 4097 46992 822 4097 46993 830 4097 46994 846 4097 46995 854 4097 46996 862 4097 46997 942 4097 46998 950 4097 46999 926 4097 47000 950 4097 47001 958 4097 47002 926 4097 47003 974 4097 47004 982 4097 47005 990 4097 47006 1022 4097 47007 1030 4097 47008 1054 4097 47009 1030 4097 47010 1038 4097 47011 1054 4097 47012 1054 4097 47013 1062 4097 47014 1070 4097 47015 1086 4097 47016 1094 4097 47017 1118 4097 47018 1094 4097 47019 1102 4097 47020 1118 4097 47021 1102 4097 47022 1110 4097 47023 1118 4097 47024 1118 4097 47025 1126 4097 47026 1150 4097 47027 1126 4097 47028 1134 4097 47029 1150 4097 47030 1134 4097 47031 1142 4097 47032 1150 4097 47033 1182 4097 47034 1190 4097 47035 1198 4097 47036 1230 4097 47037 1238 4097 47038 1214 4097 47039 1238 4097 47040 1246 4097 47041 1214 4097 47042 1246 4097 47043 1254 4097 47044 1278 4097 47045 1254 4097 47046 1262 4097 47047 1278 4097 47048 1294 4097 47049 1302 4097 47050 1278 4097 47051 1302 4097 47052 1310 4097 47053 1278 4097 47054 1310 4097 47055 1318 4097 47056 1342 4097 47057 1318 4097 47058 1326 4097 47059 1342 4097 47060 1342 4097 47061 1350 4097 47062 1358 4097 47063 1406 4097 47064 1414 4097 47065 1438 4097 47066 1414 4097 47067 1422 4097 47068 1438 4097 47069 1454 4097 47070 1462 4097 47071 1438 4097 47072 1462 4097 47073 1470 4097 47074 1438 4097 47075 1470 4097 47076 1478 4097 47077 1486 4097 47078 1518 4097 47079 1526 4097 47080 1502 4097 47081 1526 4097 47082 1534 4097 47083 1502 4097 47084 1534 4097 47085 1542 4097 47086 1550 4097 47087 1550 4097 47088 1558 4097 47089 1566 4097 47090 1566 4097 47091 1574 4097 47092 1598 4097 47093 1574 4097 47094 1582 4097 47095 1598 4097 47096 1598 4097 47097 1606 4097 47098 1614 4097 47099 1662 4097 47100 1670 4097 47101 1678 4097 47102 1678 4097 47103 1686 4097 47104 1694 4097 47105 1694 4097 47106 1702 4097 47107 1726 4097 47108 1702 4097 47109 1710 4097 47110 1726 4097 47111 1726 4097 47112 1734 4097 47113 1758 4097 47114 1734 4097 47115 1742 4097 47116 1758 4097 47117 1742 4097 47118 1750 4097 47119 1758 4097 47120 1774 4097 47121 1782 4097 47122 1790 4097 47123 1854 4097 47124 1862 4097 47125 1870 4097 47126 1870 4097 47127 1878 4097 47128 1886 4097 47129 1886 4097 47130 1894 4097 47131 1918 4097 47132 1894 4097 47133 1902 4097 47134 1918 4097 47135 1902 4097 47136 1910 4097 47137 1918 4097 47138 1918 4097 47139 1926 4097 47140 1934 4097 47141 1982 4097 47142 1990 4097 47143 2014 4097 47144 1990 4097 47145 1998 4097 47146 2014 4097 47147 1998 4097 47148 2006 4097 47149 2014 4097 47150 2014 4097 47151 2022 4097 47152 2030 4097 47153 2046 6126 47154 2054 6126 47155 2078 6126 47156 2054 4097 47157 2062 4097 47158 2078 4097 47159 2078 4097 47160 2086 4097 47161 2094 4097 47162 2094 4097 47163 2102 4097 47164 2110 4097 47165 2126 4097 47166 2134 4097 47167 2110 4097 47168 2134 4097 47169 2142 4097 47170 2110 4097 47171 2190 4097 47172 2198 4097 47173 2174 4097 47174 2198 4097 47175 2206 4097 47176 2174 4097 47177 2206 4097 47178 2214 4097 47179 2238 4097 47180 2214 4097 47181 2222 4097 47182 2238 4097 47183 2270 4097 47184 2278 4097 47185 2286 4097 47186 2286 4097 47187 2294 4097 47188 2270 4097 47189 2294 4097 47190 2302 4097 47191 2270 4097 47192 2318 4097 47193 2326 4097 47194 2302 4097 47195 2326 4097 47196 2334 4097 47197 2302 4097 47198 2350 4097 47199 2358 4097 47200 2334 4097 47201 2358 4097 47202 2366 4097 47203 2334 4097 47204 2430 4097 47205 2438 4097 47206 2462 4097 47207 2438 4097 47208 2446 4097 47209 2462 4097 47210 2462 4097 47211 2470 4097 47212 2478 4097 47213 2526 4097 47214 2534 4097 47215 2558 4097 47216 2534 4097 47217 2542 4097 47218 2558 4097 47219 2574 4097 47220 2582 4097 47221 2590 4097 47222 2590 4097 47223 2598 4097 47224 2622 4097 47225 2598 4097 47226 2606 4097 47227 2622 4097 47228 2622 4097 47229 2630 4097 47230 2638 4097 47231 2638 4097 47232 2646 4097 47233 2622 4097 47234 2646 4097 47235 2654 4097 47236 2622 4097 47237 2670 4097 47238 2678 4097 47239 2686 4097 47240 2686 4097 47241 2694 4097 47242 2718 4097 47243 2694 4097 47244 2702 4097 47245 2718 4097 47246 2718 4097 47247 2726 4097 47248 2734 4097 47249 2750 4097 47250 2758 4097 47251 2782 4097 47252 2758 4097 47253 2766 4097 47254 2782 4097 47255 2798 4097 47256 2806 4097 47257 2782 4097 47258 2806 4097 47259 2814 4097 47260 2782 4097 47261 2814 4097 47262 2822 4097 47263 2830 4097 47264 2862 4097 47265 2870 4097 47266 2878 4097 47267 2894 4097 47268 2902 4097 47269 2910 4097 47270 2990 4097 47271 2998 4097 47272 2974 4097 47273 2998 4097 47274 3006 4097 47275 2974 4097 47276 3022 4097 47277 3030 4097 47278 3038 4097 47279 3070 4097 47280 3078 4097 47281 3102 4097 47282 3078 4097 47283 3086 4097 47284 3102 4097 47285 3102 4097 47286 3110 4097 47287 3118 4097 47288 3134 4097 47289 3142 4097 47290 3166 4097 47291 3142 4097 47292 3150 4097 47293 3166 4097 47294 3150 4097 47295 3158 4097 47296 3166 4097 47297 3166 4097 47298 3174 4097 47299 3198 4097 47300 3174 4097 47301 3182 4097 47302 3198 4097 47303 3182 4097 47304 3190 4097 47305 3198 4097 47306 3230 4097 47307 3238 4097 47308 3246 4097 47309 3278 4097 47310 3286 4097 47311 3262 4097 47312 3286 4097 47313 3294 4097 47314 3262 4097 47315 3294 4097 47316 3302 4097 47317 3326 4097 47318 3302 4097 47319 3310 4097 47320 3326 4097 47321 3342 4097 47322 3350 4097 47323 3326 4097 47324 3350 4097 47325 3358 4097 47326 3326 4097 47327 3358 4097 47328 3366 4097 47329 3390 4097 47330 3366 4097 47331 3374 4097 47332 3390 4097 47333 3390 4097 47334 3398 4097 47335 3406 4097 47336 3454 4097 47337 3462 4097 47338 3486 4097 47339 3462 4097 47340 3470 4097 47341 3486 4097 47342 3502 4097 47343 3510 4097 47344 3486 4097 47345 3510 4097 47346 3518 4097 47347 3486 4097 47348 3518 4097 47349 3526 4097 47350 3534 4097 47351 3566 4097 47352 3574 4097 47353 3550 4097 47354 3574 4097 47355 3582 4097 47356 3550 4097 47357 3582 4097 47358 3590 4097 47359 3598 4097 47360 3598 4097 47361 3606 4097 47362 3614 4097 47363 3614 4097 47364 3622 4097 47365 3646 4097 47366 3622 4097 47367 3630 4097 47368 3646 4097 47369 3646 4097 47370 3654 4097 47371 3662 4097 47372 3710 4097 47373 3718 4097 47374 3726 4097 47375 3726 4097 47376 3734 4097 47377 3742 4097 47378 3742 4097 47379 3750 4097 47380 3774 4097 47381 3750 4097 47382 3758 4097 47383 3774 4097 47384 3774 4097 47385 3782 4097 47386 3806 4097 47387 3782 4097 47388 3790 4097 47389 3806 4097 47390 3790 4097 47391 3798 4097 47392 3806 4097 47393 3822 4097 47394 3830 4097 47395 3838 4097 47396 3902 4097 47397 3910 4097 47398 3918 4097 47399 3918 4097 47400 3926 4097 47401 3934 4097 47402 3934 4097 47403 3942 4097 47404 3966 4097 47405 3942 4097 47406 3950 4097 47407 3966 4097 47408 3950 4097 47409 3958 4097 47410 3966 4097 47411 3966 4097 47412 3974 4097 47413 3982 4097 47414 4030 4097 47415 4038 4097 47416 4062 4097 47417 4038 4097 47418 4046 4097 47419 4062 4097 47420 4046 4097 47421 4054 4097 47422 4062 4097 47423 4062 4097 47424 4070 4097 47425 4078 4097 47426 4094 4097 47427 4102 4097 47428 4126 4097 47429 4102 4097 47430 4110 4097 47431 4126 4097 47432 4126 4097 47433 4134 4097 47434 4142 4097 47435 4142 4097 47436 4150 4097 47437 4158 4097 47438 4174 4097 47439 4182 4097 47440 4158 4097 47441 4182 4097 47442 4190 4097 47443 4158 4097 47444 4238 4097 47445 4246 4097 47446 4222 4097 47447 4246 4097 47448 4254 4097 47449 4222 4097 47450 4254 4097 47451 4262 4097 47452 4286 4097 47453 4262 4097 47454 4270 4097 47455 4286 4097 47456 4318 4097 47457 4326 4097 47458 4334 4097 47459 4334 4097 47460 4342 4097 47461 4318 4097 47462 4342 4097 47463 4350 4097 47464 4318 4097 47465 4366 4097 47466 4374 4097 47467 4350 4097 47468 4374 4097 47469 4382 4097 47470 4350 4097 47471 4398 4097 47472 4406 4097 47473 4382 4097 47474 4406 4097 47475 4414 4097 47476 4382 4097 47477 4478 4097 47478 4486 4097 47479 4510 4097 47480 4486 4097 47481 4494 4097 47482 4510 4097 47483 4510 4097 47484 4518 4097 47485 4526 4097 47486 4574 4097 47487 4582 4097 47488 4606 4097 47489 4582 4097 47490 4590 4097 47491 4606 4097 47492 4622 4097 47493 4630 4097 47494 4638 4097 47495 4638 4097 47496 4646 4097 47497 4670 4097 47498 4646 4097 47499 4654 4097 47500 4670 4097 47501 4670 4097 47502 4678 4097 47503 4686 4097 47504 4686 4097 47505 4694 4097 47506 4670 4097 47507 4694 4097 47508 4702 4097 47509 4670 4097 47510 4718 4097 47511 4726 4097 47512 4734 4097 47513 4734 4097 47514 4742 4097 47515 4766 4097 47516 4742 4097 47517 4750 4097 47518 4766 4097 47519 4766 4097 47520 4774 4097 47521 4782 4097 47522 4798 4097 47523 4806 4097 47524 4830 4097 47525 4806 4097 47526 4814 4097 47527 4830 4097 47528 4846 4097 47529 4854 4097 47530 4830 4097 47531 4854 4097 47532 4862 4097 47533 4830 4097 47534 4862 4097 47535 4870 4097 47536 4878 4097 47537 4910 4097 47538 4918 4097 47539 4926 4097 47540 4942 4097 47541 4950 4097 47542 4958 4097 47543 5038 4097 47544 5046 4097 47545 5022 4097 47546 5046 4097 47547 5054 4097 47548 5022 4097 47549 5070 4097 47550 5078 4097 47551 5086 4097 47552 5118 4097 47553 5126 4097 47554 5150 4097 47555 5126 4097 47556 5134 4097 47557 5150 4097 47558 5150 4097 47559 5158 4097 47560 5166 4097 47561 5182 4097 47562 5190 4097 47563 5214 4097 47564 5190 4097 47565 5198 4097 47566 5214 4097 47567 5198 4097 47568 5206 4097 47569 5214 4097 47570 5214 4097 47571 5222 4097 47572 5246 4097 47573 5222 4097 47574 5230 4097 47575 5246 4097 47576 5230 4097 47577 5238 4097 47578 5246 4097 47579 5278 4097 47580 5286 4097 47581 5294 4097 47582 5326 4097 47583 5334 4097 47584 5310 4097 47585 5334 4097 47586 5342 4097 47587 5310 4097 47588 5342 4097 47589 5350 4097 47590 5374 4097 47591 5350 4097 47592 5358 4097 47593 5374 4097 47594 5390 4097 47595 5398 4097 47596 5374 4097 47597 5398 4097 47598 5406 4097 47599 5374 4097 47600 5406 4097 47601 5414 4097 47602 5438 4097 47603 5414 4097 47604 5422 4097 47605 5438 4097 47606 5438 4097 47607 5446 4097 47608 5454 4097 47609 5502 4097 47610 5510 4097 47611 5534 4097 47612 5510 4097 47613 5518 4097 47614 5534 4097 47615 5550 4097 47616 5558 4097 47617 5534 4097 47618 5558 4097 47619 5566 4097 47620 5534 4097 47621 5566 4097 47622 5574 4097 47623 5582 4097 47624 5614 4097 47625 5622 4097 47626 5598 4097 47627 5622 4097 47628 5630 4097 47629 5598 4097 47630 5630 4097 47631 5638 4097 47632 5646 4097 47633 5646 4097 47634 5654 4097 47635 5662 4097 47636 5662 4097 47637 5670 4097 47638 5694 4097 47639 5670 4097 47640 5678 4097 47641 5694 4097 47642 5694 4097 47643 5702 4097 47644 5710 4097 47645 5758 4097 47646 5766 4097 47647 5774 4097 47648 5774 4097 47649 5782 4097 47650 5790 4097 47651 5790 4097 47652 5798 4097 47653 5822 4097 47654 5798 4097 47655 5806 4097 47656 5822 4097 47657 5822 4097 47658 5830 4097 47659 5854 4097 47660 5830 4097 47661 5838 4097 47662 5854 4097 47663 5838 4097 47664 5846 4097 47665 5854 4097 47666 5870 4097 47667 5878 4097 47668 5886 4097 47669 5950 4097 47670 5958 4097 47671 5966 4097 47672 5966 4097 47673 5974 4097 47674 5982 4097 47675 5982 4097 47676 5990 4097 47677 6014 4097 47678 5990 4097 47679 5998 4097 47680 6014 4097 47681 5998 4097 47682 6006 4097 47683 6014 4097 47684 6014 4097 47685 6022 4097 47686 6030 4097 47687 6078 4097 47688 6086 4097 47689 6110 4097 47690 6086 4097 47691 6094 4097 47692 6110 4097 47693 6094 4097 47694 6102 4097 47695 6110 4097 47696 6110 4097 47697 6118 4097 47698 6126 4097 47699 6142 6127 47700 6150 6127 47701 6174 6127 47702 6150 4097 47703 6158 4097 47704 6174 4097 47705 6174 4097 47706 6182 4097 47707 6190 4097 47708 6190 4097 47709 6198 4097 47710 6206 4097 47711 6222 4097 47712 6230 4097 47713 6206 4097 47714 6230 4097 47715 6238 4097 47716 6206 4097 47717 6286 4097 47718 6294 4097 47719 6270 4097 47720 6294 4097 47721 6302 4097 47722 6270 4097 47723 6302 4097 47724 6310 4097 47725 6334 4097 47726 6310 4097 47727 6318 4097 47728 6334 4097 47729 6366 4097 47730 6374 4097 47731 6382 4097 47732 6382 4097 47733 6390 4097 47734 6366 4097 47735 6390 4097 47736 6398 4097 47737 6366 4097 47738 6414 4097 47739 6422 4097 47740 6398 4097 47741 6422 4097 47742 6430 4097 47743 6398 4097 47744 6446 4097 47745 6454 4097 47746 6430 4097 47747 6454 4097 47748 6462 4097 47749 6430 4097 47750 6526 4097 47751 6534 4097 47752 6558 4097 47753 6534 4097 47754 6542 4097 47755 6558 4097 47756 6558 4097 47757 6566 4097 47758 6574 4097 47759 6622 4097 47760 6630 4097 47761 6654 4097 47762 6630 4097 47763 6638 4097 47764 6654 4097 47765 6670 4097 47766 6678 4097 47767 6686 4097 47768 6686 4097 47769 6694 4097 47770 6718 4097 47771 6694 4097 47772 6702 4097 47773 6718 4097 47774 6718 4097 47775 6726 4097 47776 6734 4097 47777 6734 4097 47778 6742 4097 47779 6718 4097 47780 6742 4097 47781 6750 4097 47782 6718 4097 47783 6766 4097 47784 6774 4097 47785 6782 4097 47786 6782 4097 47787 6790 4097 47788 6814 4097 47789 6790 4097 47790 6798 4097 47791 6814 4097 47792 6814 4097 47793 6822 4097 47794 6830 4097 47795 6846 4097 47796 6854 4097 47797 6878 4097 47798 6854 4097 47799 6862 4097 47800 6878 4097 47801 6894 4097 47802 6902 4097 47803 6878 4097 47804 6902 4097 47805 6910 4097 47806 6878 4097 47807 6910 4097 47808 6918 4097 47809 6926 4097 47810 6958 4097 47811 6966 4097 47812 6974 4097 47813 6990 4097 47814 6998 4097 47815 7006 4097 47816 7086 4097 47817 7094 4097 47818 7070 4097 47819 7094 4097 47820 7102 4097 47821 7070 4097 47822 7118 4097 47823 7126 4097 47824 7134 4097 47825 7166 4097 47826 7174 4097 47827 7198 4097 47828 7174 4097 47829 7182 4097 47830 7198 4097 47831 7198 4097 47832 7206 4097 47833 7214 4097 47834 7230 4097 47835 7238 4097 47836 7262 4097 47837 7238 4097 47838 7246 4097 47839 7262 4097 47840 7246 4097 47841 7254 4097 47842 7262 4097 47843 7262 4097 47844 7270 4097 47845 7294 4097 47846 7270 4097 47847 7278 4097 47848 7294 4097 47849 7278 4097 47850 7286 4097 47851 7294 4097 47852 7326 4097 47853 7334 4097 47854 7342 4097 47855 7374 4097 47856 7382 4097 47857 7358 4097 47858 7382 4097 47859 7390 4097 47860 7358 4097 47861 7390 4097 47862 7398 4097 47863 7422 4097 47864 7398 4097 47865 7406 4097 47866 7422 4097 47867 7438 4097 47868 7446 4097 47869 7422 4097 47870 7446 4097 47871 7454 4097 47872 7422 4097 47873 7454 4097 47874 7462 4097 47875 7486 4097 47876 7462 4097 47877 7470 4097 47878 7486 4097 47879 7486 4097 47880 7494 4097 47881 7502 4097 47882 7550 4097 47883 7558 4097 47884 7582 4097 47885 7558 4097 47886 7566 4097 47887 7582 4097 47888 7598 4097 47889 7606 4097 47890 7582 4097 47891 7606 4097 47892 7614 4097 47893 7582 4097 47894 7614 4097 47895 7622 4097 47896 7630 4097 47897 7662 4097 47898 7670 4097 47899 7646 4097 47900 7670 4097 47901 7678 4097 47902 7646 4097 47903 7678 4097 47904 7686 4097 47905 7694 4097 47906 7694 4097 47907 7702 4097 47908 7710 4097 47909 7710 4097 47910 7718 4097 47911 7742 4097 47912 7718 4097 47913 7726 4097 47914 7742 4097 47915 7742 4097 47916 7750 4097 47917 7758 4097 47918 7806 4097 47919 7814 4097 47920 7822 4097 47921 7822 4097 47922 7830 4097 47923 7838 4097 47924 7838 4097 47925 7846 4097 47926 7870 4097 47927 7846 4097 47928 7854 4097 47929 7870 4097 47930 7870 4097 47931 7878 4097 47932 7902 4097 47933 7878 4097 47934 7886 4097 47935 7902 4097 47936 7886 4097 47937 7894 4097 47938 7902 4097 47939 7918 4097 47940 7926 4097 47941 7934 4097 47942 7998 4097 47943 8006 4097 47944 8014 4097 47945 8014 4097 47946 8022 4097 47947 8030 4097 47948 8030 4097 47949 8038 4097 47950 8062 4097 47951 8038 4097 47952 8046 4097 47953 8062 4097 47954 8046 4097 47955 8054 4097 47956 8062 4097 47957 8062 4097 47958 8070 4097 47959 8078 4097 47960 8126 4097 47961 8134 4097 47962 8158 4097 47963 8134 4097 47964 8142 4097 47965 8158 4097 47966 8142 4097 47967 8150 4097 47968 8158 4097 47969 8158 4097 47970 8166 4097 47971 8174 4097 47972 30 4097 47973 46 4097 47974 8190 4097 47975 46 4097 47976 62 4097 47977 8190 4097 47978 94 4097 47979 110 4097 47980 62 4097 47981 110 4097 47982 126 4097 47983 62 4097 47984 190 4097 47985 206 4097 47986 222 4097 47987 318 4097 47988 334 4097 47989 350 4097 47990 350 4097 47991 366 4097 47992 382 4097 47993 414 4097 47994 430 4097 47995 446 4097 47996 446 4097 47997 462 4097 47998 510 4097 47999 462 4097 48000 478 4097 48001 510 4097 48002 510 4097 48003 526 4097 48004 574 4097 48005 526 4097 48006 542 4097 48007 574 4097 48008 606 4097 48009 622 4097 48010 574 4097 48011 622 4097 48012 638 4097 48013 574 4097 48014 670 4097 48015 686 4097 48016 702 4097 48017 766 4097 48018 782 4097 48019 798 4097 48020 798 4097 48021 814 4097 48022 766 4097 48023 814 4097 48024 830 4097 48025 766 4097 48026 830 4097 48027 846 4097 48028 894 4097 48029 846 4097 48030 862 4097 48031 894 4097 48032 862 4097 48033 878 4097 48034 894 4097 48035 894 4097 48036 910 4097 48037 926 4097 48038 958 4097 48039 974 4097 48040 990 4097 48041 990 4097 48042 1006 4097 48043 1022 4097 48044 1054 4097 48045 1070 4097 48046 1086 4097 48047 1150 4097 48048 1166 4097 48049 1214 4097 48050 1166 4097 48051 1182 4097 48052 1214 4097 48053 1182 4097 48054 1198 4097 48055 1214 4097 48056 1342 4097 48057 1358 4097 48058 1374 4097 48059 1374 4097 48060 1390 4097 48061 1342 4097 48062 1390 4097 48063 1406 4097 48064 1342 4097 48065 1470 4097 48066 1486 4097 48067 1534 4097 48068 1486 4097 48069 1502 4097 48070 1534 4097 48071 1534 4097 48072 1550 4097 48073 1598 4097 48074 1550 4097 48075 1566 4097 48076 1598 4097 48077 1598 4097 48078 1614 4097 48079 1662 4097 48080 1614 4097 48081 1630 4097 48082 1662 4097 48083 1630 4097 48084 1646 4097 48085 1662 4097 48086 1662 4097 48087 1678 4097 48088 1726 4097 48089 1678 4097 48090 1694 4097 48091 1726 4097 48092 1758 4097 48093 1774 4097 48094 1726 4097 48095 1774 4097 48096 1790 4097 48097 1726 4097 48098 1790 4097 48099 1806 4097 48100 1822 4097 48101 1822 4097 48102 1838 4097 48103 1790 4097 48104 1838 4097 48105 1854 4097 48106 1790 4097 48107 1854 4097 48108 1870 4097 48109 1918 4097 48110 1870 4097 48111 1886 4097 48112 1918 4097 48113 1918 4097 48114 1934 4097 48115 1950 4097 48116 1950 4097 48117 1966 4097 48118 1982 4097 48119 2014 4097 48120 2030 4097 48121 1982 4097 48122 2030 4097 48123 2046 4097 48124 1982 4097 48125 2078 6128 48126 2094 6128 48127 2046 6128 48128 2094 4097 48129 2110 4097 48130 2046 4097 48131 2142 4097 48132 2158 4097 48133 2110 4097 48134 2158 4097 48135 2174 4097 48136 2110 4097 48137 2238 4097 48138 2254 4097 48139 2270 4097 48140 2366 4097 48141 2382 4097 48142 2398 4097 48143 2398 4097 48144 2414 4097 48145 2430 4097 48146 2462 4097 48147 2478 4097 48148 2494 4097 48149 2494 4097 48150 2510 4097 48151 2558 4097 48152 2510 4097 48153 2526 4097 48154 2558 4097 48155 2558 4097 48156 2574 4097 48157 2622 4097 48158 2574 4097 48159 2590 4097 48160 2622 4097 48161 2654 4097 48162 2670 4097 48163 2622 4097 48164 2670 4097 48165 2686 4097 48166 2622 4097 48167 2718 4097 48168 2734 4097 48169 2750 4097 48170 2814 4097 48171 2830 4097 48172 2846 4097 48173 2846 4097 48174 2862 4097 48175 2814 4097 48176 2862 4097 48177 2878 4097 48178 2814 4097 48179 2878 4097 48180 2894 4097 48181 2942 4097 48182 2894 4097 48183 2910 4097 48184 2942 4097 48185 2910 4097 48186 2926 4097 48187 2942 4097 48188 2942 4097 48189 2958 4097 48190 2974 4097 48191 3006 4097 48192 3022 4097 48193 3038 4097 48194 3038 4097 48195 3054 4097 48196 3070 4097 48197 3102 4097 48198 3118 4097 48199 3134 4097 48200 3198 4097 48201 3214 4097 48202 3262 4097 48203 3214 4097 48204 3230 4097 48205 3262 4097 48206 3230 4097 48207 3246 4097 48208 3262 4097 48209 3390 4097 48210 3406 4097 48211 3422 4097 48212 3422 4097 48213 3438 4097 48214 3390 4097 48215 3438 4097 48216 3454 4097 48217 3390 4097 48218 3518 4097 48219 3534 4097 48220 3582 4097 48221 3534 4097 48222 3550 4097 48223 3582 4097 48224 3582 4097 48225 3598 4097 48226 3646 4097 48227 3598 4097 48228 3614 4097 48229 3646 4097 48230 3646 4097 48231 3662 4097 48232 3710 4097 48233 3662 4097 48234 3678 4097 48235 3710 4097 48236 3678 4097 48237 3694 4097 48238 3710 4097 48239 3710 4097 48240 3726 4097 48241 3774 4097 48242 3726 4097 48243 3742 4097 48244 3774 4097 48245 3806 4097 48246 3822 4097 48247 3774 4097 48248 3822 4097 48249 3838 4097 48250 3774 4097 48251 3838 4097 48252 3854 4097 48253 3870 4097 48254 3870 4097 48255 3886 4097 48256 3838 4097 48257 3886 4097 48258 3902 4097 48259 3838 4097 48260 3902 4097 48261 3918 4097 48262 3966 4097 48263 3918 4097 48264 3934 4097 48265 3966 4097 48266 3966 4097 48267 3982 4097 48268 3998 4097 48269 3998 4097 48270 4014 4097 48271 4030 4097 48272 4062 4097 48273 4078 4097 48274 4030 4097 48275 4078 4097 48276 4094 4097 48277 4030 4097 48278 4126 4097 48279 4142 4097 48280 4094 4097 48281 4142 4097 48282 4158 4097 48283 4094 4097 48284 4190 4097 48285 4206 4097 48286 4158 4097 48287 4206 4097 48288 4222 4097 48289 4158 4097 48290 4286 4097 48291 4302 4097 48292 4318 4097 48293 4414 4097 48294 4430 4097 48295 4446 4097 48296 4446 4097 48297 4462 4097 48298 4478 4097 48299 4510 4097 48300 4526 4097 48301 4542 4097 48302 4542 4097 48303 4558 4097 48304 4606 4097 48305 4558 4097 48306 4574 4097 48307 4606 4097 48308 4606 4097 48309 4622 4097 48310 4670 4097 48311 4622 4097 48312 4638 4097 48313 4670 4097 48314 4702 4097 48315 4718 4097 48316 4670 4097 48317 4718 4097 48318 4734 4097 48319 4670 4097 48320 4766 4097 48321 4782 4097 48322 4798 4097 48323 4862 4097 48324 4878 4097 48325 4894 4097 48326 4894 4097 48327 4910 4097 48328 4862 4097 48329 4910 4097 48330 4926 4097 48331 4862 4097 48332 4926 4097 48333 4942 4097 48334 4990 4097 48335 4942 4097 48336 4958 4097 48337 4990 4097 48338 4958 4097 48339 4974 4097 48340 4990 4097 48341 4990 4097 48342 5006 4097 48343 5022 4097 48344 5054 4097 48345 5070 4097 48346 5086 4097 48347 5086 4097 48348 5102 4097 48349 5118 4097 48350 5150 4097 48351 5166 4097 48352 5182 4097 48353 5246 4097 48354 5262 4097 48355 5310 4097 48356 5262 4097 48357 5278 4097 48358 5310 4097 48359 5278 4097 48360 5294 4097 48361 5310 4097 48362 5438 4097 48363 5454 4097 48364 5470 4097 48365 5470 4097 48366 5486 4097 48367 5438 4097 48368 5486 4097 48369 5502 4097 48370 5438 4097 48371 5566 4097 48372 5582 4097 48373 5630 4097 48374 5582 4097 48375 5598 4097 48376 5630 4097 48377 5630 4097 48378 5646 4097 48379 5694 4097 48380 5646 4097 48381 5662 4097 48382 5694 4097 48383 5694 4097 48384 5710 4097 48385 5758 4097 48386 5710 4097 48387 5726 4097 48388 5758 4097 48389 5726 4097 48390 5742 4097 48391 5758 4097 48392 5758 4097 48393 5774 4097 48394 5822 4097 48395 5774 4097 48396 5790 4097 48397 5822 4097 48398 5854 4097 48399 5870 4097 48400 5822 4097 48401 5870 4097 48402 5886 4097 48403 5822 4097 48404 5886 4097 48405 5902 4097 48406 5918 4097 48407 5918 4097 48408 5934 4097 48409 5886 4097 48410 5934 4097 48411 5950 4097 48412 5886 4097 48413 5950 4097 48414 5966 4097 48415 6014 4097 48416 5966 4097 48417 5982 4097 48418 6014 4097 48419 6014 4097 48420 6030 4097 48421 6046 4097 48422 6046 4097 48423 6062 4097 48424 6078 4097 48425 6110 4097 48426 6126 4097 48427 6078 4097 48428 6126 4097 48429 6142 4097 48430 6078 4097 48431 6174 6129 48432 6190 6129 48433 6142 6129 48434 6190 4097 48435 6206 4097 48436 6142 4097 48437 6238 4097 48438 6254 4097 48439 6206 4097 48440 6254 4097 48441 6270 4097 48442 6206 4097 48443 6334 4097 48444 6350 4097 48445 6366 4097 48446 6462 4097 48447 6478 4097 48448 6494 4097 48449 6494 4097 48450 6510 4097 48451 6526 4097 48452 6558 4097 48453 6574 4097 48454 6590 4097 48455 6590 4097 48456 6606 4097 48457 6654 4097 48458 6606 4097 48459 6622 4097 48460 6654 4097 48461 6654 4097 48462 6670 4097 48463 6718 4097 48464 6670 4097 48465 6686 4097 48466 6718 4097 48467 6750 4097 48468 6766 4097 48469 6718 4097 48470 6766 4097 48471 6782 4097 48472 6718 4097 48473 6814 4097 48474 6830 4097 48475 6846 4097 48476 6910 4097 48477 6926 4097 48478 6942 4097 48479 6942 4097 48480 6958 4097 48481 6910 4097 48482 6958 4097 48483 6974 4097 48484 6910 4097 48485 6974 4097 48486 6990 4097 48487 7038 4097 48488 6990 4097 48489 7006 4097 48490 7038 4097 48491 7006 4097 48492 7022 4097 48493 7038 4097 48494 7038 4097 48495 7054 4097 48496 7070 4097 48497 7102 4097 48498 7118 4097 48499 7134 4097 48500 7134 4097 48501 7150 4097 48502 7166 4097 48503 7198 4097 48504 7214 4097 48505 7230 4097 48506 7294 4097 48507 7310 4097 48508 7358 4097 48509 7310 4097 48510 7326 4097 48511 7358 4097 48512 7326 4097 48513 7342 4097 48514 7358 4097 48515 7486 4097 48516 7502 4097 48517 7518 4097 48518 7518 4097 48519 7534 4097 48520 7486 4097 48521 7534 4097 48522 7550 4097 48523 7486 4097 48524 7614 4097 48525 7630 4097 48526 7678 4097 48527 7630 4097 48528 7646 4097 48529 7678 4097 48530 7678 4097 48531 7694 4097 48532 7742 4097 48533 7694 4097 48534 7710 4097 48535 7742 4097 48536 7742 4097 48537 7758 4097 48538 7806 4097 48539 7758 4097 48540 7774 4097 48541 7806 4097 48542 7774 4097 48543 7790 4097 48544 7806 4097 48545 7806 4097 48546 7822 4097 48547 7870 4097 48548 7822 4097 48549 7838 4097 48550 7870 4097 48551 7902 4097 48552 7918 4097 48553 7870 4097 48554 7918 4097 48555 7934 4097 48556 7870 4097 48557 7934 4097 48558 7950 4097 48559 7966 4097 48560 7966 4097 48561 7982 4097 48562 7934 4097 48563 7982 4097 48564 7998 4097 48565 7934 4097 48566 7998 4097 48567 8014 4097 48568 8062 4097 48569 8014 4097 48570 8030 4097 48571 8062 4097 48572 8062 4097 48573 8078 4097 48574 8094 4097 48575 8094 4097 48576 8110 4097 48577 8126 4097 48578 8158 4097 48579 8174 4097 48580 8126 4097 48581 8174 4097 48582 8190 4097 48583 8126 4097 48584 126 4097 48585 158 4097 48586 254 4097 48587 158 4097 48588 190 4097 48589 254 4097 48590 190 4097 48591 222 4097 48592 254 4097 48593 254 4097 48594 286 4097 48595 318 4097 48596 318 4097 48597 350 4097 48598 254 4097 48599 350 4097 48600 382 4097 48601 254 4097 48602 382 4097 48603 414 4097 48604 510 4097 48605 414 4097 48606 446 4097 48607 510 4097 48608 638 4097 48609 670 4097 48610 766 4097 48611 670 4097 48612 702 4097 48613 766 4097 48614 702 4097 48615 734 4097 48616 766 4097 48617 894 4097 48618 926 4097 48619 958 4097 48620 958 4097 48621 990 4097 48622 894 4097 48623 990 4097 48624 1022 4097 48625 894 4097 48626 1022 4097 48627 1054 4097 48628 1086 4097 48629 1086 4097 48630 1118 4097 48631 1022 4097 48632 1118 4097 48633 1150 4097 48634 1022 4097 48635 1214 4097 48636 1246 4097 48637 1278 4097 48638 1278 4097 48639 1310 4097 48640 1406 4097 48641 1310 4097 48642 1342 4097 48643 1406 4097 48644 1406 4097 48645 1438 4097 48646 1534 4097 48647 1438 4097 48648 1470 4097 48649 1534 4097 48650 1918 4097 48651 1950 4097 48652 2046 4097 48653 1950 6130 48654 1982 6130 48655 2046 6130 48656 2174 4097 48657 2206 4097 48658 2302 4097 48659 2206 4097 48660 2238 4097 48661 2302 4097 48662 2238 4097 48663 2270 4097 48664 2302 4097 48665 2302 4097 48666 2334 4097 48667 2366 4097 48668 2366 4097 48669 2398 4097 48670 2302 4097 48671 2398 4097 48672 2430 4097 48673 2302 4097 48674 2430 4097 48675 2462 4097 48676 2558 4097 48677 2462 4097 48678 2494 4097 48679 2558 4097 48680 2686 4097 48681 2718 4097 48682 2814 4097 48683 2718 4097 48684 2750 4097 48685 2814 4097 48686 2750 4097 48687 2782 4097 48688 2814 4097 48689 2942 4097 48690 2974 4097 48691 3006 4097 48692 3006 4097 48693 3038 4097 48694 2942 4097 48695 3038 4097 48696 3070 4097 48697 2942 4097 48698 3070 4097 48699 3102 4097 48700 3134 4097 48701 3134 4097 48702 3166 4097 48703 3070 4097 48704 3166 4097 48705 3198 4097 48706 3070 4097 48707 3262 4097 48708 3294 4097 48709 3326 4097 48710 3326 4097 48711 3358 4097 48712 3454 4097 48713 3358 4097 48714 3390 4097 48715 3454 4097 48716 3454 4097 48717 3486 4097 48718 3582 4097 48719 3486 4097 48720 3518 4097 48721 3582 4097 48722 3966 4097 48723 3998 4097 48724 4094 4097 48725 3998 4097 48726 4030 4097 48727 4094 4097 48728 4222 4097 48729 4254 4097 48730 4350 4097 48731 4254 4097 48732 4286 4097 48733 4350 4097 48734 4286 4097 48735 4318 4097 48736 4350 4097 48737 4350 4097 48738 4382 4097 48739 4414 4097 48740 4414 4097 48741 4446 4097 48742 4350 4097 48743 4446 4097 48744 4478 4097 48745 4350 4097 48746 4478 4097 48747 4510 4097 48748 4606 4097 48749 4510 4097 48750 4542 4097 48751 4606 4097 48752 4734 4097 48753 4766 4097 48754 4862 4097 48755 4766 4097 48756 4798 4097 48757 4862 4097 48758 4798 4097 48759 4830 4097 48760 4862 4097 48761 4990 4097 48762 5022 4097 48763 5054 4097 48764 5054 4097 48765 5086 4097 48766 4990 4097 48767 5086 4097 48768 5118 4097 48769 4990 4097 48770 5118 4097 48771 5150 4097 48772 5182 4097 48773 5182 4097 48774 5214 4097 48775 5118 4097 48776 5214 4097 48777 5246 4097 48778 5118 4097 48779 5310 4097 48780 5342 4097 48781 5374 4097 48782 5374 4097 48783 5406 4097 48784 5502 4097 48785 5406 4097 48786 5438 4097 48787 5502 4097 48788 5502 4097 48789 5534 4097 48790 5630 4097 48791 5534 4097 48792 5566 4097 48793 5630 4097 48794 6014 4097 48795 6046 4097 48796 6142 4097 48797 6046 6131 48798 6078 6131 48799 6142 6131 48800 6270 4097 48801 6302 4097 48802 6398 4097 48803 6302 4097 48804 6334 4097 48805 6398 4097 48806 6334 4097 48807 6366 4097 48808 6398 4097 48809 6398 4097 48810 6430 4097 48811 6462 4097 48812 6462 4097 48813 6494 4097 48814 6398 4097 48815 6494 4097 48816 6526 4097 48817 6398 4097 48818 6526 4097 48819 6558 4097 48820 6654 4097 48821 6558 4097 48822 6590 4097 48823 6654 4097 48824 6782 4097 48825 6814 4097 48826 6910 4097 48827 6814 4097 48828 6846 4097 48829 6910 4097 48830 6846 4097 48831 6878 4097 48832 6910 4097 48833 7038 4097 48834 7070 4097 48835 7102 4097 48836 7102 4097 48837 7134 4097 48838 7038 4097 48839 7134 4097 48840 7166 4097 48841 7038 4097 48842 7166 4097 48843 7198 4097 48844 7230 4097 48845 7230 4097 48846 7262 4097 48847 7166 4097 48848 7262 4097 48849 7294 4097 48850 7166 4097 48851 7358 4097 48852 7390 4097 48853 7422 4097 48854 7422 4097 48855 7454 4097 48856 7550 4097 48857 7454 4097 48858 7486 4097 48859 7550 4097 48860 7550 4097 48861 7582 4097 48862 7678 4097 48863 7582 4097 48864 7614 4097 48865 7678 4097 48866 8062 4097 48867 8094 4097 48868 8190 4097 48869 8094 4097 48870 8126 4097 48871 8190 4097 48872 8190 4097 48873 62 4097 48874 254 4097 48875 62 4097 48876 126 4097 48877 254 4097 48878 510 4097 48879 574 4097 48880 766 4097 48881 574 4097 48882 638 4097 48883 766 4097 48884 766 4097 48885 830 4097 48886 894 4097 48887 1150 4097 48888 1214 4097 48889 1022 4097 48890 1214 4097 48891 1278 4097 48892 1022 4097 48893 1534 4097 48894 1598 4097 48895 1662 4097 48896 1662 4097 48897 1726 4097 48898 1534 4097 48899 1726 4097 48900 1790 4097 48901 1534 4097 48902 1790 4097 48903 1854 4097 48904 2046 4097 48905 1854 6132 48906 1918 6132 48907 2046 6132 48908 2046 6133 48909 2110 6133 48910 2302 6133 48911 2110 6134 48912 2174 6134 48913 2302 6134 48914 2558 4097 48915 2622 4097 48916 2814 4097 48917 2622 4097 48918 2686 4097 48919 2814 4097 48920 2814 4097 48921 2878 4097 48922 2942 4097 48923 3198 4097 48924 3262 4097 48925 3070 4097 48926 3262 4097 48927 3326 4097 48928 3070 4097 48929 3582 4097 48930 3646 4097 48931 3710 4097 48932 3710 4097 48933 3774 4097 48934 3582 4097 48935 3774 4097 48936 3838 4097 48937 3582 4097 48938 3838 4097 48939 3902 4097 48940 4094 4097 48941 3902 4097 48942 3966 4097 48943 4094 4097 48944 4094 4097 48945 4158 4097 48946 4350 4097 48947 4158 4097 48948 4222 4097 48949 4350 4097 48950 4606 4097 48951 4670 4097 48952 4862 4097 48953 4670 4097 48954 4734 4097 48955 4862 4097 48956 4862 4097 48957 4926 4097 48958 4990 4097 48959 5246 4097 48960 5310 4097 48961 5118 4097 48962 5310 4097 48963 5374 4097 48964 5118 4097 48965 5630 4097 48966 5694 4097 48967 5758 4097 48968 5758 4097 48969 5822 4097 48970 5630 4097 48971 5822 4097 48972 5886 4097 48973 5630 4097 48974 5886 4097 48975 5950 4097 48976 6142 4097 48977 5950 6135 48978 6014 6135 48979 6142 6135 48980 6142 6136 48981 6206 6136 48982 6398 6136 48983 6206 6137 48984 6270 6137 48985 6398 6137 48986 6654 4097 48987 6718 4097 48988 6910 4097 48989 6718 4097 48990 6782 4097 48991 6910 4097 48992 6910 4097 48993 6974 4097 48994 7038 4097 48995 7294 4097 48996 7358 4097 48997 7166 4097 48998 7358 4097 48999 7422 4097 49000 7166 4097 49001 7678 4097 49002 7742 4097 49003 7806 4097 49004 7806 4097 49005 7870 4097 49006 7678 4097 49007 7870 4097 49008 7934 4097 49009 7678 4097 49010 7934 4097 49011 7998 4097 49012 8190 4097 49013 7998 4097 49014 8062 4097 49015 8190 4097 49016 254 4097 49017 382 4097 49018 510 4097 49019 766 4097 49020 894 4097 49021 1022 4097 49022 1278 4097 49023 1406 4097 49024 1022 4097 49025 1406 4097 49026 1534 4097 49027 1022 4097 49028 2302 4097 49029 2430 4097 49030 2558 4097 49031 2814 4097 49032 2942 4097 49033 3070 4097 49034 3326 4097 49035 3454 4097 49036 3070 4097 49037 3454 4097 49038 3582 4097 49039 3070 4097 49040 4350 4097 49041 4478 4097 49042 4606 4097 49043 4862 4097 49044 4990 4097 49045 5118 4097 49046 5374 4097 49047 5502 4097 49048 5118 4097 49049 5502 4097 49050 5630 4097 49051 5118 4097 49052 6398 4097 49053 6526 4097 49054 6654 4097 49055 6910 4097 49056 7038 4097 49057 7166 4097 49058 7422 4097 49059 7550 4097 49060 7166 4097 49061 7550 4097 49062 7678 4097 49063 7166 4097 49064 8190 4097 49065 254 4097 49066 510 4097 49067 510 4097 49068 766 4097 49069 8190 4097 49070 766 4097 49071 1022 4097 49072 8190 4097 49073 1534 4097 49074 1790 4097 49075 2046 4097 49076 2046 4097 49077 2302 4097 49078 2558 4097 49079 2558 4097 49080 2814 4097 49081 2046 4097 49082 2814 4097 49083 3070 4097 49084 2046 4097 49085 3582 4097 49086 3838 4097 49087 4094 4097 49088 4094 4097 49089 4350 4097 49090 4606 4097 49091 4606 4097 49092 4862 4097 49093 4094 4097 49094 4862 4097 49095 5118 4097 49096 4094 4097 49097 5630 4097 49098 5886 4097 49099 6142 4097 49100 6142 4097 49101 6398 4097 49102 6654 4097 49103 6654 4097 49104 6910 4097 49105 6142 4097 49106 6910 4097 49107 7166 4097 49108 6142 4097 49109 7678 4097 49110 7934 4097 49111 8190 4097 49112 1022 4097 49113 1534 4097 49114 8190 4097 49115 1534 4097 49116 2046 4097 49117 8190 4097 49118 3070 4097 49119 3582 4097 49120 2046 4097 49121 3582 4097 49122 4094 4097 49123 2046 4097 49124 5118 4097 49125 5630 4097 49126 4094 4097 49127 5630 4097 49128 6142 4097 49129 4094 4097 49130 7166 4097 49131 7678 4097 49132 6142 4097 49133 7678 4097 49134 8190 4097 49135 6142 4097 49136 8190 4097 49137 2046 4097 49138 4094 4097 49139

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + +
diff --git a/test/worlds/models/cylinder_dae/model.config b/test/worlds/models/cylinder_dae/model.config new file mode 100644 index 0000000000..012a5f420b --- /dev/null +++ b/test/worlds/models/cylinder_dae/model.config @@ -0,0 +1,16 @@ + + + + cylinder_dae + 1.0 + model.sdf + + + Jasmeet Singh + jasmeet0915@gmail.com + + + + A model of a Cylinder collada + + diff --git a/test/worlds/models/cylinder_dae/model.sdf b/test/worlds/models/cylinder_dae/model.sdf new file mode 100644 index 0000000000..5300256593 --- /dev/null +++ b/test/worlds/models/cylinder_dae/model.sdf @@ -0,0 +1,47 @@ + + + + + 0 0 0 0 0 0 + + + 1240.0 + + 0.01 + + + + meshes/cylinder.dae + + + + + 0 0 0 0 0 0 + + + meshes/cylinder.dae + + + + 0.7 0.7 0.7 1.0 + 0.7 0.7 0.7 1.0 + 0.7 0.7 0.7 1.0 + + + + 3 0 0 0 0 0 + + + 1 + 2.0 + + + + 0.7 0.0 0.0 1.0 + 0.7 0.7 0.7 1.0 + 0.7 0.7 0.7 1.0 + + + + + From ecc91e84d474102d2178ee576d37b705db953593 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Thu, 31 Aug 2023 22:29:16 +0200 Subject: [PATCH 03/50] Remove GZ_PHYSICS_ENGINE_INSTALL_DIR deprecation warnings (#2106) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- src/systems/physics/EntityFeatureMap_TEST.cc | 3 ++- src/systems/physics/Physics.cc | 3 ++- test/integration/tracked_vehicle_system.cc | 3 ++- 3 files changed, 6 insertions(+), 3 deletions(-) diff --git a/src/systems/physics/EntityFeatureMap_TEST.cc b/src/systems/physics/EntityFeatureMap_TEST.cc index 948d83851a..40fd0d9abf 100644 --- a/src/systems/physics/EntityFeatureMap_TEST.cc +++ b/src/systems/physics/EntityFeatureMap_TEST.cc @@ -25,6 +25,7 @@ #include #include #include +#include #include #include #include @@ -57,7 +58,7 @@ class EntityFeatureMapFixture: public InternalFixture<::testing::Test> const std::string pluginLib = "gz-physics-dartsim-plugin"; common::SystemPaths systemPaths; - systemPaths.AddPluginPaths({GZ_PHYSICS_ENGINE_INSTALL_DIR}); + systemPaths.AddPluginPaths(gz::physics::getEngineInstallDir()); auto pathToLib = systemPaths.FindSharedLibrary(pluginLib); ASSERT_FALSE(pathToLib.empty()) diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 047e209db9..1f6defbf44 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -48,6 +48,7 @@ #include #include #include +#include #include #include @@ -806,7 +807,7 @@ void Physics::Configure(const Entity &_entity, // * Engines installed with gz-physics common::SystemPaths systemPaths; systemPaths.SetPluginPathEnv(this->dataPtr->pluginPathEnv); - systemPaths.AddPluginPaths({GZ_PHYSICS_ENGINE_INSTALL_DIR}); + systemPaths.AddPluginPaths(gz::physics::getEngineInstallDir()); auto pathToLib = systemPaths.FindSharedLibrary(pluginLib); diff --git a/test/integration/tracked_vehicle_system.cc b/test/integration/tracked_vehicle_system.cc index 69b7155f07..b68a1de002 100644 --- a/test/integration/tracked_vehicle_system.cc +++ b/test/integration/tracked_vehicle_system.cc @@ -33,6 +33,7 @@ #include #include #include +#include #include #include #include @@ -111,7 +112,7 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> // modifications) common::SystemPaths systemPaths; systemPaths.SetPluginPathEnv("GZ_SIM_PHYSICS_ENGINE_PATH"); - systemPaths.AddPluginPaths({GZ_PHYSICS_ENGINE_INSTALL_DIR}); + systemPaths.AddPluginPaths(gz::physics::getEngineInstallDir()); auto pathToLib = systemPaths.FindSharedLibrary(*pluginLib); ASSERT_FALSE(pathToLib.empty()) From 71797164192fb79b98ccb388e14e5e949705762d Mon Sep 17 00:00:00 2001 From: Mabel Zhang Date: Fri, 1 Sep 2023 16:00:22 -0400 Subject: [PATCH 04/50] fix broken link to API (#2108) Signed-off-by: Mabel Zhang --- tutorials/terminology.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tutorials/terminology.md b/tutorials/terminology.md index b4e8df5e6c..58e29b40e9 100644 --- a/tutorials/terminology.md +++ b/tutorials/terminology.md @@ -10,14 +10,14 @@ to developers touching the source code. * **Entity**: Every "object" in the world, such as models, links, collisions, visuals, lights, joints, etc. - An entity [is just a numeric ID](namespace gz_1_1gazebo.html#ad83694d867b0e3a9446b535b5dfd208d), + An entity [is just a numeric ID](namespacegz_1_1sim.html#ad83694d867b0e3a9446b535b5dfd208d), and may have several components attached to it. Entity IDs are assigned at runtime. * **Component**: Adds a certain functionality or characteristic (e.g., pose, name, material, etc.) to an entity. Gazebo comes with various - [components](namespace gz_1_1gazebo_1_1components.html) + [components](namespacegz_1_1sim_1_1components.html) ready to be used, such as `Pose` and `Inertial`, and downstream developers can also create their own by inheriting from the [BaseComponent](classignition_1_1gazebo_1_1components_1_1BaseComponent.html) From 2dbcc6c872a204e44f4dd3e3be8c44a98b04452f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Thu, 31 Aug 2023 22:29:16 +0200 Subject: [PATCH 05/50] Remove GZ_PHYSICS_ENGINE_INSTALL_DIR deprecation warnings (#2106) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- src/systems/physics/EntityFeatureMap_TEST.cc | 3 ++- src/systems/physics/Physics.cc | 3 ++- test/integration/tracked_vehicle_system.cc | 3 ++- 3 files changed, 6 insertions(+), 3 deletions(-) diff --git a/src/systems/physics/EntityFeatureMap_TEST.cc b/src/systems/physics/EntityFeatureMap_TEST.cc index 948d83851a..40fd0d9abf 100644 --- a/src/systems/physics/EntityFeatureMap_TEST.cc +++ b/src/systems/physics/EntityFeatureMap_TEST.cc @@ -25,6 +25,7 @@ #include #include #include +#include #include #include #include @@ -57,7 +58,7 @@ class EntityFeatureMapFixture: public InternalFixture<::testing::Test> const std::string pluginLib = "gz-physics-dartsim-plugin"; common::SystemPaths systemPaths; - systemPaths.AddPluginPaths({GZ_PHYSICS_ENGINE_INSTALL_DIR}); + systemPaths.AddPluginPaths(gz::physics::getEngineInstallDir()); auto pathToLib = systemPaths.FindSharedLibrary(pluginLib); ASSERT_FALSE(pathToLib.empty()) diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 8cd8991eed..33e3db4224 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -48,6 +48,7 @@ #include #include #include +#include #include #include @@ -811,7 +812,7 @@ void Physics::Configure(const Entity &_entity, // * Engines installed with gz-physics common::SystemPaths systemPaths; systemPaths.SetPluginPathEnv(this->dataPtr->pluginPathEnv); - systemPaths.AddPluginPaths({GZ_PHYSICS_ENGINE_INSTALL_DIR}); + systemPaths.AddPluginPaths(gz::physics::getEngineInstallDir()); auto pathToLib = systemPaths.FindSharedLibrary(pluginLib); if (pathToLib.empty()) diff --git a/test/integration/tracked_vehicle_system.cc b/test/integration/tracked_vehicle_system.cc index 919939f79c..5d5f57ef8c 100644 --- a/test/integration/tracked_vehicle_system.cc +++ b/test/integration/tracked_vehicle_system.cc @@ -27,6 +27,7 @@ #include #include #include +#include #include #include #include @@ -105,7 +106,7 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> // modifications) common::SystemPaths systemPaths; systemPaths.SetPluginPathEnv("GZ_SIM_PHYSICS_ENGINE_PATH"); - systemPaths.AddPluginPaths({GZ_PHYSICS_ENGINE_INSTALL_DIR}); + systemPaths.AddPluginPaths(gz::physics::getEngineInstallDir()); auto pathToLib = systemPaths.FindSharedLibrary(*pluginLib); ASSERT_FALSE(pathToLib.empty()) From 58a0c0b8a0375ae2918d9cc2525d755a21002e62 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Fri, 1 Sep 2023 22:48:35 +0200 Subject: [PATCH 06/50] Fix typos. (#2114) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- tutorials/underwater_vehicles.md | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/tutorials/underwater_vehicles.md b/tutorials/underwater_vehicles.md index dfed5a7d9a..b9210618a9 100644 --- a/tutorials/underwater_vehicles.md +++ b/tutorials/underwater_vehicles.md @@ -1,6 +1,6 @@ \page underwater_vehicles Underwater vehicles -## Simulating Autnomous Underwater Vehicles +## Simulating Autonomous Underwater Vehicles Gazebo now supports basic simulation of underwater vehicles. This capability is based on the equations described in Fossen's ["Guidance and @@ -108,8 +108,8 @@ name="gz::sim::systems::Hydrodynamics"> Just like aeroplanes, an underwater vehicle may also use fins for stability and control. Fortunately, Gazebo already has a version of the LiftDrag plugin. In this tutorial, we will simply add two liftdrag plugins to the rudder and -elevator of MBARI's Tethys. For more info about the liftdrag plugin inluding -what the parameters mean you may look +elevator of MBARI's Tethys. For more info about the liftdrag plugin including +what the parameters mean, you may look at [this gazebo classic tutorial](http://gazebosim.org/tutorials?tut=aerodynamics&cat=physics). Essentially when we tilt the fins, we should experience a lift force which will cause the vehicle to experience a torque and the vehicle should start @@ -152,7 +152,7 @@ name="gz::sim::systems::LiftDrag"> 0 0 0 ``` -The number in this case were kindly provided by MBARI for the Tethys. +The numbers in this case were kindly provided by MBARI for the Tethys. We also need to be able to control the position of the thruster fins so we will use the joint controller plugin. ```xml From 5ebf860793c36a04c02be03c52e3713ebe6ba450 Mon Sep 17 00:00:00 2001 From: Bi0T1N <28802083+Bi0T1N@users.noreply.github.com> Date: Tue, 5 Sep 2023 21:04:01 +0200 Subject: [PATCH 07/50] Fix default topic name of JointStatePublisher (#2115) * Fix default topic name of JointStatePublisher the default topic name is specified as /joint_state in JointStatePublisher.cc --------- Signed-off-by: Bi0T1N Co-authored-by: Bi0T1N --- src/systems/joint_state_publisher/JointStatePublisher.hh | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/systems/joint_state_publisher/JointStatePublisher.hh b/src/systems/joint_state_publisher/JointStatePublisher.hh index c83d9a1197..28d2408091 100644 --- a/src/systems/joint_state_publisher/JointStatePublisher.hh +++ b/src/systems/joint_state_publisher/JointStatePublisher.hh @@ -33,8 +33,8 @@ namespace sim inline namespace GZ_SIM_VERSION_NAMESPACE { namespace systems { - /// \brief The JointStatePub system publishes state information for - /// a model. The published message type is gz::msgs::Model, and the + /// \brief The JointStatePublisher system publishes joint state information + /// for a model. The published message type is gz::msgs::Model, and the /// publication topic is determined by the `` parameter. /// /// By default the JointStatePublisher will publish all joints for @@ -45,7 +45,7 @@ namespace systems /// /// ``: Name of the topic to publish to. This parameter is optional, /// and if not provided, the joint state will be published to - /// "/world//model//state". + /// "/world//model//joint_state". /// ``: Name of a joint to publish. This parameter can be /// specified multiple times, and is optional. All joints in a model will /// be published if joint names are not specified. From b938768006899602bc5927c8ef30ef1a4dd0ca1b Mon Sep 17 00:00:00 2001 From: Bi0T1N <28802083+Bi0T1N@users.noreply.github.com> Date: Tue, 5 Sep 2023 21:57:11 +0200 Subject: [PATCH 08/50] Add link to existing issue (#2116) Signed-off-by: Bi0T1N Co-authored-by: Bi0T1N --- tutorials/terminology.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/tutorials/terminology.md b/tutorials/terminology.md index 58e29b40e9..5dd9cc8fea 100644 --- a/tutorials/terminology.md +++ b/tutorials/terminology.md @@ -73,7 +73,8 @@ to developers touching the source code. more than 1 world. * It has a single ECM with all the entities and components relevant to the levels / world / performer being simulated. - * It's still TBD how to support multiple `` in parallel. + * It's still [an open task](https://github.com/gazebosim/gz-sim/issues/18) + to support multiple `` in parallel. * It has an event manager. * It has a network manager, if simulation is distributed. * It loads up a set of systems. From 5bb1b1c6b0954bb2d849dfb53fe50f0e59f0c7bd Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Tue, 5 Sep 2023 21:57:45 -0700 Subject: [PATCH 09/50] Fix thrust cmd topic in underwater tutorial (#2120) Signed-off-by: Ian Chen --- tutorials/underwater_vehicles.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/tutorials/underwater_vehicles.md b/tutorials/underwater_vehicles.md index dfed5a7d9a..ede396e9f5 100644 --- a/tutorials/underwater_vehicles.md +++ b/tutorials/underwater_vehicles.md @@ -55,9 +55,9 @@ rpm. Under the `` or `` tag add the following: 0.2 ``` -Now if we were to publish to `/model/tethys/joint/propeller_joint/cmd_pos` +Now if we were to publish to `/model/tethys/joint/propeller_joint/cmd_thrust` ``` -gz topic -t /model/tethys/joint/propeller_joint/cmd_pos \ +gz topic -t /model/tethys/joint/propeller_joint/cmd_thrust \ -m gz.msgs.Double -p 'data: -31' ``` we should see the model move. The thrusters are governed by the equation on @@ -185,7 +185,7 @@ gz topic -t /model/tethys/joint/vertical_fins_joint/0/cmd_pos \ ``` To apply a thrust you may run the following command ``` -gz topic -t /model/tethys/joint/propeller_joint/cmd_pos \ +gz topic -t /model/tethys/joint/propeller_joint/cmd_thrust \ -m gz.msgs.Double -p 'data: -31' ``` The vehicle should move in a circle. From b43325915e5e464878286c69c68f894aaa57c40a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 7 Sep 2023 17:29:35 +0200 Subject: [PATCH 10/50] Removed warning in sensors_demos.sdf (#2122) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- examples/worlds/sensors_demo.sdf | 1 - 1 file changed, 1 deletion(-) diff --git a/examples/worlds/sensors_demo.sdf b/examples/worlds/sensors_demo.sdf index 7bc724857f..ad40dafc3a 100644 --- a/examples/worlds/sensors_demo.sdf +++ b/examples/worlds/sensors_demo.sdf @@ -417,7 +417,6 @@ 0.01 - 1 true From 491fa232b721776f72850a5a4174e1ec6e7cc6d4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 7 Sep 2023 18:37:58 +0200 Subject: [PATCH 11/50] Fixed invalid service names (#2121) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- src/SimulationRunner.cc | 12 ++++++++++-- src/systems/user_commands/UserCommands.cc | 4 ++-- 2 files changed, 12 insertions(+), 4 deletions(-) diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc index a52fcb030a..4f628a3906 100644 --- a/src/SimulationRunner.cc +++ b/src/SimulationRunner.cc @@ -47,7 +47,7 @@ #include "gz/sim/Events.hh" #include "gz/sim/SdfEntityCreator.hh" #include "gz/sim/Util.hh" - +#include "gz/transport/TopicUtils.hh" #include "network/NetworkManagerPrimary.hh" #include "SdfGenerator.hh" @@ -100,7 +100,15 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, } // Keep world name - this->worldName = _world->Name(); + this->worldName = transport::TopicUtils::AsValidTopic(_world->Name()); + + auto validWorldName = transport::TopicUtils::AsValidTopic(worldName); + if (this->worldName.empty()) + { + gzerr << "Can't start simulation runner with this world name [" + << worldName << "]." << std::endl; + return; + } this->parametersRegistry = std::make_unique< gz::transport::parameters::ParametersRegistry>( diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 73e66e36e0..c5796c5d7e 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -648,7 +648,7 @@ void UserCommands::Configure(const Entity &_entity, // Pose vector service std::string poseVectorService{ - "/world/" + worldName + "/set_pose_vector"}; + "/world/" + validWorldName + "/set_pose_vector"}; this->dataPtr->node.Advertise(poseVectorService, &UserCommandsPrivate::PoseVectorService, this->dataPtr.get()); @@ -702,7 +702,7 @@ void UserCommands::Configure(const Entity &_entity, // Visual service std::string visualService - {"/world/" + worldName + "/visual_config"}; + {"/world/" + validWorldName + "/visual_config"}; this->dataPtr->node.Advertise(visualService, &UserCommandsPrivate::VisualService, this->dataPtr.get()); From 9055d88c7dc7abd2a3291fb00e88b2c68bbcbcdc Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Thu, 7 Sep 2023 14:09:18 -0700 Subject: [PATCH 12/50] fix move to model (#2126) Signed-off-by: Ian Chen --- src/gui/plugins/view_angle/ViewAngle.cc | 4 +--- tutorials/move_camera_to_model.md | 6 +++--- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/src/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc index cc451cf264..fd430488ed 100644 --- a/src/gui/plugins/view_angle/ViewAngle.cc +++ b/src/gui/plugins/view_angle/ViewAngle.cc @@ -338,9 +338,7 @@ bool ViewAngle::OnMoveToModelService(const gz::msgs::GUICamera &_msg, Entity entityId = kNullEntity; try { - // TODO(ahcorde): When forward porting this to Garder change var type to - // unsigned int - entityId = std::get(visualToMove->UserData("gazebo-entity")); + entityId = std::get(visualToMove->UserData("gazebo-entity")); } catch(std::bad_variant_access &_e) { diff --git a/tutorials/move_camera_to_model.md b/tutorials/move_camera_to_model.md index fb008afb3b..0ba5287eeb 100644 --- a/tutorials/move_camera_to_model.md +++ b/tutorials/move_camera_to_model.md @@ -5,12 +5,12 @@ This tutorial gives an introduction to Gazebo's service `/gui/move_to/model`. Th ## How to move the camera to a model 1. Load the **View Angle** plugin. This service is only available when the **View Angle** plugin is loaded. -2. Call the service using the request message type `ignition.msgs.GUICamera` and the response message type `ignition.msgs.Boolean`. The distance to the object is defined as the z coordinate, and the direction of the camera with a quaternion. It's possible to select the projection type. +2. Call the service using the request message type `gz.msgs.GUICamera` and the response message type `gz.msgs.Boolean`. The distance to the object is defined as the z coordinate, and the direction of the camera with a quaternion. It's possible to select the projection type. For example, Let's move the camera to the `box` model looking down from 5 meters away. ```bash -ign service -s /gui/move_to/model --reqtype ignition.msgs.GUICamera --reptype ignition.msgs.Boolean -r 'name: "box", pose: {position: {z:5}, orientation: {x:0, y:0, z: -1, w:0}}, projection_type: "orbit"' --timeout 5000 +gz service -s /gui/move_to/model --reqtype gz.msgs.GUICamera --reptype gz.msgs.Boolean -r 'name: "box", pose: {position: {z:5}, orientation: {x:0, y:0, z: -1, w:0}}, projection_type: "orbit"' --timeout 5000 ``` @image html files/move_camera_to_model/box_5.gif @@ -18,7 +18,7 @@ ign service -s /gui/move_to/model --reqtype ignition.msgs.GUICamera --reptype The camera can also be placed far away, for example 20 meters: ```bash -ign service -s /gui/move_to/model --reqtype ignition.msgs.GUICamera --reptype ignition.msgs.Boolean -r 'name: "box", pose: {position: {z:20}, orientation: {x:0, y:0, z: -1, w:0}}, projection_type: "orbit"' --timeout 5000 +gz service -s /gui/move_to/model --reqtype gz.msgs.GUICamera --reptype gz.msgs.Boolean -r 'name: "box", pose: {position: {z:20}, orientation: {x:0, y:0, z: -1, w:0}}, projection_type: "orbit"' --timeout 5000 ``` @image html files/move_camera_to_model/box_20.gif From 353ad20adca925add2313a74850374bdf8f82d3c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 7 Sep 2023 23:35:01 +0200 Subject: [PATCH 13/50] Update README.md (#2124) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Update README.md Signed-off-by: Alejandro Hernández Cordero * Update README.md Co-authored-by: Ian Chen Signed-off-by: Michael Carroll --------- Signed-off-by: Alejandro Hernández Cordero Signed-off-by: Michael Carroll Co-authored-by: Michael Carroll Co-authored-by: Ian Chen --- README.md | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 825fcba24c..f12f19f841 100644 --- a/README.md +++ b/README.md @@ -78,7 +78,7 @@ introspection and control. # Install -See the [installation tutorial](https://gazebosim.org/api/gazebo/6.1/install.html). +See the [installation tutorial](https://gazebosim.org/api/sim/8/install.html). # Usage @@ -125,11 +125,11 @@ This issue is tracked [here](https://github.com/gazebosim/gz-tools/issues/8). # Documentation -See the [installation tutorial](https://gazebosim.org/api/gazebo/6.1/install.html). +See the [installation tutorial](https://gazebosim.org/api/sim/8/install.html). # Testing -See the [installation tutorial](https://gazebosim.org/api/gazebo/6.1/install.html). +See the [installation tutorial](https://gazebosim.org/api/sim/8/install.html). See the [Writing Tests section of the contributor guide](https://github.com/gazebosim/gz-sim/blob/main/CONTRIBUTING.md#writing-tests) for help creating or modifying tests. @@ -145,6 +145,7 @@ gz-sim │   └── worlds Example SDF world files. ├── include/gz/sim Header files that downstream users are expected to use. │   └── detail Header files that are not intended for downstream use, mainly template implementations. +├── python Python wrappers ├── src Source files and unit tests. │   ├── gui Graphical interface source code. │   └── systems System source code. From 923ccee7811a4f43c24322f98d95284dc4aadadb Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 8 Sep 2023 01:03:50 -0700 Subject: [PATCH 14/50] update link in particles tutorial (#2127) Signed-off-by: Ian Chen --- tutorials/particle_tutorial.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tutorials/particle_tutorial.md b/tutorials/particle_tutorial.md index b676d204de..c0c37e73b5 100644 --- a/tutorials/particle_tutorial.md +++ b/tutorials/particle_tutorial.md @@ -55,7 +55,7 @@ Here is the content of the Fog Generator [model.sdf](https://fuel.gazebosim.org/ ``` -The SDF 1.6+ specification supports having a `` SDF element as a child of ``. The particle emitter itself has several properties that can be configured, see Gazebo Rendering's [particles tutorial](https://gazebosim.org/api/rendering/4.0/particles.html) for more details on these properties. In our Fog Generator model, we are using a box type particle emitter that covers a region size of 10 by 10m. By default, the particles are emitted in the `+x` direction, hence the model as a pitch rotation of -90 degrees to rotate the particle emitter so that the particles are emitted upwards in `+z`. +The SDF 1.6+ specification supports having a `` SDF element as a child of ``. The particle emitter itself has several properties that can be configured, see Gazebo Rendering's [particles tutorial](https://gazebosim.org/api/rendering/8/particles.html) for more details on these properties. In our Fog Generator model, we are using a box type particle emitter that covers a region size of 10 by 10m. By default, the particles are emitted in the `+x` direction, hence the model as a pitch rotation of -90 degrees to rotate the particle emitter so that the particles are emitted upwards in `+z`. Let's launch the example world to see what it looks like. From d41e94c1a210648b54607f039bc664bf17a99645 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Fri, 8 Sep 2023 17:08:30 +0200 Subject: [PATCH 15/50] Update triggered_publisher.md (#2130) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- tutorials/triggered_publisher.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tutorials/triggered_publisher.md b/tutorials/triggered_publisher.md index f4b1678b4b..56768e470b 100644 --- a/tutorials/triggered_publisher.md +++ b/tutorials/triggered_publisher.md @@ -16,10 +16,10 @@ Publisher systems can be chained together by showing how the falling of the box can trigger another box to fall. Last, it covers how a service call can be triggered to reset the robot pose. The finished world SDFormat file for this tutorial can be found in -[examples/worlds/triggered_publisher.sdf](https://github.com/gazebosim/gz-sim/blob/ign-gazebo2/examples/worlds/triggered_publisher.sdf) +[examples/worlds/triggered_publisher.sdf](https://github.com/gazebosim/gz-sim/blob/gz-sim8/examples/worlds/triggered_publisher.sdf) We will use the differential drive vehicle from -[examples/worlds/diff_drive.sdf](https://github.com/gazebosim/gz-sim/blob/ign-gazebo2/examples/worlds/diff_drive.sdf), +[examples/worlds/diff_drive.sdf](https://github.com/gazebosim/gz-sim/blob/gz-sim8/examples/worlds/diff_drive.sdf), but modify the input topic of the `DiffDrive` system to `cmd_vel`. A snippet of the change to the `DiffDrive` system is shown below: From f44677a2e747ca5ab8f8209eb822db7fd575a4a8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Fri, 8 Sep 2023 17:17:07 +0200 Subject: [PATCH 16/50] Remove sdformat diff drive warning (#2129) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- examples/worlds/diff_drive.sdf | 4 ---- 1 file changed, 4 deletions(-) diff --git a/examples/worlds/diff_drive.sdf b/examples/worlds/diff_drive.sdf index a85ae7f112..0004a898c0 100644 --- a/examples/worlds/diff_drive.sdf +++ b/examples/worlds/diff_drive.sdf @@ -157,7 +157,6 @@ 1 1 0.1 - 0.1 @@ -208,7 +207,6 @@ 1 1 0.1 - 0.1 @@ -379,7 +377,6 @@ 1 1 0.1 - 0.1 @@ -430,7 +427,6 @@ 1 1 0.1 - 0.1 From 0baa39ff78ce697d57a688aaa906e961667e42c8 Mon Sep 17 00:00:00 2001 From: Voldivh Date: Fri, 8 Sep 2023 11:37:52 -0500 Subject: [PATCH 17/50] Fixes the link for the Hardware Acceleration Tutorial Signed-off-by: Voldivh --- tutorials/video_recorder.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tutorials/video_recorder.md b/tutorials/video_recorder.md index ffd06943fb..42ada67f29 100644 --- a/tutorials/video_recorder.md +++ b/tutorials/video_recorder.md @@ -106,5 +106,5 @@ generated video. The default bitrate is 2Mbps. Since Gazebo Common 3.10.2, there is support for utilizing the power of GPUs to speed up the video encoding process. See the -[Hardware-accelerated Video Encoding tutorial](https://gazebosim.org/api/common/3.10/hw-encoding.html) +[Hardware-accelerated Video Encoding tutorial](https://gazebosim.org/api/common/5/hw-encoding.html) for more details. From 183c04f6fd27e1a592954b28b5314abb390cbb03 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 8 Sep 2023 13:23:13 -0700 Subject: [PATCH 18/50] Use default physics engine in example worlds (#2134) Signed-off-by: Ian Chen --- examples/worlds/nested_model.sdf | 1 - examples/worlds/particle_emitter.sdf | 2 -- 2 files changed, 3 deletions(-) diff --git a/examples/worlds/nested_model.sdf b/examples/worlds/nested_model.sdf index 1ff1f267ba..f717a7a87b 100644 --- a/examples/worlds/nested_model.sdf +++ b/examples/worlds/nested_model.sdf @@ -8,7 +8,6 @@ - gz-physics-tpe-plugin - - gz-physics-tpe-plugin Date: Fri, 8 Sep 2023 22:43:19 +0200 Subject: [PATCH 19/50] Update underwater_vehicles.md (#2128) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- tutorials/underwater_vehicles.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/tutorials/underwater_vehicles.md b/tutorials/underwater_vehicles.md index b9210618a9..e26f52ae73 100644 --- a/tutorials/underwater_vehicles.md +++ b/tutorials/underwater_vehicles.md @@ -55,9 +55,9 @@ rpm. Under the `` or `` tag add the following: 0.2 ``` -Now if we were to publish to `/model/tethys/joint/propeller_joint/cmd_pos` +Now if we were to publish to `/model/tethys/joint/propeller_joint/cmd_thrust` ``` -gz topic -t /model/tethys/joint/propeller_joint/cmd_pos \ +gz topic -t /model/tethys/joint/propeller_joint/cmd_thrust \ -m gz.msgs.Double -p 'data: -31' ``` we should see the model move. The thrusters are governed by the equation on @@ -185,7 +185,7 @@ gz topic -t /model/tethys/joint/vertical_fins_joint/0/cmd_pos \ ``` To apply a thrust you may run the following command ``` -gz topic -t /model/tethys/joint/propeller_joint/cmd_pos \ +gz topic -t /model/tethys/joint/propeller_joint/cmd_thrust \ -m gz.msgs.Double -p 'data: -31' ``` The vehicle should move in a circle. From 967f4f12223cfdca4f09409fff43c6938374156e Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Mon, 11 Sep 2023 11:44:20 -0700 Subject: [PATCH 20/50] Fix duplicate entries in joint position controller GUI plugin (#2101) Signed-off-by: Ian Chen --- .../JointPositionController.cc | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/src/gui/plugins/joint_position_controller/JointPositionController.cc b/src/gui/plugins/joint_position_controller/JointPositionController.cc index e202513024..428edb2291 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController.cc +++ b/src/gui/plugins/joint_position_controller/JointPositionController.cc @@ -45,9 +45,12 @@ namespace gz::sim::gui /// \brief Model holding all the joints. public: JointsModel jointsModel; - /// \brief Model entity being controller. + /// \brief Model entity being controlled. public: Entity modelEntity{kNullEntity}; + /// \brief Previous model entity being controlled. + public: Entity prevModelEntity{kNullEntity}; + /// \brief Name of the model public: QString modelName{"No model selected"}; @@ -212,6 +215,12 @@ void JointPositionController::Update(const UpdateInfo &, auto jointEntities = _ecm.EntitiesByComponents(components::Joint(), components::ParentEntity(this->dataPtr->modelEntity)); + if (this->dataPtr->prevModelEntity != this->dataPtr->modelEntity) + { + this->dataPtr->prevModelEntity = this->dataPtr->modelEntity; + this->dataPtr->jointsModel.Clear(); + } + // List all joints for (const auto &jointEntity : jointEntities) { From 07129c663ebcc5a10ad3447c23e1cc516b2f1877 Mon Sep 17 00:00:00 2001 From: Voldivh Date: Tue, 12 Sep 2023 11:07:01 -0500 Subject: [PATCH 21/50] Modifies the definition of hydrodynamics plugin Signed-off-by: Voldivh --- examples/worlds/lrauv_control_demo.sdf | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/examples/worlds/lrauv_control_demo.sdf b/examples/worlds/lrauv_control_demo.sdf index bf0d43a12d..2be3dc543f 100644 --- a/examples/worlds/lrauv_control_demo.sdf +++ b/examples/worlds/lrauv_control_demo.sdf @@ -257,17 +257,17 @@ 0 -33.46 -33.46 - -6.2282 + -6.2282 0 - -601.27 + -601.27 0 - -601.27 + -601.27 0 - -0.1916 + -0.1916 0 - -632.698957 + -632.698957 0 - -632.698957 + -632.698957 0 From 4135cd1874ff20ff67d2c37995b9a0c5f4d459fb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Tue, 12 Sep 2023 18:50:08 +0200 Subject: [PATCH 22/50] Removed python trace (#2123) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- examples/scripts/python_api/systems/test_system.py | 2 -- tutorials/python_interfaces.md | 2 -- 2 files changed, 4 deletions(-) diff --git a/examples/scripts/python_api/systems/test_system.py b/examples/scripts/python_api/systems/test_system.py index fe4e807919..b5d03347b0 100644 --- a/examples/scripts/python_api/systems/test_system.py +++ b/examples/scripts/python_api/systems/test_system.py @@ -34,8 +34,6 @@ def pre_update(self, info, ecm): return if info.iterations % 3000 == 0: - print(f"{self.id} {info.real_time} pre_update") - self.link.add_world_force( ecm, Vector3d(0, 0, self.force), Vector3d(random.random(), random.random(), 0)) diff --git a/tutorials/python_interfaces.md b/tutorials/python_interfaces.md index ad0e0d8ddc..e4a75b19e8 100644 --- a/tutorials/python_interfaces.md +++ b/tutorials/python_interfaces.md @@ -118,8 +118,6 @@ class TestSystem(object): return if info.iterations % 3000 == 0: - print(f"{self.id} {info.real_time} pre_update") - self.link.add_world_force( ecm, Vector3d(0, 0, self.force), Vector3d(random.random(), random.random(), 0)) From 02c0a56573a782d5629c966de55118fea724b2d4 Mon Sep 17 00:00:00 2001 From: Voldivh Date: Tue, 12 Sep 2023 11:38:45 -0500 Subject: [PATCH 23/50] Corrects the output from the command Signed-off-by: Voldivh --- tutorials/model_command.md | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/tutorials/model_command.md b/tutorials/model_command.md index 6947b14254..d78ba82bde 100644 --- a/tutorials/model_command.md +++ b/tutorials/model_command.md @@ -45,8 +45,9 @@ Once you get the name of the model you want to see, you may run the following co - Name: chassis - Parent: vehicle_blue [8] - Mass (kg): [1.143950] - - Inertial Pose: - [0.000000 | 0.000000 | 0.000000] + - Inertial Pose [ XYZ (m) ] [ RPY (rad) ]: + [0.000000 0.000000 0.000000] + [0.000000 -0.000000 0.000000] - Inertial Matrix (kg⋅m^2): [0.126164 | 0.000000 | 0.000000] [0.000000 | 0.416519 | 0.000000] @@ -118,12 +119,12 @@ Once you get the name of the model you want to see, you may run the following co - Joint [23] - Name: caster_wheel - Parent: vehicle_blue [8] - - Type: ball - - Parent Link: caster - - Child Link: chassis + - Type: ball + - Parent Link: chassis [9] + - Child Link: caster [18] - Pose [ XYZ (m) ] [ RPY (rad) ]: - [0.000000 | 0.000000 | 0.000000] - [0.000000 | 0.000000 | 0.000000] + [0.000000 0.000000 0.000000] + [0.000000 -0.000000 0.000000] ``` From 3e6be997834c17be621201339001c18fc6e439b1 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Tue, 12 Sep 2023 11:37:37 -0700 Subject: [PATCH 24/50] Load transform control and select entities plugins in thermal camera world (#2139) Signed-off-by: Ian Chen --- examples/worlds/thermal_camera.sdf | 20 ++++++++++++++++++-- 1 file changed, 18 insertions(+), 2 deletions(-) diff --git a/examples/worlds/thermal_camera.sdf b/examples/worlds/thermal_camera.sdf index c857c36278..2a6e329032 100644 --- a/examples/worlds/thermal_camera.sdf +++ b/examples/worlds/thermal_camera.sdf @@ -88,9 +88,7 @@ false false 72 - 121 1 - floating @@ -142,6 +140,24 @@ + + + + + + + + + + + false + 5 + 5 + floating + false + + + Thermal camera From 9d79b629c9e0fed1c8635e30f06b2c61462f32d8 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Tue, 12 Sep 2023 12:35:33 -0700 Subject: [PATCH 25/50] Update video recorder tutorial screenshot (#2135) Signed-off-by: Ian Chen --- .../files/video_recorder/video_recorder.png | Bin 47398 -> 480303 bytes tutorials/video_recorder.md | 5 +++-- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/tutorials/files/video_recorder/video_recorder.png b/tutorials/files/video_recorder/video_recorder.png index f9b06895c9637633f252387fb76246224c4c7eed..65204b6358b09d9428c9e5dd0999cc43cfbbe5e0 100644 GIT binary patch literal 480303 zcmZ^~1z21`vM`Ff6N0-Y1b270;1=9~3bARr)6Wu(PbARu7C5D?Hw2ypK$JBcI!2nZBGD>1RJ zGGbz6U!4HvR<>pk5YmyUn($hxLmzW>RmdA5pj1QwK`v0zhy}0-`Y?p#h#0alf%(Q# zxH#Y1wR*y8qUhX&Pa<+8>h6C91=KTsJQ>dVFzIUWxb6d5eLNSk06Xuk0=>^6^8KRd zKkk1gfY^ydqH-(QTgw5c1 z$Dum1L71vDY9=8D=n(GUhjz%970ko`NRD9o0GU4?u*k#&z#`pZkFd*+#WMy9 zvc1CRjCNa!jga6QT45wCx>u3EiW@PgfkMpDt9>Vnic_a|1X0kAfFI$JzV<;^uM zpm26@HmV*giM&MAR+&ydDo6{}c0@`R0)E0Lj9sAdUcpP(S z(XEubV$a9m>tCD}h&;-&KKW$yB3$A(%U&ZV<4PHU<^B|Dri^7I2Mk$2(YU@W*ZeF@4SVS>$8~><0kSUk~xcfRW z0bUX^%|l;_$Yb~sx+rqO??%ubLEL`?3C$PDVaTxPh)<%Ur?gvXGpU=+pG#Cm`4ZmU zOG`gu+NBz+8b5<8VGw9oaYBr`m^?5;)i+uN1&8d134;!6qB*-0+OSoDR^d!Ih=h9T2`7#1AoK2#5vbF5;vtB404Q2VjjT{G^$&A_vGn zNfRVRMqqqmg$9PFkkcpJ{`pu$uoO=uqDYCG=(dA)g>WdMPnq`>MO~svnQ|71IFeQQ zBS9cd{`Qo-3#(4ZxKw(+&D3WXE}igPNv1-sNwgc-<#fFAd;KdVgtRgIu>^zKT8LA|~q1+w0C>lo@*dnZH-f8=3nQ3(u+CymVP+L(q^6&)JAqpp!*6faG zpCF&qRSB^CRKAu<$ET?ef@TC}pUeo06P-e*Wgg|{igZ+c%MoX7kG>u0STo#yxfQ&P zjf#o_My1PEMSV4k8`eqn{fw(dQtqQRr_!WqRvD+7TEVEiR^TOj8+SxV5Nj@hoL@YR zWGQDk*T~iw-iU7P!Xd>GM_^#rtP`q}v#j2fe)Pdr&Nb}`=9c2t={ERCbJm-KjzELJ z7PaR0msq4&N`e;lCyv9+@yw}A&&+5JcPstblX(g&Z7W!t%ceaWyE)#%+mN`au|r$l zc)|FtSiiLOa)sIE`8`Vun{=!5Df_vznW<^V8JTHdg=&HGw^A|OnWpL8gS{ihIe~m{ z)%zLdLZd39AfxE8Ika}(lg@RAP6&ZO{qlAFPC~D|8~mr0FT29=>Btp?_q9Xj$t#XEdh*I_m0p$hHUc(ru8FR( zx4wj#vE5^)S)a3xo5giY?BY)0Ryg@)$JZD~YWmKi1gy`Em>NNbAi*H!KAR9r@wo_H zvm=*2>+l_KSB@7$mrJ`d0>fS@hO^DeN0OL=F3PrbzQ?XV#x|;?6 z=rz%dKPB21tTA03yPV%HjqB#_H55Gy*~Xrub)qGar!1l_J(Yd#i`~<3e4gPsOg;4F z=LDdh!wLm-M}a6WaH=p|%pT0E{v3?ojC}(xCGX~`=g!faA}=5tn1!1GhW+xea~dcu z$hdgi0VF(34CfKjaw(M7xu*P9M@4QwI)93Xs}i=(1N=(iI)F96q?L-<05&ulW)&eb&fp z`uVql*6)_Tl2Z#c=c|pYKI`4O-44v*j;sxHRTtDG)*NaPwl*8({Ax2h?y8#5@h_yP zGX@kJ?S3D=Cww5Ru}4|dY9F#xT`Ez^3e5rl5Z6>R&D7PqQhzo%95>j>tc<_?eyR3q z@4c%(HE@q`b2*7wS^9RWt=Bo?urN)~D5*2k;Jtd*EFj`dU`=e@ax%B3+l+paeCFLH zWcM}(jR~KL#)>{qQqQmEnc?@d5v@E+V?i@d9W<3NJ?TgFBCT4ew7ppvC*@AWCZOT? zZU12!dlvgz2_^dr?~=c)PsP2<-XX05cGg)AzVn`!v#s;-QbYspcxX1CbFM3R2Nr}p z$mnIj?-c1-4z3^EZToni*5BR!=J#{1u<0ynKQ)ZAw)yv+@+oc2lYxLQ!@+XvarSXK zKzz-z8|ZO;SMAusYkv)J2Mu*zAK7oNP2BIT(ylW3=3nN&6m0fa2-&_Zu53;@z9>%? zrVU=kp9^dXcwVx<9j1>zPFPM1x68LxwClCS--g^Y3Xnc`T!%jV+Fwr+;&`j_vAVvR zG=TJPx`{nJ_M!IVxbV6peC6U>Z|k%>ia+#!U_4*jzb_`e5juJK^Wp(ky(+DlQ0+?S zs(Q74Zo1SRXnBVAgoZY*388<(=`oaGV}ACqtoP!P5A|QvFyMUX z|AL{D-f<8js$w!S@3pFllbM;lvn9aA3&%Y5y#didTH6@{;v@Cn0x6?Hb@AT+f|Z(< ziMB9W1i@jIEC^QwqT{)_$nPJqJF#l?Y_iOJpFozb0* z5#VIO#KObF!^F(W#LCL>PQl>pY42j>!C>!9`Oi-Ns~>SQXA>tY2Nx@VJ=x!Wjf?@V zE&>!3e+T;S>!1JA%){z`MzVMQmssxtGX2Fcu`n_-{deE*to(mldB0kDnAvKJTiLzq z?0pPD9u{`~f6)K`F#j{+zj12)4<`#N7x%xj{u}Clv#L9rIf()6-p6zi{2zP$i}~M? z|6=54`YZassp6k{{zvP(q6Lxonf}{of=HMHDTVKLB(f4$QhTr8z3lG=IrRQR_s{wr zhC1sAchc^FfDnd|5f@SOfIR86N+yy?qAqbXlUxV>1gPO4!K!JhFR%y*$f<;|b$+Nx z5cS)-}a|Hx-3Ni7#w zl-#XSGJ|Eu8gKI6;{6u{^s({J8;fX&Kc&j5Bz4etbETeqPs22Vua&o$F7~%uJx=Nn zR1yL#YHCjLlcVk2J`ev8BnreGoNSNoFJ01%^ie|6Ohel_J_S~e`|z&i;*-oxR%R{T zGY3NY->(sK^$LPC{Oy8|@VPcJo7r+oa#pN@nY4JbkcJckK#{gTZ1Cy3=zo2F=9(TG z z>E5(?dIh$zS=DQpn|6f7#vjR0Sm@-EYckZUR!sp+{Jo?2S3%mo$G#*eu%$}!-)z2}25E_3p4;x6EqvD})UD^{x8td?foV2C!#G?Zd6^a846x8t zFJS?w@@Trg16U`NWKD|7B2H`GaB)46ry3*iPNF|JgztgzrdGqUd2M)}Z#)x!0p}JJ zl~7zPwQx!c&Vn4hQ#j5R4;(^I8i%Z3Irg;|QPINuCnRgrxYBQ@CUOlr!>n|H!@6eh z#mncw^}xMKT!n7^Kzee<-iw;7LxD>g*=N@IYj0o7330CmHs7ub8+Cu>5B#I5*!p?K z2XK97ngM_9?-LQhkw{hlTD{3*4=Yj+q9YLTmH?g7DMWYRk~F< z_d};-IYlwxt=4}b=Y-v~Y9-{kz;f>xi(rZ}S;DL6= z;)Fi}`O%wyE@ICuO2Lw|;rkBhUOxS-2mYypdV$>LgZ|^rMDpw!h#dQgDWt2+fb?Yh zAgOWtS=%z5hMYU9YAEJRg6q|P(P^KF)f9X8Gx5&&ci7Wu3-@?8D>KtuUmXcv|Gm4e zjb$G~9e2g&SD&)iCM|(4s)OICO(=;>v*7s28`5br7s3~^_1z8S;8lVnzb&f?EKHLV z{zzKx^fJ#~k12b+_I5RZThopjCzU_)1f4dX;Kx5~)~|R*oty=ZF!c`DcQQ%VdQfR=a5uan!*=fYe=bqUrGtL((8jfx^7oE; zXuo_0xze^PdUbTNf$F^HwmMs117n1O*S+ zj+$Pl1+ZWrqgvoJ&M_5jS-EQzTUe*)Sch~|YKyI7d@&pJDj`pGWUZV_Mz+Znc5x5c%YLi0*J?A}XmvC~QmA=cxr)A~qL^d*uV|I&T`-hZjuJyQkhQd32)Bxt%1 zL3NHiRryW%X3R9ZrPVhO^BCC5CMm^^@yiPVr5!yS2c*2fAzu?d`=^Qj&z(_b;w!!k z^Tc7|2X{J`uK^y~$HWjy1<3HQl-He;%GisZKt`78lhxmW^9anynefZEg8Oa`@o&A4z?9DmY(s6!cVls-FwO zO9S3^_jJoEyS|^E?w9kuPVIl$f9x3XHp=KmGs7Gu50P;44xK8y4t4V8cq?;5a&&-( zekJ7Qu7H1aDp2z6rl#4LI6uO_ss*_i#8&_X=%0%wHz!iLx}OdS*7QbxI-81Hgd!88R~x~d%PcJ8HTpZP;G~F;A*=$mUtnq z%Z=e-cUl`cB{G~PTn@FKh;mjz)?BFWj&zKDXn&_T^w+zGnN6r&ZCEvsBX+|EiZ7q@ z1{s~M9SZfCugLnxb@{)*kJ>!_APNdVzrdIhIv1PE2Dy@lG&?>J?n-ic2i{@==yHIKqHwK7vxbryJeR7lW6it75B3tO-)Az|!^^ zA;ybIexC!H7tkt^uscLx+x|%^r&ijY%lTZb1p^ud;;h)-;id%5 zk?d}ks3ke5I^$CWs~x#9~!gS3~)Y&7~r4sy$66kc1?s`_gs~(GB|W~8Qkw99Cs=C38Z-U zHUrh%tBjf@Z>M&Gov3ap3MO$IIULZhc5WX;bR)aHyWcA9i7j3bo1gBQ=RCp;*taIw z618;>ve2drVrCCesXq(sO25R$t^G-o;Bq#FhF6>Pwm&G~FfeVE;5DBarf7wZ`s!kX zi?ApF3XPt;8M6 zdFlYLoljpx^J+D2=(Rax%=H&{(V4FBfX_$69+QXMl+TK5jT7~^ zg`zLtURYvm>l^BGE7LS}&(OEr$7t*?KAXb|UqamXE&l2`uH~BXR?uBy@mk=w$l2QY zx&LwO%x}Wx`okDt+gs(#kfq>2?h>H%@ewH|#1M$w4$Cl$zQU=b6$TDD{R)O?LQdD> zPT20K#-*-QYYOO!!}Rxm+H0<%4R>|LShz~h_0>^y^3=O(P%It&8ofO{i zKZU*>=`%QHv}sE0q2KG}H9lOBcJC9g!YX7e?+<~cjp7+r^hI~=^>kr5>f zGUJ&#enRJ4=AYtdd7BNsEF+39kB4qM`2g?w0 zC(nA}b`v~XG&er3b?Ei{(5yM_3x%%b{cuMS_#M1fwb*Us=gY-u0Kc}j9t|CFOUHQX zw)70PJeloP{@8i0*xiBHw|n-XCVl^~68LGrf~f;9+0rQSxZ(4NP9Ro z97yMss@e(h%ds=a9dpQLUFUG%uG=k-{Wg}-V|wTV49w*r9@OH^{(NI~768@jJiE0i6BVSM${@!7~nLDBLZ43Ey?~xmZM{G-jFyOmaG1T9P$_{llkc0R2?bxm||52_)*q80dk)^VG>)ow&P!q-X* z>(73ok$rV(=ntomVi$YCSz<{L^VVNcW4n_FXaP+I)lwd=DZ$I!`|)pcqoPpilPFq4 zirwSQo_~0mxa`*oJSZCbyUlIGt@{V&xGebCe&uot*xre;p9NnBEk4k^q@uH0m`JpB z3UJLdv2?(60{U~ z-kdFfu@VaKXyuGHLU6V zX6G?c)I6Cr`0LPXl8iuQfIPx@nOCo<7#rs|Q^pgfX)Zpokx5}@k;xP9#_%Qdu`D0! z7U>?CepYo9xa=GUZVpm3n4?f+!V=u&$kRXsac=m&8LkY$Zm_g{DN~)&?YsPli~UA! zDJy^F?+@JQy=Uzh{42lqU->PnmFtKle&=!AFxfuWSDnxLmA%O>_kV2CR3w&lxU;^j zoma%X*{nuiX}@i=Twhxj`20k^j#*piWFe&$?%&W4A9!Sx$8^3RmGPO9^-m2pkqFhX zL4JUF^ZD2$4LSv25z^L1GK$MCRp%5U9=0|@ z;ou|Ct!Rnlg4FihCB}}KNo1HN7Mi{^B>v-RnkGQ7wgO86{B)$_9#zoc_MGF_IUy|q zA5&yqW9+A6m03>2$KN^Xo+*kiGUH}u$&PnsllcOX#k(`4-83;zM-07p*dAE8xIzom zt9H!u;YBfjwy!<*(Do>~?yf>a?^p0t@FluKD4H0yiJCCdcU$j_y>D=ry1qD!-CMXr zdQUr|eCUt30O3mWXcSQWx#u}gMBV7Ym?Qms#+-N!3&!l{y&HX<;bIb#cWq%} z$rfCL!gOhrNz`oou$t;y=Xd9cbGU=Asj&~&JG0t0gn+(``z_a11!N@rQYvTm+sgYFYHS#dl?t1JD=Qt+I!@TB0=3fyi;KQX@V|~lDmNrf44^C(qYR#7oIL~ zh}l&d?r9|vF9LG*%D{ajcp_O}@DTDw7l}{+m^#?iG837X{^|bi=Or+@w~_j5Dx#-X z*l?1q3mbj=-iWo_t*y@o?5R ztuVK~%lu9;$2pR@RKtpe=5oC5FO&K^VQ4?um_|+^83zg?gvH4ym@xu7AC^{*L2Z-z zx$&O91?xSbgT4PiVPJYxWBhq`r$i690bzYEisc{DH?Z^;Z^{j<`-q2UE%X6lW%Ve! zstfTlJfd4scUThZA$s({j36?6dH2@hrO~f;rmgSxwDA-;sy^q56oS;|d`fgUZp76e zP>*$0l7z)OZzK$?YSPo5%vn}tndoZHN&4ss_tIL8##3qj?ZR#;fc8NBwOpaTPTmoL zYBu+AboyvhJWzj;o#S|7u}P7hC1ZGnzefI6zDM>bv&v$y!q<$B5b42<<>QvgKpqfr zK-GrRp7^sxpT@Ew9Z|EG=M3`5S0#njEkMtb>4wGDIk8}TGE^$?-!;=xh!Ak|I`=mCt9Bo+fzhDq4_Nv& zki0=@Z8Sm1FzoqRWvh1lT{FllzT_zcPN^~aC5c+|HTgnKM#=507|4?D^ItOis}8>L zi1O%_TzRDyuA)GXq*iR*Of!jF4!R&sj%K&Ouc@u6PjlWH$&KMG-Go-3nN|ZG`%iw% zU|&=ec$DNUOdi7Fef>^<(=9D%5hOYn6xg`3=TQ8Sh#iuir*vrf#c1W}+VquW-nZTM zshQbaf!HOB~I*YL~`MX{`)DegpLG2g&g70xS{HhjdkQ?w1g+(9`*~0Ys3q^G(fDBGa z@zOLb=Gan}sb9Djusx4NkJjcwC^v}=4m*H&SwlSiuiBEUOz+XkPmqZ1# z1(>I%)oAvi&Cx}33`&cYAIo>{_p6u;E+TFT3~L&_s}=eOWOcprv6GnlBZM+plFQ$t z15XvZh$_;~i;*g#_;jo7H#zJe$jXv!zwp?71##FvXM~sOyeZXX@24^~HL&nw{`BQ% zBl}HD`vwIaLVGI`{*&@0q81O7R!*KJc3(Ks+ z9Vv}{m!isX>`d%CkQbX3OKxVpFoaXl9w_K(5Ex8jSS)1UwR5|KHzKlazAywoCXSO+ z2o^TKc@3L`e`K{BHJCu2b+=w#^$jflF8eQg{!^fTd3*%I2~?mm2*i4BXR8G-hc{JX zAz!KQt%f^x!u&{_g@yyQRU5FqoncCH?tFP#gP*@PZ7V20ISDeiwLJnVHiS zxKL$+;YTj1sL`&hq%OeI&2*|rkG7(QVAo9|N_rH!U1KM%YW=y|gFkIS)35}D!{wi7 zO@67l<8DZ2Y0lF^MCg0fg#s@Y*b(}~>$!bGpM-c~Gjq(w(M~F{w{%`kZR|@N+_;vZ zVENtXS;DqY!}9kiZYmSELSpM8DQ3jKZ1mqE{gsfCf_eB^7sN-%7o=$C^}EBmixw6t zaLGsS=409Z$UY+9*7^LoH>Q6vV??(DdBLyM&fn`W{U0|XD-P8Ji8d^G7q9z3s$=Vu zc^E);S^BzEEyE4{(r*5ir@HM$d2oA%Qz+Bii^_0}So-Ov9b7!5wZsNAU|V~cn$@S{ob@S7u<$R# zEKQ-^Ke0(&dRxb?^k;{n|*(Cu719n*QgY=9wjCWTwXD>vp9qyo%=1WOz7A~mn&jA z>nK4wk{{c_4D?#(cwlyhx?Elr2q-SFvs=6vr7EoH7nhg#D?N*43`N&kmrM@oaX3R| zTVhuq=|XvR{|kZ~C}>D0uc?|{FRr}}&GYrpmzB`7cxi;tB+sH&df}-_gr#ShSVtTqVhiMmT zZJ?n4q%v719bE7y&z;e`C6jK~Oh(yC-X^ty*QPey-&)}F#Oy(PIO>pz#2&j23OPE(~%$5W<0Rf8h)A3-xJITI9$xP(G5v(&FWR-pH+g# zicLsizMLhYKe@U6wst-|H-hIWKp;qS7!}_;oOPgpTF$=mbivZ_NE{_`??Wm!mBR+KYK$7ru8^5uvi#osYZ z+4u)b_Yz*eVoXH_scL|;{7UGBc@H8m$aDMRRLri{s1@*u8Q10bmk8-fQ@jt?z6IO=@v$)31_&TA_wa;U-RdjZPe)zf0$XRCe=T{UCMRwE(j<(4HJsy&4n{{ zw@>u-UHm92#=k;*er0<}#=!X&g7Yh%`@4AByMfP|R41RFR39cpbFJGrOV5+d%~_i) z;HuamyF(lz2lA>>>xm^_cycS|ROpX@|SKE#az)$ZOBkT?NcP&j6AKS>I>G ze|S>F(Lmj?W~BH~?}Q03jGV|lr9z9>%4h?VLT05ww8>LlnidOd@g@}+D52*quSjBE z-<;w@9&9|`7t`COdx)}Gy6uZ~Xv0^mOSVl5N`#71$TKY}u{U6kJul8x2lJ}Zq&79f zdRoN5m{|Ej+Pk*dt2BTwd77;aDa=W4%d<|1rmQ?L05D5aKYfx_MX&zru)J(Z*s5Y4 zr>tbVQ>RcDPF_QfHsQ$ZgHsIJ)u&n1 z73M+jl=0B!dEeH_E~b-JL}cvCu?+bVbkt-H!xsx0;==lcKa0%$H8%r6iHrZ0B>t~i zCl)LGHe#6Ges{5SmSS2wm)ayLrO~1@-Sb1w48z|fwO)R1m{pH{$hL`U+w49UuwxJ* zH7s>AF^7F?!2kM0mXqt|$1vqO06MRmo{OUS&IZmf;Cjs#)C=y$81_0=4m=ZhfH3q;nmtlbC(m|8vPA-F4>cL$*HXWih0Cw&U59ETRFfU#EiPs0}Yni z9NsX$OYRj&Rcvj0>FY8YL6*N)10bEd?#h z6)d#!sE6B|pX5e3uRBJ|kH4UaJ-e(VA;h=YrH*E_Ddjl$#1 z8ujDZWz?!?7b86xc-UhsFAFdEn(VbEFFO^KZIE!y#!*gpIk@KA(Q!Yzj%>l2(yZ5T z9_q|wAe?*)JCMhcvKN3JWYFSBfBm~puu%lVrS9~H#N7w#UKncJZ|f8VTTN<=Rx@rB zU2|3PC`kc5#RE~NEhPkAmz!F!CadvdzDs6i<^nuN%exV%b7lsz^BFxx3}P;?u6UVW zBDL%FQb*mT&MD8S2MxvE(ibU0``=Ud>H(h0?F2g=fh5>lWeLjT3>U$4)J3Q_p$) z&_CPpiEp6L*PUsrZ*RN{XLw*gJT(?Q**=2AKwLF)I9fycG-;k6<*7JGs@6Vv_IqKo z+AT7#m@}rm=kx!};{KmN?C^g2X8_hx(g!bZ2xO+RJRUBUybPX`{Nak%-1Tgr*TrMp z?DT+Q5g5F9oEyS_JYVOb*Njt=u3mwuHSHAux6_<1^J|1nhBDY`9GC=7S?^*2i3w$Cx8=OW-^&S(Kc)Vv7QDfAN@de^i^YNm_L zHigMUOz@uyNExhenFqmTE z%7*=D+kA?9!q8xOMc8acb$CSYY!?$4VNma!Nsgs-DJe#zfdU-#yQ=%ePA4fT<`yD% z)iV3*O4FWTtu{hJGAK`RIvfSyb>&PI6>c}eGS1EO=M?z>S6Tf;Wj5WC6ZEz=)MA<> zG+(&75;sqjd*5%eWE^HO6A-zGl5ESro<|Ri60)f!x$KQ{6vVlke`v(kQ(r1(J;ab> zIXNLw+d3tBn719q%&rR{s?%x zJn`Ci{bQMdlYF!#yWO3BD(n3EQl`;@mb2#x zBvnh@7q>T4n2`D5nOUV_6S4dfrd!K@+WA)h9AJL;nb~y0xMF`O)Mf(j2EIV7Y1WhW zkKn5z8TGpK3wZ@jLGNzswo1E$dW8j(%%|cXm9gs+RZ68tEo?=ejVR^p`IJ{67#mKJbVAl?4ya) zf8L-W@_;#6o8~#nv~wUs6@N*5ct$s%8UTHMNH}F3zcO(`zmS~S5LoZm0KEYRK;>4D z3>g^y9;Aw(rkMq4y!m@Yu0Z;yO&OfkuZw33c&o|sMFXI8vy*=CE@?2D%`27MWYmL z*Jler6nstgS+K2+>}>?VH1xdRGa2+_w;9y63=YM7@ICzDP09gw=WdbGAKYN`9MYlIU z)I`9kgxo0D1~Akv5rtzG)Cvz;l@Rc3P$>isz$%8Q;yHye(<-}SkU@UoL~wE`Hz|In z*YyDqqBt|C*L)uox3aQu@W=A(X z_*wm&dotqSO_csw{;>_Ix)rVT`70AE{x<4r+I!612Q}FUrz$dftRxa6?T0CTNT|oP z`%C_uFcqmxC6Yh$Ee5i<6Uc{q^@5aL@dJa8R>is%cNN&28#^!F=OfDwyk~Gt7q&%n zjY-zO|BnqkA`O^}E8MQVg6IL#mM8Fwj~E!c`N=OfqPtZ3=0~Kve^<*wukRO!%JcH~ z2SRO5a*L9@aU~OU&d)hqQ9md()ULp(QE$$R>HBevmP!1${o7D4iBr?0S4yzU`nqiW z0Ehv@Kl;<#d*aAHIEFy|amA7=_PC_jAy{ zpAuY0F_}O4eIR@u@1|P1kUCoxTwGa7^G%|?dS;l24~&7R_&i+?dMkT-D1bm-7Ow+X zZ8pw=UW9)$8l)~iI?KM;`QEjVf&CyZ2c5xnu=7idVq7fIXs6D_gy){2Xul!^)(O<{ z?XF`b%j9BCfo3be*%qAxaBr(!Y#IG-V2bkO<>e5S{dVaWikzN0)Q%%w`rjN!oV;z2 zzmYBk+1)HQ>u$d0L6K`&%X(k8He%c^bX*p?-ACFmuXaq zY#N~9hpc$mcfu_#bV7D|!OVxJwuNr?^n_6O@t_c*;8X$l>x=qTTl5oBEccpeN2L4H zG_m*#OC{3`IxS3~g+b>hR`XBgJfC7%dqBx#-2d)(D2q z2eQ6eIdAUgT2_Hl-2fZpYZZL4A}t$eO#g_Tr%PQcp$^*JCiPD&KSCwJQ|Mwb&c;rX z=>_tfmX(D+yCbmFSlr*n-0zB~if4O^+iDaUmQ8`&spIzl>YiAcI+j^~1wAx8r$v?e`hFH1s;Ah2TGWHClZhFE``k@8iz+ZD51 zZo0PKL9}9@N#^v)_0t%GG%}2SR?&Hb1>HgsDpmuG!{^02T@lt~*7LWM6g3*7;Hf+= zzl8Z$zKA_H1&h5_!ztQYU-$2_4^_8-*b`w?Rq`r zlEMa;4{^XMk@&VgW!LCG3YR0(C99GN zZp@^+R#&{}eCk>_FtOI!$!hZD_hr4_!Zg-!p z`)S0=)!mj$X@_yosamC^NGPbUSo^4wcSt(ZFTeOM%y2N@;D7?ln4awg&DB2z7Ug$s zm6K4pKm^X?6rULhBCz0ypbktBC3$6wImK(soh7d3m^yXJIAo6;w!2()t&7bSX!V)s z<}pNu#QRxKmn+Fx+%>9=>!(FlE);R*QI#$Ffu%Ll6b%@M>hmX!Js+u*+oNJQ z*{->v(TZ@#n<{e!<05)cF@!+DvyT$X@uUF=I;lu5SV7Tf7r~w)Pp&ni~1;v({!d4NUrV&GynS_OY z{tR0TZZwQP0841-gjFc@cnehb77;% zi>vTU(_?_KpkVT=QO#H z-_ZmTezAsG3MKeA&6JuQozfFPF8=n6A8YTHzTQ8tJG}>j7ZT9M!)z&9rF4_Mg`0jb z%%SoVdX(IZm+KBa9gsxwJ$LVL!D=OQ{BrJl{@q@)FMYM7*k4(W{_R5EM$(!iTUf?8 zF(ds0p*tl4Jd6 znUcDG#}bXSC2Q>#@KM&!x6D88DsL*+oZ+b$e{Kqij~+R_n94u6Q07+0d?6gtN_!By zg7t-T3oci*4iB3NtE`_;D1#kT_$|w&r~j{o_C) znfj@C5GzU+N_dGDOeck`sN!l_f?Og@IZPMNIh24Tok)U{ul;lN z=olX0uc8~M#EF`pD7I?hwrbrDi48p@psDo_aL zXr$Tg3&Mn`wro~lFM0L^D7eXRakw^inJF)2zCIWb4fj+AS<2T`kD&CKPn-$J zaYU;uWXl)i)U7ebZ$qe3x$yYu(15yVwsFVFx11%L=hJr{xeSKq*H%=twR?$Bi5#qD z_yTbHzPFRTy{{qu+`y9#Ee<7TZni!`m~LwNr=a~YFqR5x3AF3ATeZ>0sp<}+BEwlj z8b_Nf;GjY)?<4W!Vy|eFIl>`fEkN-z<$L%+jY!v~Z%et~86Xco!1~z1dIK{N9JAfp z=X;`tSDvGaNG@`G2eiG+CG(pRUi^v2}BkgBB1qb=vGIzSt~VE`2J>Z?b0Xe%99go1AE_3 zMS`^sZ^9)nYiFmU6iGfd9!`w@fUrLENfMH=>|fJHD40}J6~-<|nV&%)i1X|G3Gn&@ zy;6y-E+4F|b0BZBB|*cL^7bf?-l6_Zb3Xh9ov|!r( z6fwR_oI^zEs`jgt`vO{_rlSQ}msbalJCYzu#B|1*-D+$_(ecS$I4?l_#V?W?F6JVWUnQ+@Fo#TM;BmnP1Ukp|wVrJ>>Q(9iKJ11Q9rAd-Va? z8n}~YDl^uUWDJ}OJYXxZkN=l?kFiG>*ug{-|60I1n>5@DH^T_a@@89jUmAW*=>};P za%9D-KAN=<)qR+Ve5;}^w{}K@>~-KQ1Co?eoNqT?7TQtZN?*`@I!#Y0eNlE&a_h$F zPFvy_Db`pfev=AROi{mvl&flG+Y~*bKTUN}8_D-0e+&EdT>%rS!vt#(5*qD4X+G%3 z2Ipbql>~PTjMv7pV5xh}flf@LYTR0!W<=r&v?6uUC_z+Nf*+qydAp?J_tBqr9(l`? z*dx2b<1L=h&VYltbgOLP-S^qLq*3&Y8NSE&e;gPU#6~= z`)*rqzKky-7b_%AI3lN>Tc!1G$e|AJtu+2z!J8&=r^)0qjBRO@GCB#@Th-^=??^M3 zrI5wYIsBe|MaP?NTIgrZS+(r!JpLZ`U%ra}eMnH#TKWO(2!vEV93YqWju~RS#J>4) zzlGtb72!{j{Aukb74nBp^5$ClHp7LW-MxEhhU1e~bBLiLl$~UWBsGI)AT2k+)V$m2 z{XkFT32=$|mbJA=!EN!RQNMM@+x$t_hGbr2Gl>1@ef3hL8xoEeM1a>n``EnY z<`UBX!A~3t*$VVh9{_J=(6{E^;BQYm6c_}OJJHckmZsoH)y?k|q%fgB(u^dC9uFzl za307{I`L|wBcbDx>;-|TnrPK#_-;+TXP4ZFs1}u^-gl-rT_(7!LX9^*+eNy(tB(mp zV=&~DK;7_-UbkstT-Gf`!P+)c1};U+p}!(I{qM?sDb{0rN@Ui}tN$`_lu#QE(^If6Ttgc;@)b$tJG!4u-^&HLtkuRMnwD7uRf>C}C6)u%Z4UmtG)YpUDG*f%<>oTt}kmWML4hFG3#~n!em4jks z+`p#)SbZV=cxjTbQhtu5fG6@a``jsjcHUzJZU1;U_()jX{xczv&J z53fdZyHicWDj!!p30W=pKac5usptynRM>-n{Z9MSs65yaFffqIK^Cu6Y-(&Gv;@A~(t+i2xtP0zmJWryC~MxvZ&Vr5Q4 zQ}^7ylR(A2J{P}v9tr5fjCJ)_OEJ!j*Nh3Xp-s?hQhB%S-9C=+G$)N`taLnNB!yzg zd?tVL&HNi8&%rIp%LMF$s49L!`IUD5x!wTxuIin*7_C?VzL!COJ8xr0>G{{y5-_9= z27nCH6|+ZZnvvR_@(R8gnl~v=9g1nj8TvH^7lUXK_Co4RQ7u2CWWS41-K&J_6J-Lp zDbEsF*lCrBITzoy0&uqLG(!li2j`e zd+w~1`HKdqXL-M@mS?%+P5}GaE8x&Kb@;NUqm>+tXj`;?*&$xyi$Y^qvmq$M#2=op zyEHu}L^Kx8-2TSy)fC&vfg`ii=0?38AIGgPdYF(WIS{^6(d=`ve(RKI1%uDgKlE;Q zocW|SSo30{J)rCBtsB>Fktefnj;Jh<&Rj7sSqu4{O?l2Ut>DbnfYGPSIo}KTE`}r_ zLKS_MZvRxL#K}IQGBJa*CgUKpat3-(&EC1rytcx?)3kp?Z*jjEY`{?)TS6|CF4W8iy=xUIBddaf-qDffOHQ zPXbXszIHd8tJL*KZRnPJGQ2_CMQLgMUG=go;iFrSM3_VLVjIJ!LFZWGE_XU&U?6;|;)RSB@x z_iDKtMWr&YnxMF4kopn%VJe4&F(!uTuU^VS4=p~4#f&l~$lyS|UG$XJJNLC~a&Gv|)8;H(4^5fDtl4X+acjp&M*c7z8o#!a*Y8X((lD7409$*wch z9r6*>0N85Q0y&2A=oJ@)r-T9E_6{uvR(7)&mAqAw43-d``l*!UpE*nC7Ci?Aa`bMD zqTk_gis2R!&TfWxShchz@({)GULEbSPZaOR9s`=I6JIvT>6v1GEILB#T>|DYids#? z=OZi3ZYm9L;Z0suWfxWHQu6f%&73jKYc>PAN1M0$*?i^pT!_qfa`z%PRz0v^MsBLUdz50fOft06f$m!jEQV^ukG;5O$dC2YZ`YzJY zysZ`MIQaxNKxjWR4tRO~KdyQeD-!?ylDNa@Dk9-u7O$0H&Pe zLai^X*%_zxN*D+eY~h%(3U z*UXKybvl-Hh#~dh0htS8%jbolUt2t^`dXKhFRx?Uz`_flTe9Mc9aJKf(?I-(Rp6IO z75^h<0POn+FcqqaJXlPxlf)Awi-SQ0q`sNjO5{K%C0w-E4*KiofA0doMRm|qwKK&* z1X83D)aRe;kB@FRtg-4g?B9iww-Pb!9OY)ScfOp`Zo!{?E{*=>4o#CIQG8mE+TW;{ z^T6NwnQy^oh6%ea+G?-sr2PMZj;0Cw@#QyLmVS@OtliJGwW` zs`>;F!;hp`og_5|R(1s}QfuAjX+A<4Mj7scnyN0gkkA#w7Qw@f>FD{RnAd{FeB%d3 zfFdAsvOTT8yQv%-Z@+9xjMbD#30U}m9C>e&{l!6IiHzQODTNptukLCyEMw%_s%g($ z@4>akAx~qnnKwg*6nTKnoRFuEtwLl%o0l%PE8)6UBK2aTpiq^ES|FLT%*wF(#68q( z34E)2!j3{~CpcLDWTm*P=F_74P7 zaQRQ2am1o&G4NmY{0y1iRWww!iQiqps;bzPIO@g2*RNPNi6)E-vKs3biKi7Ao>WGn z+c)7GEzw);vDFkuwdyNuJH;=W1Gt^`*S48ujw$wiIIQ3YHzX?uuG4K7vbu8u#hqSU z-Bi}t){egLO$QY3A>8~w0Y`;hs;NP#$*~fl{(GX;weyHv11n!wpQk)xD^ul0;Ix=E z!&X7pWFz$33+l!esk?suyTYsV&)?NghwvM1*lx!M?*C{DVM_qdt3W8z9zqMtfc?8#`~N^ z{L{e{wfZNUEu(in`5!L7<)uCvgru7&;`A6SwT5%H8DWp2<%EroiYdmuc*fK=34nF)OIr`y0KFHe{$mpyG9y?%G&HzZWTXA|?rMCa+C;jsO$ViG zpM9<;snhU)k<+bS%ZQzw+@+$e$=eFj0GPsekFzdC#WVaYdOorY4UGE`s5XH+lBFsW zz>be`m!rqt?-e_{MOnP!b0{MRB^TPUYi&&RKdmNm@VFF%w_n_aDuoHoF2dgL*48_b zIvF$DL1X44;Z4GR2QVsM!1PN4amz?ZVEdJs8IS58GM)si;}5SePxYi#Tz4ZayVC}a z1FB@3N`TT|&L%P$IV|i_wg)R$k(ZfGv%svj%*1BM0Ml1e1Z!i=pCxePjP5%VNU(NN z`*FUZT?1Tp+eNKVC3RR5AAxSqt!||s|M?!>w+hsgjNoc{Lr2DjG=ShNC-$$!jJ@WG zd>Y}xhN?G}v31GA1?d;^3mI;J07qA!M+DA$`s@Bx~%6xI~3pd$q+5=e` znn8*YWv!1&CHI@y1enuOu%gk}-0L;TbgZM<+8!nFL=AUe4Hwyndd|ogG|vc|qMw_y zNUig_F_qiLfjP4)9^PPD2p6hag+AGVyiMxTQ5SY_0I9HF>O$xZ|mY7{7B zrBk*#UumkgHiIF`wiyJPXhIif52Z&fUc99azWS38`g%D#FQ+p}X8n(D3O38Q&7ytS zwdk~6SC2E;@0VExjBF+O-4LJo*@@dQUF^sHlxyeLEJDqg*9Q3gE1{#`zv-rl)IYZ* z(Fo9A$yRypp&n^$&sYzss8C)rNqgqEu2${8P#$ z2xpQfWeMQhQDmGpDeBzUzt|+1V4ptg;v&KS9B91)X=hD*ZZgDBY{L?ufd>hHG#4L? ze4W)8Pol6`W*ceWiD(dYBmn;D*Lt{*mxn4jc^?5TaF4EnGTt`z%q5{G&Y5;Y51+&# z!o>lpMk-&+>Bku?ZCp2s!g&~7CM)#Aco?B`j}p*Trw8qSsAN4w_d#R2fk!b31uz2_ zSYn}|E^sV7+%EHAF*8KrsW;u4Nh&td>Ti|vYX>&hy^qA0K)pwHA)M3_$fAqm@6~bQ zUk8&5KtbNmUDR+!wpuJR7qsvX)`;N)JQ2w$CAhf5>{*Hf>)~F4K6J^jV_a;cmb6&j z2V<1ea7%+_bJPQNQvvrSUB28^RCqjdl`)X;Q7IPP8VS~sqa+iN!5=-h4kG<7(y zp}j&4#wi3a9sz}__N%0!!L3)U=)QyHRU;=C+lNk^`wH#1TX@BSx3hF^md4cLjxoA; ze{WkmcQ$H*%$G@>5>V$j^=-I@!CgU#5i4u2!@1_+N?IsXuNo~i9~x0Zu1;m9wrh&G zN2;Ez|G_g_OoIQ?cf*khHuWz)p_>i>D*X^3zN#)hMvz^go_Op+^E2R z6%@tzQ5YzTGL1snAp=G!u=`Msg1(89I6roEicAD>ooDTaI%qMSX@rjjfD`~0aztTD zla_KzAc8o^8@g%UTAAc!RSvQP$JSR1}^E9WMkcy|ET*gs(0AN zq^%3X-Ubd86nG6RhTiD51-F1k0gcGFf#)mcuq?p)i zUwVc%gW2`TX;(i>H{Y-6(XVmAxTc4=>jF5o8`))xvQzlX5$HUjJ?dq8OmVl|sImx{ zaR=zw)>1EcbI?AA7~Pi`xMTY>7nmo!GTQL~qDsDL*`sTmf7&8l(Xv-zVe!alJg*(Zd5QkV*FH{*8VAj~qSWgm(DEBz)8 zc&?A*qmI(nS{@U$H2a`_W(J)UW*dP`N2JKhk+%wdxwMRE_L zFcO>F9&wB3{$^bqNrNHOpoFqfG1^o z;7SD_%U($vM22#YY1Mp00K`%Z`c3yMSP4sH~?11VN`oCdY`Gw9(YI z*P4h_CEEbvBdoqY;J0G_?sV&@FZ?>va40bnjnhLOTm#)9VX@*(@eRpKo!BW+j1F#& zv}^odWq*wL+_%LSW=<(T=JKsne4f`6W%-obI+Iv+BVK$}9;sojVtvD{XQ8I;IoGEc z0VFaI1>SfE*pid+Dy*(0w99TfKj+8m;_3)ZM9Xbe8YKFgFk-@*78IwopDi5m-cVQ; zd7&+6H_tl(aS(#5tFwY8b!;dcYgH_Y>2tal=(Jt~Ls_QO7rmFIYrM}bL`g7cSTQ^K zp5h+n;IYgc5Fak5bs1ze|C^&7h(6`9XjNG@fFV={#S7D0Vg1kcRUOL6HI?K@Ejn+; zMTlkA&EdMr1r2JE=JNKC8Sx^KoW?i6$x%s~>=7i?TfO`vs$89`pihf;da%`?`nN5g zop1^&y=J0De8f4+P6!jrT^>lu1bfKLa_R??r+!%b3T4NNTKtKF0P(7nnEH_{m_R<$ zEn!cyvcmf}N6w{-D+3CweR{WF#X$yaJ`GE!X`1$qNyq=FO;*EQd$kjQzD(`2{pQzv zVXd(hq&tUMseE_^qI5u5Z&{nTR-maw%QhSWJ$)GSSB@&HPSU5BmynleNC1Mo89SV|953ETq0!heNkrCy}2vaQ@leC81lCZG4*zJWrJ)+Ce}ze| z_BnVbhWDklo@p40#O7+T@baHD5u8KEvH){WN;U&qEy`G#^a=H#9`?eLAG;00eDplMHqyWi4+HJ{!YrQ>a0Qr&57BoZ%CF2g zPmLS+E{Xm_2}|-AX20j|#ccUwvYklvTpbt5BEG}sr&C?u{n>5C)sXSl&z85AFmZcTjW_9OPafJUZ zVIw(5qNDPU6lGvRrj_J=mBT38F0)A#!NJc#cUAULeqZrZj5;-=?$p04r~&>=$@A1E z%jkzsiDX^yQNCr>c+DqfOBiTW!gI|ib7N5OvCx_Dp!6@}Vlh|FXye~lYZb-2u;A;$ z7XPl?S_3elYoiD$jLGn&^N>k+{^n%=^&#(^Mb0VeyfX#hqzP^A&6Sc&8 zd;res{)(L2SqVkTz`u&9-Ut8wVfZL&S5u1{&G+n6@*8r2uLBz{m~7A&D5i=D#yRz2 zS^yL4G2?cRXQD&6l74rfss_H>B$jqy{jk>@dSw$PX2sw+@XvTLS}Ih;U+Y6gCvP2x zs61Wjt{7-f!rpy9BT$V%32RI&j%#ocFia7TAm8q8E2MYMM9l(}+5Ce=q^3GsIF@bGq&w$b5R!mE)Ny4u7>FL_s68u3$RLnb59hDE;&ns{2u6LU zkU8wPnI=>9m>LGa5~K)Ezx3~^F`f$%FO)`TJ3sVsDuhrIp(q>wM^HXab!d}io=l}* zf2lf~a)aF?g`V1E2#^gy?X!S!?GJ1-HvLNu5^#V0p{FX+ad5~!@cs$|a)|58UMf2@ zw~NBs?e}+@6X##fmx5_`)F}Tw*ggIHfRN;yj@gzfA$L|#?8zf0(p-rsVBL)mZ|Gg) znR*o`XFT^M`0I6QF|hb2aA%0pd|50`xy%v3EoNjW?$#~#pfO(_sDLPA-g_WJH^kT2 zmy;thE~QB?A17^8o74JcqUJibYQ3UI{GQ5Wiesp-dT-=yH@*)gq4}sqn7AX*rD^Kt z?Bf*%EoPab3Bb$%m69M#n2+Cs+O;*Zc-$jhTx;w8i?2~Jw`AdDT-_H?s;smPQgAI6 z$Dogs&J~xP4p2u*H})x1Uz)LRbVM%m+^a9FsgByZ=k&`%Eos(U9d|b;2E|?^o$@9g zSed;R=~}&<&@L^2ucW9yO*_s4#96faa$5yTMz<&@IWePGt_J0)iR1S2=IiKG{E}uL zT7eH;s>IK56;8V{=yv%<3gS2va1i~YIRgN*arrm)LwYFs2ZSlWLiy(p{=~rg$OL4{ zVrYyXv6p>G#UJN)r~+-=$DT8DERLKXU->tXZZ@9r!mMj19b57Tkr-q)u_L68vq7x# zhKczrXO~ez&<~JDs_lN9WV7jcWElB4@iH*>4ucoJ#y&$+*qd7>8LUjOgeSkf$Uyjk zv}%GOB9sEf3!)Nw#GhInQ?tu+BPMDW_5lEUvFP3;_`}5X?=mx7F}0(={_WzelWkxs z0$BR^;l(_~g^)F5KbZYIZBsc@u*!&wBi;S`i2k*VZZowLzjh&SS~@iJiX4ewQP!9$ z$yXHp%`0db)~OqXb&RoP!c3a1Fj$6FD6M#fn|+8scV0CHKEiOBr6?38$X=yh4eu=j z?HDog7dwzXOIW{bmn@gO>NTaZSAEetS&G5;botyV8Qfagnd&&B7bR8NIQx=XZ5$tm zZuMXGV*8W6cRRhYv>QDx|Ce5X1^mit?(k^Yi7MRzQf=c0GDF{NHsTInn(j+_4E|%| zcS$X6Gu-!Kjl9omYmrh@vr473GUliWhluQi6t!A^F|?^vrJ-xmX#7Kz{&>>9g27Y= zx10b;#I73Dx}u!w26v2Aj<2>Xe(hHU#7zbvg#2c@Vne>o-Zn;)!Jg0P?t=e$gDwhA zU+GcL`)+6SgJ&WkZIUBu4^RrShb%xm8f^wp(H=MEFZ!`rqA}9UJo8`sV5>!go zV?@bLZa`2R9>5^|j%MO6?=-8Yj2I!bic_m&}@cJ(|71unzISQJA*WAbMcrcm=9%V1+KeOi+! zacI$=Z;9k+2EXNZ20t#}cicQV4T_8LK85MB)zM%Q)12;w335}zM`@Bf&0(Zq(GUt&3n=?(nf&I(T^ z;6j(H3EtqC&hynxZv`V%zK5I-h-^0;?w@KjkU8Ct?chaxO8L^h1G|(Q*V5jg_bvq) zR5HSBY8Bfsu+g6a!LxC)rn3();vrW0g%5bLoLdaqj;Z%WQDoDQK@44&j=uvnz(>h zx;^dOJ{4v#>(N-(@R=j*K+==1L^2Mt%Ts2)E(V9B!m>7noZ6DaJM=6#dp}nktc~z2 zmi2RE+53V8ob;c3UnrLxO8emB_vKe1B4;%Du9kQGPhOWELxHS*6d4qpLKtpr_0hmVCnoUIdmE`> zMxJv|&dqTImh?h%#e>j4E%UBphvex1(zyjuSYphiN95~|N_SViU}R5r-#@E*n7+9s zetps?=q${?Bavp8elbr{^;`WONB!W4J?-ukjthj&S6pFm#VM{NBSOH3PIs){RVBW@ zH675m5TvR1$s=!eqU9$3p4W|VHP-NF0+D8><(J6c#LKc@8H_>CZxt>Ic2|xN8Un~Ug>VY37;$G6$HQwis{w-N zFTIp|Cg$45)_95%SqZyVyD^^*iNLH#a(RSxp>znvu^oaOI&3t8z0#gg_m)^_{*GEC z4Eg*|T_x>9q`!zD>H=8%MT6eWHz*w^E!sbsor@Yq3A&p?PX#dNd?1EoW6&FnD)PaN zaLM9ILc7qY6UlkWzyWi6#hI?KNWw~YW4yo9-bYB%kItHGX4L+r-;0}PA4c<+=6dNy z(s8!x^`tmGoQy-Q^gCIQ`r{Gn8!0_xcO1f>4;+w2cVlN3oh{Os2gBUoMuw(kPM8yH=&VXTNh1H5)S$xXh z`nWY7PShrWJ%@@Ro@wUHjrmQAl!m0<2F!ICL~`l$3aI_SB0q9FcT#;>@S@us^@6sXt#LtLOs?UQ&O z0#gr=4rDY5b{*Aqb$^I#)6rr}HM+-$&{_FTb95^=%svXH&Q_=15P_WqRgsXm>~|Zh z;Zm@UC}6!Uh*mrf!lcwU+P@ZZ!>TK-ePuL20XpJ=Va}^Bme{E7fxRLOi%FZ|YP$}! z+X~1Fo~s&TrtdW1rfFuQ_1Nus9TMd$1dEa!Ee{4>SlQGuEp+pRS z%EZIl<7l%^p}iZj02oXRi1)VTpx{} z)}kP+HOlTIidWZ;2}bASxIm;j1h(PVGvaL=p5(`;mj3@Be5_(BM1Q6ShYBE#&kkJB~FHoU;D9%EwQCGOJekH{51)xibRge9#Ry)sjL_ePsL z@r44n{K|0gspU8B@MpZRA$sC_HklI#oamk7zUw!3&pt!25B_jlymw=Ir!P|R_o34t z7Wj{+Ucl*|Szy-!;^_95ixkEHQq{$H zJkv<4R~&)W{A0(8uyKSZarXJ4n0JG&f+xUn^=!zQ0GCm|Cx<_W!VcYwhabI2Byetc zx?r*|rIEt*4cmSp61JeAi_BdRS?0o2W+~<`PoO158ggFRUN`;5(CB~ z5yO|Wu*WN9aqx%Jb0j|RZzPC(nbSX~Z#>fFwlKDSL&}?Ct{_`^G2cGGri(l+a)vg3 z>IrIFD23~C>kTnnVQThy7stCmr)`3{o$itm zM92AInPXw~M(s}E&kvWOw2WU(wU)$N&Jl(kljCa&sUASlgLeGadum^N-Mx(JFCE+^ zMo4x=Fq95h1A^WNW9+_zk@rt@#YJved%NPc%@zxaUNOQFC@Dp7EUNtnY6bL#R#cR|@1*SyAScOftis ze|x(#dG7!EQlvP+RD)B+ejm*hi4~Q3_KTOvZKE(cdL+uzmvG*f04km&$ z{ivp-1&1drp&S!oj2@|sMzlX@AEg5r3)<6fQUy)-@)7lZAdSiXaH+-i8{%v#0u-#uGSyScQHlFukXL}NIgRpIM-~LH(CB=9t19CRmloP-mT^+Q|`Ie z`LnrtB}36wicAzAximo2jV3h3@Qiqs^4%R8so0=eKpheEfKxZh351S=-Y|)v>aT4}Y`zRa6PHd9|iFk}#0lsV|CPvcTs*+HYL- z6^<6<324DGnRo7Q+5BBhY#rkN6^$?H;1HM7zp?~4KB=@yP%&E!Fz^4I))#c(ncY`WAC4?9F&{&UX>U? zL1y+eu7nNVzVDcKifj_G0WS+jdW)=DD+mSvQtoE_{?1tTb`Pn*nbfavClH1(O8gb_ z&F`6g;L5)~;C6~S`%&56{b}5~sL{YL8_QItvtL<^Z_V>bKT|Rl2hg}4a_g`-6eoK8 zOji5CcX{ZZXL=rL(yN>IG3FNXo!N+W<`EcPBd+ap4M*2r0ar7%?f~~Xju1JUA_fiT zQD}{P`6>Hv+h&$>vv96l$lV%qKyV;F;aQULYD**CbW0#-cx0*O>(8ajT#&7F#Nn5y zp-$z3N($eaKXd79BdhMJ#P;0ye>RP=0GcwhL2J|+^^~&QKD~^ogpJ7~lD0rTIxg@VoBx9m`ysQF%Sx6R$CXvok zLp^wulCKnF#b*r|oOXVJXa&z797Fy zW6X)Geh|t((8X-gmcR$mBXC8e%6BT8@&2iE(Tv{_Sig4Ks{ds@#D8x%(%~RZmeq?#u!{Fgef3)=3F|9JoENGz%Mp)?Q-sby~=7sutUWb!0QJ!JafnoQy?H-D>B}p>q z(7+-3>y|YfWkVJ__ccu6q6RcSomtmPjeJbs%=`Wa)Vd9(K;=CId{ij(sel-p;9Gr+C~@JoKoQ;Omz+S>C+)ZiGR zNYkIB+r1CaC0DxTKD1*l@<+J#HgZg;i}5l0x%x9Q!rGS%74k6k4PZy+-#|f0gT2b~qpR9Lpr_wH_<5d%wA}gHnviu6V24zy_MQ1IDM6I^twTbX#7tZtg~6H78ai zm_lDqydWKm^#FX^^9Q&jn2}kUMV5)6hb5@C*^oV{!X7W;2{tXp>DSG`p`7BtJ5FmH zIl;#wAX0VI2nmDMQ)EFTygOh?Fm$!G#E8E{I@MPylA_+Eelk-{ZXvZd*-nqW(2e}O z0wt_+l~g%!zyi7CYPd?KQdK`$n385nf@`&e>W%J@dQY9v8b;^@vd-qpt1Cq5h$ki* z#GShnpYy5$zS38^FSJLCF94O*_x%BkdQmwjyX$D<%5_dlm^xaHv994QwA%yl9k*}B zmeOD=Cs;m zrxKYMTh#w~@h7RNp>Qqf3d5Rn<=?C^RhMCXFVIH>#YYoXX+_cKxL?EApMrt}tIkvW z*{sk}ciMf+XzDz8?_|JGc1n0~`MWS}24A+M=>|eDa3qSIHas*OaIW(c&_S=HAo9^NyNDgh{0XIXs}H}&b}B~PIPCWcIqBPM&0x}6jAM{_OOMW*V4 zrj=o7)QT)l1583pdcd8RU!Re3MAw|?de^1=vA@FGq&zh)tVWWIQv~LlJa^7zcT1_R}z5is(BTa3NsGmG_)WdN-tD4p!cGmcUB>)gP(G<*#V*WC2Cdar; z>92MCH;FsThY$)-@~1&DBd=G)+9hx+!LLJqZZnuadQ#a1^nEwajtZgH2l{m&xIIe&vPutP7dnDzaTe`zq&i?vpAY<$YNO9iI{3;D+Qy)=;JS zo}xdo!WKp6i-RTG&@*BDXF$Bh96gOYE|Ktog~~7V533T5%I(+Eeev}dB_Y{D5;>|w zlz#qj13%`oP6`^N_1@N7sacF1yK*Fu7hrwSKX=^e{=V_1!rl~Q?(2I4iO&19o5BPlv<0&2%a8uB!X&Z*9UN6NWA8 z@HqNRgubn?*y?pT{D3KZb#!AeczH@mD_pKh<`Cqm+TB&aDg?vmH$}4+>m0OryoFft z{a{7NDXFY;xhd59QEc2A;>ebja(yw7^$^weWPZe=6+~Gca-MZlT=PAtjFp^S4886?X~&(4ZXejSA{KNIFBzmH zapdxy>GLb9Xx5J>@AU!y_}}^VH_UjkOWSC-E}0j=WUfmp!UV4e{3gdATDJ{+JVmqO zv-7I?3^E(?#P_X4g+GJeN9i?1EM|8**XK4Q_>pE6d42)}CFDLY$6#Tw^S`WbDkuP)~TlgLlI~!lYDDqsj%wEIPpx!c=mauS2{wo$g&flW34K z?elhp<2_WT{;@^0iaCd;wR-0+$$Mq7FU#-Pt{_-Gv%E<5tTRv5=)b{|VTvA0OeSpN zCfl8)KHko}=i+i!S=fJdN!|koz90%* zed0xZSj4!XuTPA8TWttq39rxgeX|>nPYp;PZoDOK9WO5?W@)o2qK^tAz;2G#!r!W}%{~SIO!tp z`Yi6RZ53H{Kq94CIQN0|Bb^48GeFh^k99-#+2h&=UCtR|wmEmrJUuE8`*Qt0rPMX| z<-%UPo{9SkFrs#loE*(yFaZJG5wk7W@*iD#5&$_es@9SJ)kjE#qUnqO~ z+gOq*>Cmbz*Y>|~(8LBMZ=q2+y%sdqA_ECKrC!CjW2AL(JisJ1Da;lTKdqwh7FTp2 zGkND8UFpeO-@Jbnjpq)%1ZD3lEn72#IcW(>6({R#(OG`$-htU*D<9elEFBA8j={5g z-)si;v)#jbzv=DYxZG@hTJu`S7jaJ_-xv*U+Lvw&e)d$>d-a2%UtYTO$fWmGY4~s| z&NfAJnlH(3${}i=oYX{fzFT{-|9Hz`;Y{4i+&fr?rqZHk<1HjYTE4mELc;7^TGiLV z(`u-F9v*!=^^Wv&&pW@94R9QO%QX7fH81Sg0rAFb_%*C0dhk=@b7^+2eiQw;QzHO|NrXrh&shdYZ)gEdpY-~w!^Q1 zUf*w4ue=HmJ{_L(lzTUO)FmXore0huKzR+oPIKJ1A=gJW+qA|QnkN%!yH=%X(DmhTnAa{dZ@VV)!M`kzM7k|)8rYbL;C(B`%Hgo^Wr@hT0RN%)+o~epAlfVV z(Sx>}@WYX^*P<0zKL%kkCvyY>l=+zO{p(wzEl#gAU)xSbL|L%mN_&{YXC!UZckO~U zUS0N@=Nn0?gx#G^zNiVE6@3T4V06nV9O+HafQO-1cn@L+|DE&MQe6pu+Ew@0IeQ3AbkqWWv#@54*$kn3C|tQ9EYJTYn6KA<4!A$Se$kR zxmpa_=Wwq3TTC+TmXx&q3ZEDkc^p=q*L5s%Tq`7-ugiHg^QhnA!gSdJ6mrG4q;qT2 z8h5`*iY0W?+8thDZCXiLTIel>HO7pqd_ZFQ&#MSacvsdAx;(lAeskIT^KSU+T5Sv- z#iA{PNb2XAxR_5^V-jc=I%*R8=r5b7 z1cv)7puYhix#mIh)qcJ@}!!XHeeKl%hub)~_blUFpHk^I`0ua+$TOcV%)tw-<(#Xpzq31v%sL z!Pqns)=>lhz{g@62Z5K)3q-%=&xv`?D5<9ovFnW0bS>9K6h4;+yfQksl9C(lH@+9i zeZf+TG?72w{Liz1lV-J#WGa-0yDjB-bwaCk5_h2RU zA&Uiz)2QSvrH4^ek567%aa&^4B9}<#=2qD)B!ZcP0^;YN2@Iy6Zqg1csJU*KC?OnDOoUeK9l0T1wqC8Iz zRB?h-wWhT!{j19A;mcoAs;JJ1PnDXZdwy+bXRxQ`Fh@HCUOBXZE&buFmior}#|y=J ztmTQL{qOg=UykxDepS1=J6!7YolzfmT#vQ@A7I7(&=zd?21q*d>^Ya8fbjEKbWb*d z^yskN8gBH0w zHt(R11s?e0K%WVMn5hB_(rllD0tqE)_>U3eZ~Pa2L0pZqBKe#~(}g@8VJCwnWrPr| zG@33K;ZPC1&V5fK9wuvB>kvC8O-R;jzsl{^f$pKk?u_u2SR0mBb}(IBGrNduZ5EbC z1unc~9!^DbVHGSn^UdO=GpP+f=N8oHr5{XzUG#@UMErd)$O+jewcT^HVECPwZ9(^{ zLqKOdit9U`l_P4vYSxfaPUpXN;I6ozHl%ceeQ(-J#otWUJQj`bRkJl@Nb}}LwUYF6 zytl|!cRK<#?o8jXoAC_X+_CVc^V%zcXW9HSKA0fsb4@EtjA>&Zq;K|hC*a8~p1tHbH$Uw8-#PmKdJGPb(ua_qjB>r+DnC#*-?`r} zH{AuiVCg<=w~7icw)ogj;gV}`j(8dG->JUph+zF^lNSivyPEKSD_B+Rr`9iwnw=3M zWtU-=d@$%R6?$t?Y!QEL6SW;J_40BI3IM1AqLo z(d0L!6Bl;?azJI;l##!ZbVODZDD0HE`XeTaP|9QH|M3#|rEqcH{v3+vg${2% zd7S@O7;AW(dE9s->2SGCT3-v$rz37k^U&!T7pN@Q?DrybbBrd$_;72`HmhSA-W!`J zpMI2XAPk2OSYUJnNg57w7eAxh;8%SBG_HqAeZ7Pk&7Eq&yWH@pGW+E;PMcCp6;tUk zN}ETd#3OoRTP#+tg~5mxOqh2gYD|H^swg0|i1sx(GY_j`#aTJD{8ZGNAuf_^E1Uke zIin4VL(PRebLeigQLhX+`s0ju*ud0=Mw`q4y`iX31R!%vmw~a?i~krAs#6p!gjPH5 zxA5_bHS_1cNB$hc5RW&4>Z1|EnAvAeeM;P44iPH7>pBKv}F@cHLvpSxK9D zeGNWd=mE9{l)0hY%sZ}bHMiHLR_+|2EiyNEw|N*f=wDiP?+EZRM1?gjhF)blh@o~h zNy0ThIeOqXTm^4F&4vl_TJBCS`FF=RbZde_!vtJMu{|Bopm^}H!fBV<2C%^TiYbVq zn^So*#q!{hF~!CzNtyM9P1m_Of8J}jl^ty#@4F9q&C5@a@N5<$KF3z(M`!TERo8a$ z)gmzb`G+M->YRNZOg}3aJh(mrSK+*DntHG>b&ufF8_Q-}zso|m!P+%O>~29tnT(R5xjuv$HY)`- zle1kQ5sZI^2wiKJjR35-zf<%5CJ^Q9$iU^X$d-(tGLqOcM(s6rJOAKn{rdlyq#Obh zzaWIwk)}=ENOxUp^57H!fIT`FSaZ?s}3=D5IVsA zYkou&OiDq82wiwyPDSnR4pj^p_qdy*9n6M~wXufjdm|5JiF8izajnr=bDYdI9g63+ zc0@Im#9N?b(C;l$0g1*2W1zI%!A^EHOU$Iin$J3*SBipo!PH+^;BO)FuQVU~mCj5C zTte9KpE{P1>Jdj^6z>0{1yEFDS+rSNrhQ$KNZb$!KttDu>2TswyS4w%P7HwQeQf3I zWJ&b$Li*+MysqA5qd??srk;^|b>dO9Qf~f?;H^aU+ElnrXNslq(TT^5g)ba|_RX$v z^a(}v>Gjda&GR^=>)I6znn~*b3$7dy^kY;E8HxsjTur!tjHX)NcHX2sNHnI{SpPTW zkU@F1^4YI!%^A|-+Yr8TKMY#=)`GIp;OyYgKArAxNw`w7ZgUzGXixyI%R zoPgd%Zp$EBPU;BqRDqp6-x^^XV2)_b;2ALyUGHM67@ zVM=w`U;7(Uo9BLQH125xS=bz0|L2TG1GoFJ^Px=t>6hjqM2^?z_^2{^$Y4Ow_~Y^D z((NiX6mwgw&=>aX{mB7bIBw%M2Anm|J)*vAJ@L(jb;;5jKP#=mBZ>5t*z6e5H$r!a zSw?cf(rB7Fh=(8p|CqQx=h}&_w~NizcrUv%Z2k3Q7L)k`~c`yv4 zR0ryRn51ZAHM^*$@UrEJ61H9v+za-Tl+v`y# z{=Drd@g3MDP5#Gdo|ggcWjE(4+jt^_%|?#P?2p;tB(B)0r9J{yNIM;#&yd6`U@j&= zq}FCY%&SxC8InbFiv97lzwvYyy0A1wrEdm;@S4VI56+9_=7YjPx|WcYk)ZlxlKw{5 zy+A(m?V(3*=0%v|aN&|yke=QTiYj;x4nFC$Rwbd47J$>45OL3J0X_Gq@ z`VM0^+_LeMq%tMGQZy`l%i|`p;eMN0`}z~%F#5Bra7l(xqpaN^**+|ZqxSLtcobv_ z;9kN6{~VrXn&BvC!IFzV-|H>gu|u^XPHse*H{4S;-QhWK5qtC5W;Zo zyNtCQ=%iRG>1BrxiB+Mx#I*;y{b&m0z>w*7U2AYy8P%&m`l~AAe&&djmKowtayB5- zR^4D*62>V(p}3`{w;LwgqAJ6fx`14efvOvmg(w*3gxVKC>bC74dVh^^h?TnYDwj}3 z+>)}%%1G#%%RNV{0L(&ikRSpxVLIDu+~(n#Hi`ZU5dUwBgeVTFo|sgn$a!b7yad^F z?f-a>8wQ&%%0bPf#_L$pcbh}DcDAd2c;1x3ViTd2A;Czt1-z3h133~`;H%-!ADckl zZu{MaE~LON2S*f3RvP%xLSb_qTk#~mo_1o+#2d2J!OA63M%#v&l7i1>_(fL& zrS}hI!GAIB+;9ZUoUhR21M~)A^scg)uTE6$TCL;n8te_`2!?(s&5sx@{&FD0-H?K8 z!lnmPcA@{zX7W<};=Rf1i5a4eE)ID9msd3aNIXfRy#^aM*#e}wBFb@gS*jB(X)toM zYD{JQL?$mATpkS#+_*MxGG?7$yKUQFl6`#JUUnYe?bSCUHJ;cudV^vKIBon)+;Q=R zz40(wC&uu+4iS04#3Q5D%EFeh)b<+p6Ep5aZLZ1oF~|&w?>OZJA3=B1G$%j${~8NT zcC8aX_)`y(O4k#{!AePHdEGyeWqLUGeUIojgE<{{1>9WNE1Etk6+>YqjuA+1u>9 zX%;0=8B0PfS1U7WK3Evo@KRCE*&Lpx+jl)1Ma`y$SvRE3mC4<&q=y{RWjOP$c>q`? z`k5|khHU&l=5~NYKlbxAmdhuKL3Xi4z46siv-|c#FDVCB%x8wM1d_5zf(*Baabpd+ zgkDrB_H|)co}VY<{Lyd$-+F);$Xt)+-gKE@MpMkuH5szc^_o&}*&{aP! z#F_N`8{ zYymkdh20AeUq>)HK=yhTDB|$FgI*NH*Lzf+fS1`Edp}3$;axo@Q-&s`a%%BWt6|i1 zdlKSg#Nu$e`tX^Xm|!(eNnn*15!5jk`%tqy)({DCG52-!;y2J?|nQH6BD$)L^X9Mi^C=6-OJt zUGTm(Y?H_qPWQjy;zt(=S91r4nJ75XTlEp!>DfZ{p@WRo$&M+ zB?*BNoybp)s(8uI(L;$EYBU#(a0|XdYlFkKUiA-170*1X+sBZ%*=ne~vefpf4}U+Z zYe*e(g!$?doW&6FRW4!@>!F{6jCAMNCe!_HlfVg2JvE&tJk-BAd9RoMtHBjA+Y-Yy z7lOFQ6GU6KcG_f{x|jrjXMo-Xu;xnRwK<=Ig*W$p(OC9Bbj+H7IfdC{C}TOGb%{Q@ zX$iBFOA?EWaKH_Uka#PXZ4S4sL z5#Nsj=^z_JOpCOM&`cKxxbw3q(5?}1)~J*&@~ZF&d+%$98o^8A*NoguYyEaPEc z@f;_QiLXJ4@JMFS9s=89-1uvh4cBlo8|^PXTxw9~y?Hi(`@oUp!icS4_R3PjoB}l& z!;%79zGBZZP@S%2#T@%}E_!*`#r6q8NQR6J!En`BNP|fc zdTuR)?aIK6^3TT2>uA0|-ZO7FU8O{f=f8XHvSUA=3C5nT{-h5x_f4q4 zth~3-H##48FT7n_4+&1IJZWEdY&w_!rdQ%(2q6Y?0*TIe#VEDLbeQrK4l8W?+> zN@3WIzwH0IP-Z>L5uf|(pN9RkDf0;#%2UycV_L?Qh1{oEa(R#ppXJ^O=4P$z{yO1v zzbar)INPdbK#|&J6riwim(!mQAqRGaMdx7VdadT~cs8!JEKy<$vFNG&w{KuXeRRtjN;8T;u?WpBXpAjvDFD&g(EFTURj0luMUfhMC=` zJjDsF{QVQ^PT?NXGpoiJK2!~kS!wp-;}OkWMtK|=4laO?Qmk_>Oibh2Ko-rY0n?}I zZJyX*VAFf$to$inX|YME@r|Wf_~#bh9Lf{3j`8A4LtTpbDnvwoRs_O}aL8NnHy0ES z*U^MTv;AIc|D64V-JZSCQj35N3(6%dsrtZbBt!%9B&0cbyT5EfF4n-nq8+MXwG(7C zs3M!pNPJFF)0@?4L)0TETw6$HCq9i`B4y=iVETAa^>1m$G;=21Sp>XI#kyo~vei!0 z8ZmjSyjI7IowEH5BXnc)^AhbuvYV1k2c&1T2l^G&x1lAiw)nw?8!=+4eVu^|!`sV& zPUChv!kl_v?SKM-^uKEZ#waBMzGtY%K(CC~nhl?vRbK|g@BEz+Sf6>j4C?9vj8s3uS5*7PU-%sY25>r`Y3AKpZ7 zb$yUBkCw^&Z*~u*jg=*CM6V47BVQRe5M;O~bs<@(HucN-R-!w2v@ZAh`kIt>8q_V0 zg!awCe!Ap;U;7p=&Y#r~JARa>JEGC6;D=>ebcR<~)m)?Iu%=*)HhS0LMB#+Gi0Dm~ zf*GogD^M{uV2&Ff;`tc!1227m6n9nU>6He-Ct2}nl{Qew&w+eg@%DHK-T*##TFVH- zB2Sx}+zbZeb_PC4v^Kl(0*CS`rjEs2=9xJv@p57fivkKJe2$O^8HVs@XM{=EIxBMP zBtJtvA=_MYWJ`34v=>?f@@kEJycA?{gOxj^lQP$;Hl%HyomWWl{d|-Km&xi*|6*fp zhJThnTGpF6|9~3jsV!z7Z98a(a28gdL98lX+OU4GVmhVso_H{4wf26<_)R40I3OO& zLI0r2ZF+<0^Oy995}GuuwyVh0d2nQT>Q(PV_ft@)=A<$W&Bl zYB>4+8=j0Rk+EqmmaMZ$CKwAwW$R?aL#r_|XnF2qq}52#i}<>^$7eM< zf+p)Pao*KF!qAFfOvef<%L?@8M#EwAr9by%ccjx_%oU`B#(a#MGfG$X6Awf40m1Ko zNzRt?RQLuvj+&s)kR9yNqCshr$9P2QP0FpU9kGl*8v&=lSbUET8lyN`tl{!9pgp%M zaSc-c?k;_iAhDIzj-P{<6^BMAWK=$1FO5|NM@LJ z(KcHwG3zO(VPHFiv$=+GqFi>A@moxaI8SnI==3p(&&GdW!?rk+*`2BIVE9=1VC`~7 zsd^&y^E-b$BRXEYR*lV$L++hoSQ~z8%0n9^{zJw zM`OzGapL-fm+o(ZQB==wSOpCXFPAsHaQD6Sm#rKn1LL7=&Mq#D;yJ3$RVoywMsm zu}Uln?FTq(QhtE%hXsn%kS3N{T|zQURsE?!&s?OLHy_s;I(oY|UM@~YNG@Xi&M|F~o*JFdQlt5LHE2OqoIas4Wy(Ul^z?m@H?qV26d;_WRsn0eZ7m zj0ZsQWV2hN+WBV1TIT|`?Ob=Mb(eYNqiu)^PpRJoYP`}bjh8nu%b!*S543dl4ygBr zj{0Rp5ZIAB4=%n+XF|J2%hB8G#s%5v^G=>|E4f>(;lYRb-!~J2x{2k+{PVkc;a0O& z$B4Zt6Sb(wyqMtaH)5=<{e^SUOdWXidWTVjafLje=gwRi}VI z%^`_G*>X=$lZnzMiuI7$B$l_*6KsxgJe-$wR>Dg z+nvSS{v5UW&y8u;E4Q4&f3=FAmGwU;Q1|#_cPRBDbz7fWBIV417VQr%;;_a*+Dgph zHEZ0GVd9uZu8dG=c&e4{5PjC;&@~y2))Q485A=%}2D}j`)#PyQ$uxP#x)#e`n-~Zs zqSxLAmvfC~)m2jcSmRj1p(&9COf4j1Wgo(*TNABPm#B!MVJ&-P7qNCX+Q${2RIzVm z*j&s48ek2rs)CQDi)$bgzYUBE6ol|{XtPo@;6fBT-4hd%LxN4kwn~zWjoWa=Ra2sE z&efx!+Ea(~Blj1ZHtaFVbtd@9xn>o=&BD%j714*kZfYd>`ikat#FJw^uB{KkjKE2o zUZ$iU2TPC#(|RB>4hev>VuzH=Fd#@>d{gt9kc#lrs6>#$P=?i#ybgSD(6WLYbN6E{ zs&T5Dziz+AqiF|+eCXM6A&&#@>dDLp;39Kt?p{@Mw5$2OX^eC=TY@UX_*y68mn3RE zw5p+|RYcO&n9c8pJ#^@a18@%YljoW(4c)K`_fzKFu3yrOn{79Vk3aU7sp1hK!)K6| z>(JP@O8c?okTdX3OB2`L(mL2DRPT*k$@fLnkgT`ViDYdJkEH?&F+QYz(u3J5YSFzJ z%D<_~VSTzNt+n~*5+nL3*qs#>DLr{S^qT(he5JmAY;V$h+AS5jj*0iS38)^X@PJws z=b>)l1?XWtb5q=hjxTaFp~EucXVO9*UZ?!y&4ImNQkl5)ctbF;>u*YmmIq~)Ow z4PX;sx*Od6>+A%2^}DlPqm&t2PZ{}&fC1k*9= zQSWXNxopst0ubE(y@5#=$?(fDvdG>@iB3szj%0?x;QMqp9y-BL#PAubvg zlR1Oyl=n5AJ`AZsst*4HIe!w~<`O55R%d3^%ZzRvjv^L&#`BY>rY%Xxwdh@OH``I# z>Xeix8Wj(IKjp$vz?*~%a&KCz-w>QMK=UFN=qo7?d%0}bwA8carf^QEGvR?d&^4rZ z=V58gBoN@gS(n^6gRXJydTfpYaIg4*1f+Hy?N|YG&u`5<`be-5lH!Mn^Dh5JPE~-D z=N+?8%J67{cRKps5#>S8bNX)*=TmcZQU-a_A*$#=Fr1K|%GbSZ{&VDzt@7mEQ+jKGW zYxkbjEh{=UIpsHiIaq|reQtD!RKT3je9G!x9uyqNA4qUdj?z#!*Pa2Nef{_8VjG5C z(b@q4hB@c4eMwgSWW0SDxe81Dw(a_1A9^WC{kAT#ZAa|&HK2u6f~CGz#II7>382E} zy$O{p8_@7`4*}4}=?T*5p*A}8HL){+&A;#9B$mQC5aLT%io(WH3|(ZiO3tD)kZ22} zPiF0|)#a5(MKC&4-snI8;g3@hyJS-yT`G`p!8Om_H$r;Ius+wubRnvo9*_efP>XJG z#^d!454&23CqUHYb0^P~~%WT<|# z6=gv?cms{i+`%L>gS{a+9c|t0k@lf@%=zx2Yipp;2glrwUn5S93Je{Lz0j6f>J;EM zHLi#z1>h~8*Om30iud>)b&c`*b@v#*RqC7-?Dr#g4O3%kT{c{n1SahGyb8q6HG}JF zKLIcZo&${q47ZFKnDA7++FcdPxNVoMpdL5zF`Aq*sC>|7WDETZ@`;r~g4g?KH9@=r7#(PAfOF2a0inYCraNPjJH{`_7R z66h{t?ryS;^VuCgpve$AMbQwIgz|-{Ra4VbX_i2c1h3=HhYT1$pZac1ewcM} zBNs5XH1=klo=Xk4ES%9bJ+4K$=YJcSFWQKfo^;?ssoZy5gS9neloof6ntG*VP8}db zFdtPKQ>dAUKeIo&P14IQnjotJ)|v$hrJ<|6E?dp3zv=b@I@Oi#+Ppof1R~QsJWodD z|9n3OR6c=x_9ks_F_`1JcTAl!La0-k;{2TVB;c9y%@#Fj);w_3%?5dfJ&wH#+MWFG zdpaVVyS>mD(uU@^ldmy?<;-Y(j5$$?OtQHKWop(dj}L}_ z@Llh{P);KSYd4?zTFH*y1@m-N2X=_LvSNhF2+-qwH{C!fYNy2!1Msr-4uUAtYYDxf ziUxT|haA0l6Pa4le3Vkq*=sj%QaOrzTE5?tlWoRy4@ac`mX=bFcv<=DsDLEY;OerA z;eI)lVIJ5)?kg-II9NB3bksQmmThcn84uU5b;bDbR?s8rM|D5u^e5X67EUpBC=!E2wAkli|~@k&NUCG%mJ5ltlPX|nhD}C>>r@u z95j@n2{F#iRhQJNYn47amy@urvLTP->%7&*ok>I=8r>l4RKWGGYV(Ak|QMTyrVaqpQ+HHMg#R*4f-T+nlC6QlIGnd@`Znl|5*PnxKw z!yk{Tl);!`qQq6brG>+LpMicyTJLW_VbeLvvmA{%hV}dyd;iy;n}U~duo?ooDlf9{ zdbi3A7^0*6EFRlD2+c5r_FZ$h`ReO4uNHjG(<6A>d3wem`ZR->5PV#@+>>|hhwPA2pRM`w!>C}!5Ov5QBMi8y7qFW`PL1Y^&W!*g{K<~y) zpeyr*=qBR~C!lyu_}4(^KrTpPcR)0yoNr#cLT+r0N%r?uZ6xf^?AD08z^(Iz9)H-i z+A0A&{1k^w{h&I5S%j#6ZLVb%4m=@LVz3A?05=*<^aY3>8<9x2q473*KpjO}Ye`es zeo{_iqAcq=}^N8xj4B?Ni~QhypX z@;Xk1=C^ZF#ZAkj+VRor&gUwfRt<1|Xgm9~(??z7#*{VaMO=7fG2)up8Xq|@&Tyu) zG!;5{1)R)O*~~@O@o7cJ-%l8KSgV*Vfx_Yc%v@l%`d-I@waX#-__h#R^4sP|R`tD} zXR+*uCRij#K@izqF1}Gcs}6&1mc9qCJ4h=-PcI)V>! z9kDZw(vHOlCQNA?7qyHpYs&T+bLqcWpJ_5#iRY=^poTurEu}sa`hLk&Dyj{VFk*JM&>AlvQ2}mc!%1CXo$>U7Wm{)VTx70qz&PGe9x8^Vc zvGBO@+Y-JOj89x>8PcFn+;7!960?X}_3Z72zRPZ`OzWu`zZX*ll}lt{PQbf^=LYzB zTuPjyYHW3(4h}CC*5O4*GE+SUvQj>|a3KR9_13l^5AXG!`t06nuA0&mk@%&s9kwUc z;8+!HFGgQI8~JNQQBIeCs7UwxDZWGp@tUI5IY`V78*V@$8G8@yjW` zWLSSJOPRee5vk2HBDwAxzW4~kI6Xu8TPOeGG0c%Z;DOW4WAB{#aM1b)dyrJL2)Kx{ zruykLBkQzurK#&~&uDN6ca@!_1;J__-F5v~;q%FKR@sSN{g(B`#H)y18G+gia4%vG zTQ7}K4q|Y8-sfLi6H8sPY%cBj`3o z!*1mC0~bZP4%4rjg(!LXxcy9;7lBaOq|=D_Irs&UTgwf7v>A|@SGaPMKA&=(i0yNl z58s(*3;B%=?-qQP!_JL4Vo=e|VcEpaYt`+|jX|0+kV z!RloHE{MKLzMQ9b=2jHp?gz~y_CZyLHZT)w68!vRVHqVAbWRIASLHhmObL^CmHgUr z(gqWIKZlU?6wyFwFGTynvG4Nn3s99P{JS20qLpmei?}-7U-fqy{X&kS(~&D!L)+#7 z$T`}68H{PSBOKGq#SumOx+!a8SxBCXv<*P_(Kt)WbT4igG|*Lhdva zKRvD6Qdf(^+cuGGWYiWZOf1Q(uoOtY9MTK*+9Zi*C3=ECJA&b=Owbm6Rd5R&k~aL6wqPg)I?6>OA1zv$+=y7yj4YlcmR;~v3q^4Ssw3K`owR2(dLqm zO)AX>&ht=hwG7@bACd z)O3aE_bVyYaGCUgY)6A^aWJp%CSqWfg;3-s4^B`e(lffoCz+ zUO7Zi%w6Fnb*BGg9}+nn{~ATjWF-nfLN#HL{}hq#mTnquz!JV}m`1bmfvVwG;=|8dut?tE`~ZT2xJA<% z#hwmq@p)GILq{+OOmFVj(FY_s5DqKu`Y!UnY!dDJ$92I_Ue6{9IE%lF@>VQAt32Sk znUE?BUEluDz^fdR%uR3mj;k*%Rz?B;&G}L7E~he9D$9_-w89zuqJ_c#A0!{Sxdm@l zq`^PqWSSxB0zSG)&fsz~g%O2|(~dq3`*PcDjXQU~B=>}GEUicy7dS;bDxh}z+nN~0 z*q*ht(x{bmrhXYgfuouO2{-e7c2`=2BMGz6Ch2XIyD7sQMm?|g9#}-5*JC`! zM=uAe0);PzA@>)sq%^5s1Kb|@Oyi;>XJrhGr!twsOOe)9GvhBwM!`8BlIDDbXXo!~ z9dhcQyZV=}Dn5&EOq9em*pcHw_;~*65aRKr{j!${k2t)JUVZsxdMbcA=hoOuwFbXFuX*T6k(o{-m&i#FW3DH zmr!|ExIf5}*Il?US7NU`eVr*{y$@g3X~U`G_mBVa5}Oqf%AYwxF!sqR8%+{einP;3C^H~KK;l~Pa)fU+|CZj7|@Su4I1tuWS5lk`Fv(k6N+0? z=nKrDA74*VNCj--)mG&8V$4&Wg@gD_qFkyPcWElM(vFH6s+KsDF*R96O_EuZH^9aZik+PS&9Mt2634-oQ zv>oVrG{OnzRED1H#7wx&k*s~eu=vLve8I<*2tJp@ zw)xS~KwM^dM&z26D4pvJv36@7{j9ot)NFhO%hAO%N*=s_6q%#bvpm!#>ki7_gN-K* zdMcM7E5^g=IYh9;hmW++6Fc%tk={)bv|b7Wi8vkcf0x(B%K14HQxJcluSXb~$;&nb z(tj_7qy>7`w~U}}*7wVmea_V?x~}`8p=SZPlQ*y--+A&gyvS`Qk6pbf%EZN|rgkP^?` z%peZXdt1iqrNlJhx7#XxUXGp4Lvu}`j8|^yoi`)>7jc_OY`Ed+XL<&xD8?cku#4Nt zoX=aIPsyP+>NlGkLn;)LDa17eo-i^TO%9f>w|B@G#)g4T6Kh0KjLICL1G{f?h|~+` z&eVLOwc9a;WWnbOi~yq1Q-KM4{?n#~db<^(qP^@03rc89;s?OVn$G z+dcL(YEVSO8;-2bR zw;K0fq!n?-2bMtp`6ZGXW6S}eH*g<1><`AgDOa0QIPtDXCyU!*+q0Sgp@T94d7=Z~ z+eU%NcQN@}5-Nl$i?YjNoTL>oFtYuN3;9;heS{TVK7wBp1D;;dkg(^TnNl917R`Z7_ z>uXWLJo<;=B}DyWq#P|x;ae&uquDL-1w91l63IZ&tdVz*m^|lvQ<)b-&82fZw)0=9m zM=f;MQA1~Qp*&EoWlUpCN<^y9|G-Xk#@%JdI@E?PgERRm(f~G*+QjX#IhpC|Iwm@W z(Mz|>cAJfu`&XU?0*^Lpp^z#T;%J>wE%WF^?J(MA_ETY|pX=pSWW+15?{C3peX*X< z7RVBpaGhPvl}9+@0+la(-RmCbwfY#Z4~kH0eNXm?u4qd=9pYR~BFpe^KNzVP)>~M? z21p_!0kEWPm;p+JKh<}gpcCDkuUBkf!@Q@NY-ygla=?q{68|MTlnB}KvjLw;H!NxuMPH&Yw(wK4*Wo5FV zK|+zrf4_Yj{%SP!uLh;tcXC2WWI?m5Y}$nxL8OrILMMw=!!Qpq3z64mXTlgQ@#v~`^r_D61O>&cX z?<>TA;;9_6krYcPnLzE019*JWzxh<*qij^$JsvR}5Ck$&Vvv<{NR`&$OSicLeW-&=<3$vfj_ak3*>{RjgZg5O=8&+E(|Wxo5V$1$)#s z(rV9{5eq7(z2Q9cN>6mNX=yr=^mm~t2Oii7pGyeL&TIa(E()Zj68_w7=qHJRT4V?} z|7BZfkek&C`-D7b6OrR+EgmLMOpwUxLdbFR2ab}k@xlzC+VI3n6yCX#nZH=;BG{`S z(%f%)cE33|JwqQ}wr_Ku91X;vhZi|%RiHhMDYu;0_TBMlG%#DTMBY!)pDxKr4l$YM z=8=5XZWNVlUT=pXX+?8$9|!3+IE4>9L`4aH#X_FFL|vD)t9JPKRWU34zvXu}Z?2!u zmjrfSq8?PXZvt7Ky$FxlEl%SK<46cz@wv~*mnq6O^5^T^-K38`MQQ<{XNi+8*TAFmuJ^`-yyVl5J zoJK|=g?3@|b;hFiyMwdf4{JwH7p0N-hihJbhTS-Y7iFK+aa!Ql&&k^}pJf8Iks^v%adJoGsUSXHr5tV~WWMXdM8kSO2y%{LwH238iCa z6kY>)Nn})5BmNZ{wwC^;v3+tjj>?I5o0N2OHbkPV1;ztjcstDyDjzpo`(u{MR)O=; z7@GCxlf0A%<}mekA$6b&yf3QM5D}LL*Emax^M#6;E_$y*29)YjdWO;XEQ6cgVaQLC zW}0?Xm>8hwUpD1eGr=iPr>90A_qu7(3q=!PV;Bm%<@LX1YkIhTD$%&LM zvE#wI%K#uQwmUOzEjVAW>ff=dzTpSR)$$&(Hpg>K zr>`w3l)F)u+u04~Ly5B-VI$i7kKfj^d?O#RCa&S?Yxv)*@6RJ1M_+57g7dUZISRj4 zA%teI_8}LxS4GySY}DWgB184eoe7x2XKXQ)Q!$ljU1`mqmQeIHr@*c+C1_joRk|Np zLA>u>OzC*kj#!8LVF5+uHOcVEr_H*vzl&s?MjXH1R4%%`J=8G94k#W3n|NiSVf4#H zFA6S)lK%@>=?QR*SdNG(G2(|INJ^eWD%{Q|kkE~kWYvP8mI9N}ClDsdB%vj!XBWsM zFp~_=Xj>{NB`w*04G>BpPwy#={Cv>=sN0o$bB-w*qJJS=iFOwquwF`oaqXCmD`JFx zP>~ru;l$X8Dc4Hx#D1Qyx~8RQ&^=HhfaIQHoI=JK%ax>pEF;3b#?fVv8DMRuXU#i_ zA~>)^0P(AWe%Z46xbA&vTn(_kS0~B<+TiM>xUgm+@YBRI=wl3-SqGq<%(7cyg$+h4 zut6ep`~l0j`)5ANAAPYcK>{q*j*>2aglWOxMq9wb7+v%g>xVR!UE2eRQAM{EY*sd4 zQs^LY9Virm!A$Oa0o3wF&!n>Pg}ucTc}hD13@S1MO%SKMq2iQXd@Mit(ftQO1W^m$ zQar^fHptj$%n*@R!D{bKB!edm!BHh``MC=fBFEFp#xsAdI)wk+mt&YWxnnR};ih22 z=2XxeYK{@Pn-lMZ|A25AgBd0GCioy z{Q%=}=u+8x?h2RrDI@nlS=hJ_ln?I*CA!88li;?~@3K|fh;OZBqn23BgmXHwGk$wz z`X#?OUem#TI!5s?9r7X{j3M*=!XSBk;~2<<<{LZDW5|)@Mm}q#(|UF+Wls9}O{%)<)XO7^Uhj=UI*r z*OYc~G*cK>!zlV8zeBRs*r%Z7MeQ=1VVve6>vk-;w`1BddDnU!Bh6yuEN~qzCUMkv z_DS#tG(CFFw@c7Sn;}1xt4O`*Gt1Ce&sxripYJa8D<5$F_22x_e~EJzo+$W-*pU_f zFn|+(tKzc`0JRLa_RR@JWosqvxB%DCiQMYf*lL_nw#cnG7GS1QEudJgx+hMShjA_t z6ZXkHiF0h9oHV{MzU7lK%f{^(o5Pl!qPou^jv?7tgwwoqt?m6~6(?Qu_-@#02FE3B zV?OyU?!Ig#vU}ql(`-H3%v<3JqFI(fb20m$l>cS9T)una4vqb6+1u%Q71z@sodXc+ zef01}+g6>S@V9~A^h;aYC<3Cj2hJ#RfrmIdU4Uyp0l}$A_UV5SXH0$qGZ38z*(l5$ zPkO1kI>(EF)d-;HN-@LY9EZu?ghQfS1_3#!@c(Q|-wRZjn^^#riz@kVrXen}`9psg zRbk5GGgc>dE6;;_HaQUYKN;rc<_D@tDht8ANHE2RY?KJZ7Fz(t*e<1=s#% zn>E(bEqOREMp`xl*^IiPGIBc~mPjyEU-^-Nd-eUxd2;MW1u~2kevqNyceIbQKuKoOkUtwQRm$;TX|4&QXI6i35u23*JTj1 z5&LW4pGbGQER0*b`w2meQ+N_aC>ELp<%oGsa0S+0H}{L}yV%YVwwhr}w7xMWHa0gp zX~XPcTfq7v3rzB=HmC->i*Y9pS(a)Cov&5sGdWv-=3_KvowKRV+{$}sN7@b|aqPFa z1>?p{*^t=Vdj3$)1{AxHIM#7eLMcB-?7RSD{vn*_Bpd(Lzy4Q{o7$rB4;!9XaVWQJ z@gRYr@KibyG_9Emq_)AVWw?wx$3EHDIN!LYl6Uh~<#X?J8SoR@({Y@}+P|2bhT$Z( z_I0Gb3?oH2811DNbp!nXAJ9_dh%OgpUCD@X7S}hV#kgUud&2W-E{DmMN^`93J36ME zv%ZvJ{eX5awd3`AH1;;vHviN5X-S9qY!9^1*?)8Rw+R}~<&d;mc8{aMSE&_9x-4!b z7JpS}WUmsucDA;15rOIs*n(wCh)7^%OsF{o4w~)^Av4P z8NlFK7A+g+Yk6YPjw>9|8XE|G7RW~~yxA3_^kolH&;#=VTl&mn=B5-b^Qtr!{%mEY0>^DB#Dk7qu}Zx8&G~1a``2w52aAhX<;H)ov5YeQ+;@AY zAQKUcP<@!?4fd8O2x#k6)*3fZB^LBK$1TnkSmu*F`onsmbT^rQq_KHX=RS+A;Be~4 zA&)k0oIAa@4Fl}=+{H)@UkjcP@{72!)~pHmxYW45Dx#63e8bYH ztGVi8N8f*8T%&NNRi63DeU_Wfv&MYzyrG?d%{5H8L>OdUqmyS~;557wDw&;KKD@1Q zXE~an!GNEcEd24dUN|29?Z5pu$VCQYMm$|0K!=K}G*z?^WOTuhsJm5!+}E~?T+b-_ zi;N-eC?4&P@pKJFQE=xT<+p3M`eNI=!1kOiI zx>1e7)}UxTt@C&qD8-^Shn7kCn4JqD0czLvaMv4E_a? zt>eAm7mF*K_?^GH%Hh=ajqx@0C-0kmU)gM}m(2f-- zDm)xM;O4}J{NyNBZgLKs^f*2L{PXGSU;lb~?)m2|1|5?OOEYVIgit;21dM@OdEQ^pm4KQ5g5$$R@_8I@j?a zY8J*Zt7~)zZyvZF#iCgF-ZO2hTwROGj$R#1=B4*wHZ7O|ltsn&lCrIXwUDjQ2{G`! za)Ko-I=D<>dneFMpjry)`01e+X{A$JjTeR3)pbWbhD_b_FlLqs>?5Xg-G7bGU4JncgeOL}IkBU(8XPx2dzJ2lG^m_27KJj=$8Wc$xNbGli*(Ijeou_44qJ+GFui z%jf-`|Lni}+B*B=PZ?KB|FvKJ^GgaxdMHlE@;%WsSjfxtb%*{fM;&ipYPkVe^o`q7C6#&_?RONavHjpR#wU!b1JbW$? z;;yI0iznyjvwO4_L#NO?ywA+MAPBdCN#-|ih{J!2jdCc0PA8red#qAAzZJPi!cC^u zW*pz4O+a>7$Q6 zPKO{pV&M-rbU8-xjD0I~qN2*ns5g)I;f#ektmH$H%nF6fq3tKE2&FAH#TvjKbeBZYaaT9TQ-4!xI@8|E0@U?QXH3 z`~>2^u$A^dzL`F_`F48qjn~tMAAN)pB8ru?wZb3Ib@`|{CX`1D%qg*&>=sVb=E1iyd;lNG0@hsnU z{@GHdv&cgeQ~fNgMqTfcH--`~Y)@iS_e$8U=7r~TkUMAybd&|AB;q8LpNE2Y{NaMt7X`&~a{%t4#ns5`rU@p`tCE63hh zyE$p5N*-E*5zT?w$1U#~-D;SkZRC)nGj7 zLF``i^Ma85PKvo?4DQ?J&k#5}g_E^9ZxRw>0{xL2o|N&X7KSxl{Cbw5AaE6*xe-sx z9EHRf^P@=&`i((aaEm94IaF7e(tY?I-AFqZE~hJxUr(R>)Th!Hzwo(q?b3F-b>kQ5 z?blyPKl{nc>Bfzl>EOuj7Ykk#{!pM}0r29*OX=~)nfKkayM@b2u}bj$oA0Gtw{ByV z9g0p?JVlYv3Wd0I8mskoP*l8pc{g2u;!@h#*}#gzy>#c!e!Bh90ruUc^z1XwSmEyO z?f28Ik8Z&Cjdc6YU2w4Ah~l3W5V;4K7qmzMlM`jxWw98U;?BW;(^C?XXI;y`gnpFUC<2*dl0!iq z_mh6#(99vTFCM0MkmMFquqBgwK}#ar$jU7ohg9LAs)YDva2DxFm)aY}riRwtGPl-(>W z0Is02KYV0-Ohf7Oy)p8YLFq(o!$eHQS^Rm(W@tY3sE}6efSbnK7(x+PtIxsZw1F;w zMMiBAmrk&OTH?~_sK*C6MukeCQ;9GJ5&M~PKs4@5+(h&ZC6VVr6qFqt2KM<4Iqixq zPDVH-K zb>q9qjUQa=_B6!T^*)3+o$RE0qdg8!7sYDUi*j<(`K%VfIC@cRV^*ugJoWgy7yD;y zuB*&vEGG|w{C>~>e*1qA_R(3!xc>a(m6I!1<+QVWL!mc2t;lVjS@^4>ujKbvA5Rl_ zZeV{nEawamiVrf6U$0iSJVDW~;7RT%ve|=0oovYnN}S+hQPO`;kQKho^vtu*q_2MU ztGJZ#xpeL76|5RV@elF(nn3WOrgMmb+ub{RSiSa9di$+6($9YSqx2Tqk8XXK_D~G8 zo0OpVcVxw?97FbBBV(Z@#}7V>$>v<5D>2)76i1vt2zXhv&B9h8A_Jr`ViuwD*$;)8 zAEvO&8L&A!o@U(ayvs0_eZ&P8`;S=Amh&>%nhhYCfL3(HOLliIUP)K4Kb2m3=_TBJ z;n&mks~6HcKmSpB^(Ws?Km6`@)7$U7n+}e*>~V-TZSJD(ha%l4KAFDyl`o~|KJ^TW zgU;cjj);IrSdh@M!U<-Q`D{a+cE*{d{GOwKTK(W5( z)Vhwqv**|FG=q0YtmU)v%09Pzboc;BKMuS|ZhDa0F@odBIME1`jeLHv^?B02dt{6z zqZjWOhpTf`kQ3#FX7*&`>|`yr;+5ml7IKr=NJ%M}#U0Lx8*M*>!r$-z{_m$3KJys} zy4=DUc+F2^ap!EF*jt=I?30k(Q~7B-WKW*6+vHJE@|fqQu{;aMaqLTfmaY7$UES9z zmhH^l+pu(5BzkR`|4iYrtP;^OFQ?VVxyAlTc$;~RzNegodkr@Be$&J_Lc1sv&D+)p zLl%Qbuc{WvNOX$Sd(ABh(}EMAwmRNgKOEQjc&{5%)wZ@`kMbdz^c@{&yMBZkZ`~fB zQ<2Dc#%)|PK8In;>`8vCZKHMN;OEjrcN1a5AwsI~Dj>%M0lD>vdi$IQtbBjR>rm$v z%zUSZYQsaB2v%xxKmP6EBy2s!@SYD5%#?6OT<7y3L33Sa-7-%6kV{O7O&?P}WH zMv?07ZCpOe-}z%qzS4_Dko~>8>AiQ}Oh5VY_tGn`yqsQt{paa}4?eU@LH%-8lnY_Q zS<#vQ<46xq!!M&`B>a6j3ySAYL}7|PKc6q>&xfswbknSNeqU*bezrs95#796(Q@nd zpeDq8IkOFHtSHIoJHjF`fUOdvt>x4J9Atlt7c1s2T}{`Xd?tPIOJ7Rg_}#CkC$C*d zZ~W}L>8C&VcKXh@{t*Szw^8)lDaF6z%?oL3_fq=wbI+&W`1M~)U-;Y$>61@gOCQ{L zEB)=?{54kD{W!hzE>`SeCEronNrx!99iRYs_1fdG`6O25y_o*#uYbu_7QXf>Ru#VT z^Yrph-%OV-T}!|DpZsRJ{@9iD-rKLGS5Tb&_P4)cmM4375jm$_Z?FT#6GlV_f1X?@kE=f z_m{AF%o1-TiI<4GjWlE`EFIfAkUmIw?5wcq{D5=(3<`eV_{KM^wK-=VVbr$t5!>oc zJGPWAAel1TA&hv{j=7MnTH&Hy>`OnjZF#GmG-CHwql#ls*sk{Mz!w0ZLz{pq77FnUNj*x1*+Equ<0>==gUZtXVqIo0BPJTRLqYN@;D7>#uX>y+L9s7*{|Df#310S{C@FagHP^HdxD z*`NIx&IzkgB@A_lHsOB*{8CAO&l6TB zCS>PHNIvai$F|A>wtRq7W-hZ|iwWdHD z`z>5P`mwF{+uFLAb}v1K!qYWeVtN(Dz`gYTyT8C?tUpZu@DG2VUVH8JbnEV6+QU5% z{P*i}@eeWj+BjpXr+uyzR4&j9=R^c58Te(8&! zPMe3f)Azpf?ewFUf0kZ({k^okdnJAO%U?-XuUt$YV#VKEZ~Q#H`pPTm<_EX1TJHjC zar%uv#D0jo)#4vlYHnl2-{r@=@b``1`|b1$R{XvD+V|5>fB3ERP3+%aApZRg6#fv0 zU-D~-^em$5*;KxfLFC0RTc?sGLF{iN%kG_vmU-rJKszMU@XR~q_Bq1ifm+Kw)PV80 z;J&hxaLB3RdphUf|IrR?$K{Qm?7n#f8fCx6US(plU0ubw=UR*3B$c}h6-!ro(orn@ zMGoa8%3}YlKHJ7-9ev0CqHL7UV}Qh~HgXL0#jBQfW42@RAzsSFskY+!Onr&aeQRkR zgmx_Yq4^HUe2(Lq!5q+OFtOKp29Cuu$TK1g)Psn1_!uN!S$MxAS(d3fp&_JX>zqZ8 zYgH$P4=m_XBpS{rXzK(!n27E`Rvrxb^7q44eZ*JE%3%x}@Uym~>5gimTAXG@JmS(2 zqx`YnVO=~3#sp&6MB(N^SS*4}K6pw%aaDQGa-I$CGZR5u3$_1&8ttF|`Jb1V0kw&i@kw@+cY z%($^3+)T{)9Z?<_-+X0TWzDB zhil5f+2?`t9HQt@PQKUbLG--1^}C^s^uR2rK)rQVa{jHc>R%y?i}Ajl$Ds zU;K1>^6^V3Vcki;cEiAVTHde%nZaeL2M4&z?4H{l;P>y2 zZABSu$c;h~i+@{~%MR>zcDC?)chPpwevgno4|&4|yaBLa$2$*i@9d@>+>v*icTq-m z4i65%hg)Ir*0vB3zjtt$?%bs<-Qm($#J3ASoFgQ-a`$4oaQX4{(&s*xe($%xmabph zO>h46JIM=w|B&8z^PODy<7KE&Bul?FDr>}heh4i^kJ(g~N_-^|D{_bzA z@b|`hAE&JgSJG!*{A{|6JM-T8;O%tt-M6vY@Xhq$tvgt)cOhY!VcOcpe36?A+gQhm zd?n0hbNgc2y!cpp@x_|sSHZ-#*h<^$f=0-|7uqZ0d)`ASX9kI|HA21a&vZRSu3Zk~8$H zMeTJtqTjCOB%>E!e6g(fqrEmqp*sw;gx#wT!IIMj&%jdj+9AfC<}w)P@lyS7yI=yI!dSYixa@>XRbvdRS5~5+?R@D^-YBVTYD5mKF^2&@pB%J z@{YqK@c&=@#b1mR{-X8remRfmK^0X`u|RMVn+0@}R7~Oh-0sJm@9liYPU@ycv96Q9 z7)Os2yJ6~)V0&yTI8RbV8xE(~NBq=0Ey7Llxyb&0=wgavpRw3{a!|2#zPi?O`R~;Sp{Mv2{5;{mduQSHAp(^wMXZ zO`m%Da{BP*o9XZV-~T6l?}tB5ufOwQ`tW0{B12(_Hw$^}v1{oG+_>VY>(_A;3lzIh z^t*-M2Ym0{chU#%zn^a3#tkf3{6ox)hp}v;2zSwLG;%FH^VE~}dxI?Cv8ePRijg1S zapT7O>EqidWMOsT5%a{NpFK8ksq00oNPHZ3r+qv<4*$EmSYZd-k3RY!z4OjnW`FxO zemf6^DcVMjGl{l+I)LJ0y?4 zA2Iyl@h5LNjDFG&2W_y|-?Ba#^K=UE-rd9L!}ng3!EjkRf96y=au`p_AJVz=m(wVQ zKbF}p8c3VAZBOsN`%c=kV^dl;upnK%cq;uzhS#GfPN$m>WRR5caib0x>Fbqup-$z! zd2J+J(lXr}GW1$67lU@H+3+{wRH8$6&?Jd zW#V#`%Z6RFs=m@NT&fd?V_Zn*^b;o#%c3Xz+v$q-D!g&yh7LBl9peHT&y8759lX>- z7+zzPyHI#J1XRg9>f4@vlxA4Q;}@ASzCT%-hQGGqUU<4^nD<9JBrk#mHATTR|F-!% z)vVX>nZ-8z5%az)-+5)a8~5qH-zMTYla@_|rkf_awW%At=2KK!!wRA%tU#}^0@g%~ zQUg0t)#QJSM5O|2q;sPuF6~UieJAEKBkjgAZsu+*$Mj}5r0$%bafw<#MxbZRegbwp z^Jc90Vmw6hDfKwrXV(PH8e3GzIkq6@tooUVU+Ql%de=j(WqK;(zQixno!ay4V19FE zj&=KW?~JeAs?hn&xY=TzGA;&3LKgiR`i2lAwdoe`|v=;i!0)5}Ou zE`Sxnm{DM&2Fn1CLCoY0P@AgY-v-uImY_OqUXGu#`N22e_;nR^;;H(j=JNa!)&Vs* zU3N{Gep)G>+sk^7;$ooemMvT}bYQ;l3r5LZgZ1}q_W9Ef)Np)Tx8A;b~-br^KJV{HJ z^@Xtux`MV5% zpQICKFQkVu3=XbbC$GI$8thw|MsHt9*DjqGk5lQ|&AZ~!m-+^!AIZOd-I}yv?aDCx z;YoLI^l`dz_mSjZ5k|FmJ*N^cpK*O~m?XZM065F8c$-lQw^x0;i`G|J7`IRNb*9?_?5n?)UC2=SvC= zG{?ha$}UJdC7;{3MI~o9@!X7V<(*_TENJwimo;>@3e>}Kz`QzCa9`Q(R3x4NpFqS zeHTGGfqgTo(&^M|va)Ta&#>xawM3}uH*F_z0wzW#GtY6jDu^;83V~#i9Y<0EYQ7>U zKLtvh$DI2Nk<-tLsqipvQ-6jxc{K5w<=yh8dlBvLCIj%v z>UX;>??k-j%cie^$@D*cj+vs#H=qLg{%Sr4-Ou%dEf9D>#q`7E%8%td)`JPOvOK55 z@CU0lmq^tR&}7JH8~y|ckH4+yL+$MrhCdl;&dc!kpUUueFARS@I+$WfS}mi`E3fQH z`}b^1dv~r&5AI&841dScsf#z$lSO?x8Mu{N+B0ycmISX^xjdGFE?6j!E!F!_2BQ1- z@1;xU&!r>3{*unfD0NvzBH7JS-_WYGY0I{>|CLwM=FOYZfV}tc_R9-JnO`NHbbCvN zrHkqK@l)y7L%)mmirUhX*2p_>-`<@%^k9pOS~?+Ddl4?ylGX*X;IWkS;e&hfT{WW17rZlOFDhhz*Jy>mUClgHmt_V^3KUta2) zJ^o~jWUoIN{uXGdaIa44-LCrIfA1~Hzgb4Zo^;{t>GXvRddFpWy?y6?daM(G`&MmA z!@KvU4?lP(ty?va?u?vCCyyLTUw!puIv%x86!?bU@2(m7h6&B>nW` zkLk+w+iB^byfn8BrvnEMrmfQNpu7TE&HRvMw$lH7c@{2~0TpB306J?P>4+gX-fgIzVJFmSba34v$q0CA{@6$XoQpi4*D9Uv!%ArOPod zUa@j0?HC?b`?jV{n>NW~a;RFyjUi8COETQKcTdK@%Q`UTM2w5GXXM2w10bG$c^g2C z)fx|2Wf}W1$n!{#d^OTz{;lH9LHH(d3@?TFt$v~iM!I+&$1^z?i`@6CX@c5(Yo=pL z1LYa~v|6q7*T4QX5zl&%ddk*5wLBFwvCUx`{DY>8Ff~8(ZL@Dc#%7!B+Ie$yY&v5& zHvEqfH?`4jwM!hgOQw@*&)=U;zoisqx|1xOYU%{*MEggFHFZ1J_12X4Y5FgCH5xn- z|Hf2rT-6O$sUd?=mlBxzx=*8 zDs-$!Ak>nhlRD#M!|(^Vp3p;GF)?F6(+PEbbz(B=@ik5N19FV~s;-&O5=d=PmFsKf zCzG=q-^uAF#wZn))6;E#lYi&-H?X7zG*Q+*7Q=cfp>6D%whbx~$E0W4o=y^Uf{m%H z%4D(fM^~qEVBL7-XUW73^8=5Yu~VqWTJ>OpTTB2NY#Z6}tfu{7%Pc11OMmz(E1c4} zDG6Rsx~bub+V-qOvM!oq*Kq1_nPHBbG8nH3pDZ7J1X3PMJb;4aMYO+^t(*ScF51oI zd`UZ>etHdb)Bn?O4xT&*IxzA0YL4gVXYfrF<5AeP=U-;lmy&lLa#In>BOMN$_{rh&Mox>Z` z_D##vts9rq=bwL;emg1y-mS-}fBD+9Z~p-q{kEpfYgfpK^+euVSJQnR79zK=@UUZf z=-rz)v89ykylgZJd&cmLj98SU=JzHo!`;Oo&o zd@S=laq@Kf@+&Q&J%1sLdz&||(`mLcXl>aj@4}^FEV?TXyocJGkNx1-FL1dIytpNA zzTbX7nhqa5nSMWhR+GJjsWm*T12cxx!F@Yr%vzRi%j53;J$akSNXfF|6=SA|u8;~IoL*{)gjXouV?w49Bentjl_V2?O z`^M|9r{UK2@Brl*$FklB^5|QjK3%LOzsux3iBb5xjKU}6@%Y=XKgmFRK9>EmteZn) zGzfLyU;wPfwuW^Kb(I7}KjWXDl$fF*2ts}`ubL0{hoJGkP#Qzy*n3f>nFK6_ijw;{ z?qy(O5CF_Ll+un^>(YAuB3I{%3a{b)OZHW zNHzb(M3sVOs-9=9U&#?HYrYexUbwZ`Q^B8r)gP{?R@@72`P24OCHIuaNV9pOZ;H^& zLsF_I(w&gZyMDJAkmGSY#unGP@;y=mm1xdS%d)AY%Xed2U!_!VY38TG**K+AloqR+ zTTxWQOjgAu9CY-Mx6*0%5r0%?^Oq8LOhyGR>-pzD|0$j2kF{I}MOASKRH~$sVv14b zqTh<$#AHS5#|^jfl${1Z+4)X8hQnBzTwfbj)<3?!=L=~nsF{CuwOb$UcB2>gR};mk zsy%orElnsu#$gOii1t*4oqA^sEH|QS9d375gl+}Vrb!xB3sNU)ZUM1um4eW2CtY=_ z#d15Y89$>09~_za|Jg3$<>yu`COuHonZQVqu%v-2_XpZr0q3to`Y4!^gIV6 zT>%VlQ<=aeRV-c@{@7a&BMQc}t@6bBK!(3z9q!R5!`Wq>==+^K$W z{w4$8m1|eiLM^LZzj2e63hz%t@}|2vaxtAgel-2?!;kU=Olily18KXKvToeGMf(cg zONVq??KyeAu`l2{io?hEO90s*Z z7tW@0=g!G!buL}flH%((?!>9Ro44=O>Bp_KZR@u5`y4Gm;NtKtF+X3$F5yz*Y2HZ&#vM0 z=-%!0!UY54*ekJYPvoG!2w^t{Q+)szT|1!!?$jEk6UYSc|_#586 zKmA#TzjZo!`O0Z|Hp=k#oP}aAcV=hQW=3eem8p(GT}zxW)7GR~=w-<;qprJ{PCeYuCn!$Sbu3_{o!p z;(I!M_x0x*AM$vVadK2Hq4_`*4pU*irOWpcHv&Q9nh`(tnIV|qdD0*}{U=KtcVa~f zIe{$r0R~Z5<_A$b1dke&nFLjXpBS`>o#8K(pyHOuNYz|NDYCQ?;j<}vj;$FX@XfUI}4 z_N+pwtENsU(|?6(q8OE`$D(@uRD*0%S*9Rvv+hZGHW0e?R2IKmX~m@LSZGx8tg~6U zZLX37RmCrfW_g8K>WZ}UWnY5Y%vaT(L?az$DvA>bWuaV3q;}eFz4?lW8?btD_C9GQFdh@1?KEI`_GJG+&U@y9511sdMwJL4cuvRC+ zK1sK9u*V54CH?A~Z_~()yJ=wUHtj*TH@*4hn`y1@`E)+?DG$r(JvZruW`?ONPxwvDBA6@_y1% zU!Ur0!yijlG5qDjRTiazp%rO^44%7o?@n*MaUeV;kNo_77#EMp`)!f*zxSXFck+m2 z88lvr-+caw4gvX1C;#fu5iJ{Dis4TleSiM=PigH?f4X|=a5^dD-p@b&AdkT%>A*W5 zrtLfTq?M~yr|a5_@7pgVzdSBSMy_ZqEKV!dZb>`#>`m{!^JZE(Ami_uBl5`nHT@v@ z<(8NZy!(OrcTXBxxiSuC`RUtl(&-b&mA)avUvKp7_Te3Aw|L;?_x%q#oJ0mZjJO-t zuSxH}^R~P$`_d`(`QgLAi|@}NJ10P|m%;Eg8H|TD{#I#O@U<(KqJ78JzN=S8(p~ln z)S)OCSYvNWjhB26@P5xXK)yZ7=RJ2(bsq&z5anqDN$#M4XL^3ga{mN47@A+^WrE1@ z1CFqBX~Aq7^Kmhlau^;So->BOqP0_&e=3Msm)7)DC^C-erbHp(C&SNUU?OhfU?l`I zXC|WgBbOEWnywn2wSK42|4k7m9}i86KX`t&Z-*E&Gwg#Ij1Si|lWM1;syyR!Eo0-U z(6{G>V`-mBZj8Q4Y0C7|)KqFUr-O3^o=z?30kZZUemur2kG~2CzxE#6W!-}R@BjX< z<{pp;Eo$b+-IKi*sG^g?gQ})^8ihbB!GhOV0iT8|?dlwI9ql$fyE;49H&v+Rb=;=w z-j+5_rnYbWRX($c=X-4u z)zu<)>U;N{+wIu6?q}y~W>v!Y-Qdk~=ezN1@|h}LlWwN@W_@MevJ*S)dP+RQ%D9Q| zGU%GLC9caHo36w$tXpha(>U&iKM~x#Cc>fYY3i7a_p>f{n~0|(_f&A6Mn>eYOz@#T z_Gfdw&GM(I>v_<|vo$~bYxd1&lx+bS%`cAJ?r6IWf7RQBxkH4A^8E+T*z*j1RW)U- z3Rke2uEqdS*abn`@R#>Yv*B;|?pPFr0h{om1Y+|dUQ)CclP(~{JMi}1Em{W_g@ zM2AKk`R(U){P;2Le|I50UbHN2+_7JVr+wN3Z=XEI7Rc~*G+mO%-qn#yaf0s?8F*I6 zaL97cb*op(W3WdDZk&rf>NrT@^>^P(Yjp6$J(h}UiSd`8eUVO|JQW8#ERx}BaD@)+ z5dBJd{9*jLtbOP3G#l2k;?~v;Y5V5YlKH9*#rQl7e-|$6gxGtdsYiSLt>3gh9em?e zomxDs<+|(SX?8t*^2wKB*j%sEX?JYXQd=4RdgMv>)A!${!@nI(Cr;@!+*|k4Le;TF z`vAW4!MoXTsHM^8w1oBZPyQpr=Sdx4F{-`&mdRsoUD~y0Px@G=Bd;7>l27%m41XN% zQJ?B7BU?87$?;CT^;pYI) zeFpne7)Ir3dGzS9bY07EA1zp#dWY79;qK!rfA(zpLi8t&9@o-oEyGs-4Xj$9cElcn@26EmeQ8AWCypM{QsN)e;$_Ry+aLWo zZIZVihPvzW;5;G2@D&}F@^JK_PCs4}`yX!DxH$}ejLt*a!x7I>PW)ZJW@S1ck4p_6 z$@4?(vxwK_)$2E9gkC6*$MtFV{#VlO-Fvj$d3zewK8rtm^=bC1Ja;zTx_LW2mZv0! zKgKSmwsFVKG z>vyimFOs+z5gK5W8z;l~ZPwS!gYzPSmC=lI-JRMr z6{*~2w;MhsFPE3RV(5ezmZdE1ke&dotk;xf{f137?%F%_?NpgOM?9-yB3ZI(+jq@G z;#hx89K$>IU)9Ifv*VJ7=?ycE;Z44V8_#szV(_Ml+l|L`;LW<4dAG;yD0w$=%d!&R zY4AN=+KdL z>g-i51(uJV_U&u!Y^4uAelKm>yk7O*Pbal6;b;H;Oa@BrVfUyfEnM1{`d6%x;cid* z%b!0;tCufL=TFEm>cc%QUe2fbYN;>Ybr>#b7G8f3b+MGUcR+IN+^NGm-cOr#V(`N| zSL6|SEdBh$H*vD@JMX_QZ_ACbFWyNRM8EjY7qS1~od;TrEyLY1o#>0HU3XeaHNrrRW2c#Gx8rN|bRQH04>i}MWfk0T% zv}1wd=AkW0WJVz7ya1V=f?yD3V}Aq}Qe97G*d2W=@sx6{*4!}sS=erxaCtNChL2Vq z%5*n;<2o*B44aSVH88J%S=0cJ!&$06o*PeF`7Fr)Oyr&=owuuvR#e$C-Nu-Hs_e`% zJ@)nL+QwqEYa0Wvk#hnAApdd@W^Gj*LzO-L+ANv8XF_5E6NvbLsb&HhoQ-IK8~AMw zo-kD8?Se)s_*=fZY^-oKSc&o@3Ap7WZ5fSI%T)+b;*icbnNJ(d6P~slxjpSX_0dgj znhbgRUn`>-XU=7Nr&?Fp=8~r5Wu1*FkM>Cpi=sjgCTXaRs^pk_yJSrN6yO?;46fU8 ziTBc`JurMDs3D;-=T(kc%RZp3&3xH+6X~ZcYw{r9gi%+gU_A44{he^93Y$*-Q{_1s zp4$OlneNsex7WCip?4W+f_Z>rJjcd$+=Q1jnOpufo?))TvEh!5?|MpjSx2+nc*N#G zY&^#$-fW~TTT>qLB@8?pkC4;l#&Jv;xW32}%JK}!zn$PsSjmgBvYax4;VuK-OkKnlOQc~SxE9+9$71MlTG1JNNCE$CsAF4)&!{83-TUy`$B) zTBa$P*xPP_jBtzPIk<3v%s1N0?b3xaS`zwQ$nXYBL1h%Ya^*@oq60X-{+vAq&#C=t zH-;V=|9Z6KbkX8o8UENKZ-MrX+mPOQ^EEBi-JI60Seiz(Ki|Lp^?zfT?#;W8lbrF= zL(#5Uw>s^4b$1y4whs?$-?+P4O8iy2D#PDuEfsEQsqn%5t<*OB$y@I1^>hovUvIyb z$hOi)f5Gs#P9A=DWcWNTk2&o@ck--^nhWGn*Pr@Vt`&cI{AtPb>g7w)1sVQM9R4x= z^3(U};zb!idzR!q{xD!kb{qbpFXS=TBjev@8Rp)5_nkB>55$2bPtuL6=e5`2_i4$Z z9xb7MJuM$xE?$??kt4^`ci;Y)&YZg(%X}9s=})~YR6ibv+N*Kh3N7`O;qLU&UseAP zsaJjao(z8*wGZF@(a|tme(~>5Ww?|_rS?}`u(&@h9nwC7GW`Adj%=}o`>o14_~LF zhkgnpGY6c=uTbMwhChuVyzscm7}6Nd3EWX}X}p&An4cZ_xgvaxMgO%wIMnw=<`T4- z5rFD>l)aC|I*;X`F=3!_du9Q0wwS|wPr85z9QkuFY6=pL(DT4+= zQz2vXlW`x5U9dJ`H5uq?_%mKb+Vj6U+=I70jAK&I&qbz^AfO662W5__#SSDCMB6yeRWTspJGs_Q0rGi!4Q3xy5O3d8?0+tjLTJ zzpP}&Y3rjIXNF~ar&@(|QsM)fO2~S#ESaJygZVdkcA|Biop`wHzae(}nmTdb<&NFv zX1>&|X^q<{ZqgeEc(<~WuW<}>Y(8Z?Q5ksV)l8Q>o@csK{hgLv(hj%9G>*H;*NLXY zH9y11!_!v@C*7$&*HQ9n@-dG2nU7<`OCDvJ(`C77W;5<2SJ_t5;Q0A&eD`mOOFJkp zFSo61cc--ZHt`L2?0Su7xaA-Q)|9td4vuNf>qW+XD_90%>&3G2HV8QtN1572z-WPY z6dr#;7v)hzsS{N!eJF(oT;OBy5StzuL82b8#MkmvM2adt5s3$SjpdRUPqfsxHvGMx zINW1d?-HG+swKFeeI}2)(?Py&!v-yteM|exZISn%$}gPL9&G=SXWo%?^~TM#R0n@- z+ow}$W%%2p!y$(Hm!iSJEzd{HG zdtXLS8U9Y^rM|!X{DZs}W%&EE41YR&WK<`qoH~L0pK6aj8UEB2J&XIaM<54`$YW53 zzqK;d)rP-AKg;8yA;bueyoF)-JFgRY z!CSU$k@j?4mGGRK6ihV@;`^oU9(}o}F;E{o$m0?uevv-dUX?a!L9;QRz zeU*-=?vp2u=>QcO{&ceRBk3wm_YK2ebq}FP1#)q555)bIpC57GRre%d@)EMTPq>$Y zJOI8ogLB0v?yVwieic;})ePIrj8O46AA`Hao%v_%;o;%*x4-=@wOXy3Jh!#Z&dG#T zY~h>_JsYUFnJ_&lWmQJ$8dX?5|NO^4G>0~3ki{e-CKezt zSzyk}kAmSUhlcI|06+jqL_t(yADqn0@S0P_)2w4+qMw+rhbM=Bw7Zkx^8Zo90=>uA~`13*K!Wo%BSh_0rUz;nt=5*)*L#d`p~m z&GRX1pp$+Kv%ZbnE$)VAJ|$fz80Fn~Or@+FEp>IPuaxOorJHgz>n0D5FY2|7E^EqS z9*#{zY(9+pGL*Q+F+OEB{1^sK8A^KK5Xex$t*=5ckiCOypCxPJsGA>o(|7A_Sx$lSf2W2AX=fr zDHh0k@V0pN%b>Mg^5C(@9)CBlkEBnvcinGV>U-t-{dD`j435&wI-UCay7u_np%Zi0 z$xHC+)f?&4Pv!Ba!%NtIZpStmHs$g6=z&h7{o)H993pQw8UAj{Tr-AwSv=dzx=oM$dgywJ)NkF$KBwXO>ye(2k*a|R?F}=a_ZMG{Qdm>x9PmR^d3Cn zRNuT$T^O&#DLffv=ECszQ1SAWt5ZvL?cUW&uk78P2A3_AG4pJAz-^TA^7f5uI_>rw zdEp(Ex8F#*e*1ywmWJVP>GIWS=dRr{{K?~QWq-QD9(}+6l75m$<>FrU`1@b}98U6;>=`t#}{5+9y_4_YAmEn(*lXXaoP6@{2kMTo)#+{OH6pisb zzCGlLxeq1`x)<{O%6*wJgG4{R_k5o^E}xOjd!4(oV$-g+0WhC7Lif~o{u#H`YNfxu zgoZz)Z>VEj<0t8{arpCqc@4~KU=C|QH~ehf)A6jCZsm;!)O5+8wkI0Zk7xIy1sX5G zG$E6=Xqx;cRzS11iLuM7+wbm@hv|72Ge_{8A`E|!8xRP}`=y;<^zCwRVbHDyKpUTO zLhw_qb;STHyf$x@mmkn75436)W0`qP@Jh zXSjFJH_snGi`)muV?CDqftUGiZ3M?DH07Xu))6>v zzwyg9m3So|<2GaPOa9OphjhsgxXVg-Nn?J%=6ooh0kn;GWAVE4xbk~D+9n!KK#j7B zKJVFw-pUp`<2XNW;E}xrGp==Ny;e{u-n=TK35GuzQIG}0-_~tg()%CE@F!0*mik_h zvE`Hh^Z(29?wAa754Eq}P};Cr`0nA@}po>6VONtG4Wt z@n&Co{k4OsZ^?pmMh8or(mrp;j~+=QSFWXdI(fEd(Ngj1*V0uj+m+YfBP|2IC$F%z z>(?dru)`aVd;h|@b6V=lQreU0{sZ~6$;)r040fw^2*m2O>+~#slFptv7ly;tE0)Kp zzWaA?OOGGkPe1(defs_A$#nL@wRHQ=sM;rwvrQXh_GA+tK@qpwPYAwE^o%GmoKL8wa4Kp z8AfmD;0ZkDR&LmqTH2@XO)XU&?A75TCuI~p{F6@ApsmtylXOu9Gfy%Ru?g+XvG6wL>zp-bjm{JV^aZdSqzRp(3AtntqpI^XiRz>Gp#s zGN@+5U+=&w_0MkYG5BFN{K@0*xD0>afB#J^k$(NXk7U5yod$=NYcIqR$^V7C=}yRi zdN-wo9PY7Eho9_9Z@=}LPGy$IqV^Yr{s$Qj7slZrf00+-&gh@Z7cZnAztQ0<$B(63 zw{E5f^62c*K7)(p`PerwsPWvBZpagKk>0WE)~-ssc5X{=zxhg9wsesWBsr?|%xhp?123-zbhFRaeI3u4=~h0A@=n&tGiuLdOrLvsNc{|JnY=?? z;qh0|Ll6u=tYCg23%?GX<_tCC8cPY$WU@A~@#2HDDu*9% zmpS$%ql`;~2Rz6#$?om#)$*OCsr=x^&~!^1H*?**c{BbB->xUi)Tu2|UnP0H4^gFn ztdDkk%H~d-wnit$YHNO~_!IN9E{U`3>JzoaAIhf27(p-`eDu0Z8<`Ib45Xo)&bm0Xkpk#Pswl7dode@I>LFAIQ^3HbnWO-m<{QdM7)H%^J?GRLL^$DvahP7_mZ9JkBm&O2_xtzYOVb9s}W z_1>(@aPx1{Id8t*@C=_TvE{Zr+-<4)2`LalS9bMI15Y=Qs?1TI!48?*keBhIOK9e}8YfD38BS{_p>ZLpJVe55Kgq zSEt6Vm0@Uidhflr)24MR)8o5W)0q=T(ibw6ox5~3EgV>rw#u;dz6^L9*XnSJTUT_d z@5wmb6~h-sDhyj2H*ZM;+}k=N)k|UB7-Kef!P#Y2@-{86g*^ZCf{LufJEd2VP&gaN$BadFq^u ze>z-5he!1F52Vd9{Jp9@{)V)l-%ZVFj-Qan+gCqoN$Oo04L8O9a|d5(#Zq4kf4}N* zkJIO`rE9nKM^7Eb!4lj9ufL}K3wNe%G9Eq|y{Cgaeobd&n7nxDau~fZjBb%f+;D44 zTBO4%&L8_V9Y6eY`cNcW$JUM}JSBeX6|`kDp4~9xvU8rw$B>rM@~~g~LVu zD#PDedHjuNkH2H89}l}x{Vikn!8clE5Q+Xt6Y~VSF2O)br;vtzm{ye^UPN|9*>v_O)FEQF}U{`Wn0LPaL^L>-=v+~(e z!i_uA*t}*+-)g$QQpZkG^6%R#&o_s zG!VM&ri*HxKr!=)m{*K5{KX8Un5vJR!FOXF6Ogj7oOG1%n9ztPA4dK-GA^;+ ze;YpN2WU*!l(B3f{L6NfWiMOW?JVU6MjJh*9owjl0hWt#?u&k)uS&xobc9l`^ob3B z);)&5^0G0oGz40vQqH-W?leA--@2yU7i}=yIL@1oW8h9VW1dmIAGkN%Kcts0Umo`j z_Yk2p{N0g3!1qDfAM_JEsi%~Syz4IE@TI?-<-qBGg6SgjU;5*|bMveZV(Y6}M!qaF zjqzMY?6M|5!_CV&Cr>|?0o*bex5RUuCEi?0m-4wiyj_6nC+ib|$&Y!X=64WNXqFBW zc(39W$o&Ja$B*;-7`;Glbyci`Cc|UeB2FyxRa(X-HjP7%TeojXA8M&BhQGYj_e}cq zUl{(5$=m9_3`cr4E*XeZVc&WCt+Y!Xa;payrEA(#?+Y!BJ*Go0w6Zp>T)Q#7@y44v zoMKB_HLz6PYBzN%>j@p$aW&nQ@n)$`$YrT5o?thw$#AG8r-u$5l40kOjE2Lif2X|N zcE=LY5$z+$;Ud?yymg75*BiHNk+<5ACSVKGxpU{!S6_aU&MRK1Hf-9oKE3tE0mU2C z9`TkJ-pP|PNXb)-XUeKoLuvDdHPV$1wm5Y<9XWO?{qmcZxyo~JyS(}K?Ao4Qdu2x$ z{=WMBGa03Rm*MYfoD7Vo*>Wu}-o9gp3~Rg6EBp4y>#sNVxVt99<%nd&c(;6wyb;%| zm6zViI3(oUad|ub{%iW}*Ppf2SNq}V5DN@{k1+nJFMHUpj=l((%4GP%2)0Daa`Alo zP)o0O>m=Nj%k>-_y_>FGIF*jc*!b0#Uuv1``E2xilD!Bq{Pk<8?=Btg!KuP)bt>=3 zS$Wp|_DlL!hQHhQ9;A)icgrJjpO#|pOM?Ub>DILodH!8amoJZKsqVrwv`QY8l7GYc zmD(8bUb=AVXc+#!`|jIx>;7ok*xI8*PWH<9sY6}{`_sK!S9SQv<#g%ddHpd4!{4&h zKR6^^uhB`*x6=>b|0FrjraO0TYcIyt>794pNZYsLQQD`y{_dqyr_QFEH*Uq!;~||S zy=B{G9o(`&Cp}+E$B!LJKYgdY5oJ_-h|!NxEZwj~y1qk{i2EwWef7T5K#zM$% z-+R9Ahz$!|u?ALNann>kC0!?Y37bmV{APmNYRwz|rlPlboOun*Yhac&z+7aOM2Ppr zbSs}lc~MiyJdwVp+n$Md&6kbQKv&&+J|S%86ER2l=imQc@9_trClO{c*$dwImcaO~ zpgB1K4;;$5Y~a9n!AAgw40|#;P3#LC8#bBTKceCyV-LtnxyFEHvrHp3i4 zLol7=49#sQ`5WHEGkmt=rd*c286zjShR1JyE>%m0Gk5WXZ_ebn zdJoI!6no22CcgY7bKCZ<=}#Yjl!kY-Qty(*>D<}V=~F!Zj%ul|j7Dq&_efr0t7P2T zyLWfmyR(({4sQwr(Jw#$k`5m^o{pZrB*WH1d3#RU|L$R(=DJ)8hTYM}I$(PH3qq#-Y1f&fCw)t~z|;z^kvyLrW~qwLe}$QRATB#jKv%p zaZC7T((&Ubm0Kc%CHwDfYqhkL z`GC9xH){XAB`SFmryS$)c1Ol9o9l1I3wfaBv>0UB zA8?UQ9uC8wmiqqrPao*OlKymAd-NSU{7d>y2DFiDH+A^Oy0mHAa5^Z@%B|wRyg%#r zfn>j@X)?02? zLc9g0Tls9uYfVj8Zqv=jPo;tO%ptR(8v<5MqM2(GdY*^jkB?Cdb&F)Apd$XVA1{B> zx>()=4wsD>ix%sz#EY|mFFcv_L9kStVcXzGY@-KsnP2{pC?^(fm_Nj5Bp=%tGcauM zfsK)aQ}x(pS^oh> zaTrU`Hxps{AoqjzFj7BYfWk1+Em(H9ryJf}g*WAP-hDyL7$1-q!}8@rp?i#eT!S+F z^~uOYIeiiLl`It@(AT2ObzXF#H`kaztJ|C-rf8 zF75}OQ#`Ls=lY$ujKskFEOdR%`wpD)f*-ixbqcPhQ`v07nsSwTKrZJ=gX?~9najKJ z0gphraiHl$=W^qNW4)7Z@^HSSi^__hvaSL=r;??NZd1&P^{6S^Z@jDvno!LGt9Ph0 z9C~H!@=T+z_=6i>e>{`S%Z-;xRi3Zl7M^CBz^JbRE+9NOT;qWD=G!RGIriThxpXo8 zq(dpr>F|aJ546>RJmWZ=qfZBHY!q&5>!!3o;ZiV=uiWGAyosKzO3o+0bz!4e!w&^gD z4La20$>{xbPRpv#o;s1vYZ>-6?VpF?51xgw@c1nxo`6!Rfo#F@m2hjtkVfti*G9Cw!Nc zvGH7ASvFZ3T3^t&TJwg#$#gbfKCgj!4a@-z=5#L~=;R3qFpQ%6o~)eO&rrcACE` z*M>aJx-bT^yamA)XuqC_No$f{roB>yy4h zFZ9z|Z8na<53eN*euIMp(O2#2X?J(SpLJ}VJdVFw=QdgfaL}*&0Z%iGOc($$$YKCA zy=kcPWeS$p@>}+1-f&{ZG}p?NE7BG%*;=O$3YJz6=tHnqCq8n|@Bv7_Im9^BC@se) zWzGj)HN*m@bW;ZM*~=z-WO8rN2bZ)=32z1Z#D*wvO-~!$PRrxC#4&6(;>qMIWh&bS zylkKOczmNT41D|c?UR?y_OyQe`tXp&Llfh9lh*oh9mMb=M&H~6d~Bm@bpES6VK4~t zd~|=q(|k&~fg7jf+r+U<#Do&pFw->ihQH{zQ+p?p0esWYhB5DnO6MiL+v&KZHLS#M z@-J~*W**R$<>u1~=CYF3u(=kyoybL7eBq_UAI~T^44jP5Sg-WK@T<~{Tl$DO05tjj zV!3Z#@|$Vlk^}D(_?VZM43igwFsStQEt6qpg*$C6nFS;eC|nHG7&6I^p7bQ8S7;HNfW@YAIRMfLUZJFd-p+7+C42|^YzV>Fmqy16! zoV+guKVBdsst(^6(DQac2b2uR@U~=;>I zg1$JtxK}#v7yY30wX9b<5f3e34#Qvct^VkBTl@0elF{`313d8ddr`qH0@7{WOSk#`JUhs4|m z1bhCG_I>6wF`>NoNE2#$Zg2vl<+cL^3C^UmZ`*unrmg# z>+QKFeRp|$%XPhZU+u4HpB^U3cQnz%%V~5}6SnaF6Fnj*AR4^0aWPM*tk7z1 zmJuiXH8+sT^n^rDRXC=9#3{D{ec)}84@FtIa+Uu2y(J7z82$SD^)aM=L7#c@$)EPK zZnMW99v*z4W&L7cExjc(Jb&dh`OvfB1H&JinPUV*|4e#Ix!tFk*WCWKtfl-& z+|0Wb;B!x~mm)@_ojZ3%+%M0+CGvP(C?mK(a>b#|aA(mW_B<37Mp!BTkc zmDgT-Ewx&$Fp{%0yAvHS^X(SH*UPQZIZN7D`pdn+A0qsqZp!Pt>$NeFdI-RMm3h+O z7~k~33C(m*H2jQ~D}15plJu%41XG(aG)22*e8OPI ziL$XbpPp-r)F6z0i3c$^1krynXbGqT);nGg}igQJO_yP@r(_Bbg%{)Q_CC#s5*VE zyvFuw4;7ZvEYn}%S;C7KU-s(5gD-pbAwUF^D$hSjm{|op<9M<`eJqRc1Sn7VGfpK) z9R;-D$>b651SVD-?!m|P9U1&EY}oS#Zzq;Jdg*B`qqw#emnT$KsMyXR%!p{(^;mCi z2eH$GgUe&N3r5-vI`NNXzI=%BLDn|#=mTcY%3XRyVwvH+-(dmd|>(T+O`U;AcbmMlJE$qJ4+9 z#$Hb>lV7O&q~vG4F|H>X_rV*b6Y9ZP{vX9;O)z8f=_vWH2K2YxWr}NxWGueJdkGb2U#2}J9*mK z43w8Tcbm+^<-~@SvD0NehPf{1!ErE*d+=38>pF%^#T~~&SC7B_0>cY5$oMD)QSJch>mZ~ME3{k;dd6v6U59S?_)r_)%O*BX%p`v|? z7phK{L@(kQQ`H9@qF}Uq!qQiHH)8k;9;)<_>VS`=sxIlJsx9i&4>3AHJuzMc2;)}B zMhhv;@k(2n?^<5QL*@fj9*Y2=LC^d{ zPtfw-Kq0&rxCi2X(wOn{u6!PXpYM-cFWemrcRr8DJT8Hie2mjAF6%+g=+kb<9pEKB z#jV!7;je?5<{T*Qr$VY`z9@RBlDh5cP^Y^!u12Uy<`aKJ4HVtvwQJXCFClHbt^NE~ zYVR7Bl^P!|q_csqJ=x2Aaz4s5DGfa;&icp(K>CNg)u*KL#%c4T9wxYW`eFFP*o4Pf z_Pp%A*BNwkF<8${J$927d=67#Pp7RiCUL0Bpq59)Cir>q#r?s352KL7ml@IZ5Wf=^j*w}#C!ypx=?!58Ia zDBA~|ym>gLZ{B+Atu#D59DT-8KnK&42j3rBuFo;$#^oO21CN-CF>mAF4?p}6-j?8& z{73`y{Z;ZK?EoI383S|uq~}T~WkP1l4cujh5tkprE_ZBtV#D0dX5KtYc$s!N^d;Q< z92>72j?0bzGRAJ3WBLFCo-dE#Y_w}XcWA5IU()73FlED^;nK3kcK(A9@0U#H@xYkQ z<66Ta%J7ILuqRr)kCd(-g&GQSE04*%B5g%g}JTW9xQN_$lw$h z+;<+o!IFl_OTVM%OkrviKaAqr{zJeDzx)enyF{BfEa7R}+%1!c?O_@T&<%@X^G8C5x}g@Q3$OzYKqP#b|a> zu~I$xKeLEDk?>?l7#XX=9Yd0*a?lX+1SFF6PoNhxFe@hYcgeT1wOv< zI>XZmLzF|bQyEW^44><<<+hy2-`}5?m2w*CwryKw#8@TctPhSrfn4YbJy#!8q4unM zc(vhKpYhRE8K=BKbvEk4scrDH!NUC#eW8k&+~Re~(o!}}=klI^)MtF_zu7Ku=0a%7 zH<_H^uhO1z91cNWaPM$>ARkI`&v1`a_eb!ePt?%*cB&fP=$`08dXW&iEBT3M^n=TC zcSo66TMpyB zEHQ0xJ7|NSC#C!@p9p3?r5>9)F%EoOR>rQ!afw&LN;zJZwA(qEytLC>6_ECxpp0ja z?@qjcfzLfeY~zv?UF(`B9fp(mC&LbS`D%N?LQg&RjN-u;#u@nVq*M%_%pp? zo{^vhRxXD}8$UlqdEe!BV2Bb17AS@I14`5p*~&1abRY#r$dFAy73UC(pGsCC*9N5^ zu{0RAvau_3&(8}=rHFi)Hh=$46MCF~G+ZQ>d zb6pt!q94gey|4v`OF{MVk3bu9X(bFfta%ZH75ztsKF&}`sh2Bcgq!ffPzOiJm5~`Q zSsxhNYJ;NW$2{uVE3P34X~uxZ3~|V=x&y8{G5(R`f0kcy$eHD)ln_{^Hw0Q;=sLEo zkzO$X=CL9Az^`bd#)^?574aLAlghf!b<=h({s4EsTJr01a2>2S@?&I{Oq3bscedln z=*+*2;YH{qM~OF4+VZqot@O9Q{VfsChqQdIT4nl#UMj%c9gAOHAgH8sn_s(!IoFZ!-> zR-+{Fg&Q79LMERLf3N8Sd0U)P8iv1ktn#6j>+wW_Nu`LQ8YW|P7?UhA)M2D*f>V(j z8W@JTl`epx@11-@u%y2|iJo{PXFlmI>f+4$== z%d9c_VRT}-DaH_JDE9@v=}6C|fQ*E!qpTD1hLbJ>a1M(I!{7F8X&r_?ZMvREW&X`0 zRUoN~bh}3@P5~GPt*Z&WG0H=>EK~D7l)!Nx@KK2D>|sS8eER99wc!swojxAwisoP< z+TNj0fOiT_d<+=$2i|_IRx1wm-~b%!!92S0qugVmOat@%Kx{(^aQ@(M=+L3iJ05`i zF@n&n16;#hW>^$-py`HZ{J9=me#?pOXmbhgq=T}&Ov9&%Z{EblHBK2*=5o`xya{*t z%M!aCQ<0bVJBL|tPuNqN@$50}J~A(O14BpI@W+7$em7KO8Uu>{#Sj->c%_NIw+W#x zU(^$OVk*vh&nBFBR>piI8)w8u<+^x=){n~yw+#p};lmRm|F-X8NuJ@A;V(Z&Yi4dD zghi;@RPhT(K-K5AWr+&(Nb)?c3|-{K&w7i#sT)IsC^S9BB+tjtb9F!j?Lntu_{#^Y zE!6&Vv=ign!_jQ0&0Itm@~KaF$E!TzkR#U@)#*n$UHlRQ<^7(838PzkQDN2dyR$V-0^k9hONbSDx_WMML1Pnx616k&1s2tI&c}b#)q)rO_!S zVnH@`5+imw)O?xPVsOl0_?8nO41O5?@ceUNQd9=;Uxr}0k(Y@dlfVtyd-0W5UeOZY z&GKa85Q)4`nRVb8T7QsvqVCBdA6qv3Wn*fdyv7HDbjuz*^~AI?{6PzhVEvVOf55TS z7o!u)t?~L}qH38;=XTBIKCrIJ_BQ3EJs4uyI}VSs^&2H^j&7?(1} zCLdiG$Jx4|)f#)42f8Tnp=t7Uea+bSMj4al!fT3qfI~hGA3hw*f6do1b(NtBr#@hY zlP5IuC6AXmUAD_@b$hIb5(hmKJf4l~*!@+~xU7s_Ucz4HwA|P z9@f;G;~FXIcE8lnFhIHu)D2xW{83lTa}+bq*>`S%PKOTz6-Fxl&?j8p)$TWBjDUy| z2>Sd^7ZkZdDC(=w98*~|iX%=e9Ry*9tl~h*eB=Jp!dsSV3+yoyTvbQ>5mGTNqOK|> z1D)oNt{g%^0w>a01{>*ej^A7_sX8qlnP&|dgOzcs-yjD&TBx{6Rn0`7i#0Ywua$nl z%)Qa3L2Pu24&y2+0ZypPXuDwOg?A7!!Ottod__U=Q{G?jV=IwXs}=VSe^g=*W!~@b zEkiec;7~?@-_r!>hll44e@~;s7eQMM?HK7VqQ2RvgOU7nqj@%@etvbj&s{?^Z}_v0 zn|;vCKkNElHh%60$In{+roNl`XI3L+v_T6>p`Ol;Xu#(KF4;d^}kpABF9g znE4BW3=$|$xT@MP_%#iGg&;3gvYfE7CmBX2miX@3vqyXUt<6h*_z0*DlAv#VLF-9m z)@jx)FeakJB|P_W{!j?RpZa=Cd6D;kbUAs_@MU63AF%8f0|+2v{`~pi(A58AZ7Zss^(3+rkU84fMRCRh7rkI~=6?CppZ=6utyVm@qEAF` zeUvn1+Vwf6Uf(m0n=r;db)tU^uAK7AeNfg3zh>xEujK=mdI-jIK7e!Vrydb-vPC5?!H@NAJy~SKoiAf_%ew^}FHNT$ z{h`xxteY<}x`)=d);D>viomeVb>}&QPdbM_|IrWQe7iH3>0km14d~( z96cJ3atP7z0+nMsgO9Ttm>$sNY>U86~GGv zBL=`+Av~EMP)FXQF+UgGSGjHsf+2ly&YU!6L|Z}yp@mUT$W--9p^cz-K1-1Gm8ohq z1YXyliV!}*tI#*P#rRDeXjYzZ^VrSx#TcvT+()jDGUEax4b1lt&m;2OGcGf2Gd3M? z@R^Ul`s%Ck2SxsvdiCnnm}BurRrfnIzMA~VQ${Fd48SyhpdTKdH~dXgZ7&?%_X`!5 z=@%}@bF9$M0>{s>syWZP*~iWN^KL-151RSsUH@F=?|yLnyyR@^yP1Dp_0IEsz8dKE zz7E4*u6mk7s~8zgN<7Nmc;k)mU}BjZlcJb72oXV;7cu!{F2Teme;8;gD+6BMq#Gkd zHbeyP_74ndaXnG-q$CQe2}+RYmF0Sw6y~B_0xq)nuijN*u;^s?vjT}-Zy?X{pHesW zEZd^fWAS1d7#M7S5U>m=Cg|uyY4s1Ue0yo;Hq$5c8GnV&A9T6zs!1b#DTIJUy6Qv0 z+VnY%+N@L3)+rx~7(LkUk0rmHaLSTjx5FRm&O78%JuCI)(yCw{syALq_+3y;1i-rnB0@I=EXMIId*A6x?W7qoc5@Z2e5 z?gitNwA5!g99y0s_%HY=+d~`6b~ek<4f+Mgh6GfAj!Oe7bilwv@AOj`OO$utIflNh zhdh6rqAo7zDd#=(PzN($yyB05Iq>Yu&na*iDYds>;N-DWA*;N?ZBs`IXl>s!vSO%9 zud-ZZp5|5&7+ht?Jd*`$^B;?tC8{__g*>+)sOl%9Hnz9sPyzoTtnkq@`}m<_^u<-q zyB|{F?41oMmm8~TB!z%Sz z#*&}YmdE@JpKc8O@bJ9hZ@PMW(fIi;YS-G#w@Y5mRC&Lb>6f!LPcL=Zzh(OAIZvHK z*$-uU>Ky*NFw1@@)6b)oO?@}>&!f(Hp0lTcXJ`0}NuL^`7yCv{G+wU^e*=}_FaI@{ ziAsAilqVaSJZX}`q@9Te6VYt^V zZ5#2Jh~_KzS-by)TlJ+qJOvSbruD?K)SK%B7X2@JK0=tFGCBSI_upgBGwK7!6Wx-> z+|+zqs)=N!{iWd#qii<(=`Z{;gvW=SSmoi1e$i+(_Nyx3(F_3-SUn1M)rXnR^3X43 zKa$4a#IidA2EV4^FADSn5A!i>F2~l3f~s$Oak`YClqW3214&Bo!Q7Q-ITF&l%xBMpqQ z((vaGbNHGE_~_b3KMa4qxEBcS7oJHzyaG71mdpHr|2GCdchLpG?WO(bmGMd1hCkBa zaCv-NFYtnf3p_6KG_Gk~59Q!N%R9?`IXasENYUQQE-)*el`)71W;_cO>zSt?km}Gj z|J0y(YLaUk=GtXJEq?JFuECjS)slclx~ht_>1q-s%-?hsdR>3y^;7Esy^dj!^=AWM zrOLqP9Ug~HNMCI|%gCxeVOccK8ta?bbr{z%^<_EKpHX-FK5dJl67dBS8Qk8iTgk}3 zTDXiFc)8)CGCdq&kPFJb0TO%tQ3q)HHGguJEz%i*q{5g?2E{LRwo8qb`4nhn(nu8y zy)hO`!yiS~o!e~vmO3uknx+W@pXZYefAA}xiB6l2a%i|H9q z!7n&udM0@B7e+1hWzVuf8JHF?S*!_WE@z(^gvgT#kupiCCY?-M!1)hQ8LTC+@z8uBq8JC5{2x2xki$VOA)dul(MqtHLpEN$h=%! z+chrNz3%nB@6YG+{ps}wyw3BC$9bH`<2FrC=xKP&eX7Mk4jslW#p#mU^XDdh9y?Nd z1xRAAHz){zYOYQLupRzDmKwWGs4F=(*6xj7x<+^fKB!$pvb_@g^0dw=)0I>Q{xq_! zJbUtjqcx2*jRh3`FltEIxUi%bJcJzwOYkeC)vD{sKMT#s?=We*3o7yOhAx8}B>|j@ zLBz`fIWHE%$nGuUbvB&?Y2IxX0YmU&eoN4->Tb)iZPx0*K|9C_uaNuraNKMH2Ucv( ztla!XJ76~W^jw)rv0vB7Bz&%0@oa$gvrKyk?HN-HIex)uxtGT)1D7%&9HjV8ei?@3hm@Ejh!yCQ$&MSuV$)>Q0^4* z%a~9lIidbd6Ld{tP1+~BYls}_jWyb#B zNbJ4}0Qdd(_xF|c*ilz~B|qGPEOG~SQLjm(Fd^a-EKPCP=dI#)rN;dj{LdaQOIszk z4&CF63?o;C#|@gRxUgviF~BY-HNE%c;UJk6JVVrFF$nwjIP#eNWeC;m??iGCgJ-ti z;!VC$0APg1^8Hq8se7Cac4YwL-VZpB`INnS{3`&WnRCN_4wUF@kl65KH*NHMX1n(9!tP+@DpPP>x8*gdE5OrMsRq^2dgbd0p6bJR%P3%t~g7VsjB zrLu(i5J&6+pQKS&^7OqQy)sihr!SB$jRr@|biegv~L zIN=#PdA#(bM-5$nIIOwbMS(>zpN^V*V>!46D;^+4tvLq-y#3TO>H!g~!;P%%nC zB{&#+HOhn=X0FcV%_%=A?;hZ3^^P;ZdV>>=S&5coo6u5h_Y|gn_MBvsKc-P2>tJm# z+3WQUVfNu=D4%Z|P+oUWvrEZgcg=5Ko}+%_^bbq?{9bMJ+C&Dr{x==dPwpPP;KvBd zmyMT@SxsLrUoJ2-%Zn#vnBG{Tv?K*3oUEvG-G^N1H3&Y?WTw2Gzs8wDah~5n3Nq4} zSx#7l)fw*+jdgyFnt55x(?+;L|FFxi-AP&AqD8OMSiU4PPb}{=o5W^fH3I#JI_6B+ zk1u4?5Z2Oudg|@Ii3X&qW_|Y71-7nM)$p|XRUDavCSo1rfv0K&;_bH9-E6^4G*Eb# zpX=1FELw4NUuTzY&~tLVYQ5+G!nU;TU)M23DN_lIYz#ev0OsX|jgBj^|2`~)E(O*u zryCGjOSCg4Ppmfx#c5yvgfxXAAvKHTA4d29g4odZoXfQHKx+^TUea)9=uy-im-9gn zJ|^~+NUBsa-2**2s_os%)P;iIvw8M>3sc6*tt>HKADb|+bYkiokjhX{7T;zA6z_Wi z?3~Cw60%HF-KgCmlw>i6Z35W#8NjKgF|qD&`wWFUAE z6QP&!CvoOhyio)rCukP#MqZNt{plb0#zLT+Jb&b1cI4vRGSmFcQ+rfJj!W^(B?U8H zudk-^F{;$Niu=rM{hRVVp;rS;wf9XGPfei3qsxrdX zSHgi8e_iOzZE zZcSB6%*)Htb`!SpxD|;ss%Ng++hX~;0YZ8m>^K5a6}v6odBCCzQWWSx73v{-fL~S) z#{HTfd8uoUayCljA!8YQhuGnNOz$_|jIW2Hlo7`)3JkuVqHgYf(wiQTA7MWo?5o@y zNok%(x0Pp}Cb&Kx)~qeIE$;IiEeWp|)`CYqV}%8dXT1O5KhcZ7u70WET`H5VBah4E zouFE|vG4Dr$DB9HzbllyIVO(rZ3|h6J}U(KIbLwOYvi(_5Ki)fMq8U@n>nUj=32ei zYW0Dd?*^8tD-~XOw7C6w`qHNhsXL{Dv69?*<2)~sM!w4f|J6|+w-cM4<`bdU)BEaO zEetuiCST?tT}*b?Ov2QOAC`P0hN~CdU?}Byt(4dX1>#**&FyjXqsAc&=idUeJkk}=D23z#IQwhzH9S@456-fUorgr za>ah|-aQc!p0{m3tzhcU+=~-()$H$yM+$kkO{oA$*Bcz;d`Wko#;KsZf?yXcw*#wC{Kt-RMTsf;D_L`Rm%QWZYu! zoDAKrBauYa2G58j0QaHEO(P{l#xGXtK6l{e)Y#BELF{W`N84H z-4MqHQ6F_VbSxpJxjI+L&QPTPCj?6`VKI_2L#N{gTy+k{YN`N8JR%ExU8_77%^-&9 zCn=|#%5!%;3cg*UN-m}11b;^-zuSCd7IN3DQEq@~yTCe0>Xmwesv64+%sQG<8Ms%V zaJm9%-qRkPdJ)1RL=pUTq98|ry~sxNl|b1HDeAj8(MD6%ajf{^r4+M|JqmK4Ef;+g zzxxYBkMDu+ywJ=E0`mQZ8((ai>oqRAVOni@gRn0_37zYB;@;t)v&7g)x{}zf1|;PwRW~3X>pN8 zX7lw`L28yq;C|9WghU~`q{h8t*Df#B<{;vK5jPsPdyu$uf#X=SW%!JedltB)|5~c! zTSq?|{YQ>Z{BAVy$wz9JJykcmjVkDp(?%=fQ`oNYWp7|7`97dVp6*?jG|MW?!m1ke zzVp$t!838WZTyrpd&c4QlBoOG?ok2jr#>QmRurTcH&A@?8+1w#0NhR+(>Aim=u$Fq ztK}4do=994mIBLMJ#rlX`1Gm6r6na$Mh|lH4RY@!y>@b;5{7nAKkxW;tH-?}Wbxl? zZ^50TTg;5K>{l5e$_fZFO+Q1=XZrVjxPWUkYZAW1Ehc`ORs60Qqk+Q>aXWEExaol@*T!q# z9S!J?W!ma2i0$1=#VDqCIt=3CtH4AEaL@7ibYkx}rBbER!Q(`w03T(agUL<_u&kES zV#p(AY6)y!!MWmVwoKD>KIeX7+;}jK4*-J~^G)Wj;Q01fdl~3t-D2-Qw)ECUi34x zM58C+q2ZDW1Leqr##w8-et)Iz5z_}tk@7^Q*H_5%?Ariu2X>?8yw%k1b1Xh@4$Lzr zN*S--lXYVhh1+Qhez`qQav5l@E!sk>BndyaeI<7v_QN72?Xs2tAvo+p{ORzk_>02V znIGMXC>zITzJfXW|Mr`yDWWj)g;l0uj!UPl?dldhuiZdL91yw}(384Wj6*$`j-Sx>~OA6Gl?d9p=k*GhDtw%LfW^#Wi-^^%_jWIc6 z=2LlF12By0h4hPP>%QE!h?SQcusVG({H|&0fqN7AX8)miv=wvMTH*fbcln575#m7A zbiz}sO^T22#b4JQ|^kZf!H(K)GEn`E2ww~20P3J`I%}HnHEf!5`E3sSt z=s^1%^+Ty^Ty>q?&`I-ST)H2LQJd*jy=|qzNy~1iM_Zy-=n_5upagZfm}{kA#O^Y6 zUsOPbV9GLirOYQDaN#7EvgIrQS7?VXlFwM57}mI2B~LH(HpPJ{3bEH$;`zX&)stR} zaK>`($XKF`0Aux9_m>~;da_FvOHuW44gM*=IEMUdjOM<8FW$JZd*^4x8(8YX)fkA* zvIE?`z`S?&=($eQsC3=Uzi;ke^|L>0jxTyt3xYAXO_4trPa}P66a}A@-Y(ldw6f9T zq;GTzF_cYU_Txb)z?!o>j2|a2P+k+qgd-7Ka&CWK$G+UPb93sI`1P4)AD*vQ`ON<1 zkEWNcjCBrO+A)9HCec1G?&V(uw_$v!A&+(1Wo>iS0`zM?9(;mn9km>JwxZQtgsb^h z3OH2sr^lrN*HAR2Jzu$Q>Wew`Y;|qYk%^4_&u8G1=y4 zz{TFqQ7={g9HRcqZ5Nfx9@9Qr(HpM!Z89xuBn zBZ5h3`h4`?hjmS(nSwlxn&yz(W5SyP{1odc(QVkL#(J!g?T-AZ>0{zRB%nVKj*kLu zm0#OmA%d&h>x}xV?3^Nyz`n|>BOO&pPVApVqS)$XGocbT;jzS1^-E5DusD`i3}Q@q zhgJ&#HIT_2!;`UH7lT%6kH$WpoH$rp*atce?5xKkTgg!(Ol#5swgVwMN8v#sben2o zNNdet^-(#aD2Z~G(_Sp&*=JCwx7Z(E5@xuxND;3(&J}iDO8$2P^?n8n*B$PUmm)a= zGa9~Vmw(z9MKI;TOa2u3JPLW@{whl8q?;IBh23a&c-?^A9gS$)$_>lmWd+4h5qE72=^mp8b2#^g&p@Ck<(@K3|U`i^?y1-_C zI`Xrgv-_(Gj?I{t->$y;>3;WfMRS?JVMs$w%Y@yZ7t)6<hhHblEqD0ywgz(u z;k)_qDQ3=d4tEQ)SZex~e6zlWD}ZN5YU*%yc`{T#SuZEb2ZaJD5xXgG^FWhQVdLz- zL?}i_A&#yd6=QFLK`hX|@}hPl-_K*rT%}3}Uv=asaVp+gEBQ8FF?L8rp3{X~gvX_gwBQ~Ygb!MgSUcb7CJebC$AuY~@|md~nO znA_Yuf9f7()^~xSE;`)&!Mb}*=8RC;8`}gQ_f+b0 zZ}%`OTt2>vN2hyoS70>ziHQ(Umx#P{oF0Imyb%#SrOYoP_ki=XZ{&i_2a@hfs=T-2 zItUEBcH(DR(rVfElj1@aJlSe<@12C6JRu^Psnc@*?%`i|Wh)8#itLe#SMPBm?b?N3JTRBS_cQHt)&EUZ^a%Rc)^)$*y#KQ}@?a=^P?ZbQk zK{U-e4UE#VEnX7rQj9&Bg?M>^m()<5k|~O@ezs?q{RRcgvqrI}CLOsO|P#UDyP`ggBuZ>mx* z+t(fcB(R-vt~P&f*%=6+i0ibpF)c(P4EbfN|8Cy|>NnZFG2+qPG9A&;Oo;*Q6ePsG z{v%rc^E}~RLC#Hl{o@ayvNYYHQNXU{{%yZR{ehC)jZh*%GZ&2cC7t; zv<&z}5gEFd(vfM<+x5i*&vDv-mG5_Iu?R>zai~BY95p1Qbd-8-bUbqpK(|_+e_%k=1JxK z!~{6{dSWWJTP>8b3EeHH-am80iIfD68S$#|;$b-Lh4S9X`*_l=2&SE@y<@xOVT97` z`&%M)xb!@?F?A#Uo5uh&yrkp`8?L;M)jab#I%=TIalv*)y?9U zTSlMqhJBtqk}2ie`&i65jk_(G(>CsGIg`&7)PGK-QYR-5v>-mH74Jv*uf+wP{>mLI za)*rsAACwiYK-rG7;R}S6Gb%HJ*$dFRr27!OKbUu_#CxdGQcgrhth&bOaWs0wqYwC zxNLD;`C==gZ8-9m?*1xBfT_e(`#z>z$X{rtr3?2J-RThfzP!NV87QG` zmYLAsp9mp*HGyUp-``FP>!uZBlZ_-FoolHe^5&h356^5;NMdv&x;iYmLO$}#A_o3AK8-pi%47LO(bIAw@Xjwyr^SA-E@LmKE7RrM01~*dGwC!r1 zlvP9|-Yn zIQ&yA9FDrZZG<5GiKCfk%^e(XCdYK1o~KvYNxCV_Er4L+nX(C0nwyXtNzkNPfOkGv3wANnlTwb^PV>>nLx;>S ztdj6z-FKq>8=e2P_0(x;)NP=7IVf8l{q_~>rpGST9~lw3W1utp>0amyxZX#A*QWoe8ODR_UqtR6i^qrY;FrstSWIwF z={}PdJW2Qmz<)HB#cw+9X-G23PRgnE(A6#kgGFlvc4wn<%M&+pw>=7K%V*0-8={#@ z#e$KFnx9#3@^FttK$e>mzwr$auProFT%F_Q(MP zu&p*yEiS{E$n{5Mq-**cPkV-~sn#an!t4Fh*w(FqY5rzzyH1NSm6V{=alJZ4O+;Ck z@wOyz5|n}g#MQJ5o~%jr6PJT@N0Fd440Q5qndr8MN3oy#gM`TzSEi88;FyP7s@qa( zpUNL1pSOsjf2(}!oP7@>;(L3>ZRa9h*nN8LrU8As%j%1}8YYLUAQp>U~i|8*tj6XWE~Yp&7^ z1PHMmKnn1_>}*vF16>9I*>X;Yr?4Y_?5A1>gUSNt=H?+TX%EGXSw${I*!#=>T-~o) zRcnB=^sQj4pFd-d@X@o&k_qjQa~{G=cq_!1U3I;FMmQB`KzJ#l7$SCGkWehzqlkMd zXZ3p4x9J+;5!Hb`%#>#IlQ!POhB#dsMifHvVm=dWWH_<8aZgH`kys!1VR`{E? zOPcqQc}7#g7>L}bKEeelGuS$kNJrg@vlC9QhtoTf_W!c z_$SbE#C0Sjag_$h7`%4;}Mt&^+wT zJMu|D>p?b^{$922eApUGEo>&)Xij^5W8*suwXD4S*hD`2P9C=!14E~o$4j-ev|BMl zoaPl@hpcTUo|bV-GtrnP&IY+Z1~On6kMzz{_szuaw%VTHorXnCDiHdi>@(E-eH=YM z+c|1rOE}9pei5I(X!c-P4K-RXW)dk!xc*H((3&--aTr9mhCoM~OggoXGe~`D$2nm< zEM_?XeDKSph7m4Js+&2aX+QR?-JC!C3f>V-14sA~`0Y4vOF~&u)k?1w4~hY(-m|N zR3jjB0uLODn$Bsafh%h`jYlvtsqrzjYy)q4*6RbHjhv#0=6zTE?azD9%&oW37a+(8 zr@i7w1%r!IU0|gY&b#8e7$m4c43E|VK;5B;yjp>v;uNId(sc`;d7n`!e_lnEuo86n z3H1PS<^#BL_s6KRnDdzuu$KAL640qq+;+;}{dV3J(z$u2WQ_fF;D$lv?g^t2=nFo$ zKW)c9Amv(5QNs*^vWE**K!Vk9Nhs@gLRW%Hq7cUYzb2FMC~2$n5~U-HHse%gio_PX@h6 zl2VtOZZdoY^@b93TAidd@Oulvilab3yN3mBhsjqSFSlQren(jIG~TW6s!ghSl+$o~ z6si6YgS6Aq^cCVeYvP)D8`#XD(_jI$+$xHU%KY{(#-GLLOri%-@#0= z%I@l*U%#BD_JpidKlfsfV0n*HgOR#yXj-s%)gNs1FG?)mQtx1p8hsOKPjqT1i^g#VTZt=z!DZm}(mo=Gw%E`Uf zcx1TRN}E_q-=CA~vTa1&a_pMji%^mTni5I|M!c)L8J-EPXuwV-0G9h%047>%F5{n4 z66d~=thwTdm^e`rBD#j^)`7O|%SRHZl!sWx9t(70TQj?7AVpwKrazi1jDLO!cwW&F|1Bv~U9;4+d#~4p|^5aKD}NS1-BZyBvJ`-a~EB z)bVE=JYrv=$IoTQ3_9~$+x_v?&HS|z)vF=r!KZux27|5et9ZSNSZK-+Ju^I!^8Um^ zfXvBn$1$Y0ijBh-FG{gkw^Ti4PO#p(4Irs z_LQBqg=DrJ_+9h{GJ2t=l5u9?^hh->??b!UUT5OTMMQ~9Y={Q&Smn9qRFPZ7`H*;_ zrc;-=1LpUJ<=I*0U%+zNLe%9WfgLKd0VLgNM5-M*3Ge zAVEIyi6h(TPqG=*U0j$@)Q{h}yePr;9!Zi(AoTW`v$(Nk9h6RO5wVN!=YumTfPYkd&QxlqllA?)nG!^tW6q$9if%m{@ISZ_>YcCk#2?@mgXB0vGIkPA6QwDELa5mREZn$TWxDAb?yIJAd=bnC1HS z&d#-vsnNvo#s@IO$^iTI7~5NAmo8WtuQ+H0ov^njS>jB&tsHB<&SPNM#tw-%UjesJ zk2BhhLd!J!4(4oCh2I0-DI8M4e~LI;+Lfm^F-H&|KP)3)9^OveOu|a@Yg`^)GWrKX zc>Q>ZJYa-Y9>+mX3!t4-FMCAn!G=?M!xH;Lxr{?Nb~b16P&5#MJPubF!&%wUrS-4JP(6SdIgWw!e+JB2?7XeXX3@iG(piCcf3Nw={l7 zEyx9?y3rcM3koJ32_h1{fEp? zjH6T|F}FYTr?I@=O8+`|O{z_B8!+tfZM89gD@}OmP6=tf7>hvaO5#-3g ze=E1yG>>$VtebO?!(zK5vt_$DeKFudJ}x~8$wH~hBCin);BIM^_zJGMbZ57El^||~ z#ZES0R}f|*wG!k55&G|CPAf3ft*A?A2D!mNEXEa+=;w z-Q5l;pt!IcECXycn?DT+auY)+n+u~1I!1>+Y1z=Tv7K-53e<@(BO=bfBgmjBQB#n| z__E8r+d1YBPaZ$!>JbfPfX83dx#s_-2bJqzq3@8TzZR6}*CTYAu`d7&?Nj@06nL1c zPWSdlayvj9iz+?nkM#i!@E^h`=K$715QY2vnrl9WOVe*3fe&@#adrvbCik^fJU*9| zUBd^Mau~GH8oTomcQE-93iC*Em1mHLEp0RPKy>nQGiUE~B{Mb0ebzoXyiAp-uI3YJ zZJpOy5EWAm2wl_tSWfy5B4E7o1{R~r<3L;23T>_a$_5$=C)+R12uL#0Q9P_mM!C*{ zLtOHtED96uvj%1zAVWr#1ze2zSDTA^mvZL}wxs#=Din}FHruW+jNAz4hEOp*nqGB( zqo=ts!y)&=OyUvdAecKh{Fh*&rdD;XdyYepFtnHfu_P~v;gmo4mb+xQ*RB_`ad&XZ zA_>t;!zy^?84)>{3p}s*BlH8=;@MxbHM4pGXK2H4;q=v zI|bULbCOqrj3YU~VtjO0>QS8vaHk}Js9q$YH>t}_`o_S14J`bj_P%u*>xV#YypMLb ze~oAmsUY-QRe)h(`Iss>24Qj^!MS`_v?nI-oF=ubtW3j+V~(>()MfmSwx9`=~2Jgr=0qf4$0Xeyeo{(zjAJzZI36QVhRe@0QX0S!a+jamJ-XW^5fq zsrs1JT}|ScTSjwa$P2G3{N6Fj{oM?hA*_$M2YdzUkPwqtt{dR#B}H+#i~^3 z=Z)+p!+wZbP1{L{Pbx_3T6>@Jy#uv%Yzo3;qS^b2=M{Bm9;WAW z26$7nr;{$nd+k>UU@){hM^VCMpuWA(Fe;)}K7nYs=RkRCD@sE-e}!?z!OWYM zbN(mwpn{otYB0pUgC)i_{=>qe8z2%XeBr!{P}nT?pLu z{i`4mrug8Fd8ok6=?D-g%;wDtt(iipX^C{b4V&Va8dVBq6iE8*SSr`7?HH9q z?GUx#44DDlJQV2jF>vTENa|L{b^yxi4Gq1O(3drx2SqT~D4#?pNr4xF%s^ z9>WC)0;^SEM|P9myZd3Ks8UCM!+#r4xv+4~eV_yP%aqjIpz7SsDx(~h(HIdT-*p9R z0U}nTM~6Wfe>GMa`~jw;Jz$Kh0rb}(qwJ2;S`WWc6&`R$i>35={m$98gy<2R%cycE zN3pHpY;11rZ}RAmdCFkt6j5))-o#+Tb81&fn}TAQrain+K>!0ksiP*A#g{9P*h6$N zzeIW0x~x(K2r!#im}+gEmfCQD_C~ePi}%|x1DS3SF|n>9O{pByPjL0(yMces1s$@v zarcVVD-vK##C#)?#E|xr`IPD!{T*%sx%!s1e$RyPi!yJuW7~u2MY4PYskw;x9ks%K zhzru{AFW8|G5iNwx0~yTJ4McDU9|2~uFKL~Dn~5o3kj`?v|Fu;!5$i?d3}APMGsj$ zSANLbwKP8@;h*E8B>CyIdq=+Rx+**m#&RypR65glT7}nr{Y2O3;b8F{)-*5ghClt z40@zn6~!&Qd5dBcGL!d{XWC(NY5yPYET5SrX7@}?X_Yfk!`GXv)j8@!(4evWK%aLB+&+sDU7V@C)*|X>TzI3bAHV5zLPdW1p zl;7h$^ihoap^~IYs7@$XryZ9o0bbgPsXPfvIZ!l{0%R4ym-RTX^%Z~iwL{S$N;M)U z*Y3`T{+LLf$;)k6q;3Yyar-br)ZSgy%DFnQZ(sz0`{#z*bBu+sYn(Gw}g9TW)}wOGy34UgIsjX2+v zV8`M;C1Av0Vz;d$))mfs{6?_k4vP)ESB8|n>3vd*hMgbT`eXesELJl@tjq+{*U$&1 zbH*|GqvCziZ;Q~YGlXF_HR2S-Vs(#@Nm8xi;59Q9Q@yr(7&QiDhe( zztv*PW164y*x#JEviVicd#NMxUI}EU-Ju5sdSSy_iI3HoI%uC{k#j24+&Bb|X3y(} z7Mc6HuFWP1b%Zmr(A{~}NWFZGupP7inM65%8bM=W04s>TIlCkYy53HD_Q$3oBfU|( z$tQA{ztR1LbAfkl_9yPyoMf@chW$&%Z+jq`)Ft-=-(k>K^QPXjS$=T0cqW;)vY_(U!(}U%+8qr42w(;c zYpxE&Ku#B_q6mD0zmV~hm@0q|zU%5tan@dOR(WXkK<9#a>wYTBMIxi-hx+bjn6BtC zYri#mN)eXSsYqwKK?#@GC@2pl0{6e##;|_Iw?{=lHY$bD)**8zhv-`SOsG`uxJOM1 zqH=6-z^TGcg!Q(9xinuM_R@}=WF!wpKfEJKQ6i8&F>BWr3&SA8K^FEgiq0Yx1D_c} zm{g@DJ}P#PthtsUL$gXVv3hg5%Z0f!Q@TJ7*4q8X8=5C<3=wP=iu~hIGJ-s75`tZ7 zNi630E3tej)ZkucaAj;L!~4Ca({zuiO3pIN**YPFe|Gog7yqxdbJ=R6Ah(4pW4O>K zZUVx48Y!Dyss1IVK)9vmM^v&;_TF7dU_A4|+e*xJYl}(6v~-r)(tk2kT31@m5?tfa zCcWU-_-ZrDIVWg!i9{lm*?c>qt*iexj`(!#cC?2`jt7^%mJ6)$6l~`hWyNjr-RS*0 z2|B|gM_Tt?I4E;h@Or{UB1Ble!+!o`w8=7=Zt%{BsC~Cf0xr5N%rbNx48<3%RA+Lj z0jwlKG$7j}@FuqTVD_G#P(5TBt+mr$+UkJo_z-=WUeeaaF}Y6)UDPagw-`2{|EEWM z(n|GSO)TdV$XE|}#f?1&$LPLS(GkVg#7Cn5c@R+O6u?^c!z!aA%eG~M6}<+(2nd;z zfckVac->ijQm-}04=j2Xsl3G`mPDx9H3-TH0}AgcdzHbp1|E2|5}I z!(Ijg_JDPyD9(loBv&pjS}(idt9MGltT6a{eHr^gfeHJ#k4G;VoH9K5`F^^#f8(rVeHz;s*Dp2Q zqw;%2>P#x4?Fj!yoH_XKAxMDhcYTR*Cu%`+;bgegB|ZW|NJ*`FuxzKZv6Sm=jhCKz zX=R;Ufo>D$Y|in3KbZtM$w(kCz^~9Y9_hrtd_YOM$%u1abPW6izSF_V-)tI zeQvMDR%p4`XC(5P-i&FVO7X_yjF<%=QOHXy938qMx*MnmxbNBKT*o_^unWg&YSFcW zc_j`jS17Dm4HNa9GKp8W1=sRK8GzOxwh!FWj(TbbZ^HSH^w*Yeb`L0-u7nbb+}bs} zh_I-GcyiC*zh(fESAqlXI-3ZqAWxvvaa#GYH}uv$NUzno5MG>Cebg@<$;hU7dcSz7 z2$`s+c+jNGv_J5r!1p4UuQm(ERL-6ibcl#vy5FA1}o{2 zC{=GJs)aIs;}-0m7Hp72D1}m9onhYXh0Dv08C6=E7Y~Zd;M|z0T(K_yuKhQF<#E?T zSnJ9X9Kb9H$#|Sbf5Rc!M zsM=7Z!MhUs+h>xt)v;VoL7!@jgdh*%wP?6~h9)2}>?E+<4N<@u*zjZ4-IR2vpZf0O zsZ4_)5ljDBkyjWWz%ghw@yWdx4G2o^PkX{Lf93QbpGmtmFdb{QK*Q9_z#AX+jzyjT z0ilWTa^3h5D0KyTWFrsu_3||INxY3)O(w#i)?dBAeFsTBI^0ot=MLz$`ZQIh+Vzlb zlcWcIxmNpNZ*alck=D|K(3G!;lQt{bQjurA}?>T>ZO5? z{z4|j@!$cf-YhGv(1GUn{)+ynoAT@PV+)OhFp=xSev#usq$4!YgFb00s5tNDGlyKi z%=W7c2D2YgSsI?JHTDc;tr~;3-rvep2`Qqq`-|}P1H@xXDHj?0f%_;%AeN;kYm>=J zf9v;h4vH8lUtfp@!{!x_;`s>ioPKbZjdD95x%y8gL>B03DW3B89WrMkSld^vPyRKM( z*7}e6VyD+GANM<6Lpg3yj&hIlpkaGosbY%(nKG(VYPoHR9|eC^;OxA5qy984P5=tEJ_@bnzfVTK4%JUx(xY-E;7jziGpJKih6-Od6e# z?A1wH0z})yEuOo_QQ910|zM#3o_MwCfsX@7_J`^gBopvugR7>b_c zk(Kt-9|7yTPpvE=q>D2qlcXO3(Eg*32Pq*z9Jlv0q>p(OFpY+Ek-L|$)<-B4zkzoh}K){}yoJ*i4MmJDHb!vy4}FpW3W?iU*lI)2%czIoB_ z%Jyc{xMD`B`A(}b$$%#DN-0K|!UN;kHkErm1+}XwBLze7xYHM4A;zA#6W#EnJ)KYL z?Nf@tUd3I(5Vz5=L!C31kF`GsyvG*4HHP+V{x`{!G0!yqZyE#8(>pxhQz%QNZM>?- zqoBGfpIV#)rn{#I1R=Kpe9&(f6UZKp4~ z-K7+#$Hkx}(rXOxTP%f_uE95mdK;l0a1+4_LF(^(xm%=#ZIwRr=M{iw@^#Go^m_b* zP&du&z;w0AE3FQ_3?tpz?Du=#-D_bFA<0ZEYnDkoOEDZP1G}W4X}k55)TkaM*g*XO zYDta(C@bBGzMr!Dwg<8=u{*x+pnx;yI^7$+$19+iwq_ye%UUTImRa6YCN&O2y|DK2EZ2cm>8kMnFc)Lkk>Sjz{OO3Ey}ZFGZ_l}Wu2A5Q ze|zWshVO?g7f;8+-Ew_CZ$h^uPG(0+(l%?mVOCnx)6e{8YK?5Y6#tvWe za6dd>3nvhaOGioObRN=!yWVI7Jd6}Q_UNILMWt`DMu7a;qc~lKyb=PZ5|2=S$%!84 zh~g|tOqqhF6L;fff_l^u3dOmVKV#BalzDF=bNwcClkFcX6xWa7Q$b9&>c{$aLxEwc za025oXt_l|@pTq^e_vC-r`pk%%vG_X)=?MQ(@k;{`0ZUAQ$0h z#jEnnMWm{y0At+yPZ8+$C=_}AxV7~G?vDZgy6meW-*L2D93O}~Pn%UjH)q^EKJNRx zj7aug4O>9=O0G%mub9TE+%zt#KyhRmWwMrP16^~0|X*3;-T3?Er! z0(42dxyWAvHVzM+7w6p$0v^5AUcBDbIr@k%icl> zPHsuXWIxhrPRo{KvjZ`;wZ;kvPPbLn)YahMSL5E*nAbKc6DoGkTV(LOIJ{G7XI_F;|b z^gZMe>pT2IMHLrxZDK;V;?^Ij#H=kozjKfNMQptWGk9VKX3{01wd0D37z3>%)+_tsOvg?Ph~>%*^u=6vDe~E9Kc?57H?22L$@*A`-P74R z=xa7XsNG_hjj28;I!!U*n0H(4^;CY&o}$)bdhRh*CE67e-|tk zJ~?DBgj^s+%N|*XjH$F2%f~}r<>i_l6>OUhY}SPd5et!r(J?CgB(I3Rj^yCqPZ2Bn z-LiG}v{>MPpd7}1As?Wu#bDJ8(vGi*&7yjvl$yr~xMl>^z%re!m6lm1h8@ts{rvs{ zT7P7EZ(R=^jv*}RSkBabO@zN(-qaf}&Iv+Uz*nwA*8vk7udKee`aXVqVwy+n=OKe} z0!oydQb%7x`@=jmUZUJ=vUN>gTUV{S%*vd*+Cu9voMJALPzNxkOW zu=awfEBMzkmiJiHqcT62R^)|fBdn&hrg?psr>7`RL_nY<;yQ!y;MKzh7SA2Nrw(F~^oNj>w%Hm2JqRkKtKfN`?9ocK4Fi0bIm)f3whsLL4nn&12=GM0&VWUOZpA z1B(b-D=$$3<487Uco!etgm0e|b&QwsziucYmiVW}K+Zd!&EnD_7TC%1=*NhlL{D-E zL;3Fh_1$=u{Ur~pc$ou}%;|f>d(hfuo5wQ`c3pLCteRU}TZvs#+FtbCFTVcYR89ME zM*vq|G0Q|W2Rf?vkAJ-6zIpz)C*rC~IIT`BLxB=_bVrsQh+SXc7<}_ruVZEZ(wlCn zxbxXCuMP(#pqyKh$;7<`D}faWMkI9oYZ~o#fkEV)L_%#e|Jii;@dscf{?)j@r6Z-j z#sBcDeCRhs<95fD+CLYKPLW|)$yOf}pJ{(Q8@7|n5QvgiR*@AG0wrcuGebivZxH)Y z$Kkt-EJ3H3{3I4Op!8Htdnd3d8z=FP@p-b7D%!K}G&7PD0^cR8e8Crrz{|CmG*F-ESYfD|Ua$Tm0`y@^jQib(t-oI| zq41J@d-bsirV|%IWSP|e$JU$2L*4yvz*$0(A%$+saH~*uWj8~TN~kDg8Cg>HCHpKU zX)4Q9gtA6a5!v@G%g8p$Zp2szV=QAEvw23}?)&~d&+GZiKj!l}pL5Q8J=b*|^y-=x zK8)EJrG}~+T5p!}@m&3{YZ>+^D8obM}}-KcIcJgn$DRT`}`N+or`-K zr&h2|2GcFcUcXJHgEx^ztpPg5qY2!Bqy_k>E>J1{irdF_>_f02o&W+@51+uX4 zF~Rc>=PAVwLs~4piqU7vKZ%1F+c4L4{^98B8&am`>b~20P zh}94Ei&`D=9wuK>+C;Ax%)o z+vKmgAMXnEJE_u{)h1F&C_YJ*k#$3&<0B` z4*#c=@9s>25h;9YD%-ek)f2(x8S8MyJHR}Wx^&@~gJjtjAVxD(iD7+;Kk+q#t*BybKPfK0!NlNP|3#%WzzlT$xE zZeg!3mN;j0ddVgk&SaH=NE?D!Md_Cj$HEv=Y9+&F=!w;dWl}=+#Q$h=Us*J{-wr^M zoqZi-Iw6&0#g{Ek-&TwQAg-or&XV?C)qqKak?wrVx-1vCagYt zh}pc;d?HLFO##0VrBGp`*CA`63%iS3IP1N>cT<;=(ID3!bV;AG%p)#W62;%#V2m$X z+;gYBPfh1u4i9K{&Rp9_d&M-#bm$(HmCP0ev`6EG5`P_wjjL790fj9G+;5@U#Cx9w zY&#vP;7kb}adBsJqfm2wDhMM#GfFC8&j;WbxGVV6jNWO3UZa$vj#4~YSLH{4Mxu7h z-4h<2bvCD0^$ap2&r*bDUG#Y9hA@1LMvu|(*4fVVtB%l;N%HXS;?^^6*ZD&;#u@36 zj+iozxvvuU3;QKgggD*#4XT+B04LhNKbG+Rrk+VKPSk`v4B-?n^*%3w_MXGuGPhq) z4g*j*lxLhybk;{l@C{ez=jVgaT7*L?Fp?*Ph&)oLn?@Tg+@`@Aj~Afs46E!W{kS;p;j~0NE(%w4~#q%y| z6tcDTBwgf4k_ZWPtw08Q;R&~`usRo87z;uUj1db}xMXWzf|unn%=Qi)@q4%064}%2 zz5@jCE0=SOZIIrvJ+Ggvh-_cge(L~O>M+@r)bb)pceQ8*Rqs_q_zb`oLd0cMTw_B; zoiw=sZhFTIPKdEb*=DL~WJ`EkVyfmiGnTtmzP9?Pb;fJ!P}JNlf$uE?s(Wgch-cvo zzO#$KAbhvDbXMz*lHf^qxXS5R4j0Z#3lXBCB?bB)>$E#}Exw}DlQ`4)+K)n~vy^a) zvD=si8<5Ch;rB2)cLe{#bmdqPwmTvB@6jqaKA4Nmh6TkpX;wujW@kKxy&A5)pJyG5 zm~~OEl$bjM;SoQKgcgSR5H_%Z>Xlv9J#}}F7~r4L_;$G1%_b@Bn$)zly5Z9r^UH3u zTX1pYQ<+nuuoU*|^)|K-e)f5PBc5I;UlH<)9f8%`=ss9>^PfKEb)IX| zPEN|)^judlzU1VZDG;P%JdU;-!UMYeZmHF&L8dK3+#TU#p>H>XfO>*>CEfdpbYD*9%| zIE?wz!oJ=!Z<0~X6u0Xnm$NCK-lYl?_g9XCt@k`uvlqo{?pt7i_XQ^83@Fq-6Oa$MKSfTnvPPMF`H`&Rn&LW03a~mkht)oeS%<`;Fvp!RP!X>PAV~mlusn+OixK)}NfSJ6X(AJ$29oo_x^F&JR%`NoRhchh-F>qkY zZdqoVtf7Ihrb57F&Sy3(A@;9&Azy7i@N1LBm7KGbY-9j53g)i9-Ydoc;uGC)Nsl>Q z3daFH!QAXGPe;}1VnuoR*~K^yywf|W61-3x7*#xL0Kmng*sR;5o49m4vh=K~y3jhf z!OUgfkd@fIrb$burQ5%aQ6E?9f59%lpEhL~k$| zpE`S1w(-8S-!)FXNxi-KvCgdzBm8hEIYXb|8;z4W@eLQHX*EOo}%rdg>n& zkGZYQ;lo?EzPD^08~QZdP92go|3a8k_4DtpLaW?9xr(JprNIV5yxRhjZry|Ybo?{ZnvZb6NUOG{KU zWLJ<9c`n+6dL#AXa!8K?f7=t5AKPZC*1(k;mYSR2VG`ep8oF`jjz7WNh0begXX!ntm%evE!-Ot z3RQbyn9=kk=%sT))cR8tn;k}dNlJ5=2@{QurCDVrzI=p6o(fBB21$0jYz<8C{(4VA zoV#&CO0>Aq| zZa=5Fa^v14bn`c0f;Mdv{wLAikziY$yh-h1jI}T=Co^O*tE;t<8n+uKD}KR~(N9nD z5$~UKJkhwZO0E{BxM<>?{Hzw*294PiUd2R*$^bob_s-;H0BRK0zQhExpb&R*m4;+; z(xBe96^>`XV<&y<>9h+Zk;DcZVmB!e@g=#)e%`L}+2=gK&CQRc@Pzch{7T5QCIQiU zz?N`j-emmiabgasdV5p0v#`rO42Rt&&~4mliA&4YoATQa4x{Akc3Fu;s5nxqXc~G` z&C#So7yG``Hl93m{8y|&dk+AHk8o;JJ?a~JLv#L9{zEO!R=R+wr|GJK?offUv+h8| z$H2=Tw2?X%)=~PMqTN5!a2P3_HGJFkoi!K3*~_P3)t6KP7mLq$;JmUOF~A-A@SwdC!l%VRxOZ91){U&frvA`N~DXW|MCNSIC zqj3RkvW#L_DGiZc4fl=*b%uNUcwngod2kkyRY?F}7fZMY0?P-=$qWuFWD;MWt~eJ(sJXP%uwL%vb*&)Nx(A)xdAEyd9k19srXzouWpAtFU1tWW3 zyPzrT1eVoh)B$XoYIn}(KxgwU%LJ+bJgwFE>c&Dys_S%}p+@qQu~TjoHpT$@1@R#8izJll zf<1hxnsBHmHa2OaYws=lRn%3bbM{X6hYuP$-tVwh8tzgKx99wOCH~MkvSwJ;gpy9G z7pN>;<(LVTKWX{_s8cRKHuQV)=Tu^8hTB#mSW{;h;Ggn24_mu!r+WhE{Q$kHEn}P1 zyXYQ~^qO_^`2Jc7{#i@b&Z*t398=<4Im|}*COvOh7Ome^>|31vi7FS-4=qFJb1}2t zYw!7t-CO(@>O_c+L^gbC0;*OAgI8~`t}Sa_94qzU_)4aoD}Sp~ySeLp67rTLm;5Psplge8GlPiI zx;EJFPSd{y9t@caNUzB1n3X_Orx$>&EA+R1b6>}W+0zm-k}DQ>eXH-Y{I0kp+p2PJ zb8SY*dc(tC?C{?i;sDX80Ic_yTk-#vg2e<9;pD>`KVQ{e6L|!;%4-6a8+G{Z^2Nk$ zOCY>4kYVpZ`s(v9pB2Yeb<$rchr}6|?|l{YQ;K{P6Gnb%F?te=b=mEl3-1aHcvF-f z_>M?*cUa+t&9f@-Fxy~U$#%tSdFVLqN1~FmAa81Zu~jgG7xZzTQ*E~PzU%|&&4+$%OiSvX58XVDUfLRR-}*FZn_&I zt+zwp$Z11{M){ztqVBQc)?uWsiIb`_2H#(Eu)aj=OPa)2r45#k8$aE!MYu4$g{>JE z`HKHNw2Drar};{qYOM$zNE;LW^y)0wf$n&dIU?0Jy} zX=icN(g)_=o_Vt@V{zJ&L=5ksM_BST^-FdH_kRYZ5@*2ot&J{4>a7n>1`fXKI8qYh zC-t(ieZwRIH5`Fyf}F$kTx`EzahdgtG$nTbyK%{hd6EsUQ+ZXsTlY$0*S~;8SSCRk znqz?>LgievyY9qqsan))ykBaq>5$3vo~51&srv-OHHVG`q%WXYThACbXd~6x-a92E81%dnXqo=bMN`0v+fe><#E@BM?cqG zz>f>qXlBk+UlF>~?AKXnAN)O@(7hkecVxRzxj&deB#Q32I=7-fzGXuC>(O-2`WUxI zh!u*Mj*r%L(Ig}oWF=dud7RQRFUr-;%W>rR{$A-fl2R(j2_eoG0|+=hKTr3<^pSb( z`L@5QlC-}zZroF9)vd*+c zHj*%(PX56mNuFU>?UUsqKgr5$2Af_rlx4L$4_F7&&vR+s=NsU7@VJN^-LxnpATk`T ztBEEEGsjZ;`&VE&tP^W4erG}28DBAIVjOk0@<)#ji+|jE2&tD@u@3X;_0F+V+uyYM z?EdhH`MR7h#EO|!p-jrfyl}mcqB2%O@()iyMNnl#bC@=mj#%N_v<1jiIa7fEtq}ucSP97Z<+HT#k0C}8C=$J9F)(# z1Qs*q`d%m=0I$&R7@B0gOv|4$Z7tB}HjCN(X8K>Ry8}cXrvKVgEtF)L-9F}YT$VGy z&j;583}^vBBirW!vHBL`eg?UN<#9;;M)^n;xq;tLJH_dv<9k*m^lFZ6!*4U+pFNau z7CQpfR$B1yNb@2i{Uh&UGK**xmop)Anw(6(ARgu}zNkt5VK#Js^dy0*#kwG-@9>=~ z|NiQ?%nu`cms&;54;{QHn` zZFa65zVYfTle8`&bNI8ITRc_f*O$n^ z42g!B)gKfIqZeZJfW}&AI7&<;iyxH>vXTy0jm8SV%a-mGZT>F-%+*VQQm&ny7ekEP4MGx zz{roYdVm;$QDr-$g9Y{(GQ$>mua))WWx}b`t9#5zSWdLY<(*5({s8iU%7P%wkU?>C(`Aw6j%RcY>mEV)7#mBxbiP&Avdji~%YR3%ItECoVBHy${s#OVX zjMfJQ*#@VQRYgvtDqsr@zEN0JH#JZ-bdnlzO<{O+LIk5HNgVrFvu`xYoZIzE;`zy# zhKcdAM$GoAO;zux{tk2ep&r4n+Lw-NdQcdL)4_}^V$cx=zWF`0;0!Cozbol2(6KYx zMPRN2QOa9lAv?uHbUOU-)$MyyLZhD}(=R*zapbVT{SO3eR^+=O!)mPFf_+t@2T$aIu+T=bT1 z%&0RoIbgM!D@mLu6J3V~dqxw$bD2T7zKQjr-Lz$w`PDlOS0;nKJ(ryc#nuEk61t3;@RMmuDK|87(IIgG(>tk{N$lELw+x~Tu?-= zb}1ugX z4-RmeixUg018sbkcG5DuEq=(SzBF;H?Q>v9ESZ(p@+wn>w!Zp`{j@<#qC6W|w|0?4 zfXp?Na#o;54t(xECxKUCeOu!m4N+MepgyG0RLot7+8HyW=05OX^RrB~1uOqm@j#vE zn!59@?g&3>A6%Z)wvoI(zfW zz3aYX*lK3as4)|}N5?9I$S=_kpQj=ate1 z=!1gHPF%cIz1c(ST`y&tvu*9q0&a*c2VyM)O8y@IGRU@QKSTZ#N&G@Nl^~&0>WWJt zl%`2DhjhEkAdxO7jt5pjePU@CoLf?Vh7WBGmmGcemeQN3GR z8e@eTET7_Z9GTjSv22_u*xp{hxdNUGshg1y0n$b=I^~jAA%`x#T-JmFD4hwi#??sm zwK5JsI*ZJsgS(EqnN(7@kh7)vt~!(GwaB5SY7v&6zOW~~_OAZwf8%83M#-5Ekd4yI zm7zZ>A56le{C=@J(^mAA-iVw*n;vr);f2>DN%JoSPH};V3q0D5J>r;O?0y z%+wv5a#y?jagu4!gcthOmHkBi3_E~9O`uu4kw5?$3nsed6A{Q`$3B&UEN^U6z3QRt zh@obguhFq}3PlqYR^Xia)UjCaRTopp`w<+*d^3mq-{}1GIFd5d>3 zbGLtIt$!SQuLx3-LR{HcJh>Mx`eIe#gwEWB8ECCd2JkPo-a}}wh?V26A!)qchB`#C<3ni_V_;`D}TLp5*~6qdr$FRq@!GCwOHM`!;x z&#WAfo6}~dtO+=|KKwT##^ScuuY6pJnws2-}+L^lt2fe4Q8jcipz}cni5bp z{pZ(BGd#-?jX!@@PgE{fGBG8{#(g=B`qWN?p0oeIZ?SJs;bJE7X07Le+O1)$Mke`y zf1dR_8+GT@I9O;;_@&9WT*-)W<3RMKl|T!N0{$_reGA)RL+(?BAT_P#jSai2pv@xc zzbPCmS~Nu&G(`^EyB~SjGnjdH5{_%MaTKBG4l|P`|L?1opEu3%D%bU0fOnB#UD5qc z9=491%VU?n|C=lS{%>&r8;4_{VpT?JesbgY_<%P)o?zmyvVz76U>A#*BVY4jUq+GBslEI4dDsU)>Ir4g%^p!2TpEEIjipHuIhLgV2GJxhrNYS!9{_|nR)_A+x#7`mmX4RxAN5;;T)}~1SMx%D zzx*QSG>6NqHM30M>CWlGEu7=3#AN@HS(qh{I1s62p;2Ce)f+W&PXOYEiab-BCNZGx z;@6O^Uqe3M|4YLSr2QZQRnRH*nf!*C7E5TPv+D6K%tG0=uZNwk(gFF@9#*pea>BvTopCn@^Sc;2wi89lrA+9ZE}k(hQ8y@p%PQGdzBXx zyH!JpW30?gRX{oQzm@Rw;VENr8J}dXAE`aP@R(O#BsvK&YUt$&3BODm3Ey1!@%+2X zrppH;_wA0E+mwlwLthWA>VYbWzZNSh4plDide2nlBSs-zm843N~LQFVqR6<9)SUF+IT& zWVz{ecKAka13SX9=q$oRrD10-O&*w8b{w3CA2u-f` z`7ACHUkt>p1w%r?7NZhl6w7Ps=IbA1TOXVtebX3BYe;K!Dd?J(Fx0QEHywt$N zIdU39q0(C$$2zR@#>rP-aN=jfYRd=AvWyDcIZI_#4M}Q&&ASKYJa4nw!yi4xZqDU& z+e=FDKh!Hx*g8(>`e;@CPX)r7e4*cyzewJrZRX)vY7%XhG?4^emBk9KoFn9=E9wBI zy+g(MTP!i1Y(?VVr+{5cZhy@MIK0ji6tMP~(Yj_TvLnEAu{&>ByOA8~rPKI&(iQQ! zClF5>Q(o74-LTkrj+We&H@$Nj%u)sHVi@u}&b!y!XOw2nX^alWv+`dB$Q(l;^dp6^ zkpQ@Uh5RA=Z5R0iacOw)-KwZTAiOZm`_660MvWVr&b77~;T(v4(ufGfb-#V_f6TFP ze<5ZOtcs2up}09bogbqq&Q2=G{Ar zW!Z;^NliXH2_ZLUR`t9^yl{x6O<3V=qD#0$${f&?T}DB>QWw(b;$U2$c$Q>G_j+jq zNiLJ9`I@l#)ehNcwr~sfUvx-Q|Gf(D7**UwRHZhn*ceTZIptHQ6ve7d5P=g+sGf=-QuQ50Y>g$FdI%=WyWRfMpq22ctA?jzzJ0b4U3W z*m7&uJ*?~IoTBMqCJUuLAkVarpqhb6If*r940OrZ*b|Qs>$l$dnY*c-f#I7h3V&)} z{y$I?mjBUm=d5sObbzzU+WS`y%Ef%Fdr<=CKSum8I)4n@***FixHaci(@U_=D}>5% zPnsG%hq}cm2|DSCC#0aOo-N+Y4?taNQcWop!$@_$4XK;oT;-jFkF8e2d%k=BOf9YC zovip_JDd@4eWTOegP{Z;|FC=-v6u-P$5@a|OXD28JdK_!ZhaVKRwuatUBDzXqbH!+ zQTx-@%`Np?j_{;PgsFiMv(PgQT@j*bwE1Z<%rH>ZZz4)00?dr6Q=cdc4CtL3+ zeS$p-$D_lDt3NT855yEiO&cxcoM$K^!5H8dJ$`@qsE(QiXx9~tmPoxkqxDH9$UblR zOd#+hqqH#)Hg?OW*L)rm>@u-xuYI#);N7vLPwI^YVa3v zxcnWnVPJcEu<>lYd}G^{=f0K!wUoLqaIe60hIX|#&eol#L>$_RY3Pxl7BpxX%*k_< zgUH)GCNv^>$gl@@PpND2wX;d=bbO-&DG~bLwmin37vH2otZrBdf5-S-6!U)MQ{91n z)>kf7bv!bM9sc5&sELq!i)-@P4lGm*dZ)U|QBkMOKz$S8Zcm}-J8pe87GR&)2P}e^ zomYT|L6w6Rem#L^1z(~->#ahJH4$M*_~Hi;==!F9qi@%$r6-0MHPW+NnLnPE-VG`1 z3X-)N%Xla~?Al?Mn}N`eF7mQ*yVzyaBfnSf`*R_GM>wqWS~|uVr4Z2hxmGzYxbz57 zP2UPvU2pVyOLHvso7YvPrSV`m|FGpoptXH2)h#otmxC->%mNoY3sPNf7H|ctu4Y?VT;|`5=1tBGOzY4F^?k4 z2hOVT-b8=w7c=E8`RJ=#d!1yu<<|KmsPo+1Zx=Xm_Q2+Bx)7w7P|qNMq#3&-88L zQ8UN8$a=|&7UxU79g<4xy)5BLCcQcjhHkZM%SWT@vkyn_xy# zg(3v%(6B9ylR14sNJe8mihn>aZs$q6aXPP>w@t6PM_{33nA`ic`Pn%W+gX>JT#{j3 z^NQHTi%eK=40rQ;mQse9{>N4$sxN#aH71j}nJ3an9V}9Egs!*oBU8S#FhDLr{S9VQ zr*lW{WxT-L`qXj z-w64Puw>W>>82h9hS{He;uTf!!Mh;#u#kUcu(3qk5!YW3qqr{Sk(!>I03eJ|T% z`yz?Oimfo|sw);W&3D_sDgw2~DwN18mhjIAJ$gyRGMc%7re;$CduxD*U6DpgTib80 z>>dTZw*Y9=Q^?0w`P(#Di2ibekf9xvn{bvAF=E{vvF$Fh&!>&RPwx|s+brPZgqS^Q z(cY4w0fhDeXuGFGtFXWYGTqa1y?liVBkZvUCJge%-tc`{?~5tEgen^gC&UNl4x^is zq7ywlcBr>?JHJdfacs+te7}0PAZ6M(y=8tKP|zAv0t#$kE@rYYm$wsSDJC~B=|_1b z9y%IecJnm%CO#1TwupfJiFFeTH1 ztUJW4J_Y3hB-j`M1~Z?&Bkpmr4JbH{r^7*KS%{dy^%cZr#|8DbZU{ zxfZ4Zo|TuSfQ$o&P8$N0kGig)!m>n1G(%z_thh>^sf0 zwc0kCJIyV=+k^;xb`VK>IbY{C7PFgLhWK1#$(Xsj3t-{_N)u#O*kMP+3IXc(r!Rbc zzdtPk-rL1StfAq^FO&=qFq)Li$ov+FtN3xyoqs+lOfKk0MVMT3LS;S4TZHres99V5 zdjzc#QA-)c!iS<*LKCS=-o*Y--+OkInSsoCmG12E-e0c=*1A7QW23W5HOr%}C)c@l zbD0|PwoJY(A3+V1rdk#--^31b3(e5~iXwVr@R3m$(!_G`k6bS)DRZJunqW!-I~jn=3jcMAj}VEtJV9gLuA`N`8*5NmpeS zgUE@f-a(TF-u92lVHJwT+tMeg#Q3z|H+by39a?_F+6lYhmx5M*AE0FJ?PluZi7gE2 zHUG3${baz8_IKX+nY7GpmsE{6rkpD&kZwi(M_<=?oVDDu&Bz@BUsXD$pswzxb@zB~ ztALL@&B|%SQG%|j6|ep%GGlzd%evC}mqGsGo}Ee@;z+8oRpGD@-n+f-y}s;^;rIc6ftDL@Hgq!x-D2!d7G8KE zj;-#TD|A?3VHgSF?ou};C}k+|T1Ery*Qz7EAI#`)LnG)jg)MdOkIXq|x=aLHAfF#( znn@I|&IW=9GM9LRh)X%1%7e|){F2|s4|YVQhT(#ml}3sc-8L;wEF>0nVh7#y zmpvjR;sQphR-ZKq8OjDveNE9=FmXDhAZqfcR_`P$8<|`MG&5Q4$mNh`Gu?PorB!EQ zh3mS1uLVtYjyJF=i_P$`-|2-W`YWHq^t;26cln;HOj0ty!R{p+=mUq5ysX3IR7+60 zjxWE(I)t!y)h|xfsH#87GcmEqG<|eWz(>Z6vrkx~-SfGp1PRu<#5 z$%b9VW;e!YTvC2pJaqU-u+DaFMAdyig(I#%sE2n(4$=g1QykHaOk!h0D0MMUd4joJ zxkI~LAd8mVIo1m))U9im3}MJCgE|5yr_u=HDD1c)s`^7(`1SS!IQy0qnOOY>e~bRr zj~M!t5!x3B2EbIMqYA4of3gPB zt1Ti)R1AS@Qhy=hDKA$Vn4cYnqwgfE!6Gy+!}ijQIV>T##+}Rw|T;1V6Sn_;lZv@(SD=R7pD}!fIwR-y2-&e{vDv)6g{d*4%WFTJH6q23E_pca z+B^~29r#swjK&hn1U|!0C0m;uS|<02L`kn3zCk$!C$8&Ax+t&w$PG1HFG!d#ev%o6 z8~HKe{nHF?zH62hZ*Ug*MD#MsUBH6AXj=AiBVG^+y_=yrnG&&0harpJ z&Oxyitui}#Glo$|63nTSQ-Bf&$uXwjUouX4U!<;@Df8dVKc6T}`gskFad50#`d$&S zalXao=m9UI{y9f4%HG@IB3zpE56Ph$4wL~?BMG%H&L>R)HIBTugB+H)Un+42%H52J zxUwu98f&)Sgk+u98sjbM7vy)2um{-NRbfOa>H^1uzGACa&|^|9u;Yf+bMUM598D7z&uACk;RrSg zSk3%qEP+eS>3CUY0h)f05zer@^h?et{Yt|e?tPhl$np$E3HGdtmEgg~dUeJU(7t3Z z<(qSf#dW-MMpxMp*H@!z7n1)~D*V&b6g$YYnZ+DD6ZzFZMy|Q=q~j=ANPiReA_|vYEA(!TBY&7?aQO8BZ z+AV|(c>aM<-Jwfs24;T8#}Cm3$0OadE<|(#2v4_*qa3`}zslS)(Ux;DYI-z$?8I4i z(O$#3uOYoxVgnIs;P!T&IO)ltzfRcQIg!dBNk)bZVau1&wZT?p2KT$G9wNEIg!#SXHg2U zIBq?_qmQhEuN~o{2N9$tu6FQ(PeSf&cF{b66*av~^jY!r`Hy42+E6ft2>0f93|WbU z{qBJcXCwlG3TCCnHkN!$S@;=G!R1t)alsD$BTFxL`cT?BbGkJrmjW1R5_2DJSm^!? z(&+ur>;HI6S$IlMYQw2VR4oHO1!8kds7Y*o8>#4miPA2bscwm)K9!mKG`pKf%=YoJ zthP~JE&M1t24Wt4FSYCE;-CjUx0odMRwH_hq=_Eb}5WvU@H0s}c5m-FtoEA7`8|JHOx(tTO7cS0UZ< zraRK^I4Z&d4qCU9D!uu{N(alWW$g@J6z7a%st46CDL0IO1WsV8%(C$&8{hmT9_-wM zK5f@+Fje6?IQ7!;S^5bZ6UNyIjp@+Kp9t`&{DxWWy}YA@kGf1}RuAAP>7D7DunRB5 zuIhGw5~XxCAoZ(+cr@2ADBA^BTG`zLznXxWM2%-))TAfFAJT8dB2m zIvM`a9kJlD;=X*M*}702I)X1hJ(K{+D=GkuX6TS#C*1KJWqwo!dN|BV=oU@BTbk>pY>bZAS|70&Bv}$FC&SZhBmuZ7K8xa>6cHInkJL+BOtk{Pr(UfF zU$-kh7}WeAGyCeY>1?K_V_MdBGKh@t;ZO#Ii|-zv{Ae<9u_9dRJ zr39+nOJp6oSLc~Yb}(3wuC#_s-L1N;J=Gw(n9FzIQgU*GoUf$LWrasjZ}Df@@-J~t zlJzyD>E+s-J5J9JNKyhfi^Vw*v4XlfnO;R~5nr5>fohV@`u zEzlqBR`{a)GvX2;=L!F;XQ$@7^tL!@6MM{^omC30ak-v1;nWrXk8ie?GgiV5ye+RE zzV_7Tii-1rgcmQ~Y!TINSZxnux zT~R=<`R(}aJdN#M6MFN#JSxj^-cr9^4y@p(=oBA-f$-C>@U|l8qHHIp++Aljly=i( z`i79;F;zDZ2cm8UD}kUu{>lp5Ed{ia4rj+uc}khn6t<^DO8piT0N6QsYoX}Ni982N zKQM~tz)xA&r)`mkwx?mPc5j6L;`dLAu5hncYc;AQz4z&zDJzov=Dm0^VpNvs0YU7H z8rHig_0L0rz9N#K6@A8MYu0G53Be) z4GEnwnMk!H2T8D3g}Ja@>U$)`rR*Ua+WPld@beGi(sfEtZ2OAW{{CwCA}U&vo0nUd zmy_p{CeKI7C6t2iW>Z)TccSoHWBH9M`S!jy+a`rSHnLb;?r2HevkAf+S;lYs^@lFt1mV^+IXf%)>}4p{p3mVUGllGGzg|5 z2gZW*lME~aB|38k;{893WdR>=p3>bMw-q_jF$17?hiuBA4CSG8vRhrd6m?~~gt5*p zf!p|eL|8&XB6;_yIMr}(^FbYLm9DT5nie!fI48bkJbYqcB3tBbM8>iD=bz=Ow%$7~ z$yfM6tC!o%?1AIg&^EP z34ridUyt3iMH~u*{Spr9L{88Sjj>M#4FtSyd~mo( zBhygC_^Sv?`IzICp*ADCF$&UUmeewti_ngR{+}i z?zNZ&A$nPlzku7=MTgJj%A)%-*c`*bv0C`0r4(ur)^sN6WZAYnd=ojKA>G7h1%3rcgkQ{cB4) zS8Ny5yn9;`g5KA4J+2oY`A#=CI5vrwCCEu_9A>jEoEuPYDDGl%cvOZivlm$~1fzga z3khR@Q48&&wB@|Q@VR%&&w}5a-5AGIAvJ+yw_RLEzt5y<8H|dAms*t7$3QZ-M$dx! zkvRp*+L{X{^gFVs^NA%r%E@`(K zdFmRxDlxs=1l*PCDOnO5V9VZqbTPsMGQ4eQ()XxMlGm_vcF|NAuAspqhs=X4aI;%A z^aCad2Sv6vQ<>K2zk(OfWBqM2SW+abp9_cLN|4gQG(o3R*L$7CQbk)hP1j`&!R_bS z_^@nr)6Re`2{s|&1y0STsSxZTtjug5I8onXGY(YFxBP96n)*tUGDwZnR`g1ZZcUNy zM5*#0F5&$7l{aJB?(nJQ+ZVh}SyUZ)l=A6b`3;}Ex8$e3wNmIN2(sC2k8q~R$O zdYcYxi8NPG)5}8=I46N{ev-a;XP|~E zou}x%S2R;b5zNcuj92ZT?CqEIN6Sw4wbNxFe=7$bVe=2=3$4=qlAG79MW8xmecOl+ z>^YfPGg}=~Jt2Yp`JLOK8)2;FO~7hN1|0;c3gcPwA> z?KqirW1)%4<0c^T zrGgOkEjoBx`W<(TDzMmyVhW+&tacq z*LR~O5QP{V?|lj7MayPJ4_STL4TD$PJBw`TjCLho_5m&?e(U3$t?&@Z<~HjBsMrHk z1RaAow}07J=hhX8Pww4)AT@2Uw(`=sB7N6~66LY)=2!u0z*6Yf|0_VH>NPQrEiN_W z@8mZq9P1zB;^Ox`5O@MP@ljrDrfPQ{pS-{V>%MllOxNi-;w++HclvmRS1tZ~pn4`i z#A7_IL}fNN0WYQbdHJG?>Lmj=ug_aq1r9;KY({bKSNqEW5aJW8trK)T2BN@g6wLM) zrG-FA0$ily8X0!$K|NT?J4F%PW-{!scdzA>Bo6wEa|7|xB^pCg4o+`nApml}rX_eAN1PZLasrVHbdYFFy7+c4omsLTYSsef4*EXO2*E zfY*=X)D)smWV}4+O+V66hRGBSIjEUa*IBvYyngGARQgF?>p;ne^r*?*Qs{t8!+eBj zv+lf%WRHIQ&W;32Gf@p)=8~3lbrSr*e&io504bRo?n$BL8P(~Co#~hb=_C`_V$4qu zy0${?(I2S>K52Gk4)M2FqmC|m20gnS+%Qu#xTK@v(imCUsP+GF^)CKQ|Kb0?!-T}h zJBJ+RRO+1&a-5B%b#&;2atul3oWt16$e|pjD9Je$rN|+N95y+hiJT8(nDaJsnAzt0 zdVg-W-|u_)7k0b$d|lV$dR+Gh7+~9$q$1FQG34MCQ&n883r$=n!LC(3AYP|GLmz`0 zN(+57%lldj{HtFwGq%EvD=MJH-v0m1SjD$$JrVGrRVk4V<}@Uj(_Oulg!4vtdW~ zg^kB{#Ss%RzYd4va(QPGjEMe&vni>4Fli1JlK^a~1&51WK2?LV1&RT@IXw4T9zEVXLU+ev4h zK^*XW61#dPwJlUKZfNje4W=T+b5XwWhzRe=&C@pS zE5<2l!O*1)e@a_@Pcb$iO77C0pVP9oTeiyxkW+H$z_++Y``@l;{waNMx{zlqk&k?a z{O`JzWhW|AnX^QjqJ&r3KPf{;yI3ALgUQA_vzTyz(`>MA|55i@dgbab+rd-X^d7n- zyV3MO>|4H1>X##3?Uy7%HA@z9HQCLiQTu`=jo#Dy)`i{^kt^R5$K<{2J__yLbvj^< zbg_^5&&xcx_1Ri-4?8y`B+Ka{WrlHwH$OO1dOs~<56|kt+w&1-&$$~AAI;>ed(^R9 z6>#5yDAOjr0gL}VG5z_l2#G%UPvkj$wCP)1t>)W!8$l?d;oLEP>zSVP zvb=>unb8seiS^it2vD)lE8o8%ou@2s4|8X3+u2Bj0Z&xo%75GBqs_Un!4!T~%$Mt! z$58jJjX%bv>(Gf$dO>BjpOXl@=-;G3wI4M|55=u6035O+cUg-2J8DY?7g=iJCUzb2 z+FnJ5;ktWmr(6pqDORUO9KB)Y8y_U+v~t$cQ-O1;ugog6YyU_oHY!&J=4>;VkHB^A zaV44Xl7@Kk@8*v^sN&aQVnbi|qtv@pKRVe$wIl=ph>^fIs)ZW!XuTH3)7g?U6yy>1 z*UsoubSqRRrule@LAyXhK+5E0uB8GAkVkvid9rV{uwc=xy*&42GGUo#kKuyQ=q=W zd*R(K9wG{+Da)r*avN<-R!Y-XU&8;L5BRoF%@L}PwOu|vk=DM*yZ~YL-eQ7ez0Twh zV;fFLwHWg!Yq9%Km-5f0w>(UsigoN<#{;uW*4dp1Pe&eJsL6}Er&Dr*;iz}8w^ z_F;7u8}^E|9vyiG^XJWCj`+t@8D{nT`gG~5Mu&b=lHfcM=ylvHga5bAb{csn$;ow= zbXWm}v#h|+={$QlD#3cKt}D>HaWqG|;#oF|{)8g1@1;)xj9d_OuBd>o4(HI+V)n(-)& zFR8Fabs$GKfQ%GXOU8;C?pamn#fL%Jt;JOeA)B7i%^r)%pfdGp&CrLza*QWlXE4$b z#nsOsP6Oascxw>p-1>n43Aic3@=H87wwpRdLr~++5%vI@K_=1KcoKzQaB^o)a2zp5A$tBSNI>v zaTn?OcJP4LEiC?9Jd=wC!7=Bqp{^5fw5GrW69w|`-G<%z3;f1{c7gs+u_G3K(!(gT zPHO((3}<~tV)QRZ)IhxF|Naa*&p?Ujl-H#h7e%X7|--V|F zC*OqzTy@Z3A0ut|$e#L#dMPu*Peel2AR^}agq4f1m6}fFcl*_dAwc_;vEn%m;u>pg zOgtF9U1ceqRX*+N?)@6J9}{$H_1bnNM4wc`&a4IN8+c&F9zwz%*8&-OmFHk$F2X>xu`Hdt-VW_}cAJ~!7D za$`PnN(ma;S>~s0@7;@ZX*tE?HCsjH4P(r?OfIS=rQJX|>@9@{JkyvS2xeXa(KaN1 z(Isi5#x9SZfiBgafxYrY>KroQnY1YZuscakUe3QU{mX_2Q||D*!zn=T4>!=#VgtHUQrGT+;r7oBHOW0i$y?ZVh1>V~c96Ci{#19nL8goBqZMwih+QlXV2hW?o*2z>?Uc^O_Xn z*5_xbd9EBKDuNK@Y_PqbS-~q8K^}SqYyhT1=<<(jeD$!$J z#mrZ>Y@0r+sic|-uq|?w(_ooaAxj4g$er4F+B`NS|~_P(7fk;Kis zgma=CR-w-nN6N0Kf8*=aoo9}!CG6U7-FNmVzYfy2_y3#!j)A|0P6OPMlOe&zxV5kB ziDBHTybPLSSBa0=O!SnzxAEqR7ZE4Zm#+GhdLCPzam)KheMiivwD6N9LcXq-b6@bu z>$!to+y5{vLAm84U{AqI)+0@Qzaz}$^$I45wXR>TtqN6EWgZw9UHBndSJW%02Judjmqc`!&!5YV zpCEwXuH5Nri=#+xjbwA3Us7DDRRS;IKhY~5>;|(fkG!797j(kzzStuI|Ju8c5U6B@ zWg+~PvPInbPt0SCZ4Oe3e+_yO(rdY5`$(J-0Ci*DTU77b*1sjWw#CKoP?-lkEfXTY zaN=E%7!?}C$db#{CCBb&l#@c{_o#`BN|6{b_LC$fs$_n(0WNoDc8|U|y->c$U|k7d zY!04+dnIY)AVxKVxHfz1H#LF`+Kf2*mID96!Y&atf>_axd6!@Pg&mf~;t8cB3gBv4 ziQ8E3o!qgWRkeh9^2RpWF$Rn-I#3tDC;gg_E^Av$3nFFHO3V+Pn3S)8N358y&Iu|| z3n|IKz*q^SGY^euV(%p~k^rIa{}*R{RN#Zg5l*8`S6A8M!Yt`{`n^?h}O`RNR`03Jj2ct5GWXCITa zQw>)jb{YJx&YLkl$R!)Ugl!hDsT*__DSFMDNxLer>|OD+M4wcM*i#7WD+vEZ%!v2(-c|hHT0*vP@*KMiPRP zh2_3HZF7RhCGG%gGm|et7kF{pW~!iJR;1=v6WOWMy!pCa0-A& z=J>Eo>2pL!`h;p}*ir()4!R+8Fe)B$z$inKIi{e4Ik7fXyr)R^fqG;_PBRH#Dy}Ji z;7(DfZ$Snhr#mDJFPek4^(|jII{!XEv7!jh3QaS6`G%$Xi3E8zwKYmWzcq}NeThg> z3u4K&Ape=`G~&{5mC0#}EMZh$yT_>{8yoC1LfdAFNT)7WzFy^xgycjgIk&LxWr_^|B;s%{yo9R*E?Van^l{xJiSDBKRXDYa9v7aEX z;?>C9z2}&TPsA#gn!z&NP zO0eH3T?$x{GIH$t!rS(a_$qkg#8Cb<5ictzGvxDV=NEAMzERWb{nIL#A8K$^F+)F(Us`3JgB2pr7L_lQ`r1vkRhFL#U0W^pljF?1aR{uX zuYL18J9BdXr{^jARwpxejSu&?0gM*LW*bc&tK1q3+OPTv(Hn4Le$5W>&*?EzT_AJb zxOKLG-e{oT`WW{&*PrOv&jzxeBGacrTK?w$W9Bc!Hmd!hkh^;54xdVi%iV-l z0|6BEiJIQm$xJcPKd1kA@OH$fB?WyvM-e_PRDy#s3ny9S3LT->gjBxZH}9`)JFT`@ z4gdcIpBH-c_JhVwE+yj2zK*D1zZi_|QdvNBw0gLXVk~csTI#aVy!4A0k#N=#xDXGd z{Db-`FWjrvstu>Y8@n;&Ht>*&Gp|+UEi0@04c*U&Xn8~EOB4|!CJ*NI58#i){Y3K4 z_}3{D^ym6NLzVY(Xr0`Mdj5D<33g^Yl3$5Ag!2yW=<#}LR08`6skj3TPpMpz8kDPL z_abvL4=}$W@L@ zz=1;0f$>4L0dlW)F|o_?eG1(&BPs+`T|-npdVL!9TFQve)nnQmMC~Qn15T$ExisKK zt!GptKpg$pkmpqf3Bi9`jQDU#7IRQ#O^D$|B83G7`iy01q~gh&OD%XiV&7N>?s>9? zZrb%yLr(W1GX8#KASO4B?II_%wL62sBe#~U$IvT*d3Rs!y&&q-d0f*7ymT?T-Psha z00C2F1;Kla>fE3ci`s63B8_MN=Ra`Hpcr7IE9EwyCj${kE`mgIC~`;eA^TlQy?kwX z={1`Ws_+Xay>3K^3Z&(}*fY-YVTvD+&a@&elK6_R)M#X_5?v&90#xdVV=V~yYa)NF z#g4fXnIcl4%dJatPNi2)bpytCn{X~|- zycDUsmIqswK(4Ms8m95puiRfk59J1@zX$sdC{UyQXR=Q)IgtH% ziZ(}gtgJ75`mJ~EO5cPQ=IPg*HA(jEK7-*2*ursDaLC53%aaAZ8r}6zY>1Xf0u0&i zd&5nJA9Jvaak?9!w6fqFR{Q5ALQ`+(l)Lf;2Km!_kDFX|dT%AvO> zeiylZ2fMHQNNE8Sa-5T(x3jhpCmc{UQ(K-=#4p1aT+4|b(Xjyw}2kQmFn2}q3|{4{lZO4a+t+1eg@lU~M5J=7Cs zfS-ZZCnyjX*ozD1Pz$MAZsntr2*zF{4%vL43)h*!cLx>8jS8f~@A3$<=ZIZ1Pe6 zkt~0V!URXbM~?mvQg}Kf!RGDtmr^NNAt4(MqfR z3&-{r3AcgZB@?b!VZ7Ug>lcSBUo(f3cN$;y_d%`D(fvg2X}{LLMh~BHt%z>EZScm8Bttj;$2*MG*Cuo_U80E>#cq87`mYy)yUY?~}T% zKXx(d5QlAI*}?oL+|n7I%B>vq75vp(tJYmrb!Q60SBm6QzcgKnJYLt95UtBC(0eur zpfq+t2HUlcu&`Yr3uM~V9Sw)?kP6UwTb&PJoQ{@DKbSEihuIYJGDFT)3GZ)NX(&FE zt?Bm0mxpBT?#(tWE)N*>q%8I<4#w-fS4{)ICyOzReCA4LLS~#$Q_9`HL|Er(<}-}n zh_#0JV78p`lj)baGqtLg?_(wLULx5XkARRJPn7(8oq^!n!NGh1&7TlM0Y0VCcGq9) z`l|MAAG_0cH(Tg&2Yidqb7wq3a+dGQN8N3M1RR^y3m9>iFCM&)FK3vvAVKGqen<|d z`a*(!V(~xDxwS}31$`zs5sPnzy+`_A*cG zk~0yUH3Z*xy^q}f=T9+G;mUq{)Ga4P#tnW>nMj3=YM?2c2>^&@@*DpA+vFcJPgh*G zDg@Wy-P$0U``T5XuCJc8qy~jJPq9} z?R&y+-zbh7L|bH8ydnHbZX%byZh5&_n4M1Pe&2H^s)zjUF!!tPcq|&$`E0YuMvmcH zdR;T>KR+DWv`lWZGR2Qrm9@Bx^}QKZxBx_34a4c&4)%B2^E=x)ODxo6S(Zxeus(SnAw=gIyBXf-aA{+Ga)8`5;fxP zs=|`4;i1=2qBwp!7Tn6Z0=k18xMhA%02j)M!6*laW%l)gGiHo&5r53PwQ1E98qFm@ zLswY7S-DvwyH$Nr(vqaCM4OEi*pQ1}DuyAJV6E34?3@*_C2`prP z#LxUdjNq~>MFs`PHU_kQ3%L6EMBiSEEYI^;A(sY)3n>%W7zOclUp7%z<**GgC!OU->>AeZYjo?ZRRpxnd?4g(J}$J+4LtNnu(DJ<2i9cMeRkT? zBp%aMBgVb}*McCY9wfQRDvaosZOnf!T74s=A{KE`viS6WHwXm{(U0OWWz#F_>P4?s zhwcbWedfj3Nlx5RT^*8%!|cO06!BK!T?A(G!y^}Q4S=`7;3xV#jycS5?}{J4e|O`? z?ENZumDlc9cGWj_QDv`df`*1)8 z-7Un@VL0Pl+pFSfnx5sk*pt8Ot#d|_w+Pn@eiQ9(zp9q@7-&t>2|CWW=}Sc$DvF1@ zd(;rWdH9(sL?em??ulOZYgEKI$(Yw{6@1Q5NTP3DU%THo#~bKImWVf$w4QGidlucw zd!qcHJwq$e9~<}@FY@DR+5*w&kh1=AN4e&%F&4J6`d~mey0iYYRXy#N2&<-6#7Gbb z!*(@&{M$yQ?R$vJ+cU*NS3R=ON3#7)xw4&wxJ6p|$wJu64S%jXz0-o|cMbcO-1>e{ZV*o8?-^kC=^zSxTGZE+1qLfZ?1cl=C4?3YEJ6?syaBDH%V!uer%9ed188dk3(`*D+vcn4mtpOiaK=a#HWW>eY5sPHD$Gw+)5M036$I;*Ed~&6NjxiXo^j#^4=hS}ocGW=Q+yK+qJ+ zJp6a!qIHv=*$H z3}TJCv`t=u`vS15LOn&HnnRCH=ZiB%K@S_|LtQ2|7j*xM6+#vG1z9%)SzmmtQJ-t| z*To|BsImA8_=Ly}r^s-}&UF)nwETWw5aIM0eonLC8`TQ0uFfv2_oe*=$nHDW6y^@? zi;olAmi1w$wX@c9YjuZQx$g86NUX&C4XRo%KtBaTrUT)IGwOrzl!Ldl@%34|ptZ>u zzw-7NB%RrBfRG;RiyyzEyW35*R%gwy7WKO1axRdC&EBj+)w#M6D=M=`EvBY}a~e#6#?5%z#fSx=x6F znR=>LVP_5Z%d=|5?sIlH(cvLz95tlJ&zYnZsO7RQEQmz6TggM)X~e91YCi<)eh_1l z%#F}Az%=!ih?q($d;7QGZPk}D=3nN`lZCBGc+5dh`QkpDja$TrL-yAq#eI}kBBDvTV;xt)qsZ5nL;;6%fPXmfZgXR0aY?u!$ zm;&AOxKU^Q&7eU=Q?e1x6VzQ9yKZ38uaRlb6JbNb0LDOZw#+$uADp#V4Fuv||>%!jaM-@_a`Hi1SYQol)+r>~9=8pbQIF=x}g1pcaT! zG}!}5vh<_&PDC(U;M6uBr_7$75#bR2L5}^fUUM~>7t?)%aSOIg6zBi8U|T72Fq;B~ zF>*~hxBilWW4E%w8JVNYGy~JSGk%A&BW_Gf-#B>v=uA~XLIMI7yJf%P3 z!S}CR*bF3sGb>Y^5M{;+=!Kejqz8sekhPZtpQwa&m5RKh&C_2kx6T`Qpxb7YVB7aE z>ixBpU)m&mCAHCJPK3#OTi14VW{sQ-j30Ms##?TW`e&@!wN~|3bx|!i_gkM-MR^?8 zqmzFl={_Tww@9s<*C+;_2XQk?NpKnWMd-i3HuA?MTNFb+l{w{6pZt7X*rwH)VOmEZVE`h2;4rZb(zDof;c(e|fFfa+4Qw}3JBY}jqY>*15KF#K&kX%69t-MJ@M!E?Og zKsSn(s#TbYi+F^37KM9k-&_q1=b~fZZp3_s%Q(#FF z`zt`2!hxgf_IsNaT|g4J?6z8v6RUWQbEfuieD~yKnNwsEWWdC;gjLhI0c=CVAF%#Q z(>MbFK6RTi@9aW!0VwVv4&$6+-<6R=dhW0QM_vkao|Wd=F?f=!f>i=ooO${-a)=9$ zd~OlJM(H{GH!F<>=fnNU^0jQ>el;ic$x8@*j{nf2%>H4dBOKTVz!y!6m01GqZFngm zkjm+lM?&%;##-5Rn}3DuMOc50ioVPQU8q9!H!u%B$>d1hbm9jLNx!b3KYxOr{DRmi zA9=hYaC}h1F|Bcc0^&qeW-atLganp8HIlxnEpeQ|J06~sV7`q;iHC1;$=e39^f_&z z0smE}!^gG{L6S7eePbY9JR^oVS`%~%eIqyxZL>e8{>Da5kMa1pQAyIfHC#hYtxtC6 z)=$~}$N5;e(e0F{I;0kEyGK8y6sT#Cy&k=i&aa6v@UEZoP$ZC1S$Ooa61A;lpkWth zxcp?V^Vn5{biKW8d)1jj#|zu$kj<6VjjIxaz*@{YN>1&A?YA1L7F9)~%vK;ErSC$5 zxfH;SzjBBY!cwP<=8Du0C7K&jUVlLI;MzUJEW_%;UhJ$kG>%YbQV9^<5kWTXoM70I zioXDxs(n6~wXDagC{A^MRRCVLgz5g~c>#Pdz?9jqIX%eyhK$o zM%Z*+AjO=XzV88SAU+`JOXdNTO*;@L`_1m=z)|SB7#Tndjjs=jr5er4zTCZkNCYjw zlA8`IU(-c}BPUrSZ8^Gl%w`>uGY8~ja`tN}IzFxW&HR?(e|7puu1aDkV5b>n>G4 z2(AMX$~bQ-;6PUz7qxfrAAs!|5eE&pWAmWbx!BnvqSax}AwbJNeFDHgKTJCc_{s2@ zL%i*KoqYZ|wO4bhrJ!*k>-^r&Vp?TYcI#P)Ut0QN5 z74=roxZ&Y6@t)B9IGsTw9VK*OmF5YnjbIb|0vf~#anh;{e8awIl&`byv}LyCUu%Q@ zh^~;$c9J~T-Zu1%m#6bJ%#h9H@_FrUuPPrZ(#g6E z9A&bTMc}TyAjYlB|0{j>PbeU0Zyzx)%>LuoQsMV`B314(b6yubJ5jQIsczzi^5ZS9J6=K4)| z{c=KA2o`xm<)!S8lUr*43TTRTE0~x^yolzCzYulRp|10XMZH&=ZgAGtwePXN zULrhLYY$$^1O-!OEhCM?-yD@^2-gkl_GA9XiT6x$qQ9~0K_=fZT+r;ynjX4sE}c)- zC~R{168wi$z85pLMR#*ZP5_R+c+}~z-aL-Y+nl2oKGqTmrzuyK65UPBxl;X3<8(^~ zZ=)Y;j?$Aj+z5rJ=yT-5=zQ4N?);Udn!YRS$LQ0*y8ufh%-|73jmSr0j3*+acFh)0 zz?JF5SHF7~Ils$jyx(J8N5N%<^3z7u!HZ?96b99f{%~z4Of_g9ofOP6CsMXHuK<;t zw#zE5(gg9LWfMHcMXG)_HV8az+vf%2C~d`r6hKAq$`|QP6~RKtFsLk#x)r}ga&*Rci@ zEcER+r<2q+ut2v9%>NPG$xgb#m;d+(*W$Uze^>&h$r%^-iFr|n+GU&VFN($oyfqly z9rQ~Ym1pT0Q^{a0Mox_aKsRN-sCVdSh|YFCZED41((TzDyf*LFJLuE7oz0WpPM}cP zM1CN98cbJ4QSb-h$n%lUs6d(&YB=hb{l;O|La5tQ?SUZJqx6aS5)z5*bteXh|MhEVAdQ`)lz4TFr+2?Nu) z8RN3Aj!Zu*&V+}Nd2TCQ(ebV+ahp5p}ceTlq0U=?(UhMEw$MuGmWZ>!w| zEZ?Xs+ErU+n`_p!M{@x-sC@G5NJk)H9QV!jZM`KD{R!;9$Fv5-jx|QST&N8eKCRu! zZ~Q>Dt0QU@yE_&_nVF!qQ!>O-AXDffu}0 z;`@xB68tWX87`uEF0R2&^vSy80ke9;!(Qj!MdJDC8w1JKXob@cl=Ho-Fd?KRd*RbDZe*>g&%L%dlP^B zw(0WiTy+maAEiCMj0`&o6>5!@CSg85Pi=TKnj0ddEfE2#%mp&9cpLqGSh-@`8k0ct zSTjdQ{eKXFleS7ZExEc2x|LadhR!nawz(nC&SP%{M+PwxGhA8SN^hen2nhN%iU-Ge zJwuSwV}ia@&ue+6wCH1%f>|B$@Vr@tcU?x=OJ|s`cZhxk5dV*S(=pHGm>0sNj5bi* z2;=b0!sP|toLdf+7Bi<+_y5Us54tAi>|)wungbC0A_O1&h)`uTB46#z7u3V#hTKQ2 z*kzXeFZ^W~MlTR(cw#V%Jwt=l+Yu?ra+q?0lL-$-6+G=}A>ZJTbd+%h*S}d!p>Gya zqDbT(qXJqXMJBB$qm2d_=rA;~q?CNAgIPL|s0hHSL+aAFh%P8K6`puW1kK_n<6RrF zVtbRNCBKRufMS?eK>q+z17zA~1883~gTR}LxURH5rN<1dNQ{>WEtxalI4i*N>#X4J z(51FL^4$M-{PFIA3sbG$@NKg<&mVsI_C8YEPNBzz*_<&oP3;~ zhS^J7crOChvC{}S&FeWrfWX`>fZh?|y-*# zpJ@+Z0$5AezDEmIB}aX@(>&LpN3Z6-i1jAYw-uyP@r{*oSz_^ID#yJlvI@eLQ_ddTeozv(eiVVVsJ&q-khE{FN~ z4rR8Gejadga&%_)JNh!5*eB(;6S?dIjxk*2Ul1Uay)Z_48HuuGiVBGW+yQ;wwecQ3 zejvs))C;oBUQ?q6ABV8@4dS>QK$PECZakfjCpaZU3ozy6b97V{NmPbTXF*SS$j#lV zoNRMn&4y?4j1)#BrDNcPk3vE)qoub&K)tMsqB(s!Bt#6icd6EIxDCIQ;)}r^;#|e| zQ`XI2%VDg#3&)=>|5)FVVO#B*TPw3&WH%qln}UkDyCqK|vEBRK6A506X9253MS%a5 z1l^c){PF{iOI?$hW->%UKAjgdtO`n{*Ld)1 zGJMZh&N0)io6hC>^snC{not+??LH!`^Y~yf)XZf)1uFSa=B3EK6vK74_4mu@-@rCKdN5 zeeA_E&;lCF`l9+{BjlN$r;y%;nsZ)D+hp~~3v+3}fv3$ley|9L9aunMkqcQm)5%Qd z3)%_n&5v^5#s&kG_*Knl-8;ERqy(7k*!+ZdbXyWP zbDUw6h(KG)QvuWp?J`T8b--YK}j6WBgcD~Oe)2PVZg?1EhjoW!{sL--YNL`VBW zcVz3DC<>8iegwAxSXm%Mv@KpcND+=R*wC6L1^<~eN(}bPZp8_u(TZz4@HiX67&Uo{ zFfx`FP24&1C?Z#P-hXAJKn6Q*8xR+DS5$i1|?N;nEL)I1PxH( z)Ul^aWT>x)z;XDRlTEu#5Y7*KoHTE@H8lWTC6~u~8$A~d3~xO2iG~fvtzbpN6gA$T z2!W&s8LYK}>#HW_-QPu+H>$dWi*?&3RH|QZKOD3ZL41S@c)2P_R%b8OM!w zJQ59l>it>f;jk5)7kF+FG2Cn^r^zJc%g z+yPs#%%BAQ`$6B3KIcBldEWK3lqR^3_p-VcpRlWT3Vpu+$XdMUkoI5sW!OUY++7g4 zaeT*w4tr1Aee{bGgkw!51VDmzaeltyopZ%OA>QEdVAPLVf-)uKmgRbGx00p?==%iU zZTQ-z379tD64e#bHCbIwJW)zKZ+lyG87CCLjN!`^IwCQw_H~rjHX^kQaqBN$=iZhH zSuuWe!7!uzh?m8j_QvOhCo*aimJT~6Q3p$^Y=K^0$2RTc)CJSFxrBfh!A5^#K^+DN zeN66&kVczygFb;cU+)OY)pq6WzrnPp;sxO~J!@bpZMbVQsh*sM=t-gHFWTVIe*h0n z#KE>7RD!9+BSyR90Ne6=b{rQCXu*TA6dm_A2;d+`20sfCGsO!qjP;*#COqZ__5`?e z`!FN2*)3_|$_nkZZ0a-;RYy{5IEoU5tm&hbgN83zZS3Z-8j#YQg*(`Sw%8t-g3@x$ z$mbp!bFOlAb!Bw9k-UlckmxbY)mbTNn#(sO-(`2UxNd zi{-MLZ#{8OxJPdCn5})|ZL`oUCNs|PKci^~9%otL|EShI<~rCXflA_>r_1CNQ8nmI zqJHXqEm~|?9AN!Snh3lZ%rbGr6at^wVcpGfL^hWsynWWG_2Y;?Tj9GGcfjl7R_or1 zOvKhJtR2%fOCRxQ0wTI6_9o!>N0GNr3Pl_=2OpvdyB*QRXQ*lJ3#hYtBRBS@kj^tq z_vw&{tTbJKUdYVrn^~<4vDx`Pk>t=(yUdvw*3V#i1cHHty0`1D6JvLAAQ% z3PL$<+z3KD0TP00S4zxE*#gJwjUThre5DmddCV0vtpZ55Kc1o$li+h_XD+_;(!^!S zGh`18z4K;&I7J{?Vq7k-7O*o{`h87s*L(RS_V)7Chq@@Fmuln5+>Qqx#;<@s;rgvV z9xESxe)2=HaQWSOXc8irVw}+Cq6j1VG^gTWKe$<%U=u%^PKN{&_s z<59jOjwkD~m?bZsPAuGmPbcL*UfT-Wn%3ngV@uUq%>U>|v}dEX(vD z0o?)?b~6&iFE&&Qp|u3dXSU`y(q6sr$Z0*pnnQ=9ekcQPb!iih>j8@Aswy2Q3Ky=)uV&4 z&`1fDUjC4GWF%Dbaym$OOFomoecoP$(1yLPjf?q!o_?^@3BuK;~CvG!mvf@{Wya-h)qeM@R7baU)-1ENho=Jv zNqBd3`{?*0qx08z@$Q3s9*n-V%iiKMJH)(&bRsP>Jf)DRv~hQTt@|fJXtp5RAp29W5cGkGjfEHhIky`g>~%`0U@d+&=Vj z^-sFtBj~Ap^^2&U3!Q#lQk80uhPJ*0hh8y>F|~fF{Qf^_nP8}Q8!+5qwod2(cR^&X z_y_X}mgwi>Ch4hNb6O3e>r@=m{aA&${nmAqi{6FDwCZ*9x+fICEf&d9g6)Xnm<e*{Xz3V&Md%_p=t>J)8Ni*o%DTmEfxMykZpX>U0V>LSc(Ea~8EZVyO zbNQ@VBAfTj1eGxJZXdIi4|#*+%NfjBW8@3-*7gtPuto`u(E0Q4xblp~mRy-lsS~## z&t`MgA;U5ZGYv=S3r4jTD+zu2TLo4|tNyJd$+i>7)gL$D?eJ#DM+4Cp@qWn!zoh=E zt@K7?cQX%&`+Z`Mp>=UeXi($zC->)=^B3CKIk>ppfzt(V&xA+TZWH>$?S}9_kC`nD zqmud(obKLzTUx}rF^tZFWw3r&_#~zMd~$%xg16qUzMtfE;K!ZGuL<82klso)V*npCn@^hiu#fI1{;wIKesn>N+9RW9i6nD% zQDIv@-gx^+IS|M8nN;pquMb(p`JX55*unpVuV*COf}`KAR^X!5xRoS4SoeA(6JZ1& z#xSp}Kh=moo=1YDE@InWTFw(!@}(#xw1_^+d>=mIzTU5%tN%>ABzxE(h;~}Y&#@AB zAox`3W77dhHdk>uSmKA;L%{^`kA%K0v5EvF&?zb-feoLnYA!d#R4DRv`-hStA@t9@ zVL7?SnW&+4t-$5Hvm>E^h-P9A>g&w@6(yi1OKVJIj6bQvQS|Vb<3?NuGmF8c;#BH% zMh}f0TS^EQCAZ%1sm(#xBI%}Uto$=`t}-5_*CN0JZ ztd{F(Zv4`_;p==3(r3dDl~6N!^ey^FP#a+C+98sIJ8JX=1SPd^aK*A8Tl4I^e?A-#Nl(n>*7A%G06ETUR{3$HA1M+M*#Yqc0}9Nw zAj2!I^&;5k%tqFCdXB(nA>JD5$ciA+4*)qYU zb5+vL&G;=C*RK?tUG+^ei0yTV;CYt%ogt{-!FhhX7{ybbSQ%h|qj?GD3 z_OH1e#Ilx0^J%cZ9%*k(0aglL*EEVnRYSX^{}mbybQ{m}|F8EQ3((Vc+6~S*mXz1P zJPyC@-9u)4qjhx_Ej+D7-P(4n$~g)DHjz)7UmrhkCFA^t*Rw-MI8*if8*dNo=#k#D z?u-#~Hf(jM?uSCl3pCx;c=z3M!9oTScU7XUZYQb+u3XAi(TL}lh=D!4DEi7=M96Ud z2eAvs__bt`%@I`^$++h$Z8_CYaBoH(|3ore)wg*r0TG5(i=oNrFu60f>qYHFPL>Kh zL?p5cb@{TU3KH$^|~tW)nj)oW{gPFPbFd{C=cR=G!&uTM^bug}Z(rL0+9* zCCw07a)+XSpKEY8U0|gp4Go#bA;_+=Gv;ecq@udICUASNiTv&YIy~0;WSmrH;hkq^ z6g1tV9G~$8vI??)>Hai$`lzU6f9*WpetoO)SKXS- z%8LtkN&3CJX5zMC24R|~_fKRaorhJ)KY25;cr0 z{Aknujl6?m`RzMX=5oBQFxw;P|2#$>k!_kNaDDsA^GJlKzGBEi;|E^(NV&Dku5Az` zk1F*{6H2`{S<00J>wg^e%Pr>x@52lS(K0UAbJrElk0>|sI&P{>+pd*XD-||Bz-7HB zez5^>ZgRBB}=OKYMU%#mF~yX+48mwMv&JZLt(vT%vjes@Ikx zLae(hmfO;xbm`bIG(--4hl{pXZIcBF0R_?0-rV1b!9TYIg@_o|a_aWaRaZJw{zp9P z1N6oEv0#(_n2@6YyH}oZBJ7cq$EI5zD!xLm6kYz|pe4xk8kFRnHr_QO8RbYA*Z%!y z_j&Ph{Uf`HEZ3lH^Bv)?0U*zB3ZV#p6Vtuhv4GJR)^b6w^M-&FL1!3#4xEyFslZMa zU}6vNR=IzEl2xvE|JjVf<-H5aH2$o*KqA@=C-K;Hn)EZ-RR|u--IW{ruoc&|Y)^ZT z+bR+HHxF+U{dm^20+5fjYvca4ieIY^73ZH+iRb@9Y%3~?ai>Gq290%!5#W9PXVnQ5 zt1Q0Sy-tbW(CAh`G!=EQ+R9zvTb8@^<}cu5hs9rXNC_A-hd=}w(14#8q-hj1eBhh( zgW9P_Mgqj{oFMC7_-Wrti!gy{0RWBfB$ZN9FCY;5Y?AA>i3Ut5HJ~SYx`c-AKr7Wh zv)~ODPTFF3%14L%R-dmjo61|a!e9|w1k4XXgP6levxpwv*5ZlatNx|4`R$1VS0WyM zZ&La2^S}3d_9RI~JpO)9;Lpw+u$J0m?QV_$lWLPOz1dYo$STRAo|?G%KF5ga8Y#!z z1G=*npHF?h`W+FevHSFldy2`obDXb0&+x1j{kiJn*>%egI;Z_2a8d`GcSOAQiFN#{ zIW-NJ?0`&PHCE94z9fHiO!MdHACVJl&Hs%&wa$pw3?qmd-X6yPS>^}Rtilhw1-st0 zOJeqPL%AuedU(1(4$4ae}w7 zVoO@MCy_rs7U69Trx-DglmL9gras;mFnne+fv+aqhB0wUdb#Ta4YeKJhKjA?r|Gpbz%&?J5d zw;D*+mSi|0y$r_r!1{#0t93jJUYO%j0&}%wp|5~@;m!_@SshUN$(P069691;oUxyq zr%$rOlx9_B*ldVF1e@ihE=y)5;DT1QGiZY0y$|c!FI}6Y4y)X= zMK0cmwR`+C=K@>$_+Z?^XUWfB;bIX|Yr?wx8@tXv427R*4N*QUd8g+M+1G2QIG(+) ztZ;cZIKcg*nOKUniP|w)$TRqyu$%}>3~Q-aFT~Q-L5R>TrwB8mU4PcIrMv5iCNq6g z+ty+`$?;o!o2HTJNS05L64+j}iY?0=P-jXe2ygn6n&##-aik}n!^FTH18bN;?=iM%a z%lbl5pVT_3oeSMV{r;J8>fO5!`Q)0+AVY;9y^lSoq%alHhK(WmF@`&iAvAR+ij3S)&3KtEPgdfp@pgD~S<99U@3 zJ8lKsx=}8?8bz7u+PnlB__}p?o1jEmjh!@!ck1#4WqU}~>79du-V-QI?yR3H4rm(jf|x9*WF8*&Zz}h3 zzgFDZz&v-y=i5v{isg%D8Cg}$iO*$oS62VKeZ2bSI!9ut9`nO~HCEW}Ghzy0(69Z* z^Hc4v2k$$7W?B`ES^jz^2S`oxi}7K+U)476(GuFfo%{4`v((W!5yQ2UdfS;zBJZw( z9-qs-v?xP)E@EIIh564R2w&A8OX^^M2+DZ_KdHprn zbNqFKM_-chA%bzcXK10;M00J4RZGKFL!oES2cKy_3yb}r=C$WoGj3#Bww@=Uw%8hE zCIkadY28nUtCY6k5~?;IJp%6rC2QcWef4T8(p30U<8sn9`t9Uvt)_C=y;%BrQP_Ru z-j73aumMyn|nYSco zFhxIaf6dbcn>67#g=Y5iGdL}y4sWS^KnGU4&WQoaR7(9cXY$ycjRs0$e2Ey6Yk8!4 zc^=OZfrPG)Iq*1}L*+l7WXw?qe8^D@?D#h!_&KWKJ)*a8_A?CL8n~Bu?bn6pAYhQ) zCCy(*dRp-H+pCsLcVuwqKJy>FzPA>;%>aM?Q?Yvd%JQ%=FY0$@>&)Hz@^`<0C3)Xs zNtL$L6{Aj|w@Rnl%Le-E7YCEV*zqqeTo!#MuK92}PiO6tXwsvHCX14kL^f&tKhP|n zz;?w4+@+#`)r}NwT=iKb5p1383C%xNx1OjNaoRF#O6jn<63rApd+T12$#vf}xBU?; z#jEGmcP(ZbxutApJIeR&8kl!8QQ7sve?*iSu?cf zLj{+MjlR<+muj^KPy_$#U^hT9r5Uw5ndv|FPnNLJ{mkF>b)rExc7_(3G0P-pW7O8> zc-pxtIAy(3XF{$7j>M5JI(JvZLZbua1#M;ZVN>?Ijo$4Mhe%S&gonimc^(b0l%ZYQ|~i*uX=u~ z^gKz}bBR~GA;VW&Y)V#(?Geh+ZQdJeJJsxI&D45F*9AvwU~6xq*`ePf5(@cRmoA$06IkaC>^ga=?CK8Y$VvUX4&WPL zLrJK4Lf~AyM#+&qs^r^8%daRfURdp;+;kUb{^;=ZSrRi`>Wbt_ohlL34+j!0b=7+upc9T8uOoWKGtzD=(>od>SVrKrewlmMLFgXDDZmFc=yPL6!J}a?Li)n z?RVTg=upq>7H_$%7}UZblA;aZ}I!w%56QE@J4ZCfdQ9P;Re=Bh?;jB#q zJ6^PPTD;hoI@|c_9GP4Q&(xWc=?Rh*cF;WBUisLsxl`zaqRuiuG%^cT2_}DggRo&D z9X{^EDD}EP767{sJuBNDH>Uzck1~sO6#afi2WA{2rT?tF_jCC`-T6QtK`Z&buYWd) z38POhv>Y3~eCX=Qa|UV>B`N)Oc-6D-DnDk87!rkCYE*^ubC~F~O30Z%oE7iNPE z0|Mpy<)cby0w}PB(XdYSSoZBO`>>+3mwT;2Ul2IiXOX(^&~x8cy|Uc_jRwE#`s6FkivdW3~Z{Z}0BHqJg5dvu3V z=kg`w!rsO5+wF(0Ct17iV^_z~1R8S2U-1*&#Mdu0x?iOncD=_vy>q&%EYIZtEmmd|ONJcq_XsI-Tyx_AY4t!p?hr#>zUzM1Lny&{B2M+&s56 z{2vRjA|9bEy>M)^)5*l{=J(ZqLP+~fLjiF(5cjX_i`?2CtLKT7DxI*Ama!{StN$8d zZ%Dms(%8qT>{?qPfhG`k<})R;gr>!V>s3qroT?TqQ| zFuK&yd-!ZI+1eY4yQsomRM~b{4D3xT_Dibb@rGCSoJ;yQ67B~Mvf3s&_ zl12nU>ZNYG3kRVauB}{_8TZaP#qyGGY|qR~?fuP{>@ENf{lTB%F*B>` zdjPdcAD?t`Eyccy*T!i~S6yn>EAsJ{zYktR!QLe<< zfy<8^4O<+eD848{NJue4vEHV=+B@5Nu=}K!OH;S+1kz>-@!R81?SiC|dAG&9=`-t2=Ot;90)=?zvX`ahaKoL*Sju&%JP87xHv8971V>hl(NviJ4 zyeI`kD7?JeH7=N!T`YrH&+WaFT@Cs`O$c}#sj<&w4*jsg@ILW)?{l3>JVVQH!%=QE zZrOmI9OJF!)UY{B^j+_F$I%?j?qNms0q4v_Gz~vnV9bRd{`}dO&>#ETMJ%{jKh|$b z@_yC8Ga_HkFVMY)PtG+W(!;&4ZV^wsd>A0{>_LG|lc52+yBR1xJE>UOstWzHdm^Co zL#@%4PVCOG{WFInVDD?+gw+8N0j+FOkq4W(0b$ICZHtj?uM=G;>YH8JGf z%oXXhV)~b>oAu1s*|FBdZ7!ObT(mPS{w2YFy>)ILP*g-tyhF_m|I#hoQ1w@n5I=sg zyAEjhd#CM_6_I$#B)8DqF|$^FS$;^Gn)WG zmWHARquR%uL$@9WiM#(+Q50xVX{LnBQY&{Vcz>JcnooIw{Blp5jR|i{f}*`@-<6!a z4|jCQ{Dwtn9{7fhCFj9X zX{QdHO?!FJqJcqdAc|15t~F|bemVE(3uGm{-Lsz)!#Qb!3-+F8bgKj${WD?jw&A}7Q-TG3_cS~$h}Ak=k9-luL@2fmOa62s*V}TL zTKW)~V0;8Csm^24GBlf833jhAV^sFm)s-d>yC1zC%)(rz4cie&S?kX`H67uKl=|*C zxM|o?`hg?Gr@Eg%TkoNo42S(v4UuphribrCW1ya9R#O-IyymO0D|pL}pXvw)*Nedg zUEzP@HdN07{?4HYf42k(k-h^tRB8>IVobQ=dv_&%6acMYN7b)&IA)w1cx2x~yWz!K zSW5M83qY_sQM{}|6mX`Ekh$)un_p=sHlaq4Qtu3(ZAPaAnh|Pj|qcAtA}NlgQV_P#dwLdHI#Ymv}ZX*^M{oqf#^^T|1%HAlIH-8}cu z>3|f6x;jlHBjbhOn1dbas|TJSb9#roE3*n6@9KnRN_k$X`P`VHc1l{SQ=%^v_m1@1 zx9Y>>PjE?i?7ab#$;|ch**l-9U%NJ#qxPeF!yfp3(|^!dzuei76=99LF(C!?uSll! zoeTwWyx(|{+$^B)y^&+ulTE}IE_=VDlz`Ntt+owHH022;HQRrFZs`1g;5xDVme>7n zGv5CH-i!cA?p(4;&*e2l8ubqTfS)J8z8p=jjvJ1gZidY6$}o{xW zwun3{6Op6z9sX#C=u1wU*Z{|q%5pLSjGHaga=s^(x7g0{wx04vhjwZwt3{0bUkskM zs>_xLAX5NqPoS71u^`1TI;G;1?*=nd>bM88uAIgpfqXVQB8DM>Jrz%K>u^;?@Pi*O?bThKCLjwG-f3^`#z zTb%)vZ2ik}nN0^Lh$bYbW_x#y4{Ve(K&BwYSZcN)3|C$^3mUXG%0H!Gq&Mr5F(>DS z^mdWo2pBat$BeDg@?ym zJnWlRJgnM_L$dc_^goC_wW?~^gQv6AvFS@sltwe+Mt25_v-PH|!)yN}@1VGytd;sz z{eJ@&th(U;$M(wdkScebH^H8G@oErzT}ymsq>2mFN+3)L5D$;kev(DsbyS zO}P5p*~}*r+*in{**Nm-?$*YIT+AzMgH{bH!lfF`oGjUh_=68J4!RBxa#BE5V)DeS!$|6^{2 zRl$2Z>l~I_L99%m>1X&RaW=DE7~3qIybvAhe)PY9oJ69JJI(<_CK$cSzK0im1iw`t zaxrqeH5@RwY4GC{xF2wQJ{DsS^mg%V8DeSUJ{F)#fy1uOxxH-L%jEGiF0i(CyxgSb zP0thdT2{eX5NA-pwlJ-`Un=iHw#l-Bj;~`^n5Q7Aq5`aI?yuY!%87}MV;aF)p)U_Y z5_?x42*K~pqT*5@YyEiuC_FEL|0=WBzdbjSmg)-S; zn&2IxDmA&V19I&_3!lyjK+PCYg{>=PdCLkjm%PVCf|ErlFsIOU5x#Xez&*oG14wu9 zgG%fFMQqHI!Dq?p+E^r{%ta!6ss*NTg5Ywh7xTQz zCpX$33?FzrK=UWxHEvnFn1C6!;5`rLogysK-jk2ZY`gzqjuo&xx0^BQQK2T^S3Uk?aL&G0_m$(m`umN@EvWu$1~u~m!0Eytn%gQy)7l8h2B(g{qunHnse z!{`vm1c@xDG{$Ky%~rx(ixg&~l~F-(SJuX8vTq)9u$OrOR8YLW-5Txd_hGL6?DO*Z zbRgkrK>>l0-4I zd0+{c#O((zdf7^FHgteiN`_NR1?Z2;&>|>ys2s?l?VPJnh0 z5lL?i+s^cNHx+~dD-oPoe=|lcn300kCi2@EZR0rxDxCLqZWeH~Osn4e{?=hnj`eahV>Tq8IP+C`8!08DOkAeD} z9q|452Dw38@Sr8N`&C=Dq;pyVw0s9(N+nih#JZ09AUwwBB|fot@JV8t!O2K#vd=?I z*#f4et$;L&!5?MJ6)bxUu7J^#7!Wlie61@OPThD~7~~^;>-LyN_{rngvd5X)Q;$ps z(FoX2`~L-X9}rA*E0rt=TCrjV=BPS6ZI5B?IV}Pn3}ko?1u>j+=j2vGja{*p5rYwB zsD`o#e?NC{8Nq;@;>dZ?H0dHxN|+yyoYVrMs6%HFfDjplmAH2FFX+XDiXL?J8(YL= zUi4tJ;Fp3!Z#>V6@$%GC&uraz`>h8YK1b9-qu$#7WrE)X_79)0$Xp_lmkHztWYri7 z-)x%`yaN^C|JOREx#EK1hX3Z@_ZV#Y&}{gBIN?VmH@mF5T~KXa36Vn)oMqQ*ne}az zuXofZ@%(r<(*)=BU@fYCM&g@1;Kw}N3;d01vO%SYM9Mkm75&8kPW2x}c#?n^rO~6m z*=P$M#G%32T(_9}cOmaV0jIOq=*JXWdWY+D&JZgMys4^+6!v+egL#TqQp1nkKtk#_ zs2RkemQx{&W25)o4Q!Ydyl8hGguMLGPZHX*`)!yge5(szZ}Mg#=EfR&nVD2Hd3d|t zW??g*IvZ!a6ld~&NaAq?YCT(9CnnBGNBsdoW~^Mag$*C#Pn3r{24pjvzN}YLJ~`2e zw4phYS1am!Ikv$%IgGP+D0|B^KrIfh17{IjjQI(RrJp`JXI+FnthHZp;J*smXwo)0 z7d9sG&AlbTO@HCPN!Cars9^lONp*4-_C}$$f(bNgPOBs{NOLT0>__zSSzZHw+$EewLlFZ#-IkVJNso*oTLI1P^X`Z9^$H`TmgWFlqJc?ni^%x~Krx z@LFd4#*6UAIm;*cWP_rKOKYumX2S5rvt1>1Ivd`Z-0|tY=&-9mw){c7cW)eFRMDxUef=e2c*wg=f zE|!NFR}egpvYq4JcqS-T7VD4P?rO##e{fW)AwYr}I{O^?k9NDIw3v*wR zmlh*wOxLmCY1@H|t!e+Rs{%#46_cs^>i7Ezq91Sh@mBP5+`KYHooP38-cbAfQbG+( z&fOn7n76c%5o=EO46AP`i(V;n+(}AGIvWC{9MBtrm4>4U7Oed2DOim17Q9=hKl&g| z)zy;$oheVkNMa?9Ln{p8Kv;XMKYV;x)%{U4ul67gVU@+%)feI({g?A^_3GIfcrB1P z<5vMqv7{CJm5c!?x?to5Qw8g?G5n87hL>59QFrVH4HK_F5{9{e_#@k|!pTNa6@LGm zD+AKBFYwJ(_4-b=AORw>J8e=&vXq2OPV#iEe#8+3wP$t&bs9<}1LTYd-#Cp*Adrd# zg?WRn!qwKQ%7c;{3+vPB!f=y~8%=@%)QPjJ+o?U#;d@q9$`6o4e_EPg3N=}pM8@9> zX;#+bQaDYY4y;leP{g9PWjqW7_6aPdRF=+^R8aVCmJ#!1a}nu8OT4w6C%$Ox8&&)9 zqARuTv?(S;8y!7QzAGW*%&N(e4n5VB8lA|a?*1jSJC6@6hep7g8%hv=E)Z? zX%FzOz%6EhpIJT2?sWfA#nbt^7vA%W4=KWvQ*Bs{quAyF6aakI7lzl+D^yi27O-)T{ z>PU$Vs;EAr{f#2zUq+%Xpq4M+y_^BE_jF}!b8#NSj|Edl7q>^S27{au_b9Bb!UHWc|TE) zovyAZWW)O%VhMz_PVQ8A;};2A+;%JA?Dg~{(fxBLpUQ3DNaTJ94KY7IXYNB8*ey%B zyQ=-$b>Yf&V5YNWZiKT+{r)V=kmLIBfqNfX3cu8R`(Xk3cv;zYr`6TDI5K#LSMX^UBCExSLWj`3fpP}ARh{TxEd?T9>fVi%e`L0lz75@xl2*>_x_bok`z*Tvef9OPY2 zMcsYy@q|G!@U2&yGJv6Ln}WP!Uke1xwGMqvX29w(nTcI1hTQDmhG$`}%c450EHy@}VIGHv02ODoOxyYS?5gNkTmg?svvF6tzxCOuBN8%ZvJ!CN z!i5Jg*hFV{x17kQ$IrTfk6EV?{t7+HFbvA*o2QCtX^&69ZTXIf@YX(u)eaI4T7M~a z`}^n*pTw+BZ@heEuoGhKPZ%nIzoFr5@J5>8$4bW^TEt}CPCiR4Q_DHcsw_xrPoqI= z^P-Um+CV`XA&uryTjXQ9WS!-g?QKK&o*i|caS5@~P**|9$S^}l#^2}g^WLOJk3kmO zQ`H|pp^aM~g+M`{G?9tE$jr?;N47h5;>>1V&q%OSn@iS^%G8#-BQY`9%2mm+eAVTp zb{u|ZUW6Ydvka!o)awgo@iq2TloqQ_sY%H_pZc{O61-od-lrp&nhEvvP4|@VNO4X0 zRIn^}ag4fA_y*{5d{kN^I_Iz=z>?v&6&0HFg&CYN%)jjvWf3Gdsx3(uTd}pbmlyez z3uU_2&m3gEc(F%NE!20-gwb{lq^tjh2Y|2-<&s1hxg-M=W&?&qFwl9#&s?%!ml zp+Lj?Xi8UffeMgh4zx`a-py3!AWoP1c@E{)7@>yKPne;5z#A&LIp^x9okZWf6i#-Qoo{N}dOKGE)^PXA;-M;Dt2KqBy4>ztzjX)hRXF*SkINQ=^OO&vZ^rY5WEj@WODtLd_7e3|>qG0X7 z(jIMXjM%2i)IzR6k5v~NJgF}U0O|z<1YnXk#xS3KwH&)YAJ&D|&L;9)IT7znIur}^ zB=`QBozx&x5aYduXgT4@`Hd~WDP6FKwS(7m=xHFY$ zLku&NE~+$x+!`#tQ0(&1@es&~p?%brd^;Uc?$NEYd4x|FLEeZYzu1`FqI!DpjI^+# zahklt6l&?j{l29R?Hl;Bl{8kv-9EH;b0_vf`As>1mg$q(mzSb9i$<#hGRNlO9H| z6L3b05KICM?tEeDl_3qQE}d)%dTkQH9{nZ?~k}Qf|3@5U@-EYkLI3c6za_ zr<>i9w{IseHF_F8a4dgGeXe+KTq#tbA4vRI%8oU)WNyim2DF)s7M~YuG>jxFC^{tw z(=;a?^2PLwIRlyw1%4~$=B?yMY4t0WFV1+=P&GxeaOzfAYZ{aCVD*9rEga_m-uME zd4~!4cl*n)@A1|jo#E1ouB3kZ0#{PYI(y_0QQ&?ATwqht${v zUEao0k^0-y5b`HBta^0#GG^{i>>V!Pxvht%SHs`?r?pIloDc>e9Jy!vyXXWxv1#(H zyuq>>UWG6oF=cax^TY#YuuAu@MeJfH^JIU%Vep(kI*OE7Df^GHW~%AK?Wyv2Kk2TC z%CyfO5YAb>c{wLW;)ys-BUB2MYeafi2p$D{m=QLJtHL8Uk?(Iy4j3Z;-hbLtZBRb0 z{1Js^Oq`-Jgra(f(38KA&9Dv9OXmUXBa`+LAR*TzTT_ zg+I=VBZ7@LZ>f_noYaA|wH{_n`92+;i=@wrqII%kA^i;%9x)q>L;A0us`i=)@%xt{Kyc-p84@wd<)IH>k5kKKb<`-CIAF@eeOQm69 zbz_de^n|C$SM(HCb_&3OhZ!~|FnO&)3+0}R?+V`r*phIXC9OlnET;0iK{S7Rv4N2x z!apk8DT1S%P2Iic92gNmtNh*Cwuji|;(aMxeMtr6C7&|usLlG^W6FAHNNu;T=L$@o zTcUG(LE2P$0c5TZ(LkettSHi3V0+}*dNOUR?zy*&~o7uo`u^_zbWbJnTiA&%u zopydmu@0#R{HJ(vTi)5@HQUn}E@URc2XdA#)YB!O_{$4Qul7D!#RTg7Edlv*BLL?n z(z^;l=V(G*ui96O6>X}Dop`Ib@cm>1ZS=u>9B3Q^-!JmB{sv=-iQFZ&OZUfdpgZwMjg|UXI!L@`HK9Vm+>Gs;4E;h z)d$vF`jRk+)TRC_%*4eYvL361X7BS$IrlQN_E-(1&0_T1`PG89`YmG-{`VP4 zOe&-{!tH%V?Z@>yTibnd3SRG$o+2g8dE4^VfoEW~yxqvXil1cL1}?Ff?c&SZGiq5P zCvBwmyosg=UxQn0Ki?iLFHK{oZobz+Pn=+--7uZqBFrY;Xr|H~?G*6+f~``P7qUdF zdm%@wg66azwK~7bK5a=mIO=joyX;`QA5_M_4XaOby9m@i+D1QdRBY|f`Zj!dDj79I5~VZ2NyJRpGWJ9#$vO z4_4o*6a1U|7Eg)37-wjZS0VH|&f}JGN|hk@avyZ7w#xVfk^#Pv*fk*q^Jn+Wc`Kc^ zn`&xs7lmqEP=0CFtG6ag+4JpxulBiAQ{(eEvwXwHt0BVhkgfau+(BY|^u~6$o3lu) zNX`8EQg{aHSS5H3wg2FBX3RFxh%nwX`D`tSSAstKRA{ufEI`-3euLDj58q%*KXQ=; z4qBM-p0oi4>^d15MB5S=b`)G|9z`-JdGLbp#zb6Vh{Fv}_jmDvg6ZmLKwd=nw1w&K z0iDEUVZ{cMzTAb+`r(2;m%<=2Wzb5YD3#Y$0kW?{vT0m)sjmwm39zK^)vT7g&C)`o zWU-!i2GBmPj{kFP567)r?Aj6);jV=s+_6E76`LBk@?xt1oTF}2j8NVlZ9xxI2wsLe ziMz^aH4IR=9QOKrwN4y9_0YDvRJ`gb=WW}EkBcT2(DgSt6%;Va%#~;T7cCE<+=$nS zg8Y=MnqJ~q)&d(JUTU|a*#15H$ZDABPs`)E&T+Un1rQ#zibdBQ&96t(7KB4wBplFHuGSp%rtzjmZETqKvBMlqN z+*|4WdomY9${hNFVW$ouPVnp2^Kg3G&ob4y=JL5Auv-y=TaKHYF}}N^>qyad?Gm$Y^+jPt^|@4pZ$Z9f#d&*Ax7sQ-M6wYnpYc_~os{o$=W#Isad~D8 z9SYu{p4)3qw@((w`2NdgG-Io(?n@|{Jaoh=LQcz{o~y4aW$E6}@7o9JS8yVw4kzeE zICrH!w{XRsSSlv`L7gVjt&YQzG;B244$ZF!N)!HNPWVV>A>bZyb~axi;`6>1#;b#DuXzV& zA_2?7I`)fS?6tMJ6C6y*t<}5B#3od-To-MazVDr$WBnCgkCcPSapuQ;G*Ab3>ac*V zyH#=chgguc@)Edq7rF1nFP}Yv4f!M3kU%U?f5Emv$Xx zhK`-=E}bjbd{BKs%WO@;du3qSn72i}`@m@N7HI9c-N@TIb^F{8Sy{&`p`3{9jd6II zz3~-Tiq4(Yfz(+R_m_hN>*}&7OX`tv(OdV-BXDe4wtYY%x<|+H)KVI?a5f-8zi53|Q@m=DSd;r{DwXUtAuA2qtt4z4FIORoEU zlS#~va3a6Y$Coi)-(cqMdwU7F@*kC0E4Ys7+M}#*T$kR?&dtRjSgN~T#)IEQf-l!D ztChu0;wxwxsyee4iu#FRg^a>8@~5#yP=8)gO7J_$%>g3di{JEDuL796)&dgQ&$L&1 zLs&$gp@l;CkAA#nMpFHp_!NL!uCJ>j9bjJ;r9jxt=Ga_FKEIh65{4|8D--(;i1Qh1 zX4e>fJ1yj^DrGP%5RhF0Z5`TgZ0ncE$0`cJ z5sAy4H~z=g67~NNTQ8ZW>Phg}HM$SAb0GcWX~yh(rW-H;ZTvcH?ap|Q|J;E3NZQ=X z0NMWIU;O$q6AZcw^aNSd*CdYutq`V@Evg^(A3?7>^BrGmJoEi;(Qy@CJSl;+%}#9m zMC`dd!uoK3nn7D9;FcY-jIt88H#!mg_qtprXPpzaiv> zY~Sc4gY!E%5!-VGoRcWiP1K|MN|IB8sW00(o#)i9C5+d-|D1jA4%co&Z5Hkpm^xdS zeqklnh9^}bI&S((jWvE4vX?ui|9N^g89zGedUk;3-jT=sQhc_)NVBTP2h^4z)p*d@ z^LTt9lS-**ua<;NO5nW+bIRw${FtVWpqbAYAUb14TFjgJ1aYVvhlhQ!Xb4(P^`F`?|?4g1R@M(%qI@9HJeV_up z?SQx08JIdtdc#aB!)9Zk<9H-4A0{>wzmog=JvT^^9@1=vn~?-DeWxTVwngR0w_$x% z%OMu<0n$b5ozHbu8v|?N6{Bbr;nZZ%|JcV6#6deG`#)@zeW2@rlb@hSo-WibTX!w- zaK+=*rurR^+O|sVF)Z zKkGuv?f@u?q_q53lpB`6Vsqa^jt-mZ8DDQj#5|Q1Z85ORIE@AS_fdNp=%Ui9ks6}` z%)a%x>e`#~S1@mdO?CLbK3{pR`d=7r0beG$=c$>M(cMjgq{)lY%f@_%9+~J5Rvi^x zVeq@F{eQQ)(OL*~AzKf7C*>|`T!qyi9d`U-;0x}C;Qh1N$JM$%g-EO?BYutzioT=i zIf-Qg`oftZMLaOoobDcS}PRW;B&3i26pbu4IH!kPUzC&s#(Fc6DUI>n3G^ zA>RLE$Ue_JqrLpG!;l>m?p@rv=|P`{qPM^I10`qP6L-920DBz%4+~(cUJIHoyHi0U z@-^lAqGvCT2m8L6beKZax5S;;=$*^`+?sxQp*cDu>sfiCAnV(^$(SXlVwVxCx7G=N zgn@rpMlS*zO%Yz@MC?+El5_# zm22=0i{V6Zt1mA6e+=g>t_nXrNm-R7Pt2toviaw!@em@5k0S>3e*0~GT zu}h@l4f%}puNp1-!z7R|XO?rMVPZ0+2@t`xJow+WEh_H)<+~!0q2o746&(s@&fJjJ zc->U%+xy=p}hpBPKEkO_|f+4 ztPm`6Wo!vLWT4$9YZX7&OGx!4s$she>wUY<3YjYtYRV3s--$j`g3^K=Vf+e~#4oxp zx>;p+qoudqJw$uheZMVLfl~b7bm$)w&gSSxWNgf7x z)HN1$VQqoD#L4p&T-h}w<232!US)&Qk>Jz^!tm`H(Vx-GG{C&{%2z3IE?DB_1KMGs z+-gM@hi85rQ&q$dB&F0Qu~SP`vV5dY<<;qrg#K3{; z0KAZkno*g)kptVAFR%!!qj+u;;6BTk%hhG5%XSz3K&gfj`+KhIn4N+Rdffn`iC0A2=nvoXOjF&c=i^v&mbV zyPe##klCK8FTP|$#uf3aq7z=}?32Oc9s=~P< z1n33j@|L~wRTy5vS0MCaVkfdAwN3uv)9N6~zZM!+kvEax%C(qd`Qh;O%(pP zE)F<5t_!($fo|=J$y$-5+Nc2tAI}KAHV+rmGsUk(W8?5(G4AN+jPt1xUzV))z8EuY z5sZLZnmtv1eD&nudms|@fK%mfZBJraG75(r)6iNG3CkKJNz3(i^2C;UyX1zt!1-B` zosxEO&~931Jf$DX3fa(|ij=~3p8IKc>2TuAM0ndp=)HW>MeRX3!LvUG6?t7Ab7d>h z=)KRBK;Fe;aQFP?eN0!R`JTyEa`()_6} z$B+%+j2OMI`F`Tk|3%n)$5Z`=|Kr90=kxo1|NH*y@o>(4uIs+9`Fvj2tyi8IS4j;T zp=q2B7kPV=*AY;?y+v|J=-3iuhgf}p+oiGX7`udwEE=~L|J?p6aQy8yAS$I(dO*JS zkke1|TJhS(t|bgs1=$&`@hR9Ki&UrQ-=>@Y`bT8*Q0dzgd~wMmWmpPAs#_0HX@1ll zMfy&$sHoSBac$!q*9fJKPBtJW1PN_)kp60Q@|P&Ma$a^W5XMacYVO4^r;36i&)$_+=(W4f z!Z-0!wSS4!=?<0pd;Cj6+5ca^gpZrt9D@OJ3!C7~w#f4Q@H36%JF4T?llw>6FvRh! zDjEDBq=EGu&O^KV*Yo*}U6z<=CQiN5;)Ijg?dWr2=xVvu$w80#{sH{J ze%d1e%G+@r71IJ!3an!4DnE2|_`ur7TjzyZ?YwUqfbbBp&pv z2a|X;e&N!aKZVlz)8B{CwMQPSC58Jr%YJk750f$*1g-%^mBwWuV8L8ynn3tQ_Ggl- zr^?@ZFg7ZOwPEM24~4T%6F6m*k>Hr5@3&Sn~GtGLaS99~Is79xm0Uk-tR>iax00<6yQ zqjRD@2Myl_$#f?$AZOCvzb^;IfK9nE!ZpugRWX{~UPPJbd427H)oW~bEa7kGk}Gg; zS0+|a_xlA+ls7(l_rX^^m}o!ITOGf;TIn1a`s@KO)b=WDYW#Vf_}d4y`S) zS-3E(f`k4Y$z%rXcb#K2ik12!OI@-y^u_sr*lvXwF*d`JDupW^i{fuBheIU_y}q8j zqaUs{RUOf)v*Z9+x@*YPv$hu)kuDFbKDsvY>Smdo%x`&dm}&>W8*AZg3*Hmt%6m)? zY`olg=l1@3J9fPN+G+6hrjw0jp}X0j@vie@-l!FWuey{%9loLw&HlQcVfM34ubi2s`y&ytp0K@`lr36yZO8B+r4kZSmtHwhrQ7+o@w)Jb z5xe^Ojh+-q`8-8H&MP4oJ1&w%o^FZDbOb9P5QBLb=G*Weh6BY?N7|L;Tq&{jcg#Q? zx9CQ2-H64PT3>%%VH?E>^zN8%(sd``>uC!+Bg} zuqaGy^ULcjGDKO!c-;n*bkl6teV?J;!t&7>qQpVi@O89!_HOd=B0Xy#6* zJg}sDwm62t1hDv$TV+{NH<-fT-zd4r=FnkcQCWAoQ2EE%h{84Tt0}u4a;iE)-+&6V z>te3Vmq*F>b|hGScYg_(9y1@U>{4Hs8l?k4c6995dzpXb(#L~*@9{;g7?&Ea4jdnv zU2O3_;6lDJFH?VTC0rG!AyORk2c!QT`_c&-p?VXGedoHuk2FL}L(JyBegSG_K#5fA z0zG!>`j7b@FtrA~^CAMJQF-HSxa07_xRvIhU4s*EHn$_OZK$QMBkQO$ncLat;zjSz z9Y8qe3cCoi$|?^!&h_S3Jhej~9^Uyiyg{~1EZHxer@O^>p$N?K&W&@9|CVvT{O50$ zDGtW*S-HE#Qe9#qvD`hmp?8Ms(nL!5GxA*Yfd^&<+Wz^xuQ$Z<3}F)jT!GAgS73aZ ziS{WoXbO3BNwVfX_eAN^t8$_h?{k%p(f`E$nS&ndaa|kmxkt~!#5~0WS50~vA;jy~ zA*I;CM;&OG(WkP8j>J8iW#%!nJlgfK-?GJ??_HbU8uV9Re1rkAo~3gFJJwc{3bMBz zwBYmg=|t(PEgn}V=88=|_c4su&<~0q_ZrU669p0H(guz7gAVuW{K?PDivZyvfFrNi zf2`RRoWViOo$eUi^Ed9Dk|X8tkmu)X8p9%A_E!(tWpiJz(H$e*d<<{kFE%{(^FXJ{ zgW1-znTMNfF9=o&cjjY25|Z|&%1N5z58=y*O9E4NEtg!a*uKKH>IVw|AdxTw()zKB zg)Uuu*h-YACU!yAf1k*lZ%V@fYLoQyk=W9bvJNG;=(Sl8{jaE9fO!>ZH%6_}niCgZd-=M7Z7iY6fC`R93vG;)fI`kQL zA)35j5!#McOl*^@CvYkeV~-1X6H$g#Uhk(fB{i`wp1(0VZWDBp+U)bdhjZj!nhM_ zx2X4&@=dmQxXa%X!l=f1kgizp?{SitZH=10pfI5@(JAHq_v`HyQ#Qdk-w#(ir%M;E z=bOgw92(!3lMKB?nH_Nh!i(Iz#UjSxfSe6_t3exF=&=;ELP7DxZJ$Wm@l;qjc$<|AuGIO__!-%L{_qA{ z&7jxBy|`S-vgt4VMgI(Fl1Nz1N$0-C?1Nb_&Sgb#DtnVEM@heOHL=ipah9?{~X* zFHnv1ESYm!&tNdyLC12%aePnWexuxK@MYKAfY{HWE}m(e41d6gM0{6~-V;yfeW`WU z#&il7zs+7+)8&`5V&;LuCOUo_CX`-AKa9I5}xtYuJEOJp*Y#qk=G%w%vU@{jTR;tWh-n( zPov7E>J7@|+Fi8WuWU0SjX&OX7}s_%GLf1HSe4}Y+0I)LDe6Db>nzcK>b&6-qX6(H z57chp@(7ba-dPl8d3iT)(9%sbXMf-NFG%&~AcP?%OeXmVS zS_)`Ynf$}I(E2Ff_BB7e&TSCP&Tlz0lj^i`2Z$3%AP6b+?Tmmc7HHv)Sl5h&al4mC zAV80v{#;cRnU!;cGCUVio?|{UW9HNzep$ajZdvV z(0i?}Os7{fSooi-Hx#yAx{_9K69rZO#oHCt7t$&>(d56N3*;fY5#1xVKBXnjOXb!V z)4mvh4~r}zJC8B}&(lBm#0$lBKNY0a-^l#O^ti)Z4ndU`Z|1^t5A{wLywX23D~H7| zfW@9JTC%-A_m$`!oe(Lzj&@5e-wk2jcK zgbp~>%iCx9Ue0?&ZYk()<@}?63NboH7A=L)8|{s=&a$ir{p%TM6xAn$-O_02qtUi1hE{^15@DPM=Z4rtto8Qgz|XmDPQt zblunVQFi6BUyk1H8pKoWeiylCpyK8pDiww=+F8}wXTbB_yGk>J(Pdv6A#JSp$900! z*iTcv>-69DTAT}s3VFL=7ohi0mvYyG6SN>2co}o=fnL*ws)RxOG)MI6=jiYL-ev2O z#^v90xtIlBq>L~;?PIzDEsrZ2iU?Add*|<8l?^()ykKRGaNn3lx@>4XR^A)Q4Go%> zl-^XBsO-u}6SvR5{7F!V5h>Hua(1yHJ9b)n;sx#B&+nyUNG*8u=n?jtWtDr!RB%E< zLOl}n!ouHkZG+BtNeNE@-!5h?vJb9`ffJTFZinqf%e1)+i$+J~Kl}37YlxU}@!CbQ z+bQ_aSLW074Emg*kGOC933t8Ko}%g>njc@5k##TL9eR3MQYOMHQgJEmeRx<=wDCcG-IEIY4k^*jpSgz zq95(^X>x??%NySht(B|811}m{BN;sen?l`xS4LhBrrxh{t-=i``pma-|G84%G86}uqL!Y%}yE1#%Zfwup+iHwLHLHn3tRLgz`ch-naXNZdX}5>}mi)6B zJ3?V_V8N{?uEF~040@Fvx}#xVZ#?q+rPkP9MCq1MX^AJISyF*kW&H89&g5NTlcFfs{5byvR^Cx98EBHcKTSoY zI09jifGZDrzyESBE$|~^VT_Ng&G@qKw`XTqERVK}dy{H%PLPE1(*+Ps)ao)(ICJXG z%h^;ej)rZ$LYYxIUSIub55a45y;3y1o|F(Eugy?X8{n@QibSP3O;)CFCIvkRgLzvx{F5yV#XF?&beMl%L%NPOKIb9h^)gUeI4w2^^U)gw$?Q#Cg)GLNOVQ?#FcDrLKHr?w!_8OJFvzPTQ}J(ES5 zTUo+~gEbWjrVj#0eJ!i_*#QrH@0J-BjHEswnX*vVEwbcU%Q%$?&NvokYnh+HGeam7 z*YyaZ-c)i;6zvCqH#!b_9!AsQZ?I8KqlwEM#y`DwMpzbYV{=RRt_>NuMnU|>`c$Gz z_KEyRMuMT-=QVo8#>5{*cYbAmaDkqA(|1QV4>k}p|EXU2Y9LojlLzEiu1mI-r(We( z80oFn6tk^+TeMg92I+fNlSXnH`zdM{7Mq%>7LZ<3Q)52mXlu*pqx5VTH{k3#^#PVE z5~Mdg64A&l?0GuuqxJTNW^ayODs|jm+h6wf`v&r~dSMvgSb>A&d1kBIDmOuVr zC6GLi^8KG{bc!Au4P2vBQ++8JzPJ@!N@tU>K1}6tVM_mH=*ss?elsOO%cjkOpnmq( zrP6CRlw7S5%r2PWh@C4>f00?Dg|OFLmr|~~GyRE~H%k{b;b!>wV?AcCT75z&nw3_g zMxUlDbHR3c59;|yYTZ!`0PE$Ew(0E z*Ow`6BDa_X+EWv`+q8H0_kZp{uBmY*I6Zy(`2H8p+o0t&ZhxKEhj*UkYAxHgzERPA z;vY)_Jujj^JCnct7OZc>tnazLCrOWU`;`(l<srw`)95D@bXTu)pgdfttMO^g*QYk88OBRwKU@*# zVz{8DKYx;BFs{;SmVUbdcf0eg7C-aL)(Ysbh5v&}4`2;(s^5`+0^cW#sR1Ue$q3t; ze(ZXm2t{>az1GRm&yXSbtV_cD8+Fy%%F4^-Tp7QrzI@RKk~nEti?vMPJ|n884K0wS z3x=eh+=H~6`I_lOzdUnkSy`>N%RM3BrWash$xEW`;&wXAiTv;xfIXH2!VHPMeo}xd zTyBPxF$@2)0fCqBx4P%zEzHO5@V7S0doPQLITU2A39oGsGe*r5V)M!ofjxjRX7$-! z;~`CZh1wV6svVR4*X6+@&e#I8&5X=obbC(2k)#^UMy|&_TQ`?7ymURj82NV_=nKd!)3Fs$O?a3cgW)9H8Ne*bke>UFa*0%E>7P@&Gp z{2ik`{AdWHAEdpTsME8W;#CEc>eTEI?=V}+Pr@%!m*?PUZ%{sbyt)2!U^R2i*ppbc96^lhQiz{vQLnd$N-)wMxO3%L8n z6h@4`DMQKRzIL2mjWOF^OS*L2vly|}v%a|L{9#@Y*6vAs zwURXL2^z%-No1_xL~C#EDj7;oY}AocJR=Zoxc-~ly13*PcH5B?#slHt{Q>`wY19xC zWWptUZmiXY$1|fe=1ciVC^OfxLBGZ8nAlJNI%y~r=FP8MiMaSLnz_t?MAUt1t0-bS zZSp5xG6-U$>~d-QN*&h;y6ij8JUrIlP?jeP@Z1=6S1GGHQMDb1fa$fO_wsW+0JLct zwZ-^RC=SqT^9+a+kM#c>iJ}dDWPyu6x4sLp`=`l3&N(h zf8X$cxMCM<$c4Jf(MZOs-u7m5sAso=5SM)?+-x{5JObSui9u@oSj%_M0PaQr^_sNw z1UmR!^R>spI{vn8*+o4sUkY*=t+_-AKV*KUa|4=77Hk{e=k(c_gtJiVuc6yRCDk?` z0V*p6t=cG@WZy{9_2YI(nNDBJua#0`gmO-!yTT*TUBnm-rvsu?S$X-?+E_&=-zcWX zJpr9K^JDhwNP_|-OGTQZSmwMbK>8KchQ-y>3RME10VpTo&6$JW@2NxjKD$^I5~0a{ zjKA6?M)Rl+zS~&lG*X;NWXG_PW_GXn>~wIE`r4MdIv&8GxIXT#trQzYBx&3Y-&+>k zWu@zXx8qGC?rlg5_im;J38g-FPzrVNxk ziv}Qr*#I(sX#s&Mwft@$9uk%xm7~LA2UU?22gZ?1#ec9k?U8@LSrG-SL0jyr`xhWD z0#-2{SiHis32XV28PW?Z9nFcngzn3U*xgQ{b$NQuXr_+v!J%qlhKVsleM z((&4Y*BXeQy{u-ycU0(Qx||~`ubxB=@{jkwQQN!~KkW7Cy%~7It&sWQE4o&v>8&@b zf~yr;(6`HZrvdHS-4gVjB9ENyl!5}8ww9prpsY;f2bcvgg`6{Tr)Ga^?dtS=#6(EB zoOYuz1JXZ$S91^r03ViQ2?2Km5)N;@aB_3X25n6TlKe=&SbH)wY6J9Uo=r{0x4HCW zQF^I(4M;oU;^5LKaQoYkMzMyw@TvY^=W5(xj}a9YPN#plLk|9CKo4 zm(}(sZ?IG!*26a_+PfOaC8!DjynTQdVWDaS67&|-?HjhbyzYb%s>d*!Jn%#_fx~*A z0VZbT!2vYAr+7-vI6tK;ZeBVKxnHoE#*K!^8Vnd?CqV*xuRN3;M&?vltg;lHf46!} zICTZkW(`?XH{_K!HD#PN>z^7OZM;iMw^YKV0D~A{@UgXtSNuq#ZfW^uWV9B`g|pYf z&c8Y!@GgEzqzH&z{L{1}JrG%l`4_(?0`co%ZX;yG2LNxF`GXThz2FQ2bb-QXd-0GB{A0{7tQ9Fm^c(>IDsj@%);^*`okc<*3#@On} zb%_o~5e`CFJQnZ(5o3BvP5!90YVT{0M3+PWJ%uETHmz(3RYICDk}dW*!PRQUSirUd zsN~aaePkPbrHkkZ-Tp$MNE@d`Wn0Gq4>ZlbN5k0$IiG=Fjth74WI{I=r;DLCbzq%{ zJ!Sk_K}uI<5=+_UjL%tH;EMlk;dJWRh08-lvL|B$xNRuZw-jIj@`D%NkPHdp==$_w zFcyv6Mflugctbu#pcn(|Z$pLlyJ2$j#4DR|Il5iExS(b}4gYrcjBKR=PU5TSp_BNP zr4%gWh-gNl)fnLCCHAl}8WEylWNp$=3Ob`ciqk0rbd**6EtQqnPWZbQ>a1BCVk*F& z6(4YBL(waQWLk!B&7e@nx$&6pP$#3qHlBerYbD$P3PfuVMqx51u>B$1pQQm<4ob~} z(=XsqHimosU>@SEmqQ&M;uOEDEn@ihpSsQg_-`19=J`iA9>~?*ZF_KAZ97(0z0$?( z=eI&zgR0&I_3m7NfJTpm&|fctkAsnSr!=IC9p{)VE|PiUIg%>pN$f>JD4{;A_a2nv zgX|NRdGmHR&f=qTpD5!DkqJZHcj7wC#q z3EU?NM71sk0s>jfWw(D(iSR4a$OhY{vfXy#Uc@ z!+h%BjmZn0wZz$Xt}4*l!09?*as^nk!J#2g#%@8mc5+xBUWycf!6hmQI5mQ4?!~)lLFrPP-Tg z)U#n{&nvw-B0H(^Lx_dBuaSp(DQx*rO8`onKgdqSQ7Lt4)0Lf6V2`^3lC;8#ClvF@ zOVsUoB3--nW{B$nM-CerR*GUqe9F?8XM-V&ubds1W?t72#vDmY;Dx?9oG_tE+n;*) zyY4CqQxCAL#kcMO5UA1iNoTe4g9s00`s90`(PX0hIz}}v8NwFPOI1se!q})uX?Ee-o*sV zdN=M%zV*j8^6u;jlHTF-9Te2Xcf`7GSH$v6dHmmR!M9KnAbK&?()pftPZbdDQTAx# z7=|{-Kb9GwEl@iprbaSK9f2LaR`GpSqJF3LY5wB-u|RhzSe>oW5xxo^Zd{zYiq6Mo zX^UY498XTMie*)yr@PyEcd+|!YlLd4)5s$PX*L4VG2iUmwQJppkAQMDq`(r<5r8KQ z3K2L#lY+^sRc6y=BFv~obSjj4J^DXWGjG=dq0+#bA{A;vj@ zg;JZL=_8_q0P5I@0gHNPO-(WMUZ}5){|>^_scKyYN87D(pYb{>b}g%XZmeleOrs1O zEMfm3kANlGYF%Ja6N)MP2qzB^B2qI}m}qBCw{V;|3W~LO3^ADD$*lZ!U?-7pQ*r)Z z!Q%=GeGz!F5rSK9OLSAo^$bI=AXGaxn&dX!B;_xaz%JLXB>J0v(*?Lb%|Jb9MCTki zAw@>_#gE2!Gs`{P8DcSZ3}5vvJF~8LZjdkk_;NpBtlG@=Ysd6Etu%yLeo@yWr3Y7o z4$&6{y0&k6e;Wt4$YOH57&$3k^Mrz`vSr!~RMni_rh--nS<$R(!=bgEhYc&vG#{*g!1>kQO0e zZZV~6ZSut$A9b=0@G5}ZHa5t?q%KT?uJ0v+SS>mK5<%Hs;7{z!u& zMsh(sW(Y=lHS7{e_!o%akH#EjQnu%~d=6$`j#X^N!snxvu|B%Ho$S9&N#rIE zICU?cQUZo579fv4PHpW?Z61x*Np6xSD(boZk6jh(F$vC!CRefxHI-wJdIP6*-Af@CG9dbvW8?X?* zR7DE5jnHO5>Mq>Fxl(M~wn6?EG!-P!8yTyxX(c3}ouk85T*gVa1bmk=#=|Cv_I(WF zfc@si-Q_i{;n7g%*R!TcsH^iKq^kHXe;=!{Z^GU!N^L`Lq^-i*BcRUNK;^^J;!`&NQ4iE;g{)LR4y`kttvL>D z>7eg~ROyDn+CDZa!gu2Z<;Z_=rhVhbJ)u)o9|(wb;IP%&X5!M zk%5EUC=495s!B8`02OCalp7v2O8w@Y_px#5-=1i#<^BH%*0r4O|L1WKzMo8>Z;=w5g8VVb;~u z9C2x;%6)fpN<%Ip#zT2FuO1kGJ=sDHm!JXo?{ST%LmP2s;L zbQ-fQBK9&N!a8hbQJ>eupAq>Xyfqx2pDWMSX8~Oi-`vaDDA-rFVqV}+q3zsN$sE|s znl@j^X)uQZPclj5#bLa|dtBdw@kAC?XCRheXEDYtcxLQe{slFQHsgfdnAHnB3jq)8 zons9j7XWosEthHHl7e#N$qe(JUC*?-yB21^M*B*O$%W0D<)5v;3^f~tmK-8bm}r+a zoU~C!Cve}3r+V7eXfd54WjMfWiNiwz9t)7xp(|1RNHdQaFnT}KOf%WLj+dMPFs{!r zAV*5l%YZs%gmZUlp0yelOj|7QZ^I3q_NQ9Qi6OThodckS&@t3reqF|9`)oLI^xGP_ zxw}aWjAaDo&g4mqIJV*1@G#>ei)q2@&a_zw#*H0%@D3gX^XIowccu{wpsCVc(@JGg zwb<=RC3zv_veBJ0UU#Os$Pe9{+6*={AIrlgEfkH#maxR)dZ!-w;4a$X*_p%u)`s03 zv#zoO2j`r_nLn?~Thz|{m;fUr3P8GxW`r`m-TS)%w_3bXKBoNN3euFmNDe>E#N^65 zf(-2l$}e)Z7+^+y+dH9io8vPWRWvW{%l{yTiMFy@doz91PXA`Ss`?iMFylq7BOYq> zJj`(*FrOc}mXg1o$De*1fEO?8UC;%fc;}ZrGkJeA8WoA5EiZdny`6z2snJFwhNVEI z?hB_H+C8D~0WtnW44U~VlAm+Q1*AfESt86oWA+o!=b6lMJ#u+3PPI znBu&UOKLz_qnVhx`Fc4~nxzD%T!pFg)Z8c6t&tA~>kbNhoSuh9P_pVC5SE(|PKVRn zpO)fl$bVIQ4!W(&WMw(mM-up>GubFwk?nz{4NnC$lXcOXC8-iskFW!8;AO!$`mz9A zsL#w;y^<|uMM63q5$xZ|-o6n7Z927iz-ZIB@nsv>n;zEtYji!}318kt^2ED{5buz6F@nSD3bmicNX13;rV=#t4;LPAr>zQ^{+RYK!MRyjeBHrS~T&xI7 zSGj5!-ASzvL97;AI0k(WkZlQhgef5JEpgX=cy%a1xWon)1AzPNZUQOpaU>A=e!NKKbEw=^Z}CKmmxG8cp*pEA{Xju(>#HDuDcJ!yZ1l7Z)-){{p^; z0}A$U)K?B{JJfxabx8FP{TXA;4Ous6`;RC2qRal4097&ubNnto0sn9ST~wptvCiC@ zfN8^2{>5U8fQ)t?uZBA;R@t5OaRO>#vGoXMs&x%DjdBP%dO{;%;iTET2`6~Z4WJ5i zR0hAn5Ka2zWxs=h2X4k#z$_J=o~!ORbJg-VrpzUdQfFw^K8yR@_#$=u!2wu`N50Ix zVQar?Ee9JM;H6v}AeF{%FoCVBn=je(gwnGM)xGh22}ZnX%kk&~5WG>c^e^8?5igP% zPaQXIwRV_oHKpYVx=}*PKh18PQ#KaJ75dpJ9|JFD48fJnamCMf4wVYe2*>(OzHGg; zI2u5my@xY&<2SQ6APVU|elp#g)X{xA%ud4Oae~de=}Lv zmh!m-;NSarj_b{AiXXoeG1$)GLSfA?;9g)1$hKM(^dPbrH06o#o_e3KcVO3sJBXM1 z)27jIB+oKhza5_jB*4}`1OL<=c2;32#@!Qi;|R15`=OVf@3r%~XP-q&?V!ru-J z3b{>()CN6DsR`W4huc=BIini@=xTNYP=&~GvJ29F5q&l`p$)z@G}rw*7jY}#iTxB4 zE&q}Ud9!(F(q*TelRFbsg3~A&R8uUuHr8zd4Bv6(jM1(`hLq>EkkD8 zwN-Kn%i7x^7wDtY-`|>n_(0XY-g-)`KP}q?1zd~J5(y)QacvfsGd;y4GpGCu{)ns1 zy;C1n?Snso*jrmzE0e3+dM*(H7FSZ7sz}~wZNO#Zu93^o2OaFHAes?o&(a4!Ac1eq z5ic`tSUJ!*h=Brq7;FE)TV@R2%v8k7sZdCr7j1v!NRG90q6@vikCd*XzD>)_kWaaE zAz;N!tgEJM37ex^nq%?;)uUdETbrym(DW~L2=_*BOerWY#LY&fNOjgy@Lf%uFhwyN z3NNXm1mncMh7;Q#)`4i=e<42(=LU#KzUt2bm_1Mu3JKcs0rJeAjH;vgcOY7Fiw&?b zbkUKQYze>_YO2mSM{Q<4Lr(fI#DD^4H^<{;N14k|4y zEPg;%8V~l#-I}y(VE~pWw~sw>O0^dukdgv7%+L;7eTSF4P{cD|@GfUPG_-1o7-aeM{typ&wMS&?bFzA6M>5bpWiY<27DHi?MHo%e1{za z=cjT~ek_(UG32?aK4!KJao`t8J@?k=G<-YeJaNS^gQGpjuzZZW!jQv7jp5?~%cf$T z01sAV%5XNv@}CKlFP}#T35xYJ`6o7;J{C1_0HVA=_4DW-#n3SsvqiUtBg%+8(QmTW zDRkn+n3&p%O?(?-Z*9yjfXPTt3k<=Mi2%L=n})_NjbIeOkCYZzYYwnqVTb8s7-LNa zVaQ_Rh_9HV?(AW0m1Dq+GjV9z08f(0&ZzMq;gd=bLu<%g3wg!kV4&LFh_(Vy_cu!s zJ+m?VYS^-qdj?avHGT#T&^oW-krDUUXGq)t|Nu?^m!80$@VoTQN z!udj!Au~5;dNeED)~%JnkjWHVJe$vK>6%ueG)F)_zALJ9mGB`%BXA_ zMGNmq&s%ham%F!GT|Y{r>;UE0&XnSdMdILg`v&O_sX7%n2IohSX=fb!TO}0em7p4e z3g`jmvZa9NmM(=cXQ=IV)=#dV99)c?iSb9zWbOsu*60L?A^#|FC zY60sCQBfo(r=UCIvgQ|r&RuiWxqy!36AwEZTpI6+)@Sz2+Bs%!0ol9&Lp4N^i!4Fh zf&4F^slzW@SmSUXwpa2)wi1V*4YU)3A)G22k`ZG#Y|I;Pos>vPWqcHyB znBswPVdXO;-9^d?rQ1K1Tx>Y5aMEWgciwv7D9#Yh!F)|Yzip@e;4~v#QvMYaJ}$oJ z*p=+XU})p-R?Dum5Isy^1fm5>E{4oxAO6EAa8|TDYs@;3Z13aY zVHgq%{%d5ErUG}yZI`RdN!(?o3dQbj|M{tYvrahVt8lQ6gD)04`3{k5_BhR0v&J@* z67>LxZ_Ti~d5*x$GCNWgj{I}1HULe4Dy^PCq3P(S_g<~+Ho z!0!d3X58gaD4o39F=+YQ$>S^YOW=OXzkCN!Oo;z0?co2UZHg7SlzkjPZ8Sn2xn`Eq0nMAP}AS-&;#vRhXRsJmF(_zWketywU!q0yPJmz>BcaB(dj$ z;2)~M^o@a{8^1X7zF$%;@~fN<@?;EmKf#(Ou-k!32CzO+arGZ^M!9g;P;W(^a#y^& zatOo4{QsVnkscfT5qOJ;>*GM)(4XXH(^ta<_}q+TY=IHFe5>OQb`tFuWK%pYMF9ZO#LD6!;3<(%$V$UwG%y=2fwM* zB@DnK%T)7E2O3R48G;v2nAP?V5d0M!7@Uo0uXa`nN8J6$l~m5W*xLst$Kl3tj_9Z2 z1qHpF=RYMxuUia1{09<#dZw{X9iY`*HJPoiIyH8+%m&n9c{J#@_t|xoi3UVV{wSA` zH+}a@sPXG4Yrfx0GTsVl>) zPGFs!peLlD!4dpj?F>p)FFI6&_mg_!0K>vb{~m~Cy0c*%@j>718i(fAK*5KS};=fJZ!RftygeYmbYu_)2HzAVH-%}fTSi|_tr zwt8%yFlJD6#Ch%XV!-OdK6bI!O>eJWHnqCtQ5RcC@Vl^Y?tw*XP2Lp6D0qAUP(JgK zbW0r5+-dvfvFyNl;D4T>-0|2mFoxb;1yd>0ANeqk=d+EsDvJ4@zhDYkE9nx62msA# z$q?Rzyx~S)hh0bZ0Ts?#{C>r1>Ad%tdcayL1+Q!)4@|v_MZdh;F@6?J7B**IFBj}j z&{%dJT0MqvUttglr`rHS50Gawx3^ZurWJd?>vqkqoGKf?!FMjb`$T;b>jBh7MPIpAj{)=%hKmiZa z-v~R{&)g$l@2tj0e)VyUmEDMV(i_9k3!exb3g~OEO0$ zljX#KY;ayowC4K@dGy+xX`IV0pnep*VOKve)KvittsK)Qay7{e8aAKCAQP_9q3|XTrm&m1iDYw*GI@S1T7iHsLgNHi;!w z*W1X*Xjfo1+TUys^7q7}_X#KS7Dzw*mYjg0o6$aLdzz5&qQI6vZ*nL>xAWAE8Y*jg zLHW1Z4aMEwb(@j?_3@yS#h=qV@>Dh5*PqN0{25CA_QSk)c@ZWV z|B}bgXX(2W>Z)XS{Nn!^oye0m!(}nz@JTsWJzWig*-(AvA$~96m`V)X8E%jaSeOv7 z)XfhJ6h3>JDobvICy<^;ZV+qCOEV1yLh6~HUAtE@>{Q-lrjf4ufwUXUOuaTPlP!sI zY+}tJ3^X)C#7c_3bMd=-2hF=!tUry%T)C`Y30Bk8rwv(`1P(`6uRH)Oh@EyADK{AD zL)wl|Ac&w7=+z0|v-|)PQfUVtWJET;A`8Rt_mU>%JRVvA^8fcJ@i%}L;&eTbiCwX; z%C4OUD=0Tc5I=D4ewsE+6PtRpVrtL@}k~A;S7fUnwupvDxfCl{aYphMB)GM7?MbAYEd&N^*+=>9sE;-UYU0@`p`Ch$++ARtf>N?1mul3_61wcKK+Jc)QecLZCmrQwI2s=+~%k%MQ zq|2I!ITl=RtTWFSCYsXTt+B%zi=W5UOhBRhAQ{*rF7mw9yF@so1{nKG>a6BoiGu)V zA{w|9JC4gf$Va>SJ$lvg9lh7B1~da7Tg9IY_MUC6-~0By5u#f7r@KRSIlZ!~klr$7 zvUERaRQh`WcE`P zvLzuu2ugQb-Gmee-uB-Cih$+t>s8+~&2S{RWQOuD9Y&wBIXa7@7iqhn54 zrBYZsOk>ANPANgMQy?ja`5h;NMF}Q<>08lmsdU7U=lEuU5YkGO=q={Z(#Nx`%}sn0F_LU6^`bj_8$Xa!o{?3bSqD~fAt zLMQkD{&QQMlHcY!u`ev~8bF?6S4al?Z{g$1;M?le@Wt>6b%3j$E3NgN}`GyjfjZ~~xbxZy^az(R*>cyN#< zxEMPA1k(C++|OykUHYwEMw|XcTwNpNe68_TqgT~BzD+YXGZw zpg#$|9UaWu;x(xowqL^hj-A0`sjO(Py)+I`+79^ZR5{LAn^x_+FvTf1S(=RorYo^c zZz@xPCT$&_Q*i(DxgJT(gJ68@uoKF|1v%nolQ9)4(B4 zc4^pES?-d65USMKwCbO7a^BEwOaK$W=%Gx90P9JMj%v|!qdofIr_f8bVY;Amx?yf# z=HgooZjK!{4hz=XG}ab`?1K$vz?`fCTRYiwJkpcAdzEV}HEXB^#)p;l4I%%LT>@O1;h;n@DLL2cg;f;T#HG!do*XcvwGR)%$LvI~FH(3;e{{7&U;(tDv6*-di z@7n-L2d5?F<-@^rsWH9)$Y-u=u^l#I8)nNs`7EDPUALNLjkL* z;@0nHM(&^baO(4aMkhgSyIju3)*m1AL~cITec|S3Cf@gKc6Mmh_Q!9hH%^k*;`R*} zS#V4pf=rYRltiP)e$y7#w>koK5~aSLFy8BuoYxS^%*` zKva|5{}_SolP`tym-*J*;@`=uOq(D>TA})%CfAfyCH&RxxE81@{|cC5KYDEfI3Fr| z@zyFBo7s9qv7V7Lh1VYeA=SGgp(J>x>2qD6Oy3vN+PRoFeC-Qt!gx~grCV0KHI=i_ zThKRee;eHmLQdn*H&h|1u6Fb+sOj2#>lfAjx*@Xq-p3&S?m zW^P-9yHF&+CFiO$tg#H{qZjdTSyQ0I0-Q}CiUC>B`~;Qs1DgikU6T|@d4s$27d*jP zT1@~9=vx@Je0a#QGZHwZ@;y!5%B zt1^qRHshG$%VPf=p-zV3vqJF?FVu?u_j5Ya(V2u2?dmlI0?(PB8LxM@;6+ctMZ6{i z-e5lT=qwz()qjbRhoORae)ABUDc zJldj}9`y#iVH8%Dg{|zdL)dH+KA$_5_I_C3_ zkGK}-aXahCLkj=ndrq03s!?Xgge${VAv%yyqJEixVfQB*`0{smTTk~LbB$-Jp0sb4 z&;DbBa_Q7{fvvs0s=?`SjRjNR3Ywz_T1kMGf^FhXusKgUcD`zJE|lc3999`=C0Hs0 ztA>;=$eO47#pm}oA2b4f%wf5_bvS`Pf2$anm#Y-C;w#?~*(Gt9HJd2^$H)MHY?uMm2( z>dL-NB=PwCn!AIH2{%Y@5|n)Yw(K8&S9`my4SaCdp$+syMy!p>N*vVa4k(8sjFn{% zmZjMZ3PqH%-cq>vRshMDX>F~jjP;l_nnU*B2h>+d8I0pYccU{QcaG0S1son19-61Z zUd;Uyp2MHMGTC~#i0GR5Q&&06V`O^q)A=e^ri`Pej_Fa)5MDm8_2k68x}o7M+5sT0 zJX8J=fHKfG5-gHhS6^_mBxyzm^7fVF4mhx%^@cqM{kJ=^WM3XLv^`xuoGdjyH4AD3 zYfXld`LC0L=>fBqIcNF4IqmQ+8c^m(F)ZV=eKgzi19yu#^cW?kn z78Hbv-Os7K1dF4L*Ydi*&Hdyr4`c~g0soB~cPB&IDn7Oj`^qX(!A+h6;@)3!WQEXB zNiu(2F3iJYa&NZw9WXs5Ej?BaLKy*uh>AJP zSMZbj0}Fgq_C9B@Gz^iJ+S~2(o!)zJW}QkCq?EN!?KF>E7_8b0ZuN$5x<@0^XkWzv z)l5&I<>Jq?S4o8zPu@C`@%IN7taAq{2c%SKpZpX5uPVrG6<&R$R!$yhamzpZ93D=; zr^D=76~piKnam%kGNk(fe*ZBoEv@ZrTr{C#ncDc|Kk!sUMM|-SwkQe%X14?k%D$Zc zKAcM!5p>!Ke#`gWp2xKl$rd|DVu$~MS&Rh0Rc zl{Izark_qZ_7;AAQOd^t2TB0w!{qL)3J_~OF>Mvm5FsbH_ER^sv+hP=iB+Eu<)2Rt zB7nYTxt4^--j^TmiPJZl#OKqQ6SE-ytli&mc01s_9XJ!e3N!uQ>dpHDsmTXnm2@1`hJ??+4iC2&PkK^O{alNqRbh z;mv>l8_Iufu5P*APNG`MuSKvIRyAu#Ksv;?E`sdr?BS?5rkF385D&4+M)-Fn{Yr|X|0dh>k z^MFlkjWXb#-bOUybh=;N-k#q1O*k5IyiBN+!MsMz-O4$K1B&hc%j&$!&#?W#{el4a z{DcKZJ0YBghGQU^RMx0hms#iwa)S$e9`#W>5n`$kWsYdE;-MzuoiLbpy655r9hv{! zfTAba)w7?k4Pk1^Q`7^0WzC$p+9CqXLduS6;PGQ!BBhS)uixJ=-f3M*GJO4!%#nd@ zT9iJF$BF$l!qJN1ylNYBBC1P&h8kPz%c|$y%BN1_)sr%1hy^BRNL&wK$?y~@~w4knXJ@qM{<{b$JQ~qHzl3H`F69ZuaJ`+ z7`?r@cmJ)GnSXu8>-ULLhs3!?-DP3?2S?9md~XYoe^vI7oXd+iJ1a+pZ6Z0zwh$P5 zpb*4FGxs>3EiqNgG}R*N-S<@Os>k;o^@yO+e#t2+vCQ@Nsk=L=j=6_mT+i-gy|+1K zpM5(Z<)!sOn{`}Pi^uMcgyH(xBR|HZYNG`vymg1ieLxpO-!at9X+!j?#b* zluB&+B!OucB-f`m_a{66xo3ozGskvXV%yRqpaFWpZ~ob||K4{k@)t>fbABF0!b@5( zJehjclFVNS%zR5|pf=IP#7NJ3HYnbEdUf_-lWHb8acJVPirI{N@Nw1P$&Y~~n0h*P zJGFf5HwZ2yyqk>QH+;kT-PeRQb2EuQ%w??Lj)dwd4(lsX0va*QoII#n*Ku4NuWcUy zeFkniV1n@lpTP5y_`U1a9DRKkWKpclI4l+Mc^`P8UzMVZdBcaGT1&Ot6TQQjQtW%86r0uR)H>q zsCcg$^I;0<>yPga?#a756J$&8o%_ld_SJkXatwBR1`RJ%Tey=hE7Pl-xg=ce%L)&K z!K%BvX{{}ljMu!d!wT3e1n9gK_CL{+^8p9-@)`%&pHS&Lo`g69)OpWI5BLdGUh5Z+bX*Rl)-6yuDzXI*>6^d? zac1r2Sjvon2r!><<|xetjKLKnSSfW473uu+LqnIJuSq~RK5uTB?)J7{3d*E^yW1z9 z0plMlwMkbmehjwJyK$j8m)SY_&D&Hkay8|(z(%9w+AQ}(cdf3GAI0dYx<1_=v|v0q zp7(WC23FT&R~33$lH98&PT6n#;UV_(Ad&@FJ-qWTeIF^OOyRK5U`_513`8JFWhwv6 zzrQtkXwn{hKuMN8xS_PTkuA~GU6}#QV*^L4t#ZyoYVNK17W;Y8;pb$ztn%|B$JZr* zkmao1+a%6U*GcE+&${o;Hi(@|$MMZ^ZLIWJWbmI&)5BhNpK9hgi{eD4PI>Hq<;IDg z!+e(r_`F9O3Nga{_Zu(Rc*hcgeUNu$$_8$;%*BPdd}%nzduW|1_*Fnyz0rANAj+T! z0he4aoRBw50%KKdZi9T4Se}jgvh2Wr140{(9{VWw?~ab;3XlKu^;W?39|GbPYlm^# zvJZi4K#IEA0iwUTgYLNAda{xK$UeC0J;-(LNLICO0XB4f&tcO(PifdB2ICU^xY;q)btMeiFplC)65Br?# zY?nNt}1PUs`hA7ZH7-ZQjcg)U3WqC%Xj|5$3XIIL3G`7 zcNP0-ZM420B(lyxnEURS>AnAVboS!hv{qDG#`s?RKRgdWFi%o1%etJPUK|xdE_zKG zJxaf?f#jvq#GODGZLy-QC957OF)^FOB%pVH&mLs8-Tvd$Uflgq7Yu;g)0 z+tTVO-!J9?Qqu?)oB(AhQlA2)L=tz0S8;LAj&#?{iZ`7fRc_wu0JJ}~rUlgn$+dthw77OpS!*B;}TcDN-s2}UmJdv8v~jQJV44PyVuZ&u$2jo z|KJ$?5;O!GdgT7#(gK9wA#`}#7%l9cvVXHj~zSNppQWXo{~+lulLC}Al2=Mit^YGd~GKPfiPH*NHIa&*h!yz^mc zNw@Re(Qs}Uvbe0_9&EPeYyHE!gBZ~ImFn`HV)ZIRQTDY}? zi)pg8(e*Jf?wBd1CE;qTR~jY9g@S0}Gi776TwK|e;~p-*tIsKY zt()c%`S;!LsW(PJ7cE|m^ZM^hMP3(3x!^MuXF8pDA}F}liJ5q@oodXA@J;GQHX-x7 z*EBd7{SgqNmnPxXr_1js-v0A^h?LVHBp;JMLP`=9m6nskB$#8Y9=LxOC~tbS;4ue_ zs60onv`1e?ITKl|bEAPV2`y+Y9YomIeXF4{r6JkYvtQQUolCbE z{m=YcwAP=+`RUQVOZdhh{+$6G#Mi+}<@c(ix(cBP4y7UO1u;4hJ|zxy&`U3`QkDt! z1^(vbLikPVC&6w@mq^1ePNrCo_rEV?e5pW_vl^w5*s06NdF2f8#g^-eM?hdMc<6lA zd#c)jH>uK_BMcT}wr9ajk|BM{9?oUcA#di_pK{2Gp<(z9gTe<`s04oC&4~7#9Ki>0 z11#@7=bfQP)OkLdX&pGF3tjCJE^}<)Sdyp_|4^<-c?2GtM7cY~du-N-1DtSQR@%WbHK3yQY-h)Q9%xRw%cc=NrF;fr1bQ;G)*~IsjytmTno{Nb@62r?Yl(YVO0;nHop^FZY zusI%S)NYfQaztgw&$Kp8HZRm5v#smXU#x_WNyBRdgsBHT)-QWa@i>)^*<0*km$Q!2C8oL}Dvy<6U3IloHecEA<|BgKyc zlX&8VK6-2*nqcr{lRy>A4;Q^1V-&0yg)r4G;_?&9HSc6*YlY}i9rEdYDIA;7y9=I6 z>{3LlRc-GR(oRx-)HM_oa?@Mgm(7OF7=uG>-L2|Uov~GKTol+wpUrE+Hh;y=XAz~l?enPIN?vfx5~WHS_;JVNa3V6Uy(Tm zE+XZ>`}ZlooHT?1QF6A%Wkc-+;)ku{6+?k1WdA-}z7#iYR=Z`s@IKt6rPE=XDw6th z4V3A=g{~PHA_TEc{Svz=P#@UcBw9uo(_&U+?sTq=w)V4&g4&@p1)FfCR_DQD2r8+fGLeuAunXl z_OU1b(b;j?Wf>hMRdJ0mw(MgbJ2*jy*X!h2=0J{rNfDRBo;Kslj)4oq+04jHT^`iC z-NGhkf5{)m47%Pqa8{ww+=Z$#!C}d&KB&oY|Jsrle|d?^NQNX=SxJ&hPrUf+ny03% zDjF_??u#Cbrf&CbFn(lWgzuOCtd}|m;A3>fFwpeTuBF^xMDx$zhop}*thQsJ9I9fA zUTa@;@db|KYm`hijLdVB8&;4y)$04}FO9xCn7&(e{8ef6^}h&E#6ZpPO5^N!OnVG~ z{i##ApN1drY|UTu=*q2=ca0I2#j28TMQb|}9&4{tBE=%vcjKvy(84#o`0vVMe<}JR zPliGeFQCzF_DZk5b+>NW>`dj@WV&`{=D|6;o6O_r;`J?}<)Yh6!UK4ZvuMfOsC)=K zn4fD++(bU-w!%``<9A%ET>0+qI9yjLY;txsh&KTYRMsL0HsH!Pz_y@in~ zgAShjk_(s!Uz*j;gk|F!x6!@18ojhK*m!5xjW^OD&Q_nH8y_QDpRUHt%huTNcyDr1ipYXZ zmab2D_tF0fSN>0yK$gI2wm>WeQf51dBwaC#T$<(y*dU)41}-Ei_p_+6GNtwxgguHi zn@kV*^eSAS9eyn5+h>sko?cEzE1H+ks(T-+=m8EKSfT6TedG(nf$;i31ffzhJ;&4n zG;PLC)k|bZ zC@Ubucc-g3vaJ%uY_rdQ`KX_2)X;83Sa zoNkfG0Egw;>lVG*sX6p0ysmb=u8Mc zt~vkm`U(c=wlfOMW_vzCsGJKyPN+|esWTd;uHC+5GS8XW-TJ66syw2#F6nLae=+yf z7wQLzUvT7-t(F;^T`xrv=+0xTrXwy%ADKFGA2nRrggINt#lPUlw2b9leUnqxoIL!( z9q{PisWnb;TX1`UD5U+sA&v`^R8DSkxvPxIiohg%6{dEtOnDiOkei|rJwIBs~0GUI+< z0#W|4^9I7ncii7=KCgBs!oy@mF({fw$7JQ2^+e(QIbDMi^~2FS%K~^>5Uz^-7>*E_O(sGd42fW-@@-`EUA-rHI1NPSJTPQ zI=8yai|KA$&gw?U$wlEmW!LQN=yv(mm?~I@4%g~pePk;j(W&Rv>IHyhTs< zy^68=dCiZ>Kh3c+zJW6uf7_=QqA^$J?EBb(d!a5+&fL;}*Z|oX_#4jvsOnjw&-%|8ZqhngXFZvYMf35YxtkU#Cy6$Xwjk6n+LXAq2MC}EJrn?Bi ztajWazYmv|KIXPuRv}v4!OupX&e~o$nd0%i&y4^NF87||hRk>O-CKUIMYimSafNj< zgDJRoh?kv{)HRB)kd%N7D$I-0L4OGI^h@C97w$lOeaC2*DhgwH@9h|M&ZGkiE~yi3 zWD0TR!rtztJOD_^Xl=qP8*8Q(g|$IW05??_=CFy+T02{k%Mz&z*?lX7?8hz*;9}b> z6PRcy7IzBG@gYQuC{Zr|R9|N-Z9?vS1P#bm>sKBF6Y^!A5}Ui*TV8C35C2oC(aMdG zkqfoeNvP87dTz}2(_U7)X#gNa<3#p>lhhYUgnr#u+%5rNVuGxf)h4D zd@vMQKKgTtC%DW)t!AvV+;68ZU<BndgSAu`InoU_d~to#5NN=3DpY^HX*Apb>>L$4b)NvA))-Q zSxJ#aW%wV|KkiSu4^G8x7OQLy&P}_oq(bT%Ctj#Uw;gjnm2hQvY_<^6iXgw~YFoCZ>!Xj+DQ(p5pS-wC6h%dYnMq?)Wp z_`QSPvXdhmy&IAJ`78sZD}2Idj*4;HsCmcgt=3^2rktbVlZdgkOJ$fNFFOvTNEMzXvcp|Ei>)$~u|4s@!;2|@c2{V4-AKeCzXv=|YbSzaht(N~L zU+8_WNf=0CuNx+~$w?Yqq@d)Sg$R>8)A**^5 z{CbRPEZ)B?TI!=sNOCZq4o!;5n9d9@EMq_E5olRQJQ@u_Rlvwb6Wq8Hy}Mbu(`n2R z5Iw0-o$LqY^=O;2oX9JkZL7xza@b+p z$ukC^pMIQed#uMX7s*=xNKi@{ZW+<%0D?t14hYm-|36T-E4FzOVo6@lTiC}S2tiiW z(}~Q)@Ho)RRrc2P?EBy&cQbzSJf|_l^?+ZQb#_DWzRF4qYX5O29nI_KHq~xt&Z53W z$hQ=mMihVxEZdJY#M(44&-a?i6~1#!{Q1DTHW&|CAZoqfkYE%pIp&IOYb?8&1#|_R zT^TmTQ=LQwxc4ec`^jSMr6Yy-J<*MO01*ftasqp%Olx-JNWAu zSVXI>z+`kXo-?`u$7spShL!tG6#?`83^mduB#e~q|HX}e9}CXqNC=aE*(teX%OiTp z0#cZI5)VfsV3x-b4+nq3(-ZvXZ`#F93G*^(7Y>s7wzD}*Syrfu!c^MBX#PONcG!2zFqartP`L}N1sK>Z9I{@V>E}3Q6&NWC^nocH6K^Pxg zyNGhz{rSwmz?fK7j`dv077!?h-N6ZYqYtQX{d5hiK6%DeYE-k7-;z}MJcA-wfg71t z*fV}}E&t$!l3$tWgbZI?}6Sjlx+kzTe5_Al4>d8R>TAYXx+RwR)3riV9qZB z3@?x2#JcV(LJUOf)1n=u;hN{Q^_@c#OfCLlG__M;*~Yw58&2x#%p?~E85#@XnB@@( zxTcRk^AaxBGzo&J*f5*UjfLV5xT3eM?k-dal+_?I^UHZC*BO2mnmSucVRgh})nv3@ zahltKjEp0YC7u}NCU@(Q=`06h*=*TuFs@D&A=yDQ0b?!l%NCjI!C|PJ9y-8~@p{@J zv&_mY?$)6U%-*@u?x)3vg&2W)EY!@oO-Q=NHq)b(({Y@6cUZ>phiB=7P+?Ti_wisr z_)c$~VG7h&&M}J*OWP_1vV`*;hg`bP!aK7Jh(XamHP_ENzP2MDtoBRN$f%9mU_oZ0 zbEvrri>E%T5xk7UIg3S5qyG!GPskJlgzHv60S{(V z?{2<1?AV7cc;xkfYg_Np6~k=?zePF-P(%08f@ud9o0Xv%r00!>=bGcxSJ(r~jvPi@ zjS1fz55w$Rjb z|84z{bRDFBk^o0V<9duox$gJ93~SXu#|G3~;SzQX>7&WEC_WbMtC?8g_2W@Vu2cN; zX#}_@7Ivz};gzdhx!6^FAY>GeI9>77qjLM*h+nT<7=pl*%-o@D?p`wVE6!wmtrY_{ zc5*QKpYp=Ke9pR5?u?(g2^AI!bnGaGL>D}F{9@PA2Z4=v#8nO^{cZHfw$RKdJshiS zRAQx_Vf%jCr}fC|CHvz}8^|6QwiZUm^m&{Mv|pui`15HJmDG5142r61HJjgx-A9wa z5Nh;4Y{|n)%IN=xF!X1ho8*?KR)%zP44cI0#~lnMPmQ=xr$l=9~#%>tJIa|Do=h4~}4Nsp>_T(MoSe(PZ%z)5FM0bGfjii9CWk=$GTy z!Od%2m*!~%qx|A=Ri&nAU1j6DE%D#?K`yJ7ge>Q<&roc`UK^L@&5JA{vzyjxX103w zQB>ciLMSAEG}@8Nia9fUV@h-XyTB(TD<}Cw!|;&A2A`sC#uH_@VP;vA$NbRtk<~5K zhwka#axl7wm;NQzeI=*l z_v5DvM>IaWo_l6!xJwJ(2%y+?xE>%l+qhbOfo^WygusCt)}mR(3IxjPa(3uoO!gii zlU6#}Z3fZk5lDP>q&%5u~DQXQ~vJCJBrqOnH^S(`8)Ue=j|Kp|VMJwU1YmljvQV~sMVz|z%X5cuJ zsQnV#E1Zs${`r{~tHzZ02BCapYFd%*K+&*nhdl?_`~ zyA75_6<*C;XHZT#QDHLZ>m$#oGyDi9?$1;gVh|nR2u`)H+A<8~WuMKP9w7_KB*HR% zPiK_J%QwDJUBHMMlMWDe-6Z!_mGqzJlk{)=M$Xm-7k1NgVp-rM8c1l$)3B<4g?K+Y&;% z7{QWQYd=%9`CIN-k6rh7md_4CQVsqUAT1#?ry4uSB@2D#To2Nzz5L?49fdL9IeCf7 zV9dalbNR;sw4z2gJV9oP0Zk%4<(D>eDsd)FIsvMFa+BW^9=kiDU?F$1n-ReVu*_1}G_PL=Z*U^qoaLO$DmW{Dv>h6}?}ysu9?X2(Wya(VcR^Oe{Y&CIAmEeG zvMYpB8WTeR;HbAG+wW?ROMC>y7HUGr#WdL2wb0>fDNo*|gd}v|kz97pjRuW?oJ{Xx zcZ7ACDl(?tI{-Qe5Q!>SSLW zC@fbI-V_Kthm4PiFMg-cZmGq00N%x`-2~za;cc1V?Z^2xpVHOJ8NT#VdvPRmAHG}# zQS$f<5aRo$_sV?nVsV2nOsm19pn#e0&+oe_1;io1AFfd;p!QgQgQTzI&2L!Uwzf_H z^S!!#G9sn@dL!g6$Hfgh1x#>O!-neyqhC%`LU>t)%U6GXtM^sNS_$fJU|IXCHUz7D zFip}Z#Ossum@sA}L&SL`u})qmxu~Cpsfvel?pX2GHi|JQj*8Fh=FT{;F*?q7uft(y zG~dcxH@cx>A4A7+J`&brJgF{w&SkF33_AAW#&oMS)U7_3083==e<<+?S^mHeBcQJ5 z06yT$HOHB%{K`Muxd>5J+qKXu`I?STZ(eYjud{QLJI1rVmV)LjtfT1!4r{x8t=z8Uxk)9rYP5e{V82lF%Y;_H;6Yga@z zrAkVU7JQcZK0YB1@^xp57j#`sfX6B~gBLE5$X#|da;)h_&@1SHPLPlG#3jNVKc$P# z!RnGn#|j!(-%`90_}4}9{kbYpZFv@1NyC4INza$bxO(H UN>)VD6H6{P^zDDa1P z@!Qoy>?JGCBzISSw)K)+&InvUkpA*;tAPIa?xhjL8{2hRl2QJc>QCQwjlOuDW>cc) z$PcJ#ET~E3WR;oNd^-DXKry15R5h(DiL3qHd;(LBHmlt3aIL{?JaoD%%6xQT2z|DV zlw7H#_brG-sxPco>WzlyB3$Y+W$1HFN}w|NEf(j`Q19ZNes?~GTR^H&ku;Ua3F}5p z14tV7r;yC@8f9xLVpw5|Vd6{0vw}>}a1A89JP-7_UDkOW{xGKG3wMl(=ZDyC9v@5o zITVBP;!6X1SyV=0O*9t)By+6e8vU_qJXd<(?=-7ZlPH?D<=Z^Oo82n-N=(t=N_*H?AUV}2&`Z#Lg91GW(Vu*H z7&ufp>Kx}WhugX-(X%Af@~lvdK5*FUc|E*VEA{?yQbP^D;7(1ps^b`KS^VxQYe*)) zOz_@wpXfFX<+h_-X}|Xot%P=&N9(Tl;%TA-$|q*R1I{f(-3-#VWXXssuOW@)fma5v ze7TZHAo^C0TT(kJ6tOzhayG1aP@+&# zQ$?}%YAr4Bp5?oCN^EC*m$o#=3+}{@{wv<$<>mQJZh-4jdjbSMQ_am zvFhVMpE1{i1?rBYhp2B6tv913bUdL0qz2z;AKxVX{f;ma?sGUSZ`>VVs7+%}2W?z?w3JXS#4xEeZ=G^*_d zlmVGMdXL;C2};k(%Z3e9$V@52PQT)z8ZuOR7|w;K1Secveb!EOYve z{SnIYlC9cqE*i7JBn$n~ukXL+XvlxudK;20@JN?uU$XTb@vW)Ot zdb0)8GX4lvTrN5V9%MD(cDaZkss((R)NW5;H9`)raaxAoPN1q?~O zO5wtb9BC_)Rx;sBQolUCG#S=JT}22-y*IpBHWMKzhCT(>h0~`Eu(M486TXWtw}YS_9wrki#ar(kU3{c+CB{UtYb0!L5nlsx*MS) zzfR#keGNLH;ls&SHl1-jlwzjrv#^*<+-9G!K~d**b&Us~q9P!#C-P<7p4lh)ofNIP z%_*EEP=R7Rj>jTCI16srMm>do1*IvaJm~A?`Y3XizhVv#V{z_)Fy6euRFLmK8aR7Z z*~pHG!--)j-85G$Bb~T(%^ZJsr~)S{ zv)lpoeHbHquaw=Iv$cltn{iWBO)2yyX3s!$r&4p_y8oCaAv<$)B2)fYS^Q4~+;;CQ z{Z4X&iN%9@3)zVef2wO#Q1^AOx{(6Gw`KVe?1>%`n%ZCs@SDNVCNTD)uZ z&17e1S3SwgBeOr@)_BB@=q?vuPj=K%&4-Nj@;VF(SY~^e=Qbv(;K)u8Qgu|ZYc@rn7ZdlvV%1s6hf!9%^6;) ztMan`^I(Vh(;ol959YJ?vXQFjhEcD9l*PV5d4botLRM_f*1lH}E%C#CQh@AUqelxP}GK)HX+`N&WazW2ENzC^waB zQ%Vr{%v^$X&*G8C$6?!n$cZP)+jj;(GAN&%Dt6a*y+d&%-JDo(RU!W`KM?%#cPqQ( zHcNT_uz@47KZnQKt^tVyAsLuoL2Eu#(w;2Vq?vQy8v9@tYz`}eK!@Dek?nuL?*(T}|X zXu_VnI4fWx^&EF|dp_d|4s?OUWEwPk4nM@j);VQ)OTaWNMA)8>> z8Rz1VrL^a{2AGL(5~>@#o)6T|8?n>MX75+mcY?4pP)2x@RJ4L+WbY-KD{2PPz+vw% zWw?0}?64m$JhytXWK3^ml#p*#t441E0eU7;vaiJD}7^%%~j#Xm6D=f0p#gtLEDl9vCzx=A%KFtr^9EY>eSfNaj zxrZZELdY$v)x)3%1tO%E{Zo?754i4jRfhHYAN{F({wgj#Dxy9khsQe{UOv+^joRrg zddR6^HLaUGt>3DX|G%yK_}8y`b%U)e(!^XfDM7CVEf>2Q|9k;^Tg_aeKzq?4PUIQ% zlx63fO+t9gWV7MOz%r6!N|~cOj>G-t_?su~Yd0_>T?(bFnW3|-v*pRr0b5Y-`SFgW zUtQj_v-7%R`p>VYjZt@8^r&_t6llpa1?)|}u1DVURtu+hlSGf5zK(HU&)I*5*cal! z;8+d(O#LrT2BfI^BNUHG7ivbbIh<#sbvWD=jY|5NoyRdl&|KA`4z0jS-dUt6OL8Xlndckz5J`-D3gFu!|xKSv#A5?g7_@rtZwOfUBQ8U6Nti~oq; zLWtsjAjN;L9b(1$;#;~yQV_#Ag*BxIj9_=;q$#A1VKz{$^Uho0rBUn4Maa%_^Q}0O z1NB^iDCt#o?>PlrNwxXR?Ci3QWoPDTz-c=E^<|=Nj`YooL_dor(lM2f#D`0XuJ)Q{ zLN%@(y5n;xiVNE(vf#(L^HwP=iyzFN=MHqeOd0yMEMCiNXUT9RV}zU-?~>?_pHTZ- z?~HDfM*QvE+k5;2I#pLtEx)EL>Rz@5aC*Np#T=6V_~b5r;$zLW3e;ikqfW?X_qLNd zjHPT|uVi&Ox!U?%cY zLzzX@H4}&rV0@0rv1$rZ0)iRy1XV5dC&Zbaj_0#y`EZq)H)}$B%m3hZ`oFJ9G0y38 z=X}@nO!B|$xLz$3Z*cP>wEHMr5tSkHJ|%<*G@dP#q=l4aP|vw#8)Vo%ZE8@vxsx_! zkL^HiF^I9lc?W!(|)jw22ZD7!EEOm3byUe|O;7jWne8$HAmS2w^l3A|~b;Ikm zTurH}I-&lZ!BS4kZPNlFDn*!7F4?#JO%dLaKH;%zN*|ezEh2pawj+$=5u(f1ExlZ= z%O`PX>>`ez6!ahsIR{0;vw{BEiDk0F^f--DU&NvoSW>5Q`6(2Kw2#m<}%6Z0&@SAnWXM=g?({v_P zjk1T^9c|~Ss^R*9{Ez8m#-Pk(hWn-EJny^K{?ps7 zIqbVV%Yf=7qaaK`YK7lj03lpi<_LQE*!K?x)|&e(Z}!bo@ayr zvZVquujwH(D@*nigwe{}8Um6rS#A!wA-o;`NR|#ONc=&29ys%+iIdXGP&~c&T+%=l zPYPWqoV4mu@i&XM?6TwDs?zd$@AIAw`=lX-(tmlt|HvTt{f+l148uJHsaVCzFJg?# zigWpPr)_o6e;Gep;1}HEdYhaW2WMFR{^l1>;(Bk~0Nu0Mrq;|Q7HKk#nL1~y$AeHq z99t$!!3YF(ofn}a4R;s~!IE&%`*pcGEC+jL%fq)Mju=kJR-z=w`L&8PYMOOWr_R~O zg{M|PgLAzcKOz;NM6>Hymv22YnE2IB-9Z`#4lNkrl@Ag%Z^ zDo|8g1srxY=R1LuJW**hx4qytM(eP#D7H(ov_Sce%e2M9g8$trXaQI6bAo!qNRbKY z1Il#(Rc~6u2!?exNUHnIp;@$1T}(dfx`pB=m(`mHqv!J8p)ll+%tT%k%KM!-&^V!|$s`N%j$b}rX zKWjIM|8@R(MO#e+)u(KbdgCJr%+&uzt_J9Kh&&_ap6AEb4Szrz#tnZ~nY) z4wu^)(}>o{y)V{c!DMp(Ka+k;2Djf$Ffg-oU`x#+m-Ha%M3_sxpVB=GxK;+Z=N!M? z((j_J5DmU>V=CV1!kD`YNF7K#v+&+esN|8)mgmQ#`H)S@vW1ZsQpwhp(&eYu4!vbySj zOlvmRljP?D2S{{#XlkX<;p<0U`8apLZ%a3yj#V_zH4)eECvx{N6aL)g)#vyNyTHKgNa$3qpf|VF;N5_(4D-SZL%jiEc zLX5!+*xu1{zmwvccT;7R6y|AT4+gsiVk7`34DP;*Dk0&HofP%g(`J3{$*d_UDp*M` zgv>>Z_MK5jv|>MSOR~AfMmg((oU#*dwujDk17IskZq7U6G!6G&mY0~g#lloL0(Kmz z-=z^uld!pw!$aP5^<4j4iNW@Z8NNK#^*!+4 zW-H|3837^SH7gcJ;?Z#(pFzZ`c-eTjSs*R9lD2ynUf~3&XRy^=$VYeTQ#4=hM;7_nBJqi9(Q#-JB@qpG)QRFi|G|Sy6iY5_q%T=(PC% z(e&=|O#lD?f2E?AqIgB+u!^W0mXtG7k|cBza#%vh`E1OVyd;q&u^cDIA|~halv6Ck zXfe!b7|m=mw%Osg-kNh!N5Z)k()u*Mr^%C= zs;)!^jbUfQ&3ig@IaNWb&kE^0x?&vt$NNO{%D1qdj9j$Rfe9rG%uO&9V&u{krR)Of z$?##;+ZZvSfSb{7g-Zy5Ld!C5`@Q884f= ziAChDsf%-}e$imT|7FQPuz%z8+`y4jy?b>DUyA(QuXk(ZD-PiUgOv9yGy$01(eJ2U zxL~V^Djm+)ffVT2MAR6v8xVRfkYyn7`cv{Q38UFMzigNioK21W#2<$3HR>B!D0QSY z8lhQhS}FXOPnS|vxc}8s7oDpg6)Zgmjwd$D?oO3N91%TxQV(ERqyT<^mGrYU^0dD3 z(N<5|_}2@aA{(Dss7GcCps!%Y?%lrY(_b`gKPl0#Wpl53ZwyH0cb}sc6tO-6HqVM^ z42&q2el+`-B8=MR(txA&SUv&~#&}tlG!p_>QmVqfi1MEdh)+}H?4N144dF6J{!wwb zRX1>V;0E4x45;z#3Oy~g>V5S+$-Z+tfNX%ZX==(5$S^XE%Ez)xZZ=$yaq7D=X<fx4bbit_%PHI=-z`$D$3!A($4;}zx=vjFdjKlTxtRwNDVm-+P{cIxxUuXQ6zrUR*#qLPX~WI6&K?6`#VpYgG?IpG>J$ZX2n zq7sps;AVAW)=v?i@x}+G2uWx*C}`7dlGYnT9<>76B24HGEfAiyPfv+#NwP&#*1OAj zKMwROfs2LqhsE$|)2~BfC*=Qm-B=MY?uOn8#?_3V&4 zz~Je>#Z~@Bm!vL$wb7PTbK$IQJK#`@IVNr$$h>wIWn`-B-A%WJbMDn%74jYG?{H3c z9C|8xBBZN-3G#3&&cc%c*vq(ySs)96tmJlMYO%d*w0=AL*LvM{mk9YgO`2So*7nrE zi)Vu}7|9J)f|Sf0(w%v?&Z|fqec=>fQ-OY%p^3F@?jc_@5cZ0Hg`QPioUySDkgSYSk&yKc`jrp`QHW+SS0ub!<;h4J4#J{7U zP*r2bA1ph{DGkP2M2yBp60<0uZ(ubQd>$NyguG9;RnX;_wO3xt^WW?r@X_wY zHqq1MRiMhFvH!{Jl)SE)UP3lq;dhmpe5f%cDOGCFWXX46I%|_-7JlaPYX96|g|<~W zHCC~YB_O!hOco0znD30zY++H0_cZB_NR-Z*f!``s!zMd^3s@zD(Wtz*3h^fUdjAUQ z?Ss`!dvKgqT3PG|=w#_&`1h?_XZUqxaQ~pkL_G@&T`71`KW3QTcYS84Vz~jc6-XWy zF8VQg8pE3mhnN!&k;}PPiqq1>acMvk+nucrlq<1ATfq>b;u49|@WD|ci!q#v7+m%m z`lix3c)@BdVw4crk>&~`F*g%6fMsThw#D_j{x@{1nzdqgIO9I#9@!EgM(>@;??w=1 ziuQ!_NFX}#Yc34;qMl6U<0NsM9Q?9HtZga9Frp01r-O0*(&u8gzfenKsLk5`O=M2p z)A5?NK-;n|6yVm*c3Yn7P!fj7U*9JGm_I{~0dXbCsWDV5dzV;qhWCXeOwVN+KH|oG z=f6dkJujanfdW*t0gtt5eecbVh~|Ikq;dEnm)^JPKhSCX8?7w&NKcWYbI=qdHkOq=$xpa%(hv>g#aIwHxh==g4*E&Y*(B%})TWx6*vlcYl8uvQmQ{)9{CmmWq!kEVKwu z;g^gglea0aS9JZkDV`1hEB)|;Zxa<&qp2M`0SjLGBk^c!d!&nS)2&B|xt=%Z3Xn(Q z(xc4r)eVKyZfmOnYmJw}zJSloz9i#pLDO{@MjrK&CG)p!xH)7^DCE4r5j9wT(vR;2 zO8&HV;aCzDG8p10V~n1w5~}9NQ>FQjgvOV6i-JB3hlIGq78clKrQslUziqbNyGb(L zBKknR)4ad!SfBm?{|p&PoJNA0f(=xaiSTXS=F}3X1n)}B-)d{s)xi9rZ~jygf-)FS zH^(c`LkNcJdkHw(CwgsA7l#`*%9-g$%;&ewj)vg|<#5urT0SpiXSgJ%8|(L9bI_btsz~|7H%TRa7TMvR{vt{?pq7<+lDlGO z#r^kzbE+nHH*k>x^W&={`E^2B@X+?c)*b3c;v~h5c6!2QblB6Ui|ybPv1T^TB#cOvHD+K z6ODlBg_a=zqgz-&+v-t}o#3WE^A+ApMe*n3)5ENbox~tB*Sxp((MRm1&X<52gvGwe zR~P6>K=xdkq}cSK<36No9^tO$X3hkaTLage<~Q9hR$J?Ej)i~4UUzo90uf5E4+QrR zh3bp3c-buX3JA71DRMFnww}V10JNWO_i1gTv|_p}>i46rdlNqP8r{r%SX% zDVSc@XAbR6iDm*q)hh{*z-Gb?qj1kgmThx$PU@#0NW6X^p~K+815`YFuBe&`^d@ zlJ6?#+R=wyxTA{0vuV@m?BE#+fp`Ciq-Sa|*kSY2c!2TA0swC77l zirPBoR=I?Ra`=)RC>{Sc{mPaw%M<;GgD4}2QS2LgiH=NrnT~vTZhMEjMGJR8Z8Tj# z29*-lJ5=F%9_Fycs6Y-9%+sO7Znw8Z2RcqhVL6-ARO3v0$q=r_O)92Q*B=()JNaed zbsH6AU4h1E8qX13Sd<@Q5>b@ri+ZymgJ&KRm^dq3!zuOIZDeaL5RGH2tnyB4A7Ijv+ zbp9U{jQ?XSSO(!0cD?=QCO&Rd*bKbU-KPh635xz;9$Q!Tun<)u;ip#+ij;PhQu$n< z4mR;a{fu)aqatoXeL`!XcU)WLMY}UBRPxS#8AWvO-Phrr811*sxYOa?SgFV^>~OG< zFyZ;fl;yOH+YeZYUQL(4IQ2^tJQdhyEsR$aP@&jJQr7!X%`nf87HyYiJ*+-iK>Y6f z$N6V(AEZmG+7p}kg8Cs*@#$Om&);Je&Rv(x;Dt84=i<-onl#;HKFllZk*f z)!3aEb)CwG@zB6hZCTg1ih{3_qrAwO++WV&!JG|V z6jeR4`d|Y8fE*%}g|9oNMwGIhqMF zMrAGn>3oVUEE_Q14swZL4{Y`)0!k|3EVIdacQ1oYb{Y9aAn{E;cZ68VY@B)$gbOdM|LDahDyePW-S|_kc8}(X^JnL0dM}8{S17Mp=s>!mM z((-gx{~^DV?iWmYGhPM9?c(}z?o8r`PPRagYNm*VDTs;}MaIWyWwWr2;TC~G+e5xK z0jl}mz7CXj%_Zq7DBOwonVRPlGZIlbED$=_DESdh`@*#1!l1+-M@KRnJRXz4}MM%v$l*^%^Uq=Q~51Y z=c;a~n*;MxERq7)UdU;8sQU}ME*;_{?l?Krmdro z)?An2v~!vY(fJwc>A@TK=@JJ2@M~6wm5=D{_zOA*?;kI|XV4KM-}JV|x6nud^GDTS zsx2GN|Xwl9;^3VGH7 z*#U-`@e-9Nl?6|x@%f+NgVaUCJU$(*XuUlhY2U)ws%OWaK$3vW{GoH&QVD&y5hYZa z2mmGwr(j#Q!^K^Fj9~7D61jtbFMF-4ZVR9i@?d;P!J8Q#>-NJ~h6p*cb=?-u7EI*? zw3&dGaxObxlhQ&f8VS__KHF;$(ySG*)GI$m)1~dPXEYroz^l;u5ZW_y+r14)T&g|T zlAui-;AYGKc!_XSzz~9$?^vft`Jwg?iqnHxL=MCAb^Lz62V~5=CyF$kbBUp3Sl1wc zhk*mZPa+12zIHnM@>9D;p6vU76=L;0&Q#%C?MEO!aw%7te`D9(?%i{ZhXBkFHM5g0 zE)5FzQy26JW5?+*F_12(^rI`nQqH>3yY+6n}pNu zbGa#|d)?7L*_D>bPPc~)?WoXLeC##=Y3cQIRkvM!7~bM3u2U)_V$<`xSz>7x4?sS`n)1EM3dtKu4I4;Hqe7cY$|b@ffowLe3Qxmk${DnHu)scBY;boMazs1;^@e zb}~kX-!_&ZLbJwWl=-P8N{Nh}J2}^8hBg^sqdd^0)?2`*SR+;bx{Vy(C9lc>Vrf$> zEEHx5*%@K#aNc&1%|L9H>-VH@0;-olH#T~uViPIJHE&sN2q&jr7UtIcMx21d9>($G zEpXP`{P4-JVG#&(wvsIL=cQ*R&L?5SL*}Ur1n5>^;IJCsl^YuUWG&Q3S(VS<0tp&t zUSY5gitp*4Vvppz`0S{`ZEOW|+dedN*%E*e+oOe?Y0XYnuo{(Xow3ERNCNA=RCu0! zlu7n_$J$mMjIz2}nIYW8J~6bSQ9jZQ&RX5+?Y?aFzk62bwcw{anH_30i^qsPm-NM9;FGf zH<440vI~ef{j(m0UAWr8ibq%|S?2CO_xYOpqa?MqLdEbOHn#hH!#iK#&|7cCirvBKcCf^8;^VrOv`!GLO~XhgbdU{vW0rk3P5nq{_IR{+IWfJLVpv!zn(b8o(m= z7Ja`p`!WzJ>Pcv&zhGAWk!*OJrWpK1qWxW*L@Fz!BW+hVcqVJ*=EHRLtww8$I&Had zKWQ(&bXM>_1%6B6uZ70Vz}wDGx`=mG`@sN9*v3~;Ih0jCxo%o_r9j|$@Wptge1*h~ z`*&~L54m+qCv|nS;eS_TGTt(%uE!B+-;xAM-Ti<&oe3&D;$B$!$<(j=qLzdTpMJMJ zmu1NHwArEx^mybR1u_8EtREX5?E_OKO5#L>;RtN-DA@_A(QjFY7EXMIU4naVdmBWv z95@WDAr3A83sht26C+`8{@eBGoL?n|_^O*I=o?|qvjgF5{G`>BUeLBd*Z*G|v-!mCDzM2ab}Db}Sg6DUF2uS>0kpN-)ntu6IV=Sr z{~E#eLVLHDX&z$XQogL-*8xlIU(QNu{vw@2_iwzEKCi0oIj068(e|rjRFB0w7Q`uX zJq|8ypWqc41MZn)5^qhV}7#{d`byy zK)*ASV@taCd85itcJa8kgh6oW(?Va-;mr0=97oa<)jjcBwS9@ux&_m32+#deH=#*> zi-}KiI1`!@W6GylUv53_Lt|Hy`Rs-9hRxaoNkFYLBVDG}S4Veq{5T`SnKW9IHv@m* zw$Y11dFJnRufXz4{$e9$P;BJkh{{`I7&i(w5S1`s)i}K`BObLN3wP1)qpjJOedw|( ze0|l)8M!|3%^i6_nMTTcr~IJVWHu0LKjSxnDxaZ4yTE{?D`h*6%Q+dL#E+rn(Z(=+ zMWKN&ipiy)E0JtSSS?i0MW=7|cmVv@R)2!gUfiEiLPZ&Up zTq2oAlZN*&A8<*4&nW1-nE)v`u(Yf(z*-6GNZSVE^0uc?nnLfF>HL0pu86&cL1S`Z zyyP-EQ()TSHm%`9vcs432HBckSzvoYhxT zn;N1)3LBCYW!AzWW2i74=6&%Fwc)yC)^cQX$<`kkx+Yh%eu}Y#eZKdABeTzcJjh>h z{rI)De{Dc%CaL$l^n;)ayHZn9QriDKn5jLQpedlm$4x{=emR{MHUZ>-s8Bl|L>naEqG2+1L3>(_4O5Ieoos zAx)~`$?3KygV{^aoK-_C%e&>A#FtW0r0h zMEptS+H?-%#Dyj%fUZiCu}WpQE=U5YoqdP+8c&MkQl>LtnbPnWNqHOHDgL9D%b?X5 zfkDc z2wlA$O|7Jm5ttoh-E!XcXjTvV%R;h!ak8dMmh`)1oGKWaQPmIn1>1%{ zdo$JUmv~ujFou7f(5-|@m3|eReGGL#z5dSsnV_mtCsR%60->q_&iKa!8$IB2MP0Hf z&C@0St%M@{7~X-|*OrJ6e5WfhUZ#lt+K_MuWAyEA;>B;89WR%+_v)_DklzM9c+6g* zOA#2q8=Kr8~r#1D)Iu=qr8K9N5Q-7ecs>TwFuk zb;-8b(A|#;9=(}O)QZ}V2stAO<+IEZTZ$CJhxd1zwYh;w{}ucErQCwZY0u zQDN`VoPgm2!NOg)Qz-CF=oNMRH9PIAx4_b2rth{QbC$(A$iUl^5} z{6v&4K)N}I?CIknw9hlMYNL~f)<)wcmk^0lLDnbwTYx`YmhCQGrpY3nJwyvN4G!K% zW(@-85kzI@W%t721~tCC=nG5k5jEDdpNIl@O!dF(aYIJG?HN(=Iy0v4&_`B;m~6@c zPka@ts)2h3#r;Xc%e`b_AB(-B@)x!(7VYi3E^*4b&H3MTr=xwmS~%rUfmkk;=32*Y z9_c1}=e`Hql~Z)Bm??X#-)BYt<- z+S%|12)!L@B{x_rKsCe-)-9py7*ZJnOFivSOLNfPH5}%XY+rYT+&vH#*EmR<9ne=b z2=+u?{Pq!ZNS3Va*a+;#Bjwl7YSLN9?k?t8?sToZqMf`lU)0L-eEg5G)`&E-1$;U{ zXLV%wBiIPm-HihD7uaqznNLi7UPJ0UmIKq0S@ZyqHw)YBWyD145W-#wi}Q}LBd7+J z4U?s@g=YBmoqAo&p!NZ+;6ME-??e9poq~PKoFYW+Q3+6@1*KP zQTC9ezu_L-G;XkRWyU8a^84hrQ${{N{I9n{uPJUg{Z8)zh;CRId)yO{MSiClgBx-5 zY!&7UeLDitUAqK=+uA43|Npz;{$Doe7Cq_-S2qH_L6@~g(;f!ADJY;^ex7N1RqX8E8_$|<+@5;%JjA4V_#V?R&~u$I zv6CBX<9VM1QJRTqJCb$e_;JI~HJYlTVN6#&Uf0PQmrK&a5-mHhVec#hxQ5psft0H2 z>&JuMtdwnyo1hlspO|=d#?t#$2V35e_qL;3d84U3X;LxLibi7PBDiN&|1kBa>ET#$oh00`wRhV0bvME zV*J%wJHyzd!PxC-JUbbsSW%OxxKKHCLUKiZ9w*8z0k_e5 z^oPV%r`v%&=#~_Pg=CEID^Rol>ZTb;{v-Ln5_YynyKoIq^ruKy4l9K&bqU z;GO2>+f&QgqqbpQj__JAbcaA(=V*mL$GeZi4w0<{oAy&eF5Fn#&U))KlQM1(rf|$T z;(~IHd40P#2+JBtgm2ZN!g-5-i;Epx5)hTVb}^bZ_@9yG`>1dcGD?N!>U0h+#3?R^ z1zE=kgHVI1?T+pCB_|^1K`56+Tk4eyoEm|TH6HAK0?w|xe2L5R+cTW+GX#q$WlswS z9ETNoj*LIGm;hHegR=A@C(xI_`ZY0U0o-2Jyp>&%U1TvC4W+v>CMz($Fg^qB;~GU8 zT%sUSFGa%G`AcvX0ZxGKckljN~%d1a|=rX@l@fK$lQ}=ECMRHL$NDCy?K|N3r{eAy8|fxW?2CD zQOdeu)0QF3a7jd(XdekFIEU{;hV=qS@B0K;4A)ARuLaz4-OCrk!m4t-iaX?6H;~FU z@42J(UdQ#YU`Sopd!7&wsf!Uls8+~fIx9xVJqu^(^sWf4u7)8B-n4kxaf|WWmJeZ= zZ7pR0*fPnTJ&M#yX{m}7QH3E^Ni$ukVQqM>Q`c8agS!w zbxE5dj{B?s3S6C@u||;{V}~9dJf?1X;n|m2_t8vQ7><+Lsm(sqCtdyO8jj{@5}vWm`<=v^olHN z?Z4gw<^xJd&&~3RNe9p4a`G(fo*)i(@dYdw#$-3Y1WlUlZ~qjNspz47=gHMAArCSV z1~82H?BuOGv|+=rC)fo}I;fyH-<^6D`6rfJsU59rvfWv0dp8%sV+|298R;NOQS!xQ z1?jLMLoVscbxyK6&k^PkkzT`Jd3X&>uX(fe+Z_>JRlSi&U7dOD`tMT<@7Qs*O@s1- ztk{%1geI3q&TGs@f}tPS<^)kiLz)MpFOnD-(83#9$|O*|12B}W zr5da3B_61Kf=e6J&9-;t#ny&TTpmPX*y!vSOemazgwrTX>xPp#g-WPP03N$?NfL65LQ6~J1)TOlBG*>n z&Y)0X6)ucTDbu0KlYJQf#!WVa086-w(_ z|Ddp-=)QRd=^PU9IpW9u>_o((o+GV(sULNTmZU_DIxu}mZ1%lvkmUUSy)t{UyvDkJ ze+v9$+nzzJ;eYpP9@Vga>9W*g^t~@oioYa6-?TUUR*s%TYQk>VbePYTGc}$Hs_EcA z!FlT3dU3HIvW^t@IRtz;UHjY|WZ=D=QZ@3(?0mNDZ*v>h#ik9zT_>@-W+g5~_*~d^ z;nCaj0IUx@FWfd}{nFz&FYjdu*s1i8waq}qX%5BaQvT=W^wAve1${(^c~nXQCn44# zC5soYr>*tqN}s~r?;pAj*fGHhtEeZo`O~I<+~VU+{z!bn@YgWwGB?Lucv6^yV~RB^ zF4rP^yYz6t_p?&VqKZ)khJqJi&utaxX9BVe?6Srz^0#_rD1%jx=5Jjb;(W+|C#x&z z{J>_q*TVSSw7w{U|JD|jSQWXUkzJj)g&R_L=}#v9#WJg2)Z|*9M$-BnZ04tj@RM8X zZ^hv#l#dO3^9qBHBKpI2xQsz}1j^erikz`DMjp;lLb}dO1@R6Io}p|tBW&6U(9xM= zd2Fs<=$b;LE|E85HmKVH2@Ksv1_-TlYhY=`QD)V|&jd=f9SqEm`M|~iVrwAljjB14 zCj4Uk$(a-(oOPV?jX1JYYip}p2GXB~a=((7c-tVq89r`j5J_b}WMH^`f-$an>jL$~ zn$X-@xHnqcwtZT)XkiRC88;XR<6UK-1PlSrXq!vT*7gGWtOrD%<~PC_L|vipH6FCH zm-pB7m;Lwn>(+gkhUg!r1Wg^`Z+{s5_li#GJe9Ib@)+b%-=33_SF?0$Hlp{Un{sIsXpu zojY>~z{1X-NrHToyl!}H$HF+Xg7*r|9YrQo{A&CRNVHymj96<Jk=Q(QP>>RaNfxdL6ZhAT%JTOq!cQEy+F>`*;F`Q*eqDbuFX{36M~|<0DCgh6a`Z1*g*uUQ z!5MHnQe7gkd1Jc>!23uz^l;&ku`JWgQJ=D6vFf&a5Eh5Yji;YNwyjPax`s0FM?sh+ zU`-DtL;hH#)YlZ--mxfcU&4}KEhQB*4DvM*{J|~#$ifZAP(-Tmf{nzb3_Sm5+a}#t zxYHSfgKo_ADGYleYoa3EL%m|!cjjFpbt9)Bk)gOj-Nsf*mACAsrcWfH9s~%GJ>vK~ zrmX!)Y%}iwwLcx>>*@`^&fOveUPk4!i`(5=J~y*_bF#4r*I$}C`2jP~g~}yeOzfv- zQYuhKz<{$P2YG_kxQIFG>QZ?`^4uB9OotK+@7m=m;N=YBK=4v_*BabUmY;g55jMBA zWGD%3Y+guiY)pRTH2qCEd{t4uk(-`?X+Zen>qPG7m=#}u^m32I{k?o8ZtR5#gCU*2 zvm-4D7-6*6*a{M^8MB*h8Fs$Wwh-@L%@|(jf>Ju4m={C@iK-Au+YfgF zPDKc-jgG(Pt`6@b!l((c=%;qP9?g!RCUaxa`w=Sh=#Z;Cq8g?`;g5EKloRyvos9Rj zoo0_uckZ#}wA!HVHR>>%GehUUrQVczmZZ&#=bMF`w(}g%+Uh(+>&G}b>|9PZV&zH8 zLO;SNzt%6(SzoW@LS7Ai1KS+NY$O1~!l2{e58(y3@{=@^ILS`EWe|_iK$S$6b#B)0 z=xI}1jsarEMA46;!eqY@&(IXxrcrtW22KEjevdq$A0*8&Ic|butHa5w);RE9YfLE9K^AOZHsqhR{FCOVNIUN;P59*1fk?bcE8gwTa8^eQH z!zO`M9h`xsUlB(75nMHeHqNSVHdeFMujc!&r@nzy0~b^yNP)kYj>x%JX5tOF);`Xy zYX2I;s08VhnM7fxvm$-AadS#ujoFQp<`^U);j0&%nX^>7wcHKg#t3$nS}6fDzUbzf zW_nGL(A#TZi%8d78Pr^B&R4eEQ}eqU$|StY-W*|2CGe+M&k zJ2kYvi?sh3D2@4%p6MI=;!i*3?3g6!ECKC!!4mUY+vGmx9au)_wuWoMK1BV|9~mWf z91ya;yc9aqiP!`Xw6hczs@M`b&i{=1_8Hw2{_O<1uIIET&!=WHoRwt5oX1}xZkmY& z_D%?C5MJTHB6~U0SgD)$0Ty7_jOio z6#>-u&hLeKq(sfiHm$Exh@E{t_bbh+1^*2iy@b=jj5`Ojk5XFq2!3<%0_yT08qRcXHRV5S zeHrP+h!pVQzQl>`yshP@6bsYTng!~g#j@7QL=-H#bR5tB!MfEdQl0mt=2?_^D{jMk z2j_!WneE-o-Jcd@p+079 z91T^;x>Ic-o#)dpk>WVB@z-VSK8bFhH)1W9jjuc0w>cjE+#cDKy!!+q-W4B?cYg?W zR*7h3Hgam2-RZWuq-DSKvThss(ES-~PiIBXUa>#cdsln1#5ux+z_>%ju0N-bBv?Q$ z20gYmYFj9sE3~34`=!+I^m+m z>=)b|TQ1OU?dN%mfQ&tZ`-+K~3FmBQRD0=GNO;B@y-*2*G?LK|*tA!xWaCX#x#og; zcZc*t?s_Y%Q=C{HYn}J|XW42f__!;_g6DIwZFQe!kuHUtemgr_`YN^t!pY}J$}i6* zNegpZFrNgDXidP-Gtgn650`s4Jf(zaPxg5rI$C8@XNj;^hT?G4eGXlDEwNBw>(Djz4qP}j)sY$p(ZQSb z?P6T@7_n&96gw|sTPkF7dMNVJzbqSNLM%Gw6B8qqmux#$E!NNbHgmN8vq#+4{}8ok z+<66QVFarUj{A}#+SZ+wV81T@ZubC6k1lIgxSn{bvQ=@b(yr%eBmV(>2*|BZcYKHP zI_7n^;%S}vW-dZ-`fegBGC$S!kJ0RMza#JIN2jKp)0sLyM8+pnYtP!WH)tQ8%F^~~ z*|&e@%6CIvr}heKf<484t216SQ(So(4GVLNM>VC9$sDP^~rb5)GI_P?nfZDK3WAEr_RmunGsH- zZkfqr0`g9RkoN1`cz=n{D{;D{;iPcv&A#Y1pBHZsYi|} zUAR75VE%0Fc+OGRXmUxw?!$uPwOMPl*#!N68AhP%D@Idm;Di;C#?%B5y4|$bM5ssNwV5k76gq3;lXGs!$X`6CR+U+QDpvPG zc#*CwpGB?{X>;0%6`c$4t9tm$V3)qbVVXH$t z;{sLgXDx~%*^7>muB|L8r2qN9hCf*c>OmzAIyRr+F5&$NXF*G8(o>tpj5T_hEjswk z3&5?03C9DJL=e|)dvj85FV{B9j`LcR>83H#q5c>DKaFza^g-z!VX zBLCPEd0LJF+*xj#wmmMC1wK!}d~OvkNzr8w_1SzKN~rEv*OVQ3H0jtd)-cl`{-`M} zN1fZw*aGA%qXgEBiY?VP466s7vptF4nhC-UQcg$hWT#YA`GGcQj*N(yTFyFZ#+T2X zNgUK@oSM{R)r%JpThQzQ8nDq2Ku`eqPqhFy8&s+I^Rv^3B`~zlix5pzftc zr$11z)kqb_qkkPq%+cLdUcwJ&%_mRGXRMuY*G-O{olaX4i7@%mJp@X}UpXnt`5``c zhKPKzk%3>UV&%%l#ScLdqHCs`A+`^|8F!fuRj`9|^}x>|^Kq*uB>|oi^r7u@Yr2qi zuc#){{F(5L-L28jWUWrC{Lh2nICCo9KpFlJYH!Z$@1E5zp+Q&&$ZG!f(^7q*z8LiN z2@R2+D;^Q>TC~rtEn&$KaywPIzBhdSxsk!R+I^~!ZT!^srEx^Hft#o33GvBIY4}wwgzbuj*Q&Wq zD`Vw-FRn~iws6%xI7zpk;bsTB#R!%;1lSN4CfJ)JnhzvRSdZ|1%*f2t>7QQ$KxRZEkW-SnDQZF+*t{~CV|L=AdR@&%Ulrv;0>*}&E%3uXA`GzQ zS{ccH5Xzv@>18%StdT@Xz-+n8mx0(HV~#Pe@7#GK>&kN3aYGPwF@X$f9YBm--Ts0; zgt3~8w3!ZC7#u{do6N|AU~SFI`3r-x0hr3>t<{Pa6nkDoMy0Pi;^CAJ0RDnYIOo|q z(QzZy=l_gBRBMm(u*2*^S-Vm0QcG`)eY5CnS;y3H8}pabAYc+*7Ya(36PaaxXBPx- zoH&PI{YO_07%>Wel(GoxwU_;X?9uLxT8d>}X^jYV?g^N$ZTo1OK@1joc}T*2sdtz6 zk9&~c>#-%0pM@0V&5DXigIk_!u|L=9%A-AY0LAb9>VYLQus-5Y!khT}NnML;S131P zCiY*x?)-6Ws5UyT7qs|}+1;rApJaBJ+vuF5`6?r4cbbCpZ>t>UlY80K9PPzM)&S_f z4exu1UP0~Q9@C-X?kH9G>c5zev0-PeOi0qUu7X*mxOCAIhW}>0tlo&EFZKs4XGtGs ztGrDXSYzsp5t%+AoIuc5s&GA+xcB$21dHw!89opQ$v8YM z1k|`2U|-Nm;k8Pa0uPRzyN_?2UedI{ae*;z`EwT%Fa!l>=rtq7>I zun)iz2Xh}Yn1NFSP5$)sI;ZtZbIbH0JqQXMGvo*4T5sOXSDuRq-lc56YSdo{wv#7P_}3_7zdHSM(+=l=RG4 zA3B+|d!pR?D4pX(M^pEy&2fVOzuSnANokC5y%lFvqT!{&CHTbNp+gcs(3=GNJ$8bz zNC&sqge#TH<*RNxfI7WD4lG0OA;5LG4H}=RpQVo&v?=-^b|;`VL)=V++`7i1 z@53`)$cvMfv7fMQ&`kS%wH?jz$-AfWZXcXgiR}YO`j|4$q(UnJ&{(=%Rpvbq{os#o zL(FsRRZof8$(t^#S41t(B7|AWNxf7P0m&ZqX1DY4uxF|>>qhQ<^3tW|k@+8d$NLS$ zMo{6Eyla>pPEyBlQEY319hmbf088JkEqu%VRb3lt@{Ef_-OPv|1o&MQ+GQYszjbC~V@2C2CH>E1kEzd+&p#Me zy~W$ol_}nl&lUJ;82Q@8ViBC=BFzx+NV|9ErV^=6X$)49jHDKH#Xm&Zv0Vt;1$E0! z8;x!n;kOM(YuxHOYHhBqY=i{4V-wzYA36=mS5BMCS~!$_(Z|AR{=dBE6p+yGG(z?t zj(EAta`E^sg&TAif6cRcFMZ`OGBk}f%tv({Z5{5VOw@^>qAKG0?Xj{&{PLI*m{W-8 zFZ+C{;Nt2HSg>i-YdKHR09E=xWk#fgr8rH>c|&VKi#N+1GZ!6P zGfnEV_52FrZgk}l$;&O=+kvkU4JG1gfL1PRMZ6!;@m>5Kz&l%aoqn#u_S=|+EC1Au zT>S#Zo*>w~6-W5D6QN(GX}!Z=9Hvb4#Np}h*HbKF4jDIYAax@)Yy!>`9%QMDHVA3u zcg1IoBI}Nyz2w+8(whvA6^DP1H1gPw^Gm%llJ>s`dn``m@b0QEO|I6qJ9O9_)TqlNW=5-f*X4C1ZWdtKNo^^4Kg1!shTC#QpQIpH z-11lA-PS(B=GyrEXba&9BjJYCbMS!!9Xp5^y)bsc-PUhUE!qqu4U9fA9W#jav644q z@|{??IlFz=VwIfL_lVXjX*|HXtwT5f*+;@*RW+G>XReu=Vd!uF*}*K@zY&|Jd6sGRe>Gzx!#8(^WQyb3+}7m6G5UOJ4byHY1VBBlw^@)L5i}>shBl(YHYWFFi(-%m z;1?yr=cvEGxGzI%!DLiOrv2^;kXi62s5+OXCH0o7{Fz^J5X$IvF=3L^54$L1>5^9# z#PSjWl#06sjxzl9riIk?W&7MB=y;@dB-eV?kO#y@sxUek$$|b%RZ@dw#3zmTSK*xp zI(XuJ${iYgkfVf&1BI0SWmeyh|8vipzr11MDlhcilQ|C|NieSU!XkEG^@3q}@|fyQdymkz9xvtr)rD6J z*r3WqWKrh0h%uu-k*L0z#`*-5v!R>3do4HcPug;|`k!|xaLt#U$57%|Yh=2G$2GHB z6MYGI3G1tG^cHd|Nc9dewf3RA=)r|^pP_4-3mBO8&o3W4pV>Svc$6sgm>YLMX|?OI zO{Xv!Y54|U?OLF?N9*sq;1NHXYioLs8*_3DdaP@KwkY{a9`_V;FV5Gd5ZSorn{smB zzoV_04*B~s!1pzog zDCe;aq2*RaPRU`3$f-FWmpRkO`FuVf<}_n$v(4{)e?On^_xHCw{PDi7>vg@Z=jm1N zDt~Ized_mKd*I3y6je$NFE-`Cy^6j;770v)Tkf)i2C4z=+>beePZvTpHk+qvui%xK zq4c#A{jb1imDdx#@>Jp(ULv6~M%HLk{KthY@ttz?Z66b25N3A7y_x4!?+o9yg+A@@g!)yZ(=oRo6#F%hN` zul#(omIH2fpVn>}scbPlp@I`OeVU>Xt|{|Fkzz{4A6zG3#2_V@JBLC?@$dPqRzA-f z;fUrR-mo_IiO=2Xg<%(qKu^>^SoRRwva~qhB)wSdaTq=M1n)uZ2t=R zWs2nzj3DcWLbdRPDpMkN{QvqgHp>3y?D52Gn4Szen+mzbYfHi#%#18%7-6yv*O{gj zYzviHuE(3{$H)I5&tE9BZhq1vg-cFr%W{o{UC@H8!QtEh)Qm>rySe^k{^I*8v(X8{ zvlwq_`v=}ln`0_>AM%{Uu>7ZjrAnK8IcPxjtRQWloS0eQI8+G z)Y6hc;Re&pW2ul@aI(4E<|SU>ytOu-$KErzUh2N5$VN=Ea`IzSs`DWs6)K<6_Q&Yy6DWnbzhK`^t}H zv?`xh&hrFC^KNWrM!6X-Sm@TK3ts5#N}Te6o)9k3Doy8H|BduiAbQnU?Ao(Zg{h-m zZF}FW8P|tvohTOem*;11HMCf@Ol2ps5${AG3*6vccI%sW=tG`_uW&|&((D}*TE-Y= z^NiIJ?e=+oI%!Abj>lO$RkY_hG}Mseq_Xr?`iw3;ZMpWiR?>CUqPkIVVnD&Gc(?AC zkWMc}G|K_^u2M^B5oU{KByekn<5Z1so1W7}?bkZJcK}%x(#40{S|6RZ8$DS%cFR-9 zJE12uIm?XyYr1}1@R2`?k8xWhvG2UT&>sg<_jvkqVNIEL%*utJOH*cdIG*(`7M&0Y2e{oEa>3n`jd*kSJq4M^} z^H6YJQ@Hd}qyOBVR>${Rf(3HLqm}6=eU8f_?$X-@F2hJx((;YJ3)JFwn_jxWehxmi z!ii@c@$$B_xe}h-e2XD-9g+;bs8v#S`P^%r*~&KNo1tUd>yRq9391#Hg#@XNcQyv( zWj%#wBbK9ryA-MR{0sxidP4mzd!sWWZy>q!1Et}?C~hcz`FW-5nMVHue~Sr?O3+Zy zca`8X3wlY>aeDL)62{{xE?RiLEq7DPJNT=W-^PHR%xqCy(Px4#Vm6p*d4RUYp}h&$ zQd%;)Gi!E)<$aGVsMQ@47HCdx!aZvSv=Y6~wag@`^b3qeeqQb@jn*lFITd#GM6&C@C2|n&DD0{b0ur)Wu$FYctj-3(H5Y-NiKVgs4yLD9*o@w#uLu@mR7Ko~K9!XMgI ztqS|i&KPof&>PGP=*6(u&QxWOCG~uV$(SQDaEfD99lQ&)T?C;xwk0k;rd#w7!Xn4L zD5sXH!ZlsBUr&V=_PgwE=4ne;8kLLafNU}pc5afJ@H?(j+L0mb*@lii0sEz3X&vPe zngRF6h!6QqAbNGp8xU-G|Ho7HZiKU1?;a&(A&V2&8@#%HS-pKbzB=GGFDfkl+6)zQ zjL55aP#h|~LPyRns~bp}-k z3`ZniJ)Ql;@07Rr$R*+OMusTbhvTaX@$8XB_Xe#x9m3mxBu{Z^v`6of|8bveC;G9& zk!+E^+VM8Y%B_F$rPZETZT}F6mKnYrcB;iB>(e3-i*i!`Ia{X!Q-Eq1x5loP%FlcRUkCPZWm~#obQh6c`uey$j6;Lr4#K2yQjAVlEMeBhd$hM<6rVb- zv(;OA@%wn#Kug)buK}BJv-T{WWtQ#GFA{|}k zf?loaR=Y2&W$K{4vR%7pbJx;$Fvh&f1uESyKk<6Pi0tU)hpn2v*8*~%@!*wo?9!~kzsne$@?E2xFGh5K?*VTdUV`-35?V& z?$7Xpy<&&J*tdD{N)rA&?=Wq+RG%EK&?xi@#M$NoKLy$==$_xbitcWwtC!rXo%s{Z zaqOJz_vbm7De~VQ`V8DOYmBsZovrMjqp`W|N`4Fp?;TvymzBOa&ldNen;DmtzJA+X zDjCfneUjWB5*ZYa2qC@zh+oedQyWthX|&!{tE=Zqb`GT@^e6MiD=Bt+EtCUfn^5Wh zQ_C*#jz#+BPJhndXe8(Mwe@^dkkSrLO0@egs%E!u?){DNTGF)a#pd=x1_)*+x*=J` zZGn?Og{|!a@2asin5&d?jj&C!oV|2j6lg0)93zu+nKU1$DyR!=JxvC+G)Dwf z=0<7e1XYB>GU{Aj}^FdOyCpEDI2-AXrJEPRN zo3|8hPFK55w`CLDbehYP;x6rKl&h^_g|(A@>K*tN)lemttY1&JesW#(c%6Zy(PG&4 z+e%93s&f+H_$ur#4iinUJN+1?yrfaf4-MdlZM|yxLp{%B(P46}&&qW)-%e56kW;^A zI))F1VxBnO_`9ZVPiWw$`VebU2Iu>j6C78BnVk`xiV{{_-_EW(e6Jo&n%rI}grT9% z($`leMNuje1{T#%nnXoUPZOPeUV>(`P&#Z{=|678F`}y8FDH?xr+N$%(8oMQ15T9M z1NjZy)P=ZB1ia#%B2ECz_g);}hdM!#hYOc8e*dIRBf%*4vew)(%x|_%)$84#1VL(@ z_bugAS5sAP2;y)0&B3j9LEtWBn)s9lnB}yDX3eUAh112Gzh%b6+COE!I{QQU%ykj@ zja9b$Bm^Et23o435UTPYJSWlq#9y8nibi}BSH-!Qge;G9|E0CQh6zoBk?yn8GD^Oe zMdoU*FHD}&)7Ze-@BIZQNqdZxj$r1KM&aE=maNWkuaGTNxF61g6B|M|L#*gTi6kHS zLkH5FN!62}#m7}0z6}AU$=SbN0AS+NnB%V$_>;$ zQIuy|;Xa8vy{Yj)`rG``!SiB&Yo_Qv_0^m{fBJu!21z#C%r{)Sz1lZig) zv$wm=y1D#JflzHogpE-L=4)NUvGe}9xdu8B$<})gHGq4~(8^_dLN^T-OIs zO1#kM`fc9et@byfuO0UoB4!dFPNe$qbM4o&-*7K&-j(9B*NpVNxxLaTTJCVW1uJ)J zJuEapRD$Q&WU;c{T=PQPVK8&k!mXElk>tS_dea`FASU=8#A80fB^dXq^X4YT>zGHsb>Zd4gB(EQat*+9A%2;oaOfT^)b~jU|(vD2BBo|n3DQ;8iyX#HR zH6LCkjF(u~M1&&GXbIlmN-{^e?5oslDL4Zs%kCrm-q-y}`hWZFJxxhK<2ODzZ%&6d zxP^3uENtDpvfg4j zKdKr^Sw3)#MB8Y$68Wm8yzlZ!&q(p5ZNWSWlZA8`&@F}%ZPkyQo zGziZQ0hA_Op?XJR#z}hn#+|LR-hE!JRrUKLz@_3hyk2kyy}UnP02RUZHc0kaicyu{ zL0EgkcbB8>GN4xT7VImNBu}BZ*Iy_XcYEb}j2aJHcDZMegd@;v4eB3#BixM*u}voc z9Qp|BCwHy#_owQfq*w-hH;Zrah$NUu5dEaNXJgc7AOh{zH_oKw(K5{_vpxNUpzy;W z!Hx@Z2Ze7C$6!p>@H4DCyBDT+ch;!mmng|_j9Zh@{T;6H;p50lZvXgrRC|El7p>kx*5Kr?e&x`|2Fjauh93r>Yn^}FlIV*qDR31u}Bm8 z85sd>z8=v}(ue&l;s83l!4d4n@6qgwKI~V#2qoUimP1X#scCFYQtST1^Vk0mVETOU z`f3@Y=~UetQW(C~Fp)HKN+TMDZ-Tvv*V^?lZ>c3|?H(?fPM+nz?TNgtJ#w?@dh6R` zjaGCTyxC0g7v$=XZu*(sqo_ud%qyV7lPmzs>|(AR+xTL)@)j&};%pPV8MG@B=E+;x zEYybrM7is(HwR-h&!-aC9e|*$|_MzeLUdNu;%{0lVK=T+AQG_o&qPwF3DdQL7SY5gc8)=9^M0plUL)L@mD13P1 z-Rh{nvy3K0uyo-4a~=Ntph4G`!SqMKxskck@n*3)FJ&hy)_7qovY( z9HHty<#!Um*WlI*Ba6DlCT*fN=58l#&eIOY_+BcL%Q6HUj)Vw@6VG|EB>M`H~#|Izfq4GK#7Vt1O}@c zn42%05g3&{I;QCPY+UsybTfl!i#adpH}f8ee7&6%v9+58b53zYend=2^55(WxA~{a zs*S|H71X};2#t%@Z8|EQ?0IhGNkY}`zwQ7B28jUavibhzpa_2Bkk-r=)MrMY_Z73e zNZ=kPAQ)^{9zS&LYsuU!*|Qs#;;YmGyPB-0E|{p=<*#{%`M-B(?1gmKLf0*}98$Jp zvo0>#7nt7tufje|Zg0581^~vFROHQ) za}W7I<5*nHw3LFRN)6PA6~g<<1|e=iq2Zr zW6BgSDCY%QnuQ5ln<*6+JcD-4lTbtJ&5;ij-f6Qmo5S!AokoADS(YXlcKW+al2;;a z2sQcq!*3MY()T^vv|B%zR~VW*V;xcc`tP_{tzcka(O-Vu=aBI|1o z0wg8|ANaFgtfco7a0Xywft-QlC-&@J?0nPx{Vm79}# zGHcPPG6@UF{OxMwknH%OM$z6)q+K-2h)2Qf)EuR*e{PH`+9V7Vnt(N-8;@)5+Ok9j zN5Sx_1&9jns{!)w2ftAbXh3l!z1C>rVvD?@+^lpFNtX6ZCE?R{t%>F;bE9}`;upW~ z!(4EbE#J&RJ&#USOY0`GzyI-zd=vJU zNo9Oa1m-S%Vc#%v;Q^}Gs)eQm&QCRZLf@;t`8bKAwwWVr|2i|HFN1hMWH8t!g>N!D z8zk~OL~C8+#o|y3f8b9*HRTm5weB4h%52kDb{dxcnWUbJQabT*QebZUcVS{-`;>Zm zq;HMhd9icWU^$1{;bS?L>rXTLX^ONLYh`9<9}Z@(iMe@X>i#rsSE6iY>GG7mYp3{b z?q+5r(+?bLyQkj;vnYS<|4f7dJcU&Gx0;C-llr%dQ5TzptL zn;_C?{OZPWOiOs7#pM2aIim`HznSFiTk?h{lDyUxc`4T41iD;98~$YH5`e< zoC-rqg}*-3nF#)?1LtAuER~WO1rOyMlT>>K8cN~>LwpBs zM@gzh7b9*ly5udJsNH8DkEE|l$q)6}q2PD`%o+wr)ILHbb$V)?X-F9sDaurM!L?7W zutY0Av;NLA&=9|baG(>*Dhy7SZI$LPk@EMu1tnXzl&7bKRz(z+I@KB9Mr_#@&QEuSh^{B&fKOYRVG6=xFu#-?hkElgvThxwk_3g zw>PllJ6Lbtx(QlbFp&%Pr%N+YJOBR@3)9;BUK}8ytCK&7D)CfG#g8XRIsUGzyJ>O$ zlH4Cg(m0>xohJcsB-iZf`28oJWDlfoO{$+$MMkhhk{A0@ElfC!8 zL3)J8*CY4u@lwz4xan4%&Dwr@6#Gq9K}1Vt>f8M>=PpEq7sJMFRmJ^FheMxVX-U5< zdMQ#%*_{y2%ClvE~>TS}Nv+6Ekh{?Vue)qksow-{YnC@THgUVcK2kH~rl* z0G@`q(l>sGUUCqIUzEe0_y5{DMZyCP0~endGZzbO+V)KkHy>O9QsdY>wu9(7u(siJ z+Q>gjfj@2iMfy6(ylgY|+|s7>4)9o=3*kPO_(Yh0F?C&>R|Z0}q{RjArw;z#DH%Md z(l%2I-MB5rcbkNah8N#rUq282_6;@>y;f(3mPRn_1^2z%E?BWNjBY8Q{*u8)>H0Pm zRg+{jmeVfr<^y3oB_76=aKXFn7qSJ*bV7eBn8<>5rCgAM7WEifATZxSw{2M`QfE8rG;rD*As;pE<{~;D{Fn3q` zqE<9wkGo@(R_ilSUK|9uX@76tc8axs7oJ1V;=2(fL_x>-2Q4l+Mq*}G=2=TJdnR?BbVIIb=CTgrp*3) zGxSYHX5u?anYVrtJ#?EIGpvXd&ku5yN`@F!Yd}XXlUKsQLpK* zCQDg(+h}lC7j(8JUR)lESMg^hVGse{a={c@E%H*${2tOqtdlCP=(+9=!y#E!;0`4m z-o81*`SZjt=>VWlNFB@4;VONnVCldBE1E(yQ5DV%ER|^$b^@tqsz8clfLvBxdS}}~ zb*;T6(-l8Qe2Z+@l>p|yRoi)KYdwAeSfSC^$UN@iC+l|uo%MS`;%B|$Bh4pXJq{p- z5rd9yQjT64s)>UB3`<8yz`pm`J=6E2MV2NCTBlnI+)PV-kE66l01XS4Ac5^&yMsen zWw$MX5f2~=rxj4il*jYuaiKvE6+{*$RS>nNJHr|6nm6i{=l7whfA*4|dNn5_{T5w` z9QS;=suJO~(<#zEUz_{w;sGrUws(9;WNPPS4meIQ00~fv#w2}}QKC3#7f^FrN=Fxp zZC9gp;=m3p_yDo2zhaT>GhC}W9|C3N$$(x@5`E$8^`fI1CgOtY(6V2QX_@+fqC+co zTJQfWL$=$e1_NprAYB5$zxOLat%vFz5icy7WI0g^P0kA=P!9bJ^l7E+-tw7@L``>| zD2#gb>6{_$Ygk&F1+&=#GFR$i{3OS#DUs{2NKfsrNb~Os#xa@tL2+{HKtY1Nfd6ZZ%WihQUPV=%AZj24s2+yR-xOO?*%l-VjQ}n zDn0QkW3Sz_)?%(r!f{@YTbu*cB5iCx2T%zu)uK%Wd-1uLgb*--Ez17BHp^ z(_-A{RfvC2HXl)`{OWOuGVcP~=5(!Dm1j&Q2=S^zq)L>Sl)9xb6c}>k+BY*^PhkOqP0jU_*7AOh5>kX&ehxuE530JKPJLy|2*1S;^pw)h zS6=*t_!8w-`@@()6DssKnUlt^vUN&aCy59zAlJdgEPYEY1(&n*{|nj1*=nDfozegC zgg-${%ZK3+XWS|KZnZFrDAz(1OfKoWk9=*#$yBy}5?6iO5Bg3Mis_C^iv$7FU}6y2 zBMNbzDln4$rW<-vm;N2JF*x#lFN$fRmf7w$8)duB)GvkCE7;;?-PkCt4jD#dsm#mG z$M}Q`_M*r+b@jb|y$)8y66p5h;!k}1D0M6C+zJK$(&fwD_D7O|PSP+?0Cw;^_^QqY z*wdN9_m^5s5$g<0b)0XsKK_*sD}d;mrxPByT-T)oadw@=(@N-1~U^WqD%ezz6K|^`(g^>d$-S_9bkEu zYN7Vxf-n6c$X9TlCPJAfG4x+U2SANW9ed1s{4YJL;^KDr67QznVNa=(^0rcQSH{hf z=e|N7l>2M;wH?BoX&nlL%tbc%ANR`24bS82R@MKGf`06dRpHcUj{B;hy_>9E%p+k> z=)!2vzsNqG_ezyWDvKxMilR$piU^PeXCgwvUbn3L*g&?|uTG^tma6Z`WyTXr`KwV-pN5-v&w4sAChU?!0#!WXcw!;L6YKP zDmLt$b)x@>;iLXh5$>0@A8Dx}Bm-ZL zoBCSp*bT0$EAv*=1`haGXfHiyWB4@)5No2gw(r?-)bRn!<(B)SmdhXR+tyE*K`VK2VP{MZmWWS8f1x3`mAP*>) zjF~{hKKGz-%^52_#b%hL58AkH*izl?T3?2UnwWsCmxOK3%9uK@@KdqKzuwALydLJQ z#Eg0&rp^v6Ui(-Ffnf7wdP%a_St~OM=nKEHjgMQ^)WqAC3TK=~1=(o7Ya)8yZ)mra z!me_U*b<(JUw(Q)5cia@#{Zqz%%Fi9&QA<3B zmRf=~hT;omwA;&VJITsFH@oJ>{MMXZsyK72z9CY&f*vz!(Y4%5Gt!g1W2dGy{d4ZN z_3Bm&GUnEKYR41yJ7*X=lQvzSO%gfcp_&oih`WQn@#3_oTv^wtR!C>{v>a&T;;OJj zKgPIS`=rmD!i+oUi?7*!R=bbsPdzfcD>`2$nqx0At+xH}+^Tmb$}sZ^%M{zyb01UP zqHyFHViBiVe;GO%V|ot1KC7)f>sbm?Yb>fb_;i?Tv=qXBxic-Z%zhCnH7qIHOkAA$ zM<^*=QvA5q)v_;nSHfpPIzw*2&g)2g5L ze-j9M$hXt--n1OwylhuswA<~49)2|37ZiG7rRL3b;3sn8p5OIjesfps5q6pAnn`ADRx?4-X!j`q1wb7LrR(j`$?;ulbEr8bAG=twz(BZRPvn)q5f$W^@R~!mb zSX%aR+!FyhDKm0|{hG*s|I_n75Ks1pfc_6ztiLtJ33T*yeiqYZI*VG_TbRXtsJ#dU z`@<-VTcrmZaHoJioRxgQf?59E@n?Vz$nBRdrZbq-s#^xx-1BKW7=C6>Km$ef9Wq~$ z&us^Bq8xr!17CGUTs{{C@@RaG)qRUO3Gf{zUo40S9Q|$V=0B(kM6+Fat=>XNG+wh=pi_sQ+00Q}|ir(xmCy@uFAKE~k^i6J%UIp^`Lv8OI=A z&+=3nLn0)f!5qAdWg~y_jMJjys@}aXXr2jF)}nAvodE16*wy-}#&K!LaP9{I%}BwqMa=y{rx*pi_iWgBzi#M z3SBg-6!IK=np4!rAta~ln$!)|S64VRb_)V^%@)*X_Ha{Q>J7h^`A<-h6E*1v{qOd0wZ2z6Lcmnni;t^hNBA?vqZ^7QMd&LP*<@D}1@MAvH`Fs?QY2N-O z>pNva!YtkxO2vl^e$d3J>5k0ZuJ*F-liR6N;;d#=QKrd$RA`I8bCYbYBj$0emK=_H zHbT0MyyYhM+w5=G^4Zu`y}igM9@T+J`>b&t=~oBQv-6jxg*AJD3W}fGAK{yKqcKWa zOlX$$h(HhW3MdwYE$IC;{Q*3Xx0=aY%!eR2i}7YmA zPy`=rYbUqQEQ%Y_mGP^&(CVJHPeJ3}Gg<))=pxXHs-mgC<2pI2Em&bV=n!!}^z{j& zjmoZw`!1z|Y)RaVM)NSagS0X!(lsQL&2%hf#p?pu1ib5q+d(FJCsV-Kmvv zvb45fPmki$u%+k{dtK`~=*vxx{0~T5A!EA^DqxJ%LU~Hu%UcoK8CA=w*AR~k{bEC6 zP`rclVM4Ee51d9#VlD6fFa?gs8@Bt?;m6ZoO2a&JSl?$&>)m_us}2sp9E*o3*vj>X zlAe?8HvVlN)~{_uv#4DR-3k@lL!;rYdT>qM^uWPn^jk*tr=8o!G0>Tv>SDQi(sPA- zV8`qqo5dHS!~uLxhH)GP7zqD>&bT9|6mz4u_o%8)Jx_KsS>3ubUCp9zs zG8;4c?%-1Zrk?rxjVX+m3@g`ZlMXA~)LZLTbS9r!sku!!v^VUE(b18?FerCW9OVR{ zdff`@_0)s5!y3oFp|pWatEAK7w26d%kSD!~;>KJP`x^pXMwfuWzktZ|*Hdel)D=q* z0Quv#o{v0>vu4}fe?*O3>(0OEpAB2suTTYfQ;7bP$_IZ2x||E!mw5R;woB>SGpeRl zX&*R)$Ikqau$sP*nEPbL+;m^TrFTf(k|SOsZk0V1Pe(-Deiq1x>yMQr_PT5^SJYev z0M&(eg|xp?+T}Ks7291Vz=l3?e_am+%`Ig`$=e>3Nltk!d3s}V#Hmqu2FtK?e)hul z9YwPXHuC~=F9S<20G_wd;46>~yP%f_k7Z)FsoXcYtr^bifCXc1dZ{~xcMUaIaj^3y zZa}407>7QoV^xjP&OvcI94ot;n3M0S`;gjgwd0<@|8&-s0Fr)mQM+Tk85GU&5EI9=Txj z=RA}y6P22p+83mtw)#HdTLx-d^R!?O)8Ey?FPn>~TbB(jW&{4gd22)lK8A55%ZyQ7~a>ijEM z_WFGb+C2tTxZ0t!{HLxItJZ%!^JQXt&yF$WZvp`^yqUcBq=e-iW2tU`Oo2>H@>Pzm z&nvmdJF9mp3m9hO>rFUuyUgjTqyEgJsI&%27GRz3+Ic*CMTC)#XDF%UoB!g4KS5fB5hpoStm*q#)>>maTYw^vWoyFXjT>~bj8F$_7 zYQRiJq_3vc$&rjJ+-|Ki1Lxl)!PIAO>Hd{0(kZwlz z4ncG;X9CCwh?19n_6BLfbgW`tFj>DKhk~~H4p6xsnGnma8ozhqTZ2|&>S={jHY#=D zqHQysW(%PiFLz~K-()cLtWI7n(TGfwfoJ|XsO$t=ie&$6Thj8nf*RDj=0mTmbiao$ z)>@Q)5{~R`lsfx!#j&!lq&U$SSu;p&-ncd{1qBqnp~cf8_$>E$%~q54NJqzgBEFRD z-DuI$MgDo*H+!YwzY6DCkjP?CHH*Kn7CWLW#e7>cN6i+Wu%>LSLrka=^%Z( zlKaAjHrJK4X#Dp+idw%Cu zcUO5OZ1q6u-+F~i7y^llU~R~3&;ExXV+!^LX&}No1ImfMGOj?Pbj%);x6z(3_@$sM zt4jNZ$3%NS5reON_-gZZMk*j%#52?^x!`IFyn03-J8M|gswgK?{xZ%&IGlN?^ZtrX z)7_yx3S=MIqN+4o&U=M<@YVI^E@k}VKX=UNAxL7{VuD%-GtGJ^*NwUTOF!X2p?`Td z1h83dId-NG4js9~k5324Mx$rXZL)s+wN^Mx$o5T-$^I~7>Yc1GNR43KFcKi7LlYE` zzsa&3dP@Y-0{X+Q+&!P3JWJSou8*Y$0sDevf<+DiUDth1Bp<%CR7tDRsd?bO8KU+%WJ8uwo*~HNw$X5e7 z)S|r^u(_Qtc-jk#>%nn9#-p#0FELCB)8~BFtRixCNx;nS3nz#M@{6JRV}F$M{&-cHE1h_tryIUULr?pDNQX_HP(j{gCC_|QAK_tn z;4`_TE1fe#c57B3aX&&T;J4T_$8Ke-b4QHd5SoMsdvwN9QDh$N845QwDc8%~=QoLF zolmuyvf0|>!e77_mlEE~^FP@}bI z+6f1rI)0I$40&Zx&psqP|HrRT1KMYl^h8gTAdr9>`y<<$b}{2HCC&2DU31K`<3u6p zzU?{F$_oi4qOSPQIq+_eGz$N4A}h0?IOoHiCqp(5#qj*2Z%i^oufD>8pEmoPNtNQI zBNB_8RQU0YW=Px59w3XzWBWpeFObVZrGBU*9@7SCd zd4lQrqH{KQpIk{!y@^b>gKqWKi6MOLKj+8#f?P|LW$Zp3aAzSy~*G6vv zSi6(>_+~pcgxTWw?_Nj-6usIH5F5?+=N{u5Yefs*CyZnqSv*Gax2}Rjt*$?2Ve;L~aZj*uIt< z89(?ki9HWk09K-Wt%0#m2P|Sdjnp6>Znvs{*n-hM`;xz-uK%)N%}>Q-CQ~*N%V>w! zA5nM%hL%&^3Y;1Hlopch&6eB&Mwzgjc>M$P5HMhvd1Gx_FOkx6gZ0?Vst=Tilx^_; zhg>@CrXx8BAyUM%))U zEnH+JsOfI!vG2_0R^(;>pzF+jQ&P59h2dgowv2aUX7!NNT=Yx*3*>OXs?ds;ceSl+sN|$Ua@$;eDUV za{6uOS*b(PS*YZ83&`xwOxlN68)qNyfSr+(F4~XCzHc{cw_C5YU-jSJ_8 zE6x7022>!wJ5zPNt=l^yK^28BZ7C)5fz6*EKm_(SswCCs2M!cF+q!JTggt%^7XYV& zvXCqhj;yWuO192am=Lc{?a_v?AKbNlLYJVK*|I`Q z6PcdVkd+6+Apg$${5z=LLulp;eTx>kk==tYwb!3kGWx5g$tz(+GXlS>zIh)H`V{OL z%wzy!Qg5(7xr+OIyU><_Q>YOCBc-jHnsD_Tdgbt707O~}@p^J^A}n(DZp%#l;qs!( zGrA3may=#XE9O6#U5dd}<^w2oOdmJ!&+mZR4@mI`$61}A+2SKtVYx%n7h7P#FczSk zZhcXD%g0T&ZqFT@$kEuzZJ`Xr;>mPK%w0?@mX@YGeI#63AD)>;T9+~KQkt!O&?k#S zjc&|%%W0*NxPITqrS*$i01ao4_MqQHAP7hcW2GIw{?xFmKHIFq7?Hy3iqRkKijXxu zFa1txUYIpWNkL#^K5fVk>uNQp!J@aXOos7WH%|M1uLH&pcefQofh1`F)oH503KqjG zy0$O6z6|WiSiSefR$*BDubunE98^rhJZ8yWi-w9ncLJikV!k>ZmHv_>b^XV0Jp3*B z?zm^a&3x4yfKp@O#;Gd<#TK4R{<`mw+>_rgYyG*m#I(^c@#uPr59<0M z%~-?`?n(Fg&}kKSlO|6+_I?4(;r+`0HRo!HMss4f*;w>Jh-jC*9xE&p8+|% zTK%2RgI36XsjSn1LkQb5!Cj)hDVjL0hxg>{K85n)e(($(1zGs(rEt<8o4xRaH2Ee*&gu%;PIry_Vg5Im?6v)NL3*kJta3`^o56=V-m z9%=&WtS#E(i+NSBj2wOnHyU!1me6 zkm6zzbV~)pj(M|3LRoK`LJStLzvH;)uRPVI#(m4M=Kjs=aV>}ZV?PG=WOsLT#pgS7W1V>{R8m4>w6JvJ!DF_?$M!~17duJi9Ib( zzOO+2J5lo5gDP&#_5IrG-0#{GX9ejapU@}(aqy?`vs^2WKCSz3q$v3Y*)m%pRYAg7 zN<5us4&wL*0_5{0GxNovqck+snXAKu5c4HDGHan5LfpzaGD~1|#gr-~{;2@% z5ZndQ@J&e>i-~u2)+kQj5zQG#Hkja0@1*Y?%J?J$spY*gqUV4M*p z2Q@@L;j(*wSIN4|J8G?vfS{)mlaZ^B(-DHJUKYbczppE2XQPb9153cz=uDK+W-bIg z-)FV^K)nosWh#9p%p%5qRxc7t-tq#8K>`qw|L-pOK!~VtFsOHZ zj_WqV_Kg2Cer|U?aw9oEYDaPvynvP=;ki!k^q$Ngt?=RfHI~TXtXphAjK`IPwse_* zuCn1X`)MdZS0ChvuM2XV>xb`qdSBFbb$aB~4UA=%(QNi?Q8oe-K#x>A^2l~ZV>c6m zY;mZXu4GOCSp}m3@{A#nu7x!>3eK>Ig`T&yB%ET)L5wYSqP8-@faKT-x)fyXawY z2XEcbSw5T{pBhtvEP{2=L`-@ru#W&14ds^E!$F7bHPg3HBv_2@n1yk9R(HWBX45Co zKKmN81hV$tty+i#;sTD5ffp65njc`5#i0DlkMxFHc$BS0S0iJ%>$6m;X7Tl5uZIpN zSIq66kDhvGXxp6$K}E!WnE?_;Hx1|=$P{=-?*-))o&}m8+)gpJ;1t7LXN8G4t|V(x z&%Vzweyg*jDhKQ^T6B~D4CeJWFwsNax@josZ(cn~aChfa&`+kx_*_V_E&By7@o3@1 zyr=KyG0&c3{_md*iN$%mX2gTK?n=So367IQ@q%$+!`VnOUF5y@_nLo0+TjHUpC;s{ zwzsbR^1Tjm9!@Bh&r= z#_Lw8TiIRY5VoX9WT6~qtK?8(q(Tl0Avxu2Y*q=$DLLn`gpe}A92#<(vpJuSo8z1} z!^Y;j&kx`K;rV{OpNH#uT!GwP)>qov;`QncN}_4!bifB)t$JnH>&B44zr&Z$5PWRO zWv3nn4ywW}((ZCy_{=j5+u*Ld*BO!~SOTCA^fD7Zcc1#`@K_LML!O1~=A?6eAP}ok zd)a3eu<|PX&`#gh_}}Q6C%iWqh1!}uod!Ir-`Nqj-6DUr0E1TFNnrLVV=sN59;3aF zSA|0q?lFthXqUnFxPqZ`KRT39e*CoW+}0P@GX9d}(taT*5r~ z#ZmOkU^eH;UEh^y`AM2AFN|UPnj0*XcW#XbyVlr%J($t@bRK-HV!B``JXH7ugq6ye z_5hV*IVmJ_>6kmX8U?>^2RX6Luw|;{u}f*R5ySDwrT+s0a)F|6rlOiAc zc*d4>Kwnwa2d+AH_^knUTRS1Q>`^4YSzofJ_L5nRy@6h>+f98v^=uR6nuz=kJS`fO4d>QRWV3hBPj>e0imy#RiN&wVBv@>F|C|NR zHUeO)-Dn|>+FoKK7w=cNepC{Wl;X6=F_^~X=E9hM_x;4nMe zh}dAo%+LAS)4KdGW#OYa!CXjiYrqFncawZ{7VG_tvm9{Z5%?TqHuLSi#^RB7Z>Vfq ztv*~FiOe1Ln#VaX>kD~Wj~Zgm>1mDZ-LCmN4&6~*fYGvrwSY4%WyrI|)~kTY2GF0V z-;%1NwchLtN5@yJwDB_HGCwvxQgXA?i+e0SNh19B9%oqKvp|tq1*jW zZ|Mbo-MJD8I{n}JoytF4_2VGPP~7M(yOQfKfP# zCRLi2qrjlZw9$_e7)Li65bd&j5-8xzXLs?xPLEEAAGCkq{rvtuuZM+2NBdPh^_9jy zl$Y3?#%#!5PDFUiKzMx84aN%~&?n$@TPyE&^_$ZSPsx7&{U_`KZ&R8D;$Z$rOT)BO zETpf>8DoH*9WBg3jCE8#{Q|i=_91)y`HO!#Nyw^hWM)<*SKn$yvJiaHM_Pvkx4#(c zsCMy=x5c;IggG_;qQ=#c!(Cfp_oe|T78Hk(Ed@c%(&#Mf`J`Vhgq^1aAZr`md|s#; z|8U?Sjlg+Y^(1Mlj>uD|*0fQM9kVXW)DC`%P6V)SX0{{PkNku{Ud~)K%K8WUQl3Bi z0mb|owN0K}82ds9*Kr8#TlzCH!Q@3~73Xqt-eOf{5zJq>y>=OE!hgZ4r;prs4SUYt z6z~N%a7S0&K55=4U_W-JN!D_!FZ?SjeCY|u!N2|J{W6gE#f765pa89HxaQbeKNw(K z+q5Q)Sj&p^%i3XNVwlz<-4^69#hPaHn3Z&$iFO>;c0g(7VUN< z*>Er>@Mo;=e~6XSHRODQ>6nK;`Tng%emgvl)}==2nhGyiCb8^IK$@s3{qE94aXgEB z8pMYjXu<{W!?fD|#aScqk_TLe2nAWtFQjWP%ozr~cFO&u1Wg@&f;49m~bgv$X;4LxXopEUcB}Y{#9E zBRmV=&#ty@j(ydzp_t>{w1GIbs)|44qMtBsy)IQM|DBmX!*kQ)vB)uqWL3{?`|!6L zmnp=?j1$y{A$~_ZEyC*B&5fWA0@5Ht8~9f&%(F^aq2dj_=?=O;ZtXJEw@4F*K>LZG z6lvvpNT;rU^3+aYhUmigPZ1cNU;Uojle5H?fbI8J1iSW3SF}RV z3coo=wwkqVSDKG3BImjv$vjTSL=I?A7KYt|+6e!Y+Q|oKD!IuBIc8jZirg!;A?nt? zUx-VUDKPkOT4NyIubD4?p<8ZxEtzd(P2VeZ2cm~#7)AufKRaB%D=6!LI&sW=#a_$e zs<)(fyx$Efwxsm*Pfw!@3}@K8p$rgguO7e!u1aS>+Qig+JVS`le3ToXN>Wy|!U1Qu z?NyD(BdNu;?OlDQ%*3?gPRkirVE0-;K7}xL2LTdcknul~gftHE#Lpy%g#*slOlc}; zZGtVn--!LU}crcds1o>#+Md>%li&Ui|mD*&J>0YJRy zFzl|^jl~zLT;0S$({SkAKx0)m968G51?}Gd-x@>}Kf%pSn0zNn;YT6S#^L|LlyC_8 z?fIXDN@VT=7UY0@D?Tt8OHv$CvZ;kkwkqDfnen<*AC0PgoM5eWdHQ_IsfhI7 zJp;+C<|`Qx2+c&=!YK8W!{YQ@h#BXH@|KPHo6A&FaLN;pq`3R&gxzbi;rO@9!fW@e zMZS99rbGyx;v}rmEzo^)6$FKRiPe>mwWfEErn_|fw`uw#&-Cl@?=fdGE2Ur8B2w)VTj`h-WY{&KQPA(Dk z*kv)d$D9R(Ir)XbLj=#_j5!`9p~28P0{>;4s_PO(Iyy~cEK%(DA-2Zb`Saz1?wzuS zax?LrC)|$2TXgAveS5z8`N`;q2fm+NZ}xxXdv-Fl$HDP!)7^LHUrMEJ%?nJzyEMV; zo^9=&KY(N7-(vTx2#e{j0kQgU(pBNZ%4ADj&RluSTF$RDrG4%L%lzjfAUS~)yi;o6 zYCze>R*eX0U&DZ{BR#;nD-QBRzF0s{s_-J>u(iKP5j;8MK>paMdTGXmkR5gW*iDsPOV%lMb`#rgC3rw2TO>Yj zV=luKK~IC`JHfWv|KV~s-N|jHykBT@u|9F6J!b=S*mxkm{t8HFxY%LJ+x{NaJoy4Z zW!bbg@c!VFx`Jw}#-^tF@^1Q(tzN%_myxglh1Iw94WGFe#6=LvpI~>X?v1b>mVAGH zBX`V!L(>(Z-tWBw0|d0P?UGlP*SGb$559d_Ii((6+Z6xK_H5dYe$mv2kJCz?&!%co z3Nr+H70FC84uGhZlEEHaIa2#~nAh#~{GEOP&D(%=B%5vmrQL@T9-RJ|j+(gGt9clO z+nNXE5^pt{1`F;E>rB%Zkbyhg?c?F+JA2iTF6HNX^ITVTe5FYxBPl{!M(}rAw~$_@ zz<|69!;vP6&}84A4f@-UG5R#8V|%yFpXe!7`oSqk*C~*wTAH@i+@Go9OV0ZQxH3P{ zIze0O*72e=KBq=pw|-+|mz#ND*<%ts*VsggMwW$6Rz{`b8Qq4H->IsHS#GZd(liu3 zN8na)_9L5v@4r+4(TnGH7ARGTUJ~<0FrhD1iiKr;myj(^Fhjgtck16s75U~)~ z?LXWQczU+lbDKXR<6l5z#qXV?yw=3Y$qrs?(8=b01yaQCyxY+oY7uS0-@0S!P`ufT za*W9hxW#j+y?<}2P$9rv4X#H9VfJ5ypLh54IJgdfy9K3$DW zwSrDhVfJRj4dOjpCf>LavqAP#k-uVH`l6cEwvv%GzGD^}yw_iB^R(oDNH+hK_wa|6 z<+z?~fSo?0KKY+R&cMbKiRP=3$@ww0D zori*q{1p%o;dom%xPC?MeLyWec15y9f!%8GKr6ELv+9qa%z@&i;L&27INWRN`3)L zrk`M~os{v+5fCz>`_Q-ndCfOur)If1xj zl^Sf--2yh`q`A6|5~kO4`b`*(V~^42qm=LNIizFQeYgFoffDb60y5!pN=o9(lF zH`c9uzUcupJzB@^3%G>Ec3=OayeNLEg@z<4-njvOP$`9YmrZhR7>x=($Xjs(Vx1x{^WPkLPY7&X?7f!yA@^WK9x z85bdbnohrSf8XVi{WR@P)Ph5LS*qAb{mB^2F>S4Yu{*o0v5)i5yzI)bDKbkk&=1?1 zB3+FT+Oo=l<0-6A2p-wSCcMNfPieGx*B|%%kqLOtR|k zlG1clsRhRPz;qQ?GZNW*{?IZq#Ir@%RFFpINkYD!^fY!9$)xBMa7?A2KpG#_>NNA{ z$p?rlyr6OO8cS{y;VqNM+_j|GgcbY9WSYTH1o9@Q^9m(C?=Yc$#c#!>Lbv>Ep)8)N zKWMV>k0^Van_tPP#a69VoQ=Q_CX3*+M*L8+BvvbQ zzLa&kZp&&f8@m@(f7fw6K)22<3IUSM>ppnb$<+DcN6V4_*K@>Z%$${olUTef%7=j+ z%mR}4!MoB6TB;&%GMe#t*=#6I2TnY z&#r{`mm^opYK|(`_rHB8#C~M9xAZFZSBBx_B`_nw`rXI6&`^v&Ve{?Quf4F$Q`sI? z8I}|hZBz_S@wG&4LVE6VH#s{5ZgU#bHWgtU zAE1q5MySJdnWV+@@-Nh564VbB;l#w`ORK&+{}{6%4&vgYIl&Ahp)qb__T zHA^_>*=f$rxZ`}8iRPR8HPibw`x%&s-aVJfiqBnk->`dsKX3tJw{CCocxNug_=jmy zD%j5~PZxO3RSf|p_*oHHRv-L-L0d_|?Gg@DXI1Xe$|uLgwGZF6(`r+tbd@(iUfv|7 z&@1!xtj90RPE+E-12&f51H}RO?AhIQ zWk(Glo_KOq5`--#j0KMj{1d9j&Q3-|X&gG|MQ^p`xy1~`!-L@U(uzZ_x`C{OKKLBD z(wo9hLZc6T33eUk@4b9#S%cwg<>tdL$Um14G+MdGl30h?SRJ8%L1+KFYL$XJ3@THe zd0&65)ktn?MUU6ZmT6d1Uth6NefVi~i;9ShIq-p`3WI`EN9s5X99Z?543}jfClf_% z6HmAwt^K8XaX@Uil8{9XCwMuDBh^bP;M-b{zJm(3#*HQo2AT%}DMTG;sn`vqDFiU{ zq5P!#0d~t^n7kF%d^Z&EU?*NZfZsixXzQQqVPgip5ofk>Ql%xk8|Y=U3P49X95lV_ zTtPq+tjq(ly7_g5oGnRK=MYo5vYsN-Hmgx`AlHn;2~imZK{3F=Pv&3|rPqTF9wqX! z@4#wyr-BU9YeTj^2P?cyTofQcVX`EG)t+|?7Ee_JHfO_Tsw$HMH%-H0yw>6$k#<%g z`TaDY7zAFt`7RjtwZh%*SKFhFmu&F~lcKq11Sn^lSI54=Y+uZ_V7km#tdIfj?Ixtl zG~LQHv7w6R+5yW=F+N5!Z#(LhkHc&oCBuRQG<5==+DV2jp7O01YgTH|^C#-z^In3R zi7A@=K9B)!EP_wfM)hW2poD?FzZg48cDzfNTapJk?O(;8Z<#*&mo7m1%|(CjpGV-U zC^zd`&o-*%EH6$}k1UQ=WR$3LCho6v!-yaqEo!D1RcMYXk`0lq9uOsoD^#l2CeAm2 zl-8O|;6G}rsr`;eiT<2<;(x42wfY+|&Al@)pWi81LF7sfr^=V23?8$BPviv@Iq)3! zKJIdUfoo_#7E3AlSR37is?5CF)V|1%Xr>VV^J`V)byRRsUve^(aiDIj{fWyIG3K|w z0%Aq%3x+~3fmJ_njZw9(y;;hZ){@rTM%= zKw^%kS^(jmJ5MIR`}RgwL0AwEY)|lDPJW&Sq{qV_R4}A&0X=)2zHOeEf9ek6G?^mO z7v!*8i7wz!T(lt2%XdyYO|{?Q-R{v0j@>RlU)dyl#OW*|v(^ofM#WLSW>8{LDXq(S zs7+<4rz8b7~1uMn6ut?@HL&{LQn?^;-zyxkTM~Mx821*!0MQHZ- zCUYDEm7#mf+Jpf!8OA4iZa5!C{%Wri^>Xgi*633(TcW_lV}kr3aie~&npO|S$t`$$ zo>N8A#z|2)w-v;XGqvHGA`zj-p8+}fK{NERE!TO6pHyE6_b25$|4v#({y>p)wLKS! zlX4n6IIhbq;EipZ3~v7lWPNo*7d+&c;+mU2H}4BV>NfSO*vAb!iTBg;jGZ|9^?=~w zDAij1xe&Wd13J}Qxg{xjtN`=N`*Wqj)w7X&4}!nmtQ!C|quwVoB}z>F1^FPaMK|Ot zH}%X>68~z7jv^TgX&zIg^TZyX_caSaKr6^`QK49t6 z$~S<+qqQ-!aqRdIcxNDDFd#K;Nrp3WjL%{H1!`rxL!1?H{4)7&?B^1NsN};`1KQ3I z$WD`H8?`W>yd4FjkuBN|21Cz0JcZ*{D>mZ z2Jg$is5UkIvu(e6zqiBArY|W^fpHzVGCpMVFV>%_$D`WT?rv-_Vxs$2e+ z%!Ux7vqj|KT_#BqGEPIS>t=RdS;>euuV~Fei$rc!#l0h3T|J;!d@{SM4rmze*6{Jz zg7{706E~Vo;X&irr&Olm^nPev|DZOBu#^sW*@;b07XCMZzgXaOBwu)h*vF{*q*ET- zU4#tTqLfFTiQ~a1Z#kmhRV8&MIaQD*MM5KtewnC}QZ^+YL>!GerC?RSyHKs60N`PqJ0Bf{Zl zj5g?#?nY9R5&9+BvBrL2+UCp1%*X3m@8F;D*f(ojmpf|ieWK<7jjX6qW`Weh` zVx3$eryh|pCIcLoWrCx-~~2?{Fq(0RT=*jACy0f1tuT73g(9>7&lZP1k*=@nYp zfM|!Xp!Xg>o4CQS!JqDSzeRZv>@Kvl79riT-TG4{Q1;DXp|1m?zzd9ttTwd)kVf<< z^v^Fhx^rytv$}ETJS`0%%Y>-4hd5*)k|n(4jW!>q;Bt(?p7rmr;g!bdJEfPOb_^Iu zAPr4r(4qhcja9)_30?tnUdbbw$6r&Oae$I6;#GLY^}xp%KJdK!%P+#37r3^GC*UQA z&h8Fc2FO&;6}c4fm(pWYd(**!*Hpr-A5ML?SZ&8E#OHKSjv!uQ&x6h%b9(x>)oc5p z0&Qo4ZA-%;^2PoucH&SB0%88lP_3PaEG?Cx+)aG@Lshh^ZI0ESrYqpu{6%Jl(`~P; z&8m^;8&aA#&dIPReiUIS26c1ug;`S?*Yo4~LP?hDpjVphG7b@wjB>SS{sTk7m-laO zu~5N;&0VFATmh(|D5$epz^BJGP*NJ`E922!3gEEp8XPapG-SPwtCVVs`1@8PjgT05 zYE5Jy?t2lVEYAPE9k^CNRS;NJc|N5r=2ZPRge;4Ed%h5J=0}|gCmp znNP?!;hm6eDIEp8An=N>&FdmMEO-st`afv2H@GoE?ut zzj}5yjFqigyVnd>_(cAiMv^7IeKaJTEkgq-#t%=kC#NSD8KGd5ZA3Tfw69!vDuk3} zuB_2$jHr6-IyNwR>Yi=y$Z^BH{}qc@z{s2=%z4;3@{{z5|7QWLXs)#Jq)8c6ln)w> z1wwHe#5m=;KgKKnl=&@L%#GS)TUM9u{S_bmfrI;S0V!rJ882Y$W%%?S>F|IwpVxul z(2|p3d%e}<`_09Z10%YDqOpFW$%M0Rgg6k5EaA1#O#fe6Vd-2VdoKNG7^fLD>jYxnxvGcXWgmf2ga>AvG?9G;cFDm~v5 znm5v$TsYi7bB|~b!jgHi`>33%!r0imMTFu4x1>+gzV*PF#{q<>I1P%D{oTb2SJ>}7 z4wMnCOmVW2p-RjRA=$Y^G5w~7aNfX8%M*tea_N7N7+KH&hH&?^oM1aavGjDo+lm=Vf}%^YBnU@j_%?vC|C3BufoXTY#D`3;q6?w=Q&|dMQ6y zwP7y1CHjMhzi9aS^UhxkyE}RgLKOYoF^HEGkbggt5b(FOuCjhX-T3fJ2{L9icH2Sz zdZTXU&WO6l-pm(dM4F$o9O8?TTiTED0~4{y0T0x80S`ZlC<*ZI4xdY;7_XL{_YgFo z^+_{>*7_IpCF+=8TL|^4Ly$@({;g@nPCG5KKhAw$DJf^DKF3{ik$G^WnH{+g4xDQI zl~)tcZCFrf^N8_T<^;jQ8SS0)$|+4JqK=tXXEB1I$zW&^p)kAKTv%pF^Ai5Rz?d=~ zIj>$H6A~JM;Vfco763vmdwhk#wuvNzvFL-JZ9UUs6d`_EDnAru^kO!aFmj)G_c&K% z$fzQr-BUMu&qvl~_ox`JB>Uve6uE@)xf%-QZFCB_wD8rg~>>*K4CFY$|sJU z`0w~A4jD)OEF35vW4W!RM2rK>wF&cOQf^O8S?w%|Vl^+cb$GTin&EGHdsPQMZ#5WX zlvmR~@%h=^jYHlH^P{eqic=oN?gezWW?<%s6ZOIk3q=_>x6+2y<-%iDby-cSa?eG~ z#-vqHnSAJ7EaGITW&9$)Z}WXbn<)UvdW2~*4g0kdQGmKv-rMaNUBtd;BPgW0vA&*E zqMxyNFOs7KRqVZAs{+U(-%;jeMn}ge(QLDiGfi5XIbKo%sBNv6D^AiOm;$?>$qhk2 z)MC!kt%W!NYQL`*vsZMr?j(1Q*UKNrdUqZBTVc3ue!417vD51gxm(wHv*cW?#&LB$a@{A$DrU3E=ra5E z;2opMh%W#F;oh(?$eU7<0w=!&bVVQ}+)Ux(&Qz;vBO5|c9Dq9 zsRl!dI1|R!;@etSUI#B|Z)r}gQw%Vi96*)MHM%3iuz8I*fRUZ7q>y8vf=Cxgrx@f& zFCtr_Y{^tXv@tHgbl5zH_`=e9j8hg3zPAL%{P+y;TS5YJHc`b7fg@{r7)vF_&}y$D zh@qF@*$N*|QC&9zaH05$044tYqc;0ml}ql;GE*iRbR6s|vcx-_)9$H{@r8*L?&wj} ze@q8QwGeX1*YegNBt|p8?E(_|pVy&RIubP4t+GSQY0udlG{|JN|E>{f!q^>i(GXG> z7FReh@t?(^D>t32A`Tx@Q#Gr4;HbCl{~Y%|N!b8!W&l$&ixElPrW|c&;%{LWM{Nbc zs~U67-IwWh2k3b@gaz%a&<%ys zBuTEUM0&Qy=n5T)7PuDU14sQzQ*#Dj;G@}ja2nY<%myL9=U}r8w{mk+WvB~|Cz$9F z558zn>*=@s{c?gS0%DY2WXS%A9$5A2Hc0Dk1^P_}GXemIY6z{l8JHseq!vN@hBO|_ zZy)@VxX54k@+NqW8iUe+GpfwYuy!LxUrLIWqg|Dt)TTSI62-TKtDO<9#xvaMkZ&yt zq_tLHsRX1hrJEM7{gb5E@hAEh{dht{@|3&rOr&k*%DB5ASc4ip$F~>C=_iHGWS)*% z>^iUkA3PZjc=wV0^?S;rzxm!-f3B$bn{U1CvD5Rl{FzjkH=!a3{Nzhvnv8VlV!IsGOuUlP{-kED@6yNw5awv@167KjGIkGo*1IVoS z>H&?{ove`XXxjSE+Q5Ld9s$b}BD;=Dhp3~Bn=k2c%_Z`ZQdJiw7( zi1#OmnR^z~4XU-*YoutY81$XCl|R$$^*#`n`6G0Ab>tNeilUB&`A2*M7dIt;#Kn}1 z>VlDFRWjaa6OnLv&en0BK=Su9zAS+U&KB(zFUAa-b21!=@Qj}VsxS%PmTA@6t?2o@ zY+{IlMoe?3jHiOdt`)FZe4an{ARt__@_#jV5Fru0Co(F*$Y3QC4O~fQ*tcyC?uli> zdhys|N&dz7rj)^EcO-pxF5HNEi}*9za5ov|pqs?J8RnUX2vF8yBpS>|N+p5~Yw@(G zc+Tw;4sY4}(}x_pZeOCi;kNn!$hJ`c@dNl6+ot&lWQ*5=cJjRHY%;X5LI@Hi*@G$B zB9=1fm~GSGvf2fgu=yC>%n5KfaEr@C{G2d~S+JE9dU2n?k;6_L=Fy%1jYr z%%%DFI%1Fm8Z+?>`y7_Th70J??9Go1SoQ!gh*$uSaZS|D-K8u1p14ZugY;JpfH+-nzRNEg&e z$hv$2H6~so6~hbkzwu4=qhV&sBeIF3t8Bc?6XA?oT8v%e8_o0FOb=ns(vfD^_Zegx z?=iQXy?}fpqFO_{xf&Sy)e%$7MQ(sX{bxLXRq@D@au-#Q5!2j$(uM6FnZbFMH!doL z+~SA4w%RkzERkq#$tx*8v@Emkxg2J*C&sM1_cMAHk_(#y(!L_y3l4nP-0bc+~gpX$vk0B*F~h z`{(*$-(%Qd1I`>EfqQ&uOlGw%fv39kv+4r5Kr#aC zW~Mpc-{rcb4$Mh65Pr+S`oYf$Tdxf=!?R?oFR-)L^h5A*$LP@ZP8^~HTT zgmh=36QpoEEqTYqbIH{DDx@S0C;lVmrh}B#oQ0#OZD9>!we*O7jC@(KX}mk zkveZswRZgnXglg`CUOf&=ZfyEpt$1t%l@CEQ4Z-u>E@PvevkK|!AWI?P~SBMPCO08 zFAYYVYE(X{dDtnp|78EWrJ{)5c-L4&o*PZque~eL&;2CXB84!)lp)%n7-jv~HSguz z*WC<^+#jb6u5ygLJ#eR^gX4a_UVz@u^U5QDUt}$Jtlx2_wDezVp{FC!O%0%Cf2IlC z(sLG7APTE73qWm1c#cG9b zeRQ&%h%(EVv;MKZ*N-8-ln;KL*A=5y>+oor_d`re%3yrE2fJJaKZaZW)wa#Y@5>+j zD0M@A?nL`Ry=q8ivUs@NPiEEo&OLl_RCqdS=4}hSE?{Q%PE4&mL<2K|KpXwJuA=y2 zGDR2Sko>*LG0VtEe&C#TjNXeyVs7lMAm1nlL$i#U1W#QXg_qTv$x!ezm~_5Ue3N$3 z&tWJ_G~SJzccb=G&}5G^*gx~j@HZ3-%(nhrggJ;J4<3G4*CL_v*D~~3{dx2cYjH4S z5c>z_l*Y#nsK2d12KU1#`ZciU=7gdR`Sh4&;`OL3=buduv!skK3!xC-V))OPI~HRv zY8Y-VPMXVKwEU#1h9#70zjhEN?u7l~4FoRlOESvS@vqCfCZZBu!b4%f)P4BjHoSwb z_=jzN+bg`|LhZ=X3oUf+!#bCgcAB^fP@~J>kR=J8%3c1$>5K$_9PGtDwsL0mNu#qC z-xkroRgcL42@353nk&oNt2QHZ=&*#c4h^N(OaA3 zz~f7_^bO*1L>5_imL*h5HxQ@p=+T?wFtV>8;;N@Ck}lAVKDz&6JK7v!xNkp)|^e@TRwbQD|x zvTLe@3*Dl@N}?L^8Za|hBf>nEvPQ=*nOTsYK^?pI^&fBBK+(Jo~Ojc_&5@p zNE$5efPI^EV1C5M$q{bsETi%mnt)f@%B7Ch-W-Hg66@hX=sXZW6=k|$;KlGD1d&b6 z#eB6~N7Cv2N}{fRGHuN$^ zgBsuiZJufzIj3jCdK=E4>o)6*~?x={*C$Fc?NogJHp`i^=q#GfNlTe zp5Yu&XS?b4>z6yg4TB)&OVJcyD`aOR#s?p;jHollDbrX>Wr`tZZVA$8e4Zr&Jiwjo zO9=G1@ybGBjN0f^m|Ksj9@4H&3e4gYCGB=zk$?TjTv)OW7`x_V0%faG4N6%Sn z5J^zk2wORbf(N;q3kA^T?+klc$4B(0IQK(M9j$}tJj4Fnz-?b=yN-^OPpaJ47MAeQ zMM2bZVSWh1=->E|>{Sw9;SgU9_~m4@oP1C@HN!O1-AZH;xeMb!YMb)YHCH*0;EG-k zklpP;Grfs)VO?Y{WUCB5b!)|i)7o_qbqBroKd2k_NItH{@6r5Z62|RIurk-wzXcCI z@C3}ov~=p7E>NSs$%+c3n}(%dB1R5v9g3M^X`=q49_-scGBe97CcT)((3H*RDG2dd zlElcWnrLEY)z&zSJFnS&7T(ConhSWSMb7#gk9{26Hvrla{+paK1ir(VkCEs;gE@Ey z`~If$AJ_(ordLMV(9c6I7dj-rj0b7{y2|m4?QEeRnG}F&1Tmrxv()jh&An6P*x>E# zW*yGi)9CK}5`8D`G4#i<-*q$i7g|{&cP@g^?07{Xocw?I^fw22RaeHSa1Dx_u(nnK z&AoB>`^wm5P*7}{GR&uo1i)|V1~=cguzO~vkO(Ncg0wIz`sG$oExW5>H)Ve`f~&l> z*%Q$I_e3C&<}5{dt?=Z8j(eNhT&`8-W5lDqWdj27b@07uW}Ldot|rZOu_ zFZ(%z@v%h^YB#9%8scEs^$GyJe#>{KUfN^cS4UaEZNZ z={N0GkJ_a{)Wl~V-mofm4ujli1f??PK!uunD~5=zYe!e=q0LjwlaGScQ2p zEDGSde*0U-adbc?XpC#~4W`zc#RdwqziNvvOWVK?#%#yUQQGxzJK3sG)ErMn(>HX4 z-9t-rmhLo9TGXHho2dFmuq8YAtKIc~!H1>_aQX4Rq4+u-Qn~U_nZH$oGVGvGGg2q& zR?V%{%9+*rN0@shEoLlw+U;#+TpZiRhP+X3(a+;?9m7Tj|NT~X@U%Z!6vx!JWN`of zi^dd4%TqD?OR(DIoNY~b?^ch|gVV&`#}fI$zcV3wE<3G%I#=gI7Jb8hQB0}=mXkGj zcaQM<1VM>0yq3Tj;Z`d)>#C`IG}x=v^^01isBn~h7R2=H@Qy66?$hKD22#Oi(5@1L^V!)-9++l1+zyqV(&H)<@DVNleL2A(oM$il$9r6bHOg+ z1xVGkeRX@(sIf80jzzs9Rqk;EzqBVVA68Z}E3=?KrD2zAJyfrs{xi0?co1m4fX0Hn zgCFyrMyu6nP8Ui&0lR604e02`?S8w(sq^hL{o)nS9Xr4l?{9UB_j(~~mIPV3UoZ|F z{cEbHRZx|$EM~S8R7VWkzqNbIvpMb~AkoS7zGaf1OQ5XSV6$l3%(Cz+uD`hUK@b%$ z8awt4t0RG2;`ncEVn;ap0z0`+#rkq;!1+5I;&_xMiGL={x1mxmfqOl&3B zb7W1OKhp&G-D*0_>NF#}4R!??!Z9uy5h20A)&Ny;KGHyq=glHF*=n*h(DQ2ig|t9? ztTEet^sAETF~qGJX`P1saYu=X(T1&1*gdoc}iy~nsH zfD@zQCW^JUkP9u9K3T^JczF8HYy(XI(%4|!bt}=M_pAcnbuC~t z0OF-wN5pPfdi>J*=xhjcU?pD@5D121D?jCkv+?IC=X}C4I3Q}cOH*hUigRxFb8QnO ze5dM0(L$tQ9kaQTPXUQd8Fj|+pYI>ZiO4m2#Ke4m$D*k$Bg;*CHJy1bXnR#}8`2~MpUfG!o-LkW9lwD7yZFGqZA9~g z?`N<_@7D1Bh*62^a}&ik&+I2ChIu-n#bQ1>&Zg^*gi zVUYJpwYhn@{1m;WAsef4+@-bjqKw9s&^ozvTmQY1(8N1!I&FVuMOp;|)Xmp?oWl|V z+v*;p-%opfjpzPIT8=|7tOt-KWRFo=f@Qduq2BSS=YD zu6m6n(H7-!Iq0NE()d*&a$fOk3L^|%d+DpaqFFxMSz*m`lDM?<5VtkvE)8N}cX?3E z_})0Syb#)+BI%*497B{~0=FDTXl-%`>w38H_7xqo)$io|6<&Md3C;3K1T8+6gj!JM zQ$Pu6aqZ*?c^Dw4TU#>n{qr|CfMR?yC&3``O4kAE{5y&YI~TA*JZeLC&BF~0I~o@K zT$^z+l2YgU{y+7d@X7V*TCZba%~6Y+N7g9u5=4H$~XFBh!w<8VNe zY_@+r&3kM3^>_u-R-2nk%{M)Xaj6V?u@=-JO($vixtK4ptRfVU+-M|)=v3M*)OMer zfvRU|rbt_!!otHmI=$Kez49FS<_yAu_09c$6=YdIX^(o}6t=Q3A}A4jse|xtwGhFk zvMU7zen_yy@wu$u87c#brl9j{1M%&{y0vTHWl8(DVc7hNP#mxffXXA-mt^=^s*s%v zYf+S3!(isbs<7M0*W_x5Syzf8$+12gsv zWPPjP=+prkvRLCsoaO z<^9a<_16P&RK$;3uW`MX>y{iNE*e(-*t4d}5*76bB2U_}`YlK8cdfu<| z4B__OCe6H~g!&+8nX?u1(cIp{x-tF1#CGgxelqQ+OKfI!lVR}cn~N|`&k;>;R12@l zl166J5!I4Xg<3%|h8BF&v9eWu$+#>Tprb-7+9FbUB~i>VP7a5eVtJ z|M4I?{!jy<7Idla!CA|eu;`0Xq0Mxp-EMCod&yQk<;9}?Gl7HBXSr=(?et_rycfC!9@!vabLExWVHu#b0 zh8}rZ^ov_G!y2@~@{FxKLs}Itft%_U*;Y}@_;m$5p9=VwCOpq~sM@fO>YIOfB8Hch z0YX%NUuy;X6=-XAe354;n1GtYG4{_DmN^uSuQ{14iT;yyzOJMj395#xKeJ_$1Z}9B zR?8rfxp_-NEqT|bxV*1y9o5B;OD_-!%7>#g)Qqsvgz zsK>I?b>XdnUBcz*N+(a}G?k%o$0m4?eP|2))W#=e7*x1YyW1O}GmH!i@|falR>8$A zz8v4{>o(sGjj9%`QasDcUT6T35`*#DvDKP$LT?fem6Eo@@3*^l7`*DtgiU6}2h!rN zB|Dv-Ygv5E>Vkzi)fN2FX&&oKYg5MmjC7g8i>eAal=UZV>D$clVuRjbT4QEorw`&eg|zGPyaLXuH~*LO7Z6F-J`#D?Ay+$ZZ`+^nc%7JRj24fB;8H z`mYv5BDUidqFJ%@CPIh0tz_)JbR=^1-`u~4b%*iW3GV@f} zIjc#cw>k>8d~d38q%1?7=xlI?fjCv>YJ(bV@&jBJ#S>>|A4F3>qum@ zNOqb1**a#jdj-}4!kT9-1}@b86`ALQ_>Xy6bLFFUxd7^@E=bGQne<@1d zV)ll2daRH5OkIL~WI7(`*&D;W<7Esjh}>kM!+ac_i!h!WlrOfDE7hl4gC>jTvrNy}x~D z62Egl@qUS(yX7@dpi#*os%I{2@r>k_lFCY}a?DRD1FbQ@^=QCUlnj zrSu5oWysNGT+v)+CeOuw5IUu7VxLWEXmb&#Sp5@|O^7);u zr7K;V7^5ac?D1SRflpfqha9MLX)z`7v5K)0yT;JH()?sV$x;>_c1VYHu#;SPYAU9K zgP1F2taaq81P`M9q-9K?2shMVTl~VMv~NxoX?Y*Ih!*%n=xm0z&68g_aDE% z_xWRw&px|8@9TA4ujlK~x%IAly!X=?7W>ESYAZ1L*})z?5~|R2Bv=rs>|?X{T)DWx z)5h5hCKDA9M%R@kq7+Q;$HvOpm%{n&c3<&VhB@zK5MvCk%WU=}uGTM3EyN>p+o_~4 z1Ir$O)7sOXf^OK#1anp6nYP#rV(mge>!-a`ol$wUCE&RETqO9@p!8%?2jeJfjxE2T zFc%o*uRSz;zY!LxM!K6_u~fHR^cA@!p@s4QAFbkuQ~S`Qyn}T|pVc<`dy6vF+|B;# z;CX&q6*J3x>lZ2hxV@`&7(Goka1jO_NhCcPwzMb|eClAD7_aB57HXEnN!O1;gx_#Pa+H*Yomrm&1G^1&ro^RF>(_EmWsVCnpOQu15$!n8qAF$K}fbTUn;ML=#3``3Kv!7;>vtE~K13h4GE zJ=92}BI!#e=}iVu*C6yqsppF$W#n@8BM7fT=*J~_krg{kU;W{(#e{RdB&b4p-NbChmdj^svGeZD_!ej}GGwFA?Ia$cFDALi+QUFD)NjV@|L1j_SLi}-_ZV)VX%0U83;XJA z@p*G)$Af3ZBc%4xRwLLK$HDXb@_O-fVGuT#-rCr_ ze;RlhIw(TIRyqA0`gL*cGlA5NkQ3Tyey~N)&G*K`c$Bl$5bHf9@QPCb$W=v$m6K+917f(+LQi9j+Kk(TLf-oI{qf`$Cl&3U&IN z>HqI+evwWu`RIVo+!fI};n@O6=u9_h$5U?zUn9PG(i{LGpb+a-KrN2TD;}JPcYt+d zz7{2l7}6N}fhj<0wv(r#(tUpQ6u0QB!2YSK#|G+!JH!fOQ+>dlc(Vt`ZX?HRS{1x5 z!JTZV9~2q}^NJe%&yN)7E$0w#)TS%v`8W>p1h;@?R!0?Nk4O`}XlJ)}=L0`%%BV%RnSiBrBSDgfP5qFE#z!9HBiDhg;~xq{~YQ1*OikJG2Nw z0`h>OsEr(7bUk3^m|@ESPyBP8Zocd5Q4B7hGEkQ24D+Twp*&02iQp`0h2CXKxJfDu zBA!kL>a(}3pjb|2^iXLS^slIBfa9bw?5*rhV_#29MoDAoqml#4vYw4P>F%#%qP2A# zMYa;pUp^hVVSm!bZq+E>yBj&?JCxx4vcUceVNg1EfgvW|bd$ROvxn(r8Ji0XbLe;P zd{XkO3hSKU)pv(_f2~Q5$N{puR9}*p^y-XW=LOd_x+VuWFEtF#@`WyjH$cN67JtBW z%)e{wQ5^WR$onlyug+S4Ag9FQwLO-mSa2Xsq^Hd#N2G?tF*^@TOJnul=Bot<3*}BH zO`j!4w1187!!VyETakHF@zSA@Cer-Z0&(v0m%u;1082NMcx^Es%n#;!OeqDj(B5`w zc~G9*pv}?BgLlTtZPx37w>oTmHNtts`&Y}06ZhW@;NlTeQ4_KcAz+F!<&3szQ2$7q zsl%3+=htaE-p>@$dhwK?&s2qpvbtE(P8YhWR;c#|hv6Ge^8kirt!{|f(+kGklE<_;KM75fKBl9{u376emJ&CqKo zohN@z811L8APC+;v+cSH8a??m6A2`&qgl79!GCw=UAT-nyXD=NuY|kMieQ_ne?liJ z6tH8$8zfk_1is>3BkZL~%iA~y*KbL9-kWyLOXMx;@@Ts=U0cFyjvQ*O7)jHq{*V{O zoaE&c_;eJGG4utyDr?RVs9KjF9Y+ibTzDa(O>V>QfSbywD; zOgyxH#H4AsU_OcCUKrAf9$&I!|DnWILT0@IV%h@>kjFeSN%Lk~$p);RTpA%tw``W= zj>T#S56vSwd}JI3-}An)jFTNq=l0_7$}5M{TcsrRp*&h#=$AW#w;Sl-TPg=j5jW<) zUD7DG{FkC~iN|aypG&5ikR*IRmP|_CZYuITrX|mnVd}^ zJ2aWuz<1RM0b6jCipfY_&_}RaB4R;`FDyN~IXfr)AfZlX1IQ5@I8HpD{1zo+JNLyM z%K`G3f|{egiM+MC>g`&9qMSkG^RqXCb%q@P7 znh!h4=p*ERX}bz+rIa5==QlRu5$gx1h$31D^vX0Fw`HC*>2W|}~r=c|}jAC?-a+gFbc1wLnx2NAvpM>)Hy;WOu*o*g_ zZBqLjvx6-W_K47Zx5SlexiEb5Xo++BlKgz!SDZ3>WvX`-2E2Lyes0bR8CFM1qy!~m z8RuT=pQV~W!w2Stb6|41$Vy;`E6WCe(IWrRQKc+Bh$ln#5mXJPh7Tp#76d(r?;i8~l(Y?ZL-k z;g2mxpMVGu1q!#Yc!NC$BCT%E)h(DSNnQy9pAyB9rl~9XYrR6c8S!uvPiQz2YKX)K zv>(*PNO7zr^>9OKpIe$6p4x}H8R7qaxtdosa%F6ITYoSscVc{!$v`}|@xh!L*C*|a z(e*uKUCC}}YZs2VcdICb-v`-i|E!bXYX_?+FBV*yWa$d~OK;U;lY^UaFqzXO!LxBH z|Lj-?(E~*zT%6H#2BsHf`hb=gro6$wgIUwMw_>f4tKbpixcp%bA~G%bW;U4>O11%w zKhRC3JA6TKPmb(xp4ADRD*N_p%uUk!8<;N%9>(c*-}Di-!_mK(M<*a)95%v zoWDwQx4;W2IBfPm2>XbM1L4X!M7V@wghO0xvTJ3=%Hs%GNZXD_9iq)We$R|&HNLMq zu75nUMxGUTtkj;e{bGL^c^Mfo-jV4Wp){iKI#IlBDrd%DG4KP!biwkp()G1*JlfZ# zDt}p5yGO0DDzj1ou-fpw@?6tI?9b=Z!t#{Tdt1S_;lxdhcQfL{&KXx?j{H{9D2=t&NgBVU&FP z*BDAquo+fRdH1!b^WeypH#Ysg!%5vvH$uK%KlTf^uye{OGh4)oeJzIlo?W2HTZr)? z)ms@!aaVU1%G(${MhlmvR=5k<;*#rA&X4iCr?%B4ojTXA2}LnDbKudR;ZxKGpxW~R z97|qn(Je`wDo$VAjLcdo*)oD{zB6lX3$KQkE#!CKe2M=0CK(lLoVg!p+;T)Qct}dt zP&`b{7QCb&&q+}BhBu^us)D^%r&py|L9@-FGSBlJXb%ww4{Wg>2CrQgbc6dIA07$a z`-LYLC=3dBPHvUFi-WpzmvA4yLKrd&cL-+hy1&5%RZH7#ZsgAU<;ChX3anmFhoBjK zYR(G8L|$f2+K6GrO(A#iMVI0ZO6yHCX3xajoks2Pjznn&=d(r@yKv)POO=SNd2?A| z8J1K1yxDRZ=B;E)D4*2-q<(+70J!d{2xIkDiluImZ<6-iPVGW^J8L*;bBRaZP2Bvx zr?30hD}dyVAM-7K^-Mn1gnvaUZ21ngW`?~wt3s@i!AjwGF^=Jax?c@kpgG* zwn*x>6NsX=Qm#jr5Y;#XLW_+};uCEob@`NNQdI(`9W7z#pU}iMlV6rm+6kM~czn==F+sf1_>I+&`dkW~Sd(Zb3Ve3+-oL{=B<7LW8vF+SCpfv?TmHU~f z$FU!EL5FXidlqdZxiZt2`XjWDYLK3#BDooM@vtG6FCOu%*eJ|v5p7MgdR@*5~INSOBC%2AA%_Y7I?dP0ce%u1n0_3>X; zc*dU+PC0gXg#LP44fXckUid<~Kk9mLIW+5oJM41udGn@0o0ozoClLnaBlw_CY3Sf) zC73WSM-kXjnoIDWOHx|DxXgdsbER6~Nrfy+RsMH^u3WcFB;SLf^6IepirGexJ+sQg zwqBnDJeHdkVNFj$;fY9>ZNUe%yAY2K4zZzeE6`i08tvXt+qp4yW68&7A^dfn_1wg3 zXLI$QJ7fMIjWqXe%`$}nkAsjvlgRWb(DxVcgR$17)^L8W=>uzKvhJ6>v={?QG;HpJ zI?#wUXF#8d2(1%q$M0U*nC+fMi-xpM2iy-s5JRcbc!%13ddVG){*c=^ z{4ooPe0mmO;f~IWHz3UgtKB|Z``iKtevONLY(xciMQ>ed-;&{}TrD=U_(xqnR3uhb zOX9a_9nG9e_Ll~E`hPLvejZj|V_!nny@QXB4^LI;RU|1Rpj)YVj3~I{6^mmQtE*4x zvI=n$3D_;?aoJ~lmN)Xf5^3wsK6mSIzYt?{o~OZlyy9;ePlyThqLymddh2g+h~V8% z2Vvh?hgri+nUQ!mU_wvCLV-GO?jOYgy;ORIFa>gOwrZ&!35&LoSw=2BY>SF9Eu zPpvUN0KM0X)?d$L37zKkd)yzdqnp5(CG$?I0R$&g0QoHFQ49X8D186R7mjiz8Yw*! zB__MRqVDF!u(>jf`ssqbABYFgoEm2%b8-y3#R`(=aAt2D-S z3P|?PHVFluzpo4QViWpw%3NjO+O{)2Oq965Tdg(R7g{jXL|*;z?C{^YJ%^k=uz!1e zD1fEMq6IvUbt>BU47dI*IHoW%6G~!dw@hIFjuEK^{JHrGacs#6z1b8q z+G8KtKD%{&m0;`YS*7-K|LweW7{PG&s4!8gN0&@67&CJZ;1-(H$JORk=f@TC`zf-O zL(y-6Y-JLwfE26tG9-f5zaaO8m{&!KZUjhg*7|Y>g7`_EQ_QTLM78NhON=MzqNe$; zTi(v@a#mx%gmM`>VdQg&^&F9BTfASibV*%OZsOM>GS{tVK|iKnXW^{;lIlxcL5cG@ zH*uGEI6q0gW^?aDB=)Y@kg0*WF>cXyDWv1`M$*?P@x2RT0l_n0;jo3HB9eC}G(I(k z(8lhq2Y(fxw_f8EI@oN{b*EArL-cW*Eow*$c0A1#=qFv^^Rd@*%)ia|DYm=m@9~M2 z^Geim$R(;b9S*Z@i-qvA9%IYdA>G`xM>_jjaOGwC;`6$_n*u12#hVr`z1g;Z6MICM zxl?d6jZ(mY1){eF`mn9NB3;WRFl_suP37(gZ8g9#siPv#*|gL<;A0`@tmOQTznc8q z#Z{a<={pSWZbc|O%5`pN%le)%(}sui%|5?^@CTmRxs>L~Nz`Df$%Nhx{1vf~?t zrvtU`%|!4NS>q@tSRwHk9wMU8jO(#T5+i3U5bEMkanR@KELc zsD2{tQ5GL=6t>w^UtcdiVE<8ZH)3Ap-Zs};-uY#~W@008Z`HliD4NJ%sY4|f?r(P9 zfJt#D<^kQpCGP&t;+v9Uyjpd(W*n9@PSul^i0zcp{|_}I*;qXl?#bKCT^}wqH(FVU zQER|k3Qh8TGls_+abM6mJaQ z@5t$(FCo87Y!?;oH^OMsM@}!-Zo=!?y^g=$%Vpo``&4RL2S+8ug4ua^2X53xuJ~M8 z_I;N6jqwpjd#C<;uhr1&vRz*{9jwl|zaE+G*V{|0VtveOfJ3%+dev|VcqjlZ&exFA zVUs>%_>pOA@iu$H4hhQE{hQ{^WVQP6JN%5=pb7x7eR zQp88`6{lZQCK4rU3Gf4}uqp5&jL?Ltnn7ieF4zj0{|ptoZL;P--+_fsmKKVw<-WX- zjio064gGRY1q6e%c}bu;de%1o1kCxS5qHu4Yy7uZZBgbG%l2ffi_b-b7iu_2B+WlA zLtil&{0|J%_&S&!w%wQ}iYqW@wb<=jn&DXWEL)96WI~46)umKTD``24C-$3z%J#pL zF7!9Qk!bmy8rctZ6AWio!b!ciNzfdH@f7pVdcRQZGZwi}k*k4wmJbvfT|a~VEN$-?ZIY*{f~vaNoa^B zAn+c{6@N!p0X+_wFcf%xLto1_;=)WD_+2&g-JemvfD;mW_y5-^A67e)7Kd5nd;p4P ztN&GIH=}~&b!bjy{0!)$?w%;kN1}JH2TLaZYHURN%LI0-66rgrE4JKy7g>y>TTkF2 zjgN`j1X)-9VikJL%iNvchHv|h0Fu37&wl=QqJ?(O{1o&u4*@1uMS~=W+YiwZ^hL-= zmj)S?5oh(!n->|{=0qt>H@73doUKQTYG*$s8ASRot603**!p^4-gl=VcGACa8tpaX zPxYGxPblQ2O6m{~Q*aI<~lbEdF11AG=b8-9k(^CkpgsmoXkV63QPHJ&0)sm;fL#Qb~l4dH-W znHskU6QK416d;3f^QnUMw-G`9MuEL<3_?|qF~RRecX(jr>_VjN4XZ&)F2~|0UiakW zT)85xS{wCe7R51zI4X3}z$FM0@1+c+4ke%A-LVdROvcfUthC=AryiJlwdefkpO@>|j+ z(3`c+11op-P7d2FoUGPQ^l6}vh)WX03wgnI`!*lwD`BpEtpF!Uj3y#5sd)a-!o7pI zJi;2~pD96+PROHhm@yG-Bgm6NU}j6GZ~}n+{2>S-IcZN1j08&^Dh%{(Z-H_=26j4n zMdE}=;zL~#{2D;*W~*E_`zm9Y`wC$3ZKl+`H(Hfb_2;%-^!+^+mG@~)lR)-tOv$zb zl>66bk5ZH>r*lsA6m1}cS)=^)pV8Mj0uvR!2~rkwxqLFne2NbrkKL#_{4*Lx3oekZ zE5r?syvGuyg5A;c{SWN5pd*Lo2Emkc1h`VGCA}xNJWN7`YPJj_8UXf2MRD=2tAmL6 z3?hA_ka}fj^g~|b;Qf4>-t=aJNiio6N&h0^U7up~&Y(6R40*v#yj6uN0&Gdtkh}|l z-|p_5$Y=SQCEO-1xQ=5lG_AIFQMvhJ3i;xd8}=NqdVp}5Aw~yP$EHFsX%ELW#5fmI z^a)By@9fnSQY$6UPU^S=(cQpB;+d9`Z= z2X$%(g*I~v>VlJk?K$Sat-cqpUiYw`5rdCbh&&g~`VqbM%umz+z4kdO4^LN&cpWX> zo}AY67UX>tI!$0bn(a|$U$@kN7uG6Q?~PuaJBPsD`Y!Sfr#2`UR0J;TGu!PtZ|rJk zo40Si+kb^;-iq9)=>~`bIX1d;W({QTky$oVX5bC=noGfpXGSu=>$h* zgeC;`R=-%QC%^fc%;+*0(-1aO-|2xcfwDQvv7){y*BR-IE@<38SUeqCFxqtxb;y2iJ* zRz2>rZBv~Um zc9*uy&dJa-?13PXy)mv^sdQ(!npK+u6FfWOdW;{fy(1CorKhg7opex{KH?HPzLi8A z&NUh^ZyN5C$Mj_wQoi3M@{2lD@f=_KMNRxQ{eZ+ft;}2F@>$Em9atAh4KJ9Iw&W8^ z8(Ux2tVTRQt*-ew)nN>BbzM6v)zxb$l%^z7m z*}u(cH|6Z0%}OgTPy^520L_odNM1BdA}N4Y`)l)&c@hF(&DgyD@`w8&J!AH@=4*!(*IFVOkM5r;79jbPEN?8i zbymb?VJX!S{6u||avDI|_swAc)hirt?Z;l+jS)=9EEx9lBh4(>Cv5lQzrd1_ukpkr z@Z5{H1ril|HwhN^PX)vE(q6Nz_2gB&sgZNTvPH1R0ZyjiUF5&!E!!vLoPRBgaJY}g z49S~~ZgJUAg})fu-fQqy&mBd!rzAV_eZ6!c+`(b%VX@_M(Nf~-&L){GF8a>0(eH(#YEgb-EadN#9lv1l?d|7mm5bXALI+(S(&xxC?*a-UzM{n9&^;q$J zQGg2y*iQpv$3A54wS}#P%CfRP9k0nNlN`Bu&<~jtMzwa!DgcmfWB7PmihA^sm8td& zy~X&=*`}v04gU!_BaE_6YBJ}`1();Iw1wQBn1_JN@{A*00Br+;@wN6u0ATW0RIbP) zjfQ4iM%wzTX1x^9mT~(ZwQTxzohIQ=hW*aYDS|Cmt1i6TFO(1heNqEMy%r=LX@mO{ z=>r=k8g8XCihC7~csqp)EJ_r1%zf`K#>_;+$ZA*LeGj|>x?79=ox;r2tqlk*s+3Zt~nh|3ku`Q37vxYg$^Pj4~ac>90sC_9d?YJdXT27Eq^guusQ z+kd{r9eXZ+EVQ5n7Uw@o((Vq7^qt$T%S{mTmfFp!eFD#phAIaa57G0Fk?v0*Ir%tJ zQ26dz^@h~m{ogt6B%Y=I>NhD_iw;##fJV~|e+CZjHTZ6BUg1EvaLCv$1sL`hO;+yQG>n z>AUuSHnHh}X(a)7fQ@&|1Q~MKl#E}6Le#|QgAu9l^*R?zqGBBE@EP;o6( zQSjGtMExVVqPV$aqMP0z9A$O>P_I#p@E@aoK<6E7ddt;aRp53k!gc;k0!KsSt1+0T zB0aw&VI_YyQe$B2#xyE+uH|@k3@p0jx@P%(nYOl+0S_Z%H58F+Uo+VFY|Vu=;`n-1 zozlpYn@$v@t0G zA{1dSRBbO8Sd0&PG-^+f%cl4}O`Af&D*jhA?BLITLlBV*yl*|2DAJ~1ZsH9cA?>|h zn(RaX#9>i2hhAleS?|rGW=gnNUMCVe7l#zkST@#Eio%wQb2`LnCJwfEI2vv|b#Yg3 z#WP$@cD72)n`zfHt~lO0a}sQLIm6s&B=PZFX^B2nh^4)@SnoendvQz7m)8}z9(Wug zW%b?PxQpq$zPOdNKWIMXJg5a1j4SCf9&kx^gIP23$`MrF$u6V1g*=~aMF?G0P-~;g z{@Z6_8{A-Yqu!`4BFF$=mC>#x#t+;8=9|@T2e*f`POin9WZacW!Oo*5!K=c0=sf9f z(xqsKO6yvBd!Ou%UARVQcp6J}CY4ca+3{%iL{twsN(c8sixyjiS-xaGWr3JX32b__ zb4t`yc;Ws91Yx@TQK!+%=Zyew|3VwD0^&k-qmJnJnI>`v?}(vyzDF@puG;6SKL{km z=roB?$_CXI|=AJ9qlEg6zu%=;X6m!7?vTO)NbY_VlNn zN^Iq)0t?LE^?9?Q8A?g<#QGX>k^<>=1i+8`yLt8LvUW!YM-6k!gtV`GKvudCFsF)<@o z$}OBGmfhSOYbMXk9hMlc8?6E+pQ+af%YF|UDcIn!O~0(iL-Pf08U{W>KA&-K=<6{Y z#>ee`+JY}n8`^q*MFpfz@rI6SiO(b9*)8fi0lPL|ZZCf~Z(0^&zpGZbmDzn17yI`h z@djWc`hh-*b%boAOz9SE7(I*e6_Z^4SUcJ(qy`H5ggq)&U6OC*yIvkBFl=HQ`Zln8 z41KS~#*+M{&g^K9Z9d4M4auI8+~@L?8CmI7w{~_?_b<}R(csAA6n$8jQLz9gb}kXInFYAD`7%0CamXZQn3Z;dLE&c4H4d)0&KNmVybhD<+jR5f$XUoDDS&BZW%st zl3;*{{_87%89qwv`r2dC^K}6(wrnE>ujP%KGH#x3Z-6K(rY>oIbZ5NZg%ZK^_sHHfP{A%uJZ4?19CUFhCKx z@alLOWX8i2$LjjIWrjRIryt7{U1NR#7v7(N&O2pMp~B!Aq>$*hx4qQW@VjlZjTqF~ zE-o!{_rIv-PGS-qZ%LQ;6KETQ?|xf__}3pt!W1(?sy~otu3fD{UvWCL^J1_xBL-C| zC>^6zE=-HQ132)L#mCmu`z^Bq*#nLZLQK1YENv;hA{qgE7~n1~{%qnV=FnZL|F`)F zx-G0ahoW0|Cmkft;XNY9{1d199va#KG;E6h8E#E;pIC@epBqj~k!WK4UjHwsM|*`} zS4etwQJkmsl+b08I8K6=w&3S#*f$oEun)yEN(<9!5;LnzV$Kg$6^6*f?Y9j8ChG?h zol6jsx7<+L`+Zf+_*DbbF>>?ItQc>p75mXZ;lu^P9c0fOej}m~Am+Cv;-J#Od$v&@%5$S6=t&ai8%cn&OEWGif`>y%F5rNZFxuEIGP51Y41@bRn^h(Q7{2h2Cg} zx3b%R7*Y+P6{tG`K z$SkI#S>T9H;r?HUDQ6oeO(EAUTr`oa~5&K}|3C5u@N1 zg{30qH-^DSY2Dz`K+-&^C-9Bz>E1k-V_?0xgCSY-ok<3~s(hmRu}d<9lNA%T@2qeh zLE6lRmFINwp1TnX2Ou2ve@yQ$i2dVpjJ1j!qc80Z$R|SZOo7{hCxDQi*6~=pr>#K$ z@pOQT0*z5~5fMO1WFQ!d-e(Z;wh2(@R-mZUui27^e@)7STmb%6lgn*>o){FQ@%wX+n?(oZ6DT>2-X8338-syloW~gR0%@<~_+U}( zb^+smm}Pk!ZMCqZrEhzw-gQ!`IKF64xK+EXd!g63NP|w9Di6WaqIb0g@#70i4M`e?5&}gXEZwSnQC%U4zr^K^bRWpQ4 zTLp3|ia+2MtX0sZ=${Eo&YybdFs+zP(SZgh1-?4`u2t(KTV2>h(X{J(Ly7gc!eam6}HCmU#}pApLa z@Fx0*uG>|@+8xUdO;VC$$IhU8O~kjM!%@+wgWq$7*Q7nryS{F0fpQqoIm(>5LvMQ0 zec;npSDSWZga?FwZ{<6qF4M|q?2Z`uXcJI36 zU>KYPnO4(s|GaI*Pfl>M8v8e{HuB5#-bi}M!`)vyO$U2O)}uBPV0*YV;pzFjo(n!8 z1-d@d&p1HCI{i`hvq37PXltFUbVX=dISr`flU+wLj0t)KgM18bFY`cIwT@_)Ms7|*)6 zY#i|ZY!bTW{9-|F&i3f2+BK z`1Wd;U71IY>==hhO?*1jVe*phV=I?@lAB(_Ygdl#hOB110ywHK)HmQGe}+ElQE7Xw^#GLWdt?CMMT?PgUHW6| zA3d6g`z@&dwcyuL_ynlsxtgWc>)HA-39x0Vs0{y@l(#qX*}B^~e#2O*4)_mu|ElBY zK4R)gDw+(B&X2i^KsO}5)R|}Qo-CIpq8aBd9$zTBF@5sLGj*m)@Ab# zU)2`I_0^GNK{XRIFG5SGgJ!I+5ylEUYU)Ozr6FJc?detuahjiJg!1K{5_ z9ir;l$tv~xi2LLmr@J&94dy)9@sYQ`vcI~+eH-ph%6<+nNn>%d0}H}1H?iY?$oXUW zO9h>j-@H4~s|D#PhaZA}`OIvbOAz#i?m17+wA%}Z^!{S%eqhZ{sTyuUACI%I&sPTj zX(69MT)Kta5=r;(Cs6eHgXXPi1_SE~xVKGg{zzEoavHUabCR(2Y^^=+p_p{i6NLCv zX}lFiYc#|i9l_+Q{VgVo%J+>&TGOP7WV8CWuafsW-?vBUik{myi^u`X+osn&*&YH2 zqdB4zV4%UchqXCncUs26bcAM8{n;xg%0*@pb@zkRf#~CusjLDsx1i%e}Jrc8pAVYz-zmAGCzN^((;-cRONvrU41% zmPtuUFWeebpRG0#j@gwfu1WgcBgz1l+n_N{LO0>o!xc7lu)dl<;XTsgq zhPNWY!<}6v=CsNqSEpVqJOH8sI;8k={eBkb5%nEJ==GIBv?3u@=G{9_%x0qB@{=>+ z)>3V*c>vskD8$_09lGX{pQFzWJ1X5SH~uxqtx*sZs>k|wAOeb z2-6EXTP6>h8;mmjS2ST{+k#i|7<-CXVRQvENkf+BE3CBY?R{-p6#5W{q$)ghhW?F{l3_VlEKnZIIDxwsQ&pT*9$q zVUj(ZCkO*q8i(p*qf}LtSKSs^Sh8n>n=839EEP0|hiWT?TmCzB$*Av1#3wn;kAu6f zc(kVKcwIHwuf4KBNR^5|KN%nemB(wy!UqNxj24(_-M4XNKPf;BJ20hkz8>9C#I$qw zgeV$~S&0$onSIRzq^_pM-oX7E?#l!4EzwG&vLm+}zRjn=B)=ePGaR{#O{&ipn|k2; zE&!BE~2H zSzH;5#*W__-$;}srko5tJ{mIO)fVyE*Hg1U%Qn!s6BC7av}v1+Dx|p)#f34o(+fj@ zitbz$6T*c9XOI02M^f!e_9aS`q|PZW=TNMKlPb+!d42}9t~V^Om~Io+_dk+kvt$bV z^Sdl|jAplFiEV)zq4U)R_opLR7kICRn7InU@lG!e#GmYn@xteqMrKXLX)X zE_8>8{9fH-bE~mIE+eBKAKa_vdYY^`0mf4Y@QKN0?@~Z#-r4=m zq#hHGyZZPQ=3FKT9eKiFIP9U@-C+Rd1bF({+|hPgc1ZBKm4x5q|4WUhkDxuU^NEqm z_sg~V(?}XVuLfjYa9uL8tOEH>$I&TuXLx5(1_-*y*F z5!1WRG}wq06|!}7N#ymOF3*O@{>;4KO>aUkOZc?-i8*8zMM-16Z@b*)$7ju@>gBqk zi+u0)a5;)wABb@Y24KWuEt8@2$VX7y4$n+V11!EIlAcN(bQK_Dfi2%53$nh8i2yGu zCxP?KFctTSVa+X$QETKkwN%Ft>NruPYag0QW!BoA7VUqDS0;s%yU#Y*FK04iN5Gxb zKLQ(kyah%DM8;T;)L#VhX7t#@hs z#C&I3YAD_j)vt?QObDhW+X6jC1mxqO#cW$UqULpU3jFuu4f~yj&so2}J5ohdhUMie z@U~QTH-64Cxa1|X^YhOZ>>Q0|<~<#sw8LwY%VysBW{^R|I=U}(=^AZ|4rH?A7{G`q z0@g~Y5b;?)N106%rs1Yl=c2Ebq?8hGB_kUeQc%TA*+kN%?)^-Iwz)W|@VCXpWq^_| zZOh|AGTM%pu~%iD6>l^4j%@BLuESMpm>QjQj)-#?H^N+0V6-H8v2InXdmxhc(t;hP zd`D+0d)}3+dNmkC_p5>K!f9@(tqO~@q!?Y^Y_3H;-|RAUh@AEJ`JUC*8EbIagO^ya z2k$G%LdPJzc{(n6DF*vIZ%!k(_X_uRlwN6AKRMChwMuaQ@i4R72>JdO9V(tEQ(uUn z<^B$l|smNa-*-Wwpz~yYFXd(0&-LfyrHrvg! zfEZ36D<>T&anW+@9pKh{#eknF0{D;;z<;af0^j;%>3!Z8-64_>N^H<7NF7q1VmXe6zcERZa@|X3UREqQAwMWPHMyqi%%SS*%E!;uLR0_;a%M+Vq5%rtgK`@E$F=W zhiOsSE|o5AAAxZc5&J7Zi)c;MOpt&Ll-?k=%g0SS$1wRqAFAq?gGK!Q;%5n5E5E#@ zsdZXSUeRFf=jg(b^TdZUb{798^Gjkr{p)=>O!_BF2Vb z{DtHP}o6A`%ws}Y5^ zkSqQvw>zu|%(i+!h*5>(a-_E8wBH5C4u!wZJ3?=_@R7)87laA(U~-OKs(KUG=$os% z0e!qbgKe$gCB#*X-E2&B_oGF(eY9WxO&l2L0-A5Z2i^44dwZmH9`lZuw!dP0VYpgB zNUYwlN!dDWSJbpNT_@nn;_lHk-UXYx7wMf9>2m(mppk35IsP(dP9`RRds%(YvW|Na zIq*id{YM(BUF&DH53eFuOqZM!NUuO#eV%6fdHrR`U{&tg!bTZ?*49+6A;VS@x;8fb zaS7l$cY#V22lZ5lU=jT#^vNi5p_Wci z)@(lY(eg`xk)yH*u^|>A!)nh{pt&d>doL>I(LT*e*-)FU{$twPcP^KB0xav)>tXBr zYV#UkTkmG}g2dD674wD$GvD`+h}^nfE!MbRUu*Sxn9a0*p$K6c@UVYA5;67ZXZbtJ zB#-PO5!`C)=0dfpvLQ?wM>#ZEAt?pxrn}0WF!Jj1pEu2(hmL$dl7F zmZh+-5eiG!=R96bk4$mLS-F@xmkfhGlHbQ^1GzrS=1R43Q$u0sqIF9GZ0xX1tD4Sy z_Ai7%nW~U~3GG;lvl6Jyrg|@WT|oaA(gS2Udz59^RAp&IsDTh{Z(uQE5gpJ+AIl^m%w&q}n#{TX)~ zJ%U3;&NKk;Y(He%IJ7lyjQz9M_MDnhK@Nq^w|R;}J4am|S$~5d>$=Pz%7~!zY0N@E z7 zxd6&qhvX&eq5hAibB|}T|NnTUl3Q7F-$_mtS?*#*%waZhm!wRoTf$aJ$YJEPIc$kS zPKg}CmXO>PIpoxAWDRpZGl#J`YuKD-C%=9F_-+5}uj_F=u6?f0=Y4p+pRfG0aJqa< zVtboL8XgiRe4@5dh;MHL5Ts7|G-V5^GRgk`S!N2E#}^%#Ta*3cc4mvOeU<7kp0qEQ z_#owxme3D3#rEskVKSd0f|N4sh~Ksw?_Tkdr6H}=h4L$U<4Y{XpPk= zoS60^ZbrA-Ksh?2#IzY}H%4#oOof)voeSiI1t@BF${hM_ECI4_GVG5~pru;kjSZ zXW_RsQS@7QqlC*X&odJB4Z9l(lkkA<;*x&cXCk!7jQSb1kW07{-lD=1Tp%uV8LUy< zh`eSYMW)Q2c_S+<)*zzAs2DyvP&W|b_H4FL=B@P^6w`#P#UK`!&eSD%b3exi&rJWR zy<(a+qxf7u4+cULr?VPUNb)OZ_HPe*aCdDKvm`2!WU`}de~Jl{(4KL7%m zZX)<%u*>ThT!NH`w*|UioAC5!ih6HScQ z0+dxj0tNn3L~41>x>o^cAq$0h^cGHPKdaA5#p_iN{Vlpg8U2Y+-3WzO@NtbCVZUz(;o*E(9NK$*J_c}$n_sREy zM|k;Veho`c25oQuws`qR(es*Z|LNY=r^)xu)?j}8{BaJ)a#t;7p8@9d{E`Yd(Nk8# z$(r}m-2Mel(@jfKcTUV8?N3fo;yiJR)mcp0?dBB9vca!wZ#;%#^pf%4FXkr)0)4f> zO+~*w9#qU~RAwP&Zjo!enzA}J2gC=-Y#Ri0^7_zs*O~$`qQTfVQQyanXx$ag1w&_2 zlZhAKKefQj$bYpN z(sh+`H}z>X?p+{bIH9aIh9_^DVi{o9ZOlE??dQGCfOOGEI_u##Fs8JtZEzCYOWTN z1X^Dw=G2XD-Hd2q5GC8*;#sT`$Y@A$K@ozOe0yV<6J)%R`wkxFWzt)vw;B&d_*IrJ z9bA|+-7tFVFf2^3p67PF7t79g)%PmE)r8){DqXjMeSZQ=?bO!iD#XMpVO=t2*!8pCH^o-oW!?k+vFS|D$0YJoWiyM`5`Sl>?ybJp67 z-6Chd7ZI1VnI{aP*0aDh4~J1jcCn?`qC8DQL|@&Ys=qX;@lqx%tX!LnR);Oj0N;0K zY6@FE5ZOO?S&6QkuU-2`^Q9eUB6cYZq1Q1VQi$Y}&1%HJi*Gn@P%gbkep=lUm#yFm_ng_)NGuuqoCF=v3v zn)D&Uvs;6@+t>Apkj1KSS)+;((h(3#5u40QjRB!{Rj+QpGmO>8(Hd_0-5Qdv`SL@D zf4%v*8XbSJ-0V#sl2?1i)K^=e@D}>KRK>)qiXtP~0y4Dz$q3|DRK{41D3u!Kjglra zi+G+&7>~}SMFl!pyQxTZt!3u2C_=(u4r76FYv7Es#{Fv9p}xB|KdNWDuhvYtk90r- zOHYeD)K)38Zv%162BI5e&~j1AUC7OA78oB^yVa{54}@LoAVBo#>7D&$Z--uc+D&T3tK= zvvGo0Hz!q5?1NcHluJOBRzKWs>H2TI2A3EhS99ahwTx3NqPO#63YgP7=souCBW`#A z_8v1&l?AY~*NzyyVNv|~vAH|h!E??6z8@_FXY&r@9iRlXQ#rq4Syjq$1Zn3Z?)O$C zAl~?Ct8n0Lj#RwEe^C>V?mpCfT7ZzRE$_K_J7Xs7Ipsbr_!=aTrFnEtTOex$LZ@`d zj-3grzdKmvry2H#tw^S9s>TK)%EY`%gDt#_2|8Tt8ci)^ET)FYhrZFr*<_0EJ0Lkj z{<0J38L-+(wC8Gefs^fUrEc43Xm;rW?X9WuXM z=WA+Zv5GLveo?8lKo|336_{JjZi{Y_v7K-ZZAx`Gfcw~=%?ps&`VoiH>&*h0Gt;{{ ze9l84MTflMN{L~oM7S#TbZfZe>O&U}SqT^SJ|?ca(}&P0FPg>IF$JYQ6HX&&PA(iE z{2%z{NDPj>K^H$ns@s-*cNna)#`*>egPi=tcYZm4D}>RaY*c4oaAg{8Bu32(aNz{R z#0j*S=4ZyT{zYEp# z4&1XFi+MXh5*0}Dh}L8FNN(PcEHT`|b6wqUcu1P=Ub*{&H+_Vr%s5I|Pf3)Q6Pwjl zqu(T{`otBr*NFb-qV?5C0yyP5cMV*QfoBn2p!oj3&8KG){Hef)4X(XY@&ba`*Ehy4!P zt<)jUJv?pbjlYWt-T{W$0TSxB2eV5R6G!~K>MhHScbJ_FJhke|E z?geG^>v2rwXW{m5kgx&NcJDXQcs}Fq)BxjM+S zDko}O(2XLK%6#2687ExtJ%C$DLWbCzn1HmWm5gNU;7^c#oOg$C8-86m*1E5j^L2o6 zMr-DsVQ(ri3pL_OE0)gg1do&^DAsWvN;%GKD7L(5HWV z3v|Tf^B9FY=l&h=5^2IP8->0{zmN3|f3oa61e=WjuZ#^ZbwJ_kr^geafeSHZG8;{L z=OcPiENkqtCI0&UuId{(MXB&ynF{hVU@b>FI!W%~2@FmH0Nn`dJ?wD`fnIkyV>Z)h zE&U$>f<2Gq=$IY>dS;eR-vkh8x(PsWlw2ytCsz7Zs{21u8S7)8Ziwe-MW}_SveUk2 z$y!mWKCM=HQVK;c6yOQ*2?QOn+;(04rC~NB5;A<4>Tq}H{JjmNI zVlaQ^V>}AVX{gL6+8ML18_&5(glZZ^avM?uz}p03TAsBc%28}Tl`ipI#jaA8t^hgZ zRksLswORPtRHRXADrvvdQ75{TMc3Jd#XHg$k)PfWe16kPi6(uveP^0N68ptp-fj#i z!pCBcHMO(w^D5iJCR4@+c$=1~@Ls`UsgJQa^2$s6 zm3!S*)T<*qwEnkLLH_I4uJ?IE+%uyOa&}=RKWNNownU|HJ(b7lj>ml0lMP?+3XtX; z8BZj0c7Jm;TreAb0(A0qbxs{z25#n69)`Y$AnW;Ja*jb3=Az-a*~W5q@n_DW!Zr1g z=w{`;n4mXcN%-NfK`KZY!t?qc;5S7QFRJFkh`0)z*``L6tc`kuHJ#!Pf!IPMbnNhp#ZG7f>jTi>KQ%Cp1FJ$pyaO+W2} zk6VbowVORkqcn9vezzGgf1zl^H2>XEau1`_hs!Qi>wb~iPTP2)cKEog78P*eKShY> z6`0Zwj@y?HJfujOQeR124YO9>-Vd-o0AN+mo!#M|CDQF|9cf{G+InF@K=oi}KPju$ z&B&@5MdGF`omFekpCBEM=d@U1Hut=$xw=X#wcWT&Qq06If=MR6t81xnsH5RGB{+&K z+Eo4@cXOvOwcJUf`Z*D$Q&JEQ&%KdR^=~Ovs+4QN{u>l+E8wPH;)mf?K1A5#iEFvy zi`TI}A7ON#TGzI)jrnB0b^t?SV2;r{I8o0Z82!dJ6b(NWSO0l z!F$j2i9f+z7NaB_vUIcRoT~oQwm5bS|CAb(o&l$x$F9AoUAwb*yVPjo?*8Se6r3i= zXaCzq+ljMNF|(JABQA9DI?%OU0gO4UMzWoYr$W8g!m$YhGwVKefBt1-c4PA|;kgdM z&1w|Yv^O%mb1iKEPD(YQRCi5UacR3ds=qw#eL=sLxu!45DvO7RMxsDEgw2A&8-C8r zH!z=M?qX`y>CyGHAwW>iPFw~YV~pI6zsH<0eP$kX;QPrxL4TI!223p_lD(9SsFx(j z2M_Z-g+FuV%^pnddX8P74Rha`&_b^XW(%uzrN0F7vL+qB?Xsq1TM@GkoKX(`B*J%c(;aP^Udg~v_bGcx*uy)*Lc+2|+acIdK>Enx zzA1Je5(megTud*DQp z$NH~Y;9U;V@q{Ql&E!m*CH~Pied9x})n}wQX5o{*kn^WVX*VYvaVW?*6ijKP~`>i9ZZS!LCp*a`7DiCXnRg~(Nuh>dU z{$0rM3fCC1_oMgyYvG|`Vzj*S<+E^Fft9ftM0#$^C0Qa|rf&@QB^^GFjz|Gd9oN~` zBk0ku5qcjpdoHPLy3e^UuV4=Ule;R2-{oHnVi&+$QqnNzayM75qP%*6d4Z1_%Q{;m zcYGZ;YizB=wmTZ5Hfq)^joxm}K0Z`8X)~@J<4rqj`cqr_wk>ozc1QpcWkKT5xz$H0 zeK6XqiX76bC@V%Zt>Zqe6W#kSx6+$yoe%3HZMriH$M0Hg?@>j7)<^O5TN&rsEdg@j z8)89>0xsqd@W>TipZm!H|NaTqGui+4rF!5&_`mavFRYca0A0A@pJMjcv&sNQt7#9% ze8K!YV*hhsWA96UFMZGan#z$%>gUpJUB}0hg7;R^?l<2t!d=aeFCj zUAN~_E?ui%0HP(|UA`Xc?#vqmZ>hYCK}8ex;bxbwARm|WJ|fL&wyR05@RB2?8!w=& zTU+Tm+k^L)x~T_YeJ{qY8@f%FMJP3&yK0;@eaKl=J76JvwB>G|K}3i6cp`w4+Zh0crY&|bjr(;eZoIM>G3dIBbnVl*R;0*G(FM*Ur; zG|N*RNUl>n9fRveMO^jTdDAJJzw(#KYxl@xSbK)A&{~QKFiG4uzc1pEqVP=-4)+)uy}8v=$DfW>l|Z`)<|tpIkQ16CaLI6c58& zMmxKIAT7HdMQAS9u2sokUxRJ)&>~F)%xtQ+oajy8B7IygD9mjyf-@W4-Yo=(fG%16+CH8YIBed`yl?9;6!$vH$1{FgI@_0 zIirVprs1rW4hH?Jm2}|MPkR{*G{reC!5^s`qcD2>HE_qFT}&ilNtG? zmHL}^bIzBo-5-)7&1jX)ho5ou@!~Z?>*oNt zup{4l2~wS)8u%H;Dn!n~?Q*(ZVxKrUwpH*78OIlqgT)w6b4h*Wm_JvCRbSOLJf!He zpfU5YHQ&&_^q#k&DGt@p)5*&FS8F*LlK!6) z$mkYVz>KxCUeHI<<<>q}N5(}ikDgqG zN<3KntRSrrT4(!a0{YV?g2%4>2n!jx8_lzn)Zgk=n!ijvWdZ7zOav9&E>)z2PmpMk zCtQ^;RmOEXb$?Axb6S#G^d1hi?ddW3;Z2nBQ9gN*&So{q9yb(w*s%7M{(gt!7Ko-Z z@HNvBNsujBc<`VUF6v1EIwx9me4HOqs#5vJ;1D9eXa$4~TL2n5nxsIdan`30m5!?Efc0*`N)I@OF z3p|GAWbHydMMl#W{{;RC02t}=D+q@9?eCJM_HKG1oV!8SS0((?Zb~b->2$=|Wbt(k zWos}%J%h`aDS#=1gq1qQ46^4Pax6xE5k0R9vq*2;h!CHpC{g7dF^r&1ZwrwG3 z(FTHHcdoXCp6>G4W6M7W<6h1o4R=y(1ihWz=*jkc{$yI#h^aKef2GV#ML+wi#&+I? z#tX$|7pC|8O1%$hPxWx0xyNWZ6Ud1 zPR6dksuME8x4irc0+^L0odXp{dfQeog~f{3hSN;SVUSvujXK^o`ohYE9c{+O#S4Pd z>$P0uEwt7t)_w6q64h#@ty{Z@F*x+jb9)HgnYWM{Oe}SSEM{bsvr>cA5?wbE*FUYi zvlDpc`!8f;@`&aol(kbO9NKaR?x)1a^sq-`lHDzb0V*Eo|cK$sk*iY@I*IB`{*jut;m0_?uPMue&lQ+ z=o(&}a^=EWYXy)|&Ie7DABJSOJz$O~PMRMU?4`6()q(dgktsr+m7|Iq`wjV@YvW&0 zk8L1!7*XZH4#_)m;xPMQ$A)ot0ntu)@Iy>x#?F91f*o;3srn{q{dM=>lujFI&>_TH zZ{+0DpZ~`EwJSR2k5$Tb!0O;DRfrpgmC9WUa722J|XH;2&g(r41) z6A{p@NZ>b47ltd(qBO&*{;2Uv4Kl!O_GG_0M{UpxVE$Gh8Y$co`LV zVwB%6$nm=k;AdU*TlXUM{Mx%LAA!2-`}$asN$erB0*X$ovRHrZ!E`FIZcfS&tvIG_ z1#P3{%9ah0ay|!Wm8zZq9Fyn~9%{K>Cz~wyM}1XtffW>CJ?M7GwRi_asO1JNBXpoK zssQ(5^hM@cI^Z0w8cU;}D7E!l6iE^-!OY3;;O$Hs=VKaPy;iiv)Q{@it5y#9-wFWO z+D-gJEOfwU`x}{tYhBp>we#b^%P8k`li$);ZiBh z2{}i_Xq)j3qUb4jtfeclT+EvR;cEF0UA9Y)v}1EYPd+IwCGxq)f9Wz}_uGaJ3KA5F z;o4UC_^Kl-HL2vFpEhrj!>LOmnTTRb(a(ZB)=}$G`ZaYukm|7BBsyvGmr2)O37*TN z81s)a_o`=7d>@s*y|U?Hb)@nm3#iC>TAn)h$BxN=oT@K+@x4v3G^@Hor0hp^B}Lx# zUW&aI0>?4O6@5({Rjg=DzMkF#cXXz=L7vj#LIbX+6*+o1sx$n?*hs19V+HZ6m9Pw2 zg!iH)3HuB=CP`)oUVzl1_n0siSXb3A23=bz=j!toMF6~^7%%ttC-cbL2XC05OU|8@ z+6%~yw8cOBJ$cYWD#o^fvE3PR^wUJY0j=wI61p_53He4`pu^ht#v@S6*O17iC|{hm zj|t67DKHSH@Qug026;Yv`$24pLOV%E|9x(QO807E`#H4@mp`5WeX4!Y(_Z(|ouu7# znZZ-mrfai5mD9lx>8h%<8=|e(L$L4#bmOIvQ?8J;Rd4cRh=vrvUn*|&ZeiYBtpX`U zV#(1aT`J11@thO3%B)}i3iO8-`0Y;t3MeCa(kAwwOa}bhW5LXC(2V6W_zTYf7$GONTTiYOZjHr zsewn2Yj0?ZdNJ(EiA^ae-Iq;KH%U|ITyGK_F%+)`q{k-4bAHFmHdk;~RJ-(*x1xbs zOgGY|{huNx6E8FyQe+xDMqGSsI!Ar&6H!th_Bw=kM1lP~?psVuGYmQaROL7-J)oA| z0ry&!7dQWJ@lCV|Vp+D>nMm%NjARIhZ_x?gkGcPk8Ewyv-g7W%$e^^ys*}?Wl2_@P zm`hzTX1*J#RDG`yl_CD<+>7Q|6Ss$MVoD}|on1O^Ps@x+51y&lq67o|Eh6@4$r-mL z$l|ltG*$fFO+&^{ehwGBc4GsV?`>yE${V?Q?Dohrd;{s|%pX@FaQejR*|QL82wPP{ zYNhNcze>wWk}tmgC!y07k9IyF3H+N2N&NubwwAm9V)r|M#daS~C3I_B$rU`^e$kz_ z;e_%&hTd}!y1!gqr!c3ySb*p9&uCuJr46R29>4k_GWT2STpZY~>S6!HQAPr3sPnoS z1d6_Sr6{!aQeWQo%ad&3=2U)V4%+p6g}j#f)2(#9kDEH8PGWeA$$QMRO$|IgJQeQf zIv8%q)iZ4aGGBpHiEYgt5NAe zZV{iGxnJZYnp}9JtNo7!by2!Pg1P;ugY9tO%(Hg(7T=z+9-spc&rb|z#-s!LhStZ< zCLW9Z75|i!sS&)~w*B+v-AvHc&8WiFJv(KpKJJDjYu{Dh7wd1Bz$>~(u!4t48^8c1 zc8;{Hp5aW@BC9u$&9vc1sd{Q;ci7-gBS^WwM6ZlHVW;Mhs_+QoWYoy<5%PXrktOVc zp)HYP3HGIDMd_0~=Ab$Z1EHA}5WAp!;aJhPpeP3_wu8T>Nap=g;I8;3#u6P=3HtIDWFJAhxBuZy}T9OeV^Osj=s>|#0B)l5Vt zLuL7yh(B~Cv3}T3g&pJDQ^0b)i7yptR#c47Z9;c-Z#k!Vmh!nV4t6MiZxiPGr9*Mj z^!IyTook$xIUiiEdQ2(Sq#u)Pr~X3jpKt?TEe{jDLpH*|N2r!GxHaAM^1oU3J{qMF zqla7&l#V#C))U1O_1*o_lg8Krygiqi2QZf?ycW}w%Q2F~OQTKh{*HGwSKErT0c4oX z>d#7=1i7+@!($x8VF@$037O3`+C5}_-`NWaEavI&?DipV*im)pRm}6}=!)Fde6NpP z{946NEBv#2R}!;=wKjhNZSz|bA@&a-aqvOQ5q@A=xEBo$Gz z^ogUd)@^taBoHPKjh^rG4dmNjonJJ+f}KJB-ELIlfI0Fz1}0>x>tBHK>KkqXH8<`e zUPs}km0#Ol3Hsp?6)dbyB!e8hI$dj1tm}`<^4;^7Md$2+VDQa&P1%a-%isSjO=+Jc2G zRpUt<#cZ5mtlh7_DYOm^2Vc%D;T+dbrq2IY;X1);jV~FUlP$~;RUDd6bt{pno$!U{$m)J!- z+0(hM@g`#SuIW}UV71BcPp&y<`NxWG8HSt4doSC;uu+M3J-d@2{Lc1pw>7Hke$?o; z^Y6@6wR_DV!c%kb>k-~s3oIP5>bLW|YL~|F4CI&$rl3DHxx7}c;HSYaHVDTt3Ust>8>>~gez?l zo@7s>c9`VUEHK0z^B@&_0?k?Kc)(&OZxr5UF@3Bn=b5X^CZ{j%UqG6j`szIxO{Q;I zhwE9*y8dq4d2UJ_4Pt%F&23I_Qro!SrrE&___+y(H9EogR>TB%KA62|ZPaYAG%noy zUYEv@+HeP~oW|%)tY>+R|I zkbCIPiPq5QW*cLknQr9J@rr`4D^MRwFRH;NLvM>V8ssC}DH zO={5&Ydco$t!BToss-~GFhx^S4~)0n$G9>mrGU}i6>llgyMg4um6b(vaF?oDWoE>a zqKKLx$DJ~-30@>~{VYpCnjjq~k#rJtx?Ca}p7T$BhX#%P@llkd?>U_}TC!kzaWG7C z{)yzokGU;Fwc?~@aFm7l?P*Lx@yV12CH2;2bhhV zY=&_5X<&+6dsIG9{$6l_K4$r3aPJMw<_KCvlsP-<`vNq z*aCj;Rb?d{qD;w_`E7TA5z~1gltRc@rhn<*GIQXT;ZgTZjL0%xE}lNsxoP9wXDdm{%b`i0@|F;dEb<3 z0SVzgG-UZIYY$aArInEf8CRh50W=Qe@|eoS2dK?CqG0S{}`Pfe=i|`b{ z)t$}Jr1qK007C4wk(=inV>I}+HI)QXzT&;!##)jF{CH2IX|n-v=h%=j!`++yB%*cA zgHwqc2up%4x&H~i*!$mDB4+1)QqUdj>0@S`u znae8^zIKVFaJ>zmm7S)oxhjU@2~%PJmd^Q@r8vL)Pp(8?F7>j77?Ox0Ixm>Zb-AImY0W}d|E_X{$3UX zSI;Dj9kA$3wOf4MRr8A+*b;tuEQhC2H4;_s?*s^Az65WZ6*ts8gg!t-cJ66TbVE(f zyXVctJ!DVCkYa6=vto2XXwStH%VQ_dX!`1HTSqqWwg-_X!DsFG9`2s-72bpmlJy2h z%$jW>JHgDAvKQVUda~HZ)RYhz)7%zJn%h*}e!0WL1D>xcRkPlu5&@i3QhWz(x3C`^ z>CVk6+l0|z!oVeN2fDxZ3fWLHtBsPlkHQfAi)%`t!Y!%<;tcO0&zJ@>LnbsBuo;JD z?M;Hyg4RuWJ>ypL0Z*CN+6n3f|KD;eCIe5&)HWzd0-Y z!uxc}{^yNSKjG~lf#xt2P*or<$^5?MPXTa40=uskbjPcpm-8p!jZ0C7RXjU@n2le0 zPnE!c!lg{RbwooijVlG0=G})%%NDcyORE| z*b27}4>^J|d$#sGxyJbJ6&TQ$tI6Cb_#8SQ9g&72H6b_5a(H2DUnM_8!rifMaQzRj zHSt8L^U8bq^NodW+Nr&*R_zgD8)qJE?>}P~_bB78LjwQt@DAkrn5rGST9F9LZ|Cm? zpH+8)f3@1C+WY4CS0&&c=g3)``CWSR6Nal3Wm;y@O z04|~_J7xT0DED_IjQV%J1jb+UH8Pew{ll1`F(+>?@q7riSD_S4C-z7-PQ5uw3BU`B zi2ArQ3{<0Mm)!`f*tQyDh?YY#2u9TrkC0DjRW!`FAdB50x{mnYYO$AIrJ-`AYRe?~ zvuLl$Cgjo=1o+H3*^MUd(KICTj46rZdXdyqJeDrbFb5x9VO3U(#!~s*yDRBFjE-HLHZ-t{$}OefX&`vRV98ca%^t}vy`UZD)*E`R(vhX27UBFkq>2K z-NeVCE*3!OVv)~VpL41zYeuZ>Amwc2mp+Jmnu+ezP+`zK<9aE3Y3;AA(8tv%<$?o~~cV%hncw!aGPqvD{81j|^7^|7|TD^iQk?IiT40thVv(ZQyb~e9RZvOf6nqm*;=KfJGz3kFC*=$Dnde#n?9XWq|!3$FL`(*zDx%;4)o=ao8@53fri`0DXksLlTsuHpB zMc7O0NzRL}<>Y}?jxl;EvD)6}i`lR^pjF25Ftu?Ofa8XI7zZQtHNZq6nSpi`u* z!rWn7yD@)mA)K~a++AdgW5Vw*a&p6)DSb~}u4E{q%;zUyk(~sZOfu&rhFxR~pR>># zRTgjwUf>9HCy_H5wWYtpf*MV?`Yc%!kQQbMhT`>|KU?m$B$B^0*{{1ey)-P(?RA*- zhxIh>2LrB!pIz9(u52NG?8VWDTEzDU#qL5%N1G?r81$dg5dP2Bx=_hTo6Bjn(bqMi zKRZAYtM=2rqoamZ_>X_UH9zhA!>OPM^PSsKm0-}UnYVm+c;kmUr8Q?T2x=F#dr=eh`;&t{CD^{I4oAJ_J%;v9w9l;v zAnzWp_F><{>t$>Otd@L@brgG1O4%vPj@}*F;+b&UG0dJ$DJ9y<0BFb9?@!=nb$HA0 zH-a#$sNUFbpQd~@dpYv#>Q{jCVqW;?g7Fmif>a4=CYy8RmT_>4*(X>aOr9MYx3`g+y5yx~hr4e$Sqs#sa#6 z7rcayTw8m0k=6TBd~g3^{>D^;>!m5FD1|Q&$#CfQMBYXu13{&rL#Em-UP&|SS;7ex z6~@x^73?-r?1Y}Fea+n6V{#3%W9-bC7t6*Kv!w?GQ9Iw(*wzYj}1P zTOcex?6&=>!nHR&XFcVRz@2U*rmS=9=vu@0|4h^i$ET+DC9nPH3X;tCuPzLP zm4d~73+51ETYd*~weS6J}R~y^X6?FdQtQCujfmld#m5pk$pJG=Seq&o!}N>e?NitD6Fr` zx@&6g^ursflpOZk%JB2E(Fy^%Z0(%Zk9hmF>TeH(^q)gxytc%{9@K2%q~wf3d!VpK zWOa9*=#*(8sr)00ku|&;ShtbMe$LPDHJP$p3UaY7L-=lolIfqs|KX#%@{SZ1he=ka z9zr$W_<_B{tkm_kT4reu7En6WgYtAU8ESIMIBM=jeo}Pr44i%sQ7civcK3q3pJddS zeQFGl4Qja3@cS40bofZVC2qt13_?{Y-smI|L9@wkU&{i9Wl3R9%oYHbg5T6dF5X0Z zf-Ophz*qkL7V$AcfH?~|a~Qm2I64}nw&XmsI$je!l!US&V*~474TUs=`SWusSMmtB zaHIF;u&&hl7A=^b^JINx5st2allkNu#QvT~Zqc?h>z*J;m@!Z7cH^P3mvJ%hA1(I) zgBnIbi;8wi{@ja*I=vf&1$gaOh)M0O435D1!}1E>H7Cs;+ctZ2oIlJoO`q5(BBFn9 z3a|XIEUGt)EyPW(S*TaK{ZEV%8Zg2Q8{>x3d7+Dk&u{yH;m_~K{^7=2GL^KZ_KaSl zX+#AQf2}s=Ii3FP??#hLL5D9-Q!IpI=2>>e_pS*G(oVw4Gaz4gj<{`vu$V;QgYR3a)FK1(~;#dJ7Mtwsk3mbQYjz# zM|;hvyW-*X5a8|PZt#kY?r3mj&{jzDtqQ;L`nWqvtmV*3fHfTbw@#4r-^n1}ve9WQ zolXv2pk{D(r#Qw>-6FZz1N_mRz~*-FJ+-UybQ%x89U;wjA|p8u0a>_|d6k?gdy|AXT zVg3}RwX`dI)XM~t`&y}0dsGq8Bs{&4ERI^+9Z3X|CvEU) zQSgXq>+Tg}CE3HsEP&@0WFd1cr!3G}wK}}WJi_AN`oVxvv&*s(>R$XE!gD^bUl7JOKmcqObr?8>dm$4)65F`u&F5vs{+51YZbYY*{a{y)z!G7y9cJy~Kq=Vi=I%2TjYpYy?+p?-@+7-_83!${d zw9O+YpsBG@!RitJ^zpLH_1%8Q;bb=MkMVD01s9c8*gYg}B`QofwlCHi^b?Zi?!vlR zQS#-!;l?+gH|+l6AU*Z1S1!E6Sk z57&&TzO?ju$N2tc_IiAnA%Jggzj@X#{e^aE!s=;n;ndQ-gM)v)4t96_6FchSxP8t^ zdh3s^NCGdpOTuS>z?a$5w;aLk2(I3#Y&W2d zG*_PO$3x<}AmOWM?I8$rDt|m{ZfZgC7(Eqv22pRmwptl6+P0wVE-%in7@r<;)%XxM$y{lnzf>NUZyf50%YnFqd1<(+r+&@k-XlPF`xzH=^MuW z5C|lE>Jxg=I>HgKSSy|BKa~ts4ok0p(7mil&y{EtgnWrLwD2Eu?EG}a!DYnKZpLG4 zLdE#PicpiPkTmGpY}$vB4Id<5X#c%f?VrGNK4G!uWZoL%?R!AeM~8qd;h0G$W_Vv>qd>y{_>&Mmn{72=WA5`w)@gzf zn{9A7=I$o|-jysEU(xL{SasN$xteO#eP8d|z1 zDfF6zvy#_87b(F0kESz^N_u<4edRIhkWzWlOa(huR;HwuBZBEEGfON_SvgRdsX5@7 zpa`0pdCb`yazJy+Oigo6!71k{=XpXLa0EdC87{wj*IkRnpRC3D?(g3Fect!^JOVl% zCh+R;mP6G3_PBP4WEQh^E&D9NsWl0j)b4C72%4MX<*kbk95iYR>iuUm@`1pZvu%Oh zhc;`?R&+Ye)|EPHkn_pz3lX7bH_XCHdt)ra%8CHoBT9mzXZ!s)i(c7t9)p`XX;+gS z3xZ?ov|TFdt$tyml~IiBfOy z)Jy_y^J9%DA>boy3jx9?ES!&KUW(>VIbY$7_P;?vDH&Vn<9X9wL_0omP;I~;QN268 z`v>CZz9do$N|ElwBh=CtB4|f`H#Wy8>Fcm5hmS*B)4A>5GE-g`xQr$s*Y0;$c;)YK zk_9&4k}O`vsw&=|+W97IRvK!8(BJ!1)f04%t97^wFuw|R+Sb_QB`VVfw@6<*IA>ua z%#4t;OTPiCYaJYOB5eRA%FNyfLY%=-od+LJVhDZgVjtV=ZwRUx;nzk`dqwee9kkOP zw(%ElTH2a=vX@(?S^*@fJMV4^fLE(}!M@T*pCA1lx}VFw$PF zTrFAtech~q-IPE5KF`(nkr{mSWon|Q#7IC;UhS>(iQF?{V9`i?MZ;ZPE11-R>`b)M$+Zvx@%*k-n3Stp8Jz*iw!_0vR2_2ox1 zf)@VhcpFoBxbJZPx}&ytJTq3?33Biiw_H!_$mBGk=`pJHwY9w0Am!)bAti6J@qU@T zBu1%Is71N2?g@cqQ2*!Uxz3Rp!kr}DX!7e`v20g6&0r1znr4yTtuB1#b)qMV{j8R1 zx;RINjHO##xcdt2e+OyVw@465FAJtTBOYX$#|;1a(~s*|6U9$W0S{(-UaD|gxjPJ03b!(CaQ zQ`wvISC@Ss6w~(1TeV6UN@Pvj)x@9{f-GMEcj4Ygep}N&+B`PvweTDFjQ51lC(Z=G z)d{%pHs9j3Egkmmz(hK_`h(JB%i~BSY{a+x=Pd5WG^VjFB0#cs2xult{g`LF+Bpm8 z)>V^O*vlz_?CQ5KoQd}PTL!iE==;S~a3#`kFEw4vw&8e2y%W;le$!wk3}$9bJL zAKNfZx^XJ~wFQ_7NY-Y@XH?f?)+fziNl!+Q8;6{HB}%uk4nKWKqng}H&fl7HIsik( zezjNlkB;w`>$%?JmP33R@(YuUgR^gvYCxWTnxc(Jy^-j z>;R4|JFCt0hz8>5<0L^OzDn-IOLBBL4G&jSze+C|&5QLm6gwG5Y73b?_u|CU`z}~D zgRzw^iL$HjKG=H~7*9zJ@r6TG#oSNRC!)Fi)fe^Dj>ENeBWRPG^giyBW;>&w&e*EV z`LNOhCNsyqUNGK$nGLY}ZMm8-oTSYz7Vj&)_fz9i{}$$P&g_mjqP1S@FVs~V-`0<6 zYZ1pYa+JL;eL+m`w%N{)~hn=fm&P#vj*1@rm}p{vHYip#wg8G7L?)J zF2Y2}H^kbqLpngp2)c8_NIK>OX||TJsOa(IAoOeB5Z=rdKNJfK*OU4x zX_MC-92{1SE_NU~%qUWB5G}U?wi_Lw2k?wp!P0jN7W&$DPji^U{aazro^@Zir6hLD zRW#Sj@a65MTz4U%h*IyKr^IZuGYa1O{MPdsTnH(;MRP( z{yN&x*qzh^?RpCD3IDV`dv=^8*<`3q0|)5c7utSOioOBMVEe6W=`jp>`!fxE-YzaLPB3@Al*5D1q z6L7O&BW4bgeo1dozeyPwiA^*XW+4ngTnLxEY81W;yar;~f{o_;=$XJhECE+wl;+_i ziJknoCzM7y&{;Af7|q+9{EVRp-Nl~dOcT<>yZ-Ar(LDs1!(F%Ije>{MtS-NfH`&PV z2b&JdgiBscdvh2#J4)QG5PcQUnB-%^wtdj*^z)F$E9^aDJ<$urn0#!d-bRHd;=736 z3%9B`L6!2%h1O_UWM@yN-_sIZ2hY)_HN;vQ;r<;g3QNEG1vY=X?MVKN9pzT7YIrkv z^6>2^Q*8((P~%TpzMyIMm$ob(VUKm-tDBMAjJJs^cGJzLpQW!w^gfwtH;m8F&6?Jg zv6{RG&Ydq@yRV6ZuEfy%8;oQ!)ec2k9ofu?$Nd>8O4zwc+Ss}ww$k2@xIL8WBW4=_ z@YqHSB8u`;mBx?M_G=FCtuprwh29ajem1pC! zxQTlPuKB&?xe^oU(n9fjO1K7>8&xxRhjT$)D+3vRKkmXX8t}MWP^xjgVZiAQ#kKSG zy!$|!KRvdFfQc575QY?+!;ifXhnN|+_T=UjCuAK;jVAALK8NZxCmF(XnKK{t~( zKI+e07BEQxyO6MWupn5r@nET(C>J=3CjZEneJ^n)P{Mq(HTZ%}jrSKP>R+1rJ}#8u zvxM4^x%qj|LyNZ#r2jeJA}Rkj>W|L9?Y^0Pm=HpoT%DD>lG@kcwdIAbJQEOmeW?F^ zFpF1MFBfzkcT)1%%#j4-`(S*zjzZCA2Ik}HAD?{&d;%}K8g_*T2K8@9kR;#gHm0a= zR_4lMjNO5Kx7|Vpar-)DS+gw!rTXL})(2i8P5g@xHVaIny0VQVmemcOssA`%HISQ_ z%WW;C;OV*Iw7GT%9d>UI8A%42p>>_91PBeEaUhp~mr0TYMq*tQBD_Vsy4mWzK=vtb~c5Sj@O z(x!y?PIlEI_N%(rf{90ekpUZ9yuN)R@Ibj%9Z|t(27sm3*jxL%$S8X~C9o`PL0$d| zvPN#)3T$FgYK!YC{GD%}>CXWRho!9MH2{Qju#`4O2EZ{x=l=!L7k^Cceyllv7tFY~ zf3J%LmVj_S5PTXQJsnIh+jg=%Qctm1io;R+jx4=;G~FxQiJUQ`)|}qIwpd6+LmpsXZU1q#T9QAM*F#K->*0*av)Wu zkXN3C@;|FPtURS$7{FF3lsw}0hWxfQvM-ddvDt*c2HZRRXpFPxKt^4^TA0T$&@BqAJB*Dvwm*hFvHnD zNb-nUzm&wS>aFTyrD*TtRk`VcYC(tc)EbGYPKH04y^A0Zubs|?POwDabdL~c*(pU& za-Xi~i=+@7q|=|#vT?N_z0g;kb)Lk)z? z)jZzA2p1%n$g=n!0hk^cT*aOjT@LssC04>|xuKk($q-Kq-(8keni9j(Ou6NP+lVy_ z;8nJyz?%I*63mcyv~fS#vb*;yA40rEm+87PlW3aK-M8p~wznctV&$$uR%{nm1einr zVP^Ry`piEEGyLZ6K`Dy}nB%zsp`n>y^2YcKScHbAYj{zQjKS};pzE=(iK5;7|Qz8=aE zA?@yVY9jY*ZsyxQUS~&UbHh`KkMUG9yp=#diK#a!E=Su#R%P2R3PV}TraZoSq2xPe z{VF?I&ju3hGrgHsiN-Q#8PUMDXX zH2?d?Yw*bu8`l9o|2}}MrRq~b{B@ff&k^CdjH}=W)uev5!Z|`3=b^M!QHZ!>z{S*E zx0KQ7lzSXCn%CbFw##t4(%GsyKZ-Nw7=-Y@i%EDyi2UY8H;Uo4amW}J<-RegkK)Q8 zIWBh%(TiR-M&p zM09`#7R5XR1XT$_Qtz+}h;l62Pb=g6&cbsv2LN!|9)f5UUHV01b!CIzK62e-HHlrG zFIaE^c4ENKK#S)cl_=p}QiV_zXUw_LYE@HTS==}MRM`17l**!xNh zGpckiD_0p#jwcFfiV64e``!5R};ufN^HP%(7i2P2ZqsA+8R z85WW^P7wSOdgu6Gw}hu!_igIbCjU4+V&hd_az7VtQTy}2<|1U<)C9vqbo^u?WR9$ zGsEM7)ekKdWhf8>ff`v^BNzfrPFszJ}KPcDC9dTZr&iJ!S#F#tyWdxM#~AN-7^x zET* zXz`sptQ-ueZ8!t05UE7+I6e9aO#h;R8CEp2?P^+*6uRpH4%mhH=E|L)o^zh$Hjfxj z`dbZ>R9NMlFUaHxy)Ru|SWSyMx?%I8f1oM%2^8Ud=p21074oe}D`=u8sG|cbZjX^0&ER`vE-DLFELVMRNy6YYSo_XFzmfp`_XT(D%?tx^KbSLGpNjVs1x+sC+Om8`D;OQ!|fxaO{GEbaUJ!Dtck^QaQB9pJ+4ErCF zlL7GS6XCZY@E=6Kz%tQ7z8n99D`fMe?m!|gJ1K(SmoIU<91aOAPhtKc|0Ijv&;mKu z$BpKrYJz5U_>qKa;npDpALCI+XBnv;U7>=OHUR9|XxEjDrLM=T;3=g*4fZ1GC9bE$ zVttO3#5*9nE3y%}AjH6JXR|58ZT}ZvrE!sDP85zw{;sYhG^~k${VrBvlPZ+&>gv|z z0OAo-Dp|X%gi>|+o)t$9Bj#$Cb?%_&(@1(DBgs3uXS-0fehCm~L z^Vy6YBE(dKp>^~^<62f?{*}J>7gQ;OQFLldbWNPk0sPd5m-|MeTHADG$X!`_11b)o zy%6gQOzY6fDANo|3A+GCx50NKkvR7bL`s4#SglP^2y8ROJ^AcI;aumnZ7tp-S_4a5 zxzDHfRoLGmDnBxhY!zGzupKOI%_of9;M~z?Kv#CmcN870Cw?5e7ER#4tPDuZKZ{)$ zASDt$#@@rQU)9DXu>wG4ypOYQ3mhW$PI_+?ba}Qp?Kg-;Ct*wYgJ40&dNSXp{WxvUVKakuR~JJW8f2(;&9dq#^>21pjHIPuxyU6AK5U`{ z+!U+Ny#1r@g5p+gmL~HoGunOIfh*@l2$;O;;{%$uR?W=RNb(dWRW+=IUG-Sh>tPM0 z9)H5Bf0{&L^1*>sgrR3Gjxg-dYu{F%{F<*#S_M+zDP2b?r1Aue)mB z*Ml_5S7SiOb{f89yjP;7^gW*3s>c?P2QXNn_eMve4(MnB>uP!;*Dplq+>bVw>1u1T zbE(*L5&VXZakJHT!yES%D7!~%J?=Pb4+I=5W-2QS{pR~KLaW+!9CIVIwFqfQGo%^p z41_pq#xDy>eKqUjdb`yU^EeBvE5uC#z9#Gi;wiS_uAfWW!8 z0yFr1EMrx+5QX+NtP5=KMO#qTmmkiBC2Y35q-E! z(tmjQsK)&QCGv4X^?4sAqJy#C9gBFv`eEcn&cF}+iJ~Le*KZQYNYl2bFh}Hjm4!Yr zYtF&*n6JE?Myu7ir@5UK=#yHOsLpb#{!eOH1}{(+x)VseT#{CK*{05%e+kC+H`mwa zJgDPrD}&w5>Kh*-nc1g&0hSaqrz-4mt+rRTbIZHIYW4kfL4Sj=9kLG<&Co60L zVm^|n_lXOr;St1HKISxdx#nR)Y@RjbRk9iaymEu!}u22tOY@D~Da5lzz4w zJfwFDnVY}YF&vn@gM0_Fnz!UL9ymbL5&~nQ}5Y)ynqNz3A5M&e(wtEd2M;- zP42_T0iPx{ZJD`gGhmax zeL4F=)Ep(rLHRr9;Z7i-2p8iigMt(m`v3wC! zp%BMBnq_|#|B|#7`gb3JQCaE!%J6}h zpR2PG{MTgSOt2R_!IET-9agk~_Um4wQ=}ek^9v-<_P>ihnERVPr&|B*|DTP0$XGMc z!+Ex7ecOY-gZR0Dpno;3zLt^8o%qdvY7QSlq|zD)xS%emf$(E#h96S;=53z?ph$k* z`uEFB2K3FGT1L55RoOB@vni==#W;F5WR4I349Y;djM~t3Q7yRb2M@Te_`~$H&=8ybJRB(mgTW?}h z!uDqTQOVNv#V3u|&OA4(%7|tF3H6BMC~kMyU;Gvo!O*0(*aD3(A%)E1DDwwgd8Yfl zduhv3LYb%2(ytzW$9Bice<2QH`#ZdbpyJ9KZIuAKOAp&=S6zR@WgS7`fA><-Wj< zM{vaO)FZtf->*q9V`sb7{Bn-^*A`mSnT{&y!(wP?e@bnFL$L;Mn?YB=Qv(TqZ)6Sg zEo*e@T*Y0#3Ez^g{j=L29!g+6qVhMG2QunZsT!;doMVzIr?f@Pz7=ak&=n>i+DdZ= zEmxPE?-0BxF0*GI;om1I(qLNT!oH&>VY5)iQUFW;gG^0<`Y(%()iA%(a0zD4EdAWS z1n&4Q=O~F6SX(#bpX*Q+wzaxCKN$9{8UD)1Rsq{$#m@3L4fh@u?*~TKS!6!M&_tTa z@b+`W%J{00dFE~TAuGOeiTK2bzh8n$JG4PbA@DD_PuyPkt~90l=0yCPKkwqL=u60- zhUkyO((VJl^w})3LmQGAAo*s+I4jJ~u?7C;Vd~8XlD@C&siQZxhc?_Z+$DkcY#)7P zTg;S@_vXpm^J%c^% z{I5dfalN7agXr2M1Exx>&hRVFH~kHf0I#+NN_KkdRuiGF^H8A~Ix!)!H-lT?vB#*u z{yL0O<({(J50duwKD#XXFQGfQvUTB(Ou+H4#$SjQS$_WXvEP=M3Sm}gF<9-LG0ewO zzW~Dir7Y$$ABS75Ej?1&hMp4#kYX z-$&8B>J@gm$#C#a@os%_j@w#8XGzh2h!p1`rjgYu@S4QzOI=8rNSZJ$HfZ$WBHjEE zZ{X>hmgzHR^kDnh@*MGE+z{7YyYBtCc4XG5u!Z+%DY2g=9A@9&(SfO(v4)M|e7E(M z@cK{LR;>i$sxcs}k6HT+epU6E>7)9Nq-vERtK}B2n|D>Yymbe-?2>4&3Q%*?C0SNP z_qRhv$i(PU0*rDQ2_$eR2cH^8S5iKzf`U>`1Cp&Yxd>X<2w6+iZ z&cv_c6P*Ans8z#5!TWGU+Bh(I=gD?E;@~B_srCyJb$ci12j)$*uXV!de=+)7%s59M z{OmL-*%-<{R>yh5c5(paE#2IBtu$GnN26yPik$!J$;+5F>8S1?zo3@BL)v-^Ua)6M zSH15jgP0P>+VG1Tv|t2iqQamAI&q@%Wy__>0YyY;OJ5Tha`=+9qzup+oFd&3TvJ$9 zS>fz|DUCil7F6^(;5o%#=r1IIr1>*{J`udqGmjp=mS=alcxu=@S6S&Bcdk(1`y8Q+ z`YNjnxsls^Qkq-y(888^;5YfK{1+T1zVc1|ME{!!6Y%_UrpSXh0@VHNa?os$>GFA? zlp8nUev)}c2>n9w$ntj1vE7SJIZrI}`_Wku*~Jp>Eqx8=`Mxt42lV%VogS?)md)Hp z!bRBS`Hz_-|?LZ{6T(JHI$^AcAVI1WTN?6uk=L)-UU&PBgzWyLQ)U}lue(X;~I zGzux^@7y}8z8d3P^TnO2LRcS(tHSqP)?fA6uE=t*t=!T;aw}`G=8tQ68E)kD-;LSX zs;rm@uLvU3)2oLuh&ou`qI|FJQW?6*V4RJQ|$k;iTYmAQ9R z2kcIGMw64(7!`@SvUJ|#qmt85PpY4C{Q{)~TTvv(y(BUtBI7hC2Xsq&Zo3FkY&Ysu zNOGknmM5WCmkk2+jm64Xl!)Kfz^gdU!O`0#fR-)cxk*TgpxO;ECgskfdOnu7>`@Cw z{S1AAeiW-t8Y~EwQc>?h5$F_IJS_rw3}QHS@IPx%K|JToO~TV!#?PB;^9*SYxoNgJ z3chsZ6s#9nvSNPxy@l?DyRVo>;&0ht?3D>$!c~d4-N6oh>&_ zC}ouv@fJ;mN(!!_Crwh5r=WCY(J^1uZXjx-s3Eb0we-h_*=_eRa9yAth<=FpOM96! z)ETOMw)Qk|s@?sduWdW+s*l@mwbA@bHlv>%;8m#VZ4)=^m8*zR`r5#o)?P_+%2trL;GMdrdVdx3iSVMEKl$7T>r1RmIjQ?i+WJ&(ZVNfn_R=_jxg`Vy! zpqX`GK;=IUx8%Kv{J3L+y~0&nPIs2Za7P-ry>CqfW3!GZ1VVtzf zljCu$eBLWba2mtFIPLG>kDIA>Thbq<>CP8m^=<7d577p34Q5J9(9NXj`C!6z;(r=a z-ZE9y^#(5%ZwAU5uZS!*Mk+2f>~!nr?WMFn#6zff$`7RKmdp6W#?xe`0;x)D>`y`+GDa>bBlrjIply z+{883G*yhKa1MsHzF1JxKGuD6VfTU3Ej;7>@)28*8i@N(OeqCpmWIy4oP68YT=&K3 zF|Be~Ijsu<_I%ymD@w&*az3HO3P6@0lO7)lTSd0_~KQxk~%$_3A5md-7k zJzH>)6dg4hvE)j9RU4^(ZN;Mx3XN!q)(Z(HLiErNV}vc0USL^^p0L|7q&HeI0}Dk{ zGScV>f4cG1Qj??W9GYp6;ff`X;c_6$I6X!7> zWxNzRQr*sVZ4}hNa%P!zH$;rV?qQay*hl;tO-dKeyI9qySiC11v)$N>dSZf{+^k@p zKo-8&GE?9+qI7Ed&k9RokUIx>j(A;~|M;}ed^8smBfakQ^JBi+(+Gj}l$<|@z-tI~ zU(c67D@RqL=Nr7aO7_28k5VBx&we)**6A?w8rv)Mhnxg!3h9lNU>m;QEEbKYE8CD> zTXAQeMFz7lQFAvh?TLpqKd(k?hn6l|ei3r>X6S*WmKYCr(&FJmOR$XmDT9U`*}4|z z?xxbQVPKyeU(F^d$6gg3#rhxbJPXchy5?)JVB9+VTDH(Uqg*8F5P}{q`#xIWh|vB; zC>yef^3x}96u|04?WLNx9`{IY-;LF~(2OR`&lD-$mHgUS$d|Y{DB;vgE~YS}~Hulyolj%lFoT zyM}8IH7BVZkH5;ft{SW&qVOl_+#W6AX5;_z0NXu>6IN?@`E!vWg{U&zmUG2=<@Ohx zUJUBuyoa&maad(0{n11^?prsi;B=}QKm)a~tw$@*!U(ULC+f{5;qoWy=S&(jXw1bMb)d$^rA zLl!1zFsD9AE;cOx;fimUm7@5)=|)8pZ$j1XhYZO}bB|io2VEC4^^EFOIc3+c^n#{) zR$MM3LzT-`if~T1+o>Ohz5=1Yp9iw2hEX+>de(6Q>lOD#hj6Zx*GK*iJ!0n=w5lI( z&9YOiAOQy5x<>x0Kkua?$5W6F1hzT9l6o;!CRkk?(DgV04g=T@rAyNrk5Biv-hm)2 zJneK#ZZ;cBw27Cp3=IU42-^Tjlz&M~H5Fj7DLcOUON3wFGOi2Huu$-b6Vr^}#&&1{ zF;NS$sKv&8S4IO8Ku;+gQbAEpkWM*TFE%1_u3EkVZJ&be#H#g08tKsqpN+;Xo^$$t z5Fq_2itWLAHwveRVr%C$kPVB4x~k(Nn!7rVUgj-N#QLIc3zvXgz+3;&Nq8ns!6Q0M4%TV`n$#E$xhWQ+ATsC`LoU(XOcTL>o`*YkjI~e;#c_Rn5X2^am zTUQ%**sQMX=={go9mUO~di)vej(9IeSqXN^ye-i1%wJ+QB16lGiFJON_Vk9G1Eyu{ zVPTfE4-2;)46a)V?CfLCPheT5jR@exoU%Anv`#5XQ{+3-xyajqY$?rs;>TLdD$e+i zWUse#6ZTY6U8En{fU0XqKww+Tnbk}ycu%lZSxQXx^EI1f^%4D14ctQJhUkBy5VwET zf&KdJS(tT-0Z*SZvMnP?ZbHd=W;cmW@Sj=tDpgiV^~vEs$gI@#08qPPZJ}D1>3yX? z96+A&T30Nziv1&f%;39zjlELf6)NG|lo40;S^x6#qW$GpQrySKJ3~pAWLBNWEJr7< z`f8U}cSPzz5SZ_FQ|6WH0v)!3>Wf9)7)a;XxDkl;PI6RyM`3+@o#J$-IDcyb&AkS+ z*1|q_#9xK6)GyFRcYR&`TmON60N{r;kf+sEH!H46sEbV*_k*V%(|T#fhh(IQw@Y{p zbun-WpP(dZM?4L7vqr@*z$fFSwOka$I8BK?GMxqwn0evi70~H*3*VleISw9j=yh}e ze|LqO!t6_qRuEusB}+&dNIX{rM{h7QUpCRSrX4-MBt~&g+ubX#I%mtgoDIribt>Uh z{{{O&W6pyBkUx^a9U`GRL2IGpx68d}NM)-?YSK(F>sPG$f}i?FY1jrFv)l1w8AW6+ z(W0@)L=>qFz0#s`6Oubpu$ru7a3n(%4lir3>f&C1aq?bzl&_nZmC}DnPZ@&qOJ~_j zCs&RpSe{Wgi8pKWn)7)6YEA|}F>Yu>@FyN$i;LqfHijq5KH4$B#~`X(T0hm*vyxb% zsA$5`R=`QgQY-p2t@_m!t08+_2ci(Z80ilQv-;p%fJhPJ1Z#Z@BS${n47B;`TgVme zs+`Ad;X->oRtK)Fdbvb*Q#?-5Z7N+UAhSpQ``&S(A1R&Ogc*Q#$Ig0YFu?6^!Fv2a zsnyD5!^IU1et4ao*%#Y+>-wstX8e+Xr+E`uxS3SM{9iSp#Hp0CU(9VtXtmOc*6Z3GGB`yu0qQiXXNIu^yVX ziSmM^&rKN*z2NExe8fAua@%~Pu+_^tar;g<<|k-%a|a^#W!;j3U3@WrNL+$>nnVY4<{53x(LC9*1=EYr&WjFhfZcgm(0%6|FA71NN`7!n`xU&Hp&01M|pOK^Gv;d{^yqH6byRUfL)IbsuY z9#{mY-OL*XKds$;_XE75$88vte4xA%54y}+T3g`Zc@Zd5R`$+yji<( z$q{b2X)DctAKQ$1`#2p^;2)!m$){IJ>z1C7+)FZ;u+{pqpI>|(gtih*d9+HaLYD*; z@>i;k>;4Sl`AibHi%KQ(5@D#CJP?KW>$^t?e{U*e6KeP&Dxwp`wcvc6dNjd`-onhK z_QeiaVXoSe!}>m}P7DM@Nmfxp;n`a;09@x|FQ?%`$_W}!V8#LjF^r3DAuA}{VVbtCuf=lfv5lHHJ% zWUCmO!7V|Eihlms{k~+Ef%4fi(k|N1ZJIs{+Fza^R6iXx`?WWrl1@D!!FWEuRef*p zvz4%06Y@0o@X*3RCFHQ3Rqb(^!)NrSxQ|Xr_R6B_Xn&V>{@J!}@bi_LM1Y8&LA+{< z*6NTvbZ+IDi<*67+tDz2fcN(VV>e~{PRPR32mKECX9r`T{a|X#&wrNBV<0EsI(C2O z!LhsJ4kiB=tQ)~^2-yk4v%(-3UZd6_GUV$%l6pEl9?!uGjlV+Sf@?i2%83Q95?l{@ zJt#-^$M=b(l7+o~O<>C{Q1$Z?fPU-m2qXveycLC=!@8f%^S5GY z^!gE>vIub8U}PFg0f3CCqE7lvo(}wf4_)o?{t3XZy=ro_c8?`)4I5@#s9GyOpeCNMFH>_Qfb)fJnVY9G%X6Ssd#ZW zEN59q8gB2~<^7^v`+an?sE1>U*y{DXA-kxS@g@Gt!ra!-Ee2j|ZhNY+B6Qj8Ogd-I#skWv`{6mqU)ddc)srUbYPAj_o^BKMp zzas?C^Qf|2;js2>H+u`P&wq8mBDUbQ^BqI*oEGpyM7M~nJL5h+!IU>}GRep1oZGhy zwTsICZiWN!KGh?;fFQffq6ep{&MT#>TW zXeA?jU_Z2lj2!W5vTsyY`lP?UuFkie(HH?mqs2~R+}pBe8SxIz?mes@CEs&D5gWuW z2egR!DLH15UpixShQV#(9`_yfko}M}^z>T-%>h}+bRkeDRVXX6i;d~ueKNj-&*XpS zTtWWY$}JKw@NHtmy*J<2&ll_9PWrb-A9JP8iKOlPu}m5jTN<1A69IWA1p}{a09A-Z zEtM@m@&P|$kZ>b!d$wUL>>ODS3@ghG{yhJQ{0D*F2-_D`ld){A%heuX{K5sBNo%X~ z6IFIDA}O)9G%L6GFl$z}z#kkN@S;oYE_*}|vJkGJbtXn6LyMbZzJ*1MPwS?$G=xWW zOxTD7L`wH5=8Nw8C+R~~GhssdUB|v_s~F_Y+)i7mI_yPV)e9_!=!IQ8obZTrn>|$e zCvbmx4uqKg+9a|PR8ZTT=v?~B%+hWgh>;kTRrdO{|lms zjs@L3My-AW^;*BjepP2t+fV){72|GjuVeN<;wx_JvtINwC;k2|Eqg1XzM-9>v>opd z3==*$W#2vbl(jhiTA%ld$Uvy2L1e&F@3EtQVrYjyjs;}yy-mmbOqzO$Tz(f~ShqO8 zI+$-XnQnEhy>Vuze+P+;3IMNU(HcCpXVUC@-~F+{0F!?O2sJflliF%fciQ&bOVa$D z6ibHc@97^HK%H7L1p5U*ZhbXXwY_sjGrW%-m;8ifhkeOafp=$NRWfw6ncegC*P?g+ zcmvbk{NLl`_eJgu5c`JVA5klHjwQ1=M(Ec!bBaoPancLwTCFWR?`9AAGzZOIiyy@v z`Bm7g>Fq&x6JH>}7PP|l?y;y5C(+eWWh?gBPFIyYFP<8(#UY*6813RY+mqIK2sqpH zGX3ofvu}!PYFEFpqG3h34`%fVO<%zD2*OcKy_j&ar9Yla z1_O_JGoQdK$bYA}KBq|HRlWo)`fE_@BFe-{5y!Ozvd{cHp+<-jo2=??%yrR2Uj6N#rd0Cr!w&-XA$02oRcY=Nq-AgbXtS??MB2xVKDWT%H zv8ETjE?eTez1irU8^U@8zWNQw@Q?V(ajt9afHtH#3ZJN&<4pDJR{*}<1o_psdr8GH z3P`_sWz)Mk=|c}1HBY|o@=2^s_znq;Mq$7rx%a}niiHwCvsfX)X8))!y55U>eY8OS zit{At9nqGk6WwpUl9di1GXT&%Itx=UD zBhv$;x&)!dC&p|W><_|sK1{dZ?=5}>ZIo}1HmSkdMc54}j^XtC*yYZ#5R+80*T?Mi z>O|sA0KT9@mvZWi!wHjJ?M___CdsQ({+11k4LUy^D zY8?ZB?-`Z#Mt4ZJ=}VE-l?*sHZCGA2jGGfPp3l>Uw?G-t>TR)TJ%h$sBQ>`^UmKRj zEw;;ECe~o{7xk?N!VQ96_}da2l7?%ndfv#+cfKCwzp8Y-*hLT4paWYMqYp#Jim`OU zpTquNxjLTKT4R9?0a7~iupgV-P4E}H+HEr`_RbmMV%9JM26?atcM#EO_%kfd<8-#i z1f+T^2kB0-fnN{7Qmez#hE7v&9fLJeN?@aDDL}8k>#0*OtdRPGmboVRQSnIz;7!Pq zmS8IRt;>?a&i7Z{oZ7tJp^rLOK`S%HZ?lor8i_iJS}XsuU7Q`Ryz3;uE<)r675mO- z!eYfVT@E(JN|q>&Ll_4$>VPOVihIe(CUxke^L(ZQ#+v27cF~*bQ=%xERr;cBugM(K zwm5i}(x~H}Y(71{6!KO7@R?tsq)$g2RpeL&o?oXDY{|@!1{74{^yK#U=4e?7`i-n+ zp=g*jUmNdqr7d`l2DbauT-bd+6L)vjjor~eLx@xVc?J)S3=f-C4hQ$)GGehjC#rqeE6*4 zUC=^iDzLa@)8%jQl|VLBNl@SLNqV6Z^|MAp6ZyRuCjX3pFT+7Gjz=3N8Plh~O(E%Q?MS>yGKQKzWhf4zim->lE)__)?kQTmo9`N;1T8An^7+8(EW za)mQMCGyCMeB>$QWJlQ6ZhVVg&|>H>*`1-VyPfA<`+Vq4H$YRg712aoV`NfpD{|i` zSGnrp7ZL+N?Uw#);YAv&;f?l8@=oDXJ3VmK8L|#81*`x7ZO%OpJLDyX#;hAJk4=7c zX>HdoMOG`0ur=6~XH2_Fbfc6J(GnSA?Em>=k9!2QLI2hFcb3(n9arKB5<=n3m)!2s zO_uZTcwdB%r#DG2cz?rn7A0rlY?`DzJkXmM(DUG1o7*q4 z|6>Q1Bms8567*rKR-se)0mzih+Pidas}09(%0Hrt<18m5>%+nx>y&j##GKY#vs=8>(1?+6X4<9a3@yWkWN?-1iVzaS&svO$Mf=tp5IDTjZ&yLBLF80YySgOu9tN4tZ z?g#>$*&LhjU-yx#qE9azY}>@(isGTA4PM%+ag$0<{dPk%UM)QFng<4`at~Jg$e$|5 z_UxDu<&TwLNn@~{mRU8f{)q8d$bU!|Rou(2P_Xba$Lx-2s`kR!tnoga<`hBCEKl=7nykjI zK6sh>x&?=u{)%Zgu2+MN4n_>6EQPHEmw(_a>MwO#8`TNJ4r0(Fg ze;ELJgZ4Z`uO=f#*iQ?>B+x!@Jw&Ag!@8=68o9M zVfnW~jpv?+ePL%Ro&^N-{bF@Qurqt-56mBK#x+WqAAScl_>XN4*2a86)vWw5C&>r1 z{tr**9?$gq$NfrKB~~e`9F|m)SX9oes8q_7qMTN#DChIWY$RXFVGc10qtcS3gL7lf z=kqzIVY4x(9gJ;lbMJTGkH`K0{@eAruJ_^fdcIa9H;12-EmTjk zEr@5_d0XJ%!Oj-b#w;C#bpkdTs{IX*5%YbclEK)nY;0ocU=TKFwi8;~3MeJ!?*Bts znqprBOU}e7BK9t(E5t`Ma~I?2f5!c+kIhQ>3^w`#c*$`h>2)`hIf_4Ig&y}v z^t7D2)hF;$c{Lp#(Q*mYT42G6fFFKdTaAlvyMIXijBww-L4(^WQy1bwM+Pe|gVqDw zK!!6$DaMH2^56+8lv7kW&TZwKt{#uwBAw}oc*vF4G&S|$RUA~#1ftkGWPTd^+|4QC z)ue-S+*U1~bF$L$NBy&yS;wHryzWbr7NK02u!vIt77)l~k?fsq0L2Rx&|=E*x#4fF zj{iIu+5KsHZL%VB_!8)%uQ&4phSzoXUvdxY0;%=H_pzw-E90?$t|*iG?NQUADWaFC z+7^R0Mx6U1_$7UED)$I`^+%y|~ zZXw9YrS}|iKX<7js%_T*sudRBYVhdCmTg7-UC7z;4E)+;#p?tk{zHJg%n{nhM0wsR ziGh#_*r5voN=tYZn8lBmieGFCvY&8C-&Z$4-N7$`D zOFVxT#6Dbu7~j|u+qWpg`oY}jvjoc;GV7lB_-UKMs9Q2m19DjYJu;Za);a@TPc+Fs ztV$Fqw0Sk%1wsU`FxhF_y8i76Fy5>3e0XC|SCmfgv#egsYv|_MgPd3G@5!ICZS7YL zjfRs>Xwzj;Uonp&5=vd+4Xc%sM)zdS5qXpfwZUheZC=aL9iip$J7p>#K8jH`nZTt; ztyoNcQ6=ZN7S)7_W4qiA;4SNtvBHv_#(!D?GL19~G=1nrgI?LG_E-s%54b!F>rf9+ zd(|SYdx=%N-x(tqemT@LXna*-Xkiq*&oC{{aSOOIjxunW(CIYK74mZT1g#Ay;MS>W zCoywdN%@aeA`a+&A4uYXLrKYlAPpFO0CPa)lgv-v_u_t)RK!>Vu zpK=yZ7JE&J+c+@gz#>lLkh$J+OR(ufJCQR?b4Ik9Yw1con62Q>=yJMF-hUo?QTVJ5 z)OyK`m#!>B3$g^QopHpT3pdTTMpS9u;XUFR>xUdwVmWHC!u@wd-FM{`t4s@q z^~r!O#q9O1&&xKpoJ&O2^oOi;bOFK}Q9o+cNE_-G#A9~!oQJd+L~D$(>M|Hj=|(Jr z$`Z=U=2C06e}-F8)7i7X(R8Fj3&O8OQKS~K$D_j_tuJI;%gnuh4(DTK18s{U3F0to z`~Jl!X0QDL;i^Id=c3yHD{Y%b+CoXD7tdIax0-SJjrv1(6R}j+)~sEhzbo}xn4WQ> zzOsQK<}C5bgs~pIpk+q!a(hT&nRrV=hm5og#w05l80`O(>83>cYw}6u@mAPA=y^#( zwb^`FRk8u^b%#l<<+$XB4K8OH-Fl$L!5D4s7H*!od;2H2W8tD2pQ)I!2IS1>%dy5y zjx@MD9wg`Y%1HAczI;M7xRfH(!@pAw%S%$q?z6;$D(WP5h33ujpEm5V-nw zN51cWDus`cVOXst<;!YnHKeIW?y)|JDK+v;5V=XW34P8U^~{2Po3o=K<7d=&31sX9nT=qsKU%v$S{{Ote5_!WZijSKLx zqVveIEdwyUGq-D#fs#MjAq$r9zCu?oh&z9{m^eMip)ROnjm5sl6vTIWL+@>Iaf|4W z?mu_-Wp@2; zoJcISAv^cx_Lc42tMV#Ov}m>KIgb*e4YHw1kW6gnOb#W7JxSc_Gv!XRw(&mx3x0Ef z2&&TGZ&E=|c%^SgTXC87YMMc++p+sXZ6<9u&*s>Db2XT?)SGkUxBkQGgok~Ss5goQ zV;kqd0j_tNqoLC-aX&M#@llJrA)g;i&x{}IQ7KeHutGty*3`=Z=hNnrkz>0p8? zr@@5L9gotvWp?JCwa~#v*UP2fiW?ivWgZ7+T@B1lX>@{8jG+0=@zUlJR zbI14n?nkx}_AyH`cmA!pcCojj;4yuxa!$nm-4I{9n05tl#YFJyHAvl==(RBN-{=Sc z)!sm4PUpxU)4$97dzkrG**jLM*qh;a>M%rnsJN!DtX1Z?w!m_7_p-INF;SCJ$;25I zdXLvLusp4c?1x#@DE%kaTdZFPsn072Yd!&y-kks1QHZ)gr%{6T!hk~Hd(i9&ka+hT zev^*}`rONVFEbsIe-@o##UD8DKaE$(l=7vmBFry4JGG~ChwzN=kBjXu!6Q$-J2xESp{||xb5o1|*LPjy5T+ZK zMF37bV9)%*!jS_@RIsc2Tnq}4y^x?dH!NpQ8XgWytTDp&LM2`|r_&%hkNDpioo89| z$L%?>BK_};tl6U>=2Zb1$hRLldq-!Wv`ZuBf;ro6nZYakz!=2D zbUpXD{@GgW(o}$jQqg0l#%pFTHoqAE>3t-=qsJNlbuQXgVwAj7Wp*qEt1_hG^_UU0ngjAEfFx-z;ciRdtu*> zo11w2OJWIX<+MR!U5v*#{A&;A=UwkNc+Rcc&|XwT$W{w8)sircnzN5`rY}Vy2T^N} z&jZbQnLZDgl(8kEW;MYLi+Eg$=WUDhYalX2F&nN^xTKh{)@YqksAqu60u(Jjfc%sL z55W1S(ci9*39MOp?Sqo=nwO8|PH&o)a!{l8#FhPS&b-2(n#G=2$%f)N1(QR!GcjpF zN%X@FC@c6(Wj8GGXk0w!It1t#TTYMhlkrfRjdY2r5I-@Sn13ltvkmy@*`tS8?wU~^ z2#|50HDqJF19h}j#rs^#dRT{@ajls~+=Cdy#>L-jCS>oxJj{>Gx`apHqy{U}EG5f- zSXf!gobkzPtEIIGHLQ}^B4V=)*u;nC25I>}N`e3#d_wuZ~PAS{L z^-8%Q@1EcU#bd!5^J&qZo1iD3OM12xp$-o8rG#AS3~r8-<-QqNvC9*G#_+5q-*pko zXpOA_BSV??h^))d5@uCy1hpLXzskIiZP zi~pg{Vp{=;RbJc(_{VQWKC<|U-dZV-nhdU^x5wz{SGk@Tx+1g^&TU$n@pA?Ixmy9b zUSp_JfRS6(LcVY+W09kfuaKa3GBmbd_LJx{ywv>WtAf4>wbHdD4?S60^IooAF!7yu?8&5Y76a z!scwwSMsZyNCsoXySQj#I2XN$6OaG5BCW$Ve_u0`cnx0L4tzymq{*o$jwP?QwKOD> z$`j!mA5Fx@Tg3b_^Mllv@f9YK25%aAg{k{;{{sZHU8T&9^8R+Sc%8n+z zlG}S_SK#8a=KMW65x8^&BQ1T+qXiz`q%UMexQNuiE2wY$B%H~I!VxIdW9}M0!cjx; zUOa8=rz>%<&(g-SCAAfW^WP;T_d19a;%?H|5miX)XIN)fw}iae%<@Q7(qEUS-S;lh zpsgHG3`rY9>T=UFJ=W5>JD+Ptsj-?4rh<DJM-6n^Nt8%-v7#SU;S1`<4ar+w_ z%m_id2jw>r--#^D@^tQ+{tr9YVh}ycEsVj*od>VU=R}F_sv!N)w@e332R}|yQ>9Tq znHym+6$OXHBcr^H4<+OXwO=zer3UxO4wmtD52>nDR{m;t+V&aP z{KCw@?|^j{GLzG#$1M?F@a811I|@f?^GSo;p90#B2*n*CW+}jOv}R0?(;=;UK!jhl z$!q(TBFQ%lmh;tqJ$0?hwJqyi&uV==US|L%H25KERE+K*S;$TO1eZ zBSz}+>a;-u3@1g-)-&j%7P+2q@z)~$-WMa{XO8#z zjpQTi!Xoqxbc3_@CnFZzj zY2+i{&=l~-^L6=^7`-rqbxzBo^W~#y%FY8 z+xOhVCF%O+bBW$c@ykj{=9=TMqnJU^skd;M_`BY1yt+poBj=9zebn_feD>4UwB^3k z4TT_))%Y4v9Su0|h|J`PY~3i{lJ+$0t1&tQMm$=@9Y<29*th=`u_Ecxbx>IYlc}>h z-W5lO6dFYKig2Kl@ze0QZ^ z%cYuLePDfcGjs$a3Cz9cbacJSbs~V78Npa zmXv}W7QWLtO4(XNGeCxM->$OGG}%KP^!C#Y54`AEl->AAjq(8Iqbb&5jO|mu=7DB+ z@h{>7M3=iOI<3~__3Pb>8AIRKJRAPKiYBd^Y70#bR|LimluZg&n9_;U?;kuEOxQ0M z>5AJbpCxameuEInMBD|yyf(HO-6I$HH^-VFSy$TJ6E*Wvaup3io?>JS_4JA%jd+T*(Q*OX*@35~ z9+WfpRBOk(7^J-Q98+a}4ZLdWFMI+W3o{E9$En-xPV!3|QErY6oUIX+q|?st7f;1=m;RKj16+E+Hv4>A{*kZ0^JM4Mh4Zw;>=N zHP%)|m(BUspw^ArQun*9j^*kiO`|}m%;6>;tKt5+oKm40m|t|0{ZiTG4D%)US|5I` z$%({_izY#hP9y&6fTh1=v+EXOVwE59?$_3BopR6J`7x%UVc0q3gZsrV7C=GwroP1N z@ak+c9x^9b_P~-RVDR`(`e6uK}|9f2v?-79NgXX*+k!#_< z(vL*T{MHKEyw7e;xT7tclhQbx@t#uc7H5!<#!3c0oVs|UM-2F$SXfQ}Fh}C-DiL^< zDQs%_<>0OO5oj+1^t@Ei%!8hKG{l?FxHwn$vs zWR9Y+hqA*;d_&`W$TVz{;CVr8D>~+5_9Yd-_BU{O-$e-Za1^>cl*}MzV<#K2XOJ{70A z;DY;cd)4*@$;SE%e5?Sm;23p5Ti6itUEMo=hTnotF|MNCau-ggAMpI1`I`ao@^Wv{ zL(_sv==wdFrHrT5TOR1y^4rwSROwguaz7H%$T{LtR%TQ@_keNp6BF~mN}d1E^@ol@ zdLNuR3Gx2ak6*iDIz=+!Q+X5>a@gWrJz1v*VnqEJe17BXB`8MRdx?MWit(xcZg)#n zIsO?q)O}ee`>iot zjmX39_y0c&;JndS$IRtirm9;!%}(NIDM>9c9pr-H=OET=Q+tVrGO*znD@~gciUo0- z&1Zvirt`4W;^eB@=m{ldS3$XTAuAb5I~cNe0EUR1mc2v^S^QZv17@YDH3N{W5sEUD z)@1SwU3r6e zG}Xnho7ex}{~Z;bRh7CZp%1I9_-q{dcL(3Lt1>qO%%DcYQhYK0x>>enCLs1pa`q|a z{kP>>H^XPkwr~ptS}tJC?0;!Q?SC)#n;{G3f|hq3iPFhm?XUH7X77M*_&K@WZ}n@r zlV&+=kxi4!sLJ;_SoZiM#-=mQxT=E2&RXK>Sm&}J3BPH61*kYuGu5yU{-i{vYjJ)R zz47N#HoFa|&GJ;5wG_@n(Df(vU$p{nnrdMnkppH`329Y2Ha))@This4fuij@v(4`4 z-_>y2{E#pST6Q}lG+nvbP^q?jP}=B|c~GtH{k)&K4GK3;A`ZAc91c1zpAaehqK&YAa?%0*_V?sV=5hSbXGE<^$LUUh=+$Gz&B?>>t7{e<`AIqLdCUnM;fBYsbnOa+4UWd=JT2lv&HeF>fi62knj5Zur=VH*a z`a0R8lMHW_&bXg(<>A1jjQBW2HB*Ni8g;h?mhexd`CdXnS@=c3s?^oFzYgP^sxr8t zc7{FU<$V6qcjXo*Xtu=?ed3{_{$3LalOHaS(dIOd{sP}ab3aMEP=aD|eIr&&cu%a= zQdQ<-Sd3y;9DO6}Pybog<+1o1eD}|+>1J;wo@@Db{@e;xFayLGnAA3WRN|WA;>QDI z58(Z(8WI-IDIR5CA?dd7^6w$ESAe)%H}|ym5jGc`ZlBf2_!EbFYw6v9SEDz zi?gy=B9KO5PNh(qE2F@_Bu`SO@2wBo={y)kL zIP%y$B$wS~q)?%IQELBZiuBuxZyWPkD2c3ow>B5=Xir-2rOR$Xwne^hnSPXetT1cu zyP%+`j}aRY=`p&%tny8J@`5_=>U*L=WFP$g-p{0pDjmh~3EvAkpfk6KL0Fcqw?}K4ILH^CRZi|Auhh4q17X!jS1F1nc!zOXP zxkB7L?nl^nvKC)L8ZGA>m%%hI*MkLpEw@{Cd2vpXXAH=^Tn9dmH}qz4%s@2a^Jw-k zbcOe?4Tjbw-eq3u$Z{HA)f(+sl$eCqRoQNG<?7k7);+t)>8wA>`Lp z+}nVxhfxS6;B4JtLK2@QQ4U5qI^i>Yv|5p`t-d5SPFCgU*pa)W%ua$u5qkVt{tt9R z0w_)R8ZSXgEbo(y>+*Is$>b%2g0=lN@ruvxGk@XhEZg*qOa?b=gG3ld`Ykf^SW3e)|Tg%j0;KEhUsaht&E?up@h>R#J7=SaZJzA1= z83kyks_gZjR~(&6O=%x>nKrKmhjtx+K|hdwsHKSO6R#UXud5zC z*mmB)6sYGRFngcs0nW14fjKa;pmJ<(s6wAk*aE-M73AUlvy^L0J7r)*S7*x-3K26gE_bx+dK85_+jSF$2Sk^1= zkeWFuqkz@n4h^L0Ix%lWqCI`A@3RhClIVYAF#PG9we*~#*{@`pKI@E-{~>yZ_UvbH z9Yy$Y!j57xQf!B!&i#)V3mBr#WmE8e?|__v6yp(`NBcOCHuj3VxL3C(qJ7cEihz94 zM;og-i5EYXmoPo{0lO_o86m=Ci8_>8Y;$-#NfPHd ze&T3~-W_;Rp}lb$dNG&_gKFmJ^;{CRLpCbvo`t{88oEleI)tp*yZSod3e!0;bG z)P2O)$`337#s4?WrRF;on&FC1$Y^`5OKQz?W=6+jgJbr~E66zf&xrY>|3%DlQy#{G zjg5*-5jibMW%=92}GEUkV!%CB3#`MWhizni;cTu*@MY=_! zjr`g){mX`l&4He(_JZ<8(BmG!XD8nKe%GmpQQE`EK|sjdoN*I0Xkwcki3??+|0MjI zYVhkD0Hv=f1{^ys{nTe)Prm0n+~DSrJ-m7yxXA=IM2#4?T!D%|rTL8cfi2_=9Q+Gh z7rB*mT|WDYHr{hau%wO+WxXQ|4p1hyxnNj3@TQH5F?&srZP`xoY9YC~mJb+Vr<&u7 zc~cw`yAEi5SmBH?P$ocA22**vQRx`&#PS1}V_Vo_s2~Q?e3w;L>7uh*rPhxefkV@a z8I||4hJfQkct-hJqo#~Di`oB~bT)DH{$;fdJ-IJa(LL#kH&fEKnx46m zycCn|2qZNN7H8~VRR2hR2z%Kcc)3M-&eB36X@~6K782l_p=)m>;dacIJyIa4e#Oh) zuMiinJZlFoefiU*DO;nUEX?0sHc%5BPu8;`PrH5acl)Am9&GY-&@m_$2jQ9*26}Z6 zCW?-t=Lt1O)I?1(ihp)W>YA*(n}y%}zBH_>Nc_fyV)gDr>`R3~YRBQx^LKo@;B%7} zbeE!P@csZ(2i;X~ z4RyM}9Gw-i0O|gN_M8%Cd(iK&*CJ0e)kNKFP7ivX3HlcY%pJS(yBPX?XFS5yzh)^VIETYX&S zAw|T!#q0~~Dm859KVDg`;yPQtr{sbc&Kf-4nv}wBjxh!L4$g4U*D)m@Cx-LT6aq(P zWO0}%17o}8)T+x)S*6)7G2YW9yiGR&%#=S5;X1xXn%*(XV{84HohICctNb8{#``A+ zw)@P*l+$7Cfz<_wCvg^8E2~xwdse!%CagN(0yfbnj9#)c)#xFbM|!*XEAc<(wKE!0 zVOTPclE*f9TD`uw`B2?a7|$+7^T%)`1n=4+UcAttKXy0QZ|szBDrB*d| zKxBzAC9m$m`n4axHh;K|b714dvwO31JFPla?XnovPtM?aoqN>v;(KHyQ+4H}i7j)N zhu=6?(_kt=@MGy7^PL8VEV%EVbgK*cdE&zuYZIj>66kH5bcI1dlJG=1$kEH)NBYlSxG^hmx%(6NW;*u^|FW_ zgD{C1FBlz-YbqLpPoGfd?nn<_e+Loi$>kwb5ghYLzrhYI#FI2I<w0N&)!gI}rMUe5icK}h67})SC}@iRK|A0pkzaXrDKlW1 zhU^1`f7EhznrbPuFw6^%U`m+n@TF%iZ>3J#E{~<#V@f3GgVBLvv*k8GNsfsYW;#Gf z4cLZ6j%KVg>)*>>Nc@=Yz4RLN*=w=FZ7_=kDdj62y2^TmZ`b36= z$OIRtuk@ewVqpDf2`Vy<$VmDvU(xU*?!EAXq!zuOzE5fnfvHV0M13=-RwYaJd)vqM zIAqeviLfbMIq;9yLx3}sDaB6C)Znruq@;5TjXrW7 z+TPg`i|SC%n4X@<&E>lDU|XC-xq)Dxy%cFzJaBKbX#8-;e#yT1m-fz70IS!a(~)6k zt;BC9#;#rpdZEc5)PnWX2Gj5j?@dg@Ov9O}5E8cqVWhPB{4~jn7pB*bEgIxHVwlcZ zy%{f@s7*Vx>4&+eJi>f_G=JS}KH+>SyNt7ksO{TE7ab)}Z70<19xA_gUvwfJwKGN= zt1}9pz5rpL^7wP2IH&01EVI`KrN~hh-{=96JNqU!hO?boAKWox^?DJY?UVawaWQD$ zuBRr`9?C%Gu(Fls(MK)&ds3U-hzz3MV2yZfsl#3phq#%ftunt=)|hMWwE$VEutv@$ zvCun}me=gfp8Wp)UE!_@`pu6fneS|Sv+(^4OY^7Htv3iciXIsr6TXcBW&AYowM*R- zUw}l^V2{Sw!a^|N{S?P@ok zY*!hQt2fFGkn*QN54YY-zOEOQ{p8G^X4Ny)yoK$zjxC&_Hpw;Dx<(tSpG7SBI*k%5 z3dXZ`X`(wpNP6v8_+hS09Yo^(j&w!e=XDS(f|SvoNO!B9;m-?xF)pKv!+>4n|w)G@hev)MrscFfGZ{Q1tY*;-*< zf=76Ib790GX!el_-(wUCT{$*w-fWUexgHi4OXhqgnNu=ewvNc4rg&%iaKyj3MU z*$9J-Fo}7=bDei@U(FEw(hk2N!3iebQ1tMC@yEQ|bT_J)|2s?|ap;xs z|C!2ZkJ=%t&XTAOYCV{u!AU{cR+V2{&9_ z4{F>UNzbd<9XoFJl02P%I0k}fi!)9Wex7{$&8Td9?B9m_@(v?z2(8`}xdhf*=$)(N zWSDWQy`k^Arq^-cnj=UAngyC|idQ$q(?=+gDQHD250lDqu0r* zCOQ>7uEO5>TN`4SiX&3>k3GOGc>TC-oz1Y3xI<Wk6Tf@yr|JAQ*ztU`04XdYm;1u?de{w1h@98mDhaI)!fHJ&0clD)nxkHV z_8A1kf`nu*{U!8dW`N72#pIbH-iCNSEDF7UL)3!bVHOPVs@XQc)O>Z-b(fC?F-~_> z+hXtOVzbzC+2fC>(TO{ziQDNXa zddNC;l5(8>1!{D(jk-G*8EFYL0632s5E7>t6hi^6{l$QRmpoY1v}-JqW(}p_Fr7J7 zEeKlgj|(kRO3neu5;tOdx1EMtJK-P5#6b$8EZ&F!nG22|&c_+4X2>8f90?J=ya zEHdAQsPk9hSv)m5`?uNsIepzZ&}qVyr@EZ@w3LqwA@RZ^!LQ3c?GM~cDw!K~l;UJT zZtRN7H>;&}1f6CD4-4&^z1XeZI4a z8nZZ%N)qESoUHCO5?02kg{eq>X3On}JSIJ=o3Z9NcuT@&bnhS7d}EQG*eIngV|c)5 zKREfxHvfp{YIDC=>PK>Og;IFH@xX%OAKl)cm(y*ymjARW*P5zO7un|MQ+&T$$Xdlz zHci%{@RMhM8cd1%zp}9K7V6C1A56=(?7T)hiVq(i&^!C!NY4?YABLaRMd`%{A(S^e zg5JoV`_-;#d{$z(Lwq`z>>bc)Z9jkWr5^X*YX^{cdIkm^U9c3NntrRiS2D2Mx%Q-# z;B&`!YgEnFbJDC?&yPlnCCSoU5!)liwPA{)~NCPDTy3 z^|;}~uX3C4Wgh@&ye1K-lrall-tpqg3mNyw@)igzI*lC6DAFw<%xk39Fx1ZeOXz`3 z&*($iV9w)d->azwW;aqnqxC1ki$b|qs>g8FlF~!)lP3|j-E@da+hwcl)Bt9>uD zCGxgm`FSF0v6w+JbvwbtwSd_Mcd+AI$)UXA;h)wa1rndo?$gQ>NAkxq3(uv#^bx4v zE&eh4^JA9JxBG@WT6X_29-FoWaL>frWBNUu#fHT8b;QsKc>O2UVma2qlUU+>YEN3Q zucw-_U5eYyFYRg}-q%UpLqT6nScu#xbi-q#nxUdmc4k!iX8#(YNzF^!$pTRJRb{-o z;>DSHrlZPW8xXVKBH2D$G9j8&q=(jxnCS*sF>*8mwDEcg7r2Jxhyarl)%HFM4Aw~( z`2KP`(;#}~R`~dIiUg3q%Y?IMa^Ho;&JDVy8Fa>$0W8Dp{^q@cauu6sHl!|m`*G!Lc#zhq+(JXwE z3y<;H&JDcxm--Qm6x|?l-*y?T#Ya{xx8s(-l?S@(KT0d`Z!<2>5uKzzddw6=X?xO5 z?s63an#fhoq8D>EPHdx|X$)=dE#l7Vex$HppZe`%k85m=h6}gD?av%${rwbbAjM-L z9TsMe9C@i#Jti&5Bequ=H+`*yd_>JUN6!V z$?Tt29Ka*n(5XgA8yCSlszg2Lf?J3p8StmEns`28;>ZsPPJP*mupF?BpNH72uWGyy zSJU+~c2lJdD<|Rj<@m*cEXO5*A=DTo;>QLYD}y14xfr6*!e!4ds(x)ts`x&5dt%}p zhwg}xquihUsrJvltMH@mSsT|Y;B|v8_W7M@@6cT8Yl81)^f-xli;;WSDvTs=&#}EJ zV3k@8YlHr`_i%_jUTLmbcVGD+fM1y4*%2jDvdIJ?s8+4i_wr|rK6zN|OgJXW3wn=X z$SVf9%<<)5-0VUt79F|J8FU|eez^NRSNJ`g41HV z zZ9(cI1H_jIC5>@bRqGy8FaETsyJYA!ZVls6pAV%KijPkr59bV*AL}bL@o%>aWA6+@ z-P7ilyIc7VovcB8T4gU3>h1R-MYc#z)Z0jJ=xrB=`kW%_PqWXKIUeTWBakr~0P4W8 z?tsoYmR#@?$dn|am%`kA+6iw7-%;()>1~_5MG{gBCY{2%;1jrPLKYjDR$f|z_U@`Vd)*kgaS!)`j0}vIF z%KSFStqi^CIamzu{_!U0auHFW^-6y+4J;uM5PiRU3eKKTgXo#ukv0NOr3+KtHZRK? z^4Lk>ccgV`>zq#>pm!%0XTQr97LUO&MN%^on~V3~4HzNm0=7LuF;2cl1zQsNs2S=S z{Oonl;{v_-b1W)B9Bb20*rS!;7_OyAVBDb}YE%K}5x4qnwg0mYSmP0FCAkkh;-#kI zKY6YT^>{(FE7~PhZw{8DhDe1L+q+^;zxB_FvWsU}zt=MJV~^Kd=p1DxApgR4Gu3C& zYF`9~`ctPv+Sc!T)BA-3a=BOj#v5|dQPjA9N5xOBiqnY(sz!Izxu2f9?oMo*?|GZ3 z;yh{2`&QnZ7Kr>B&YXS4UPo2v)zGnG1}v@zdBjB^PuXqOa?k2&xJLt{SO8>B>F=McSz=%V&Mbm%Fx-n#T2 zU(;E+R>y(uT$Kpsc{!PYZI<+>0AoJWLm`g@l9#aBzPNIcbq{4F2kysyvqz3u1u9`C zD1;t<-PZetpO#&YBe^LfewCu9P zyJ#nI0r_;5GrP1dYzE9}x4BKY>MhAEKr5zN*88rg%)t~HM}C*TO0UAT7IisN>LHvc zE%c{IaAyI^<6p8sJNdmv_H})<*}P|R4l*~#3o+9H-iVM(RO1h+4<-s;%@Q6;Rs`^` z<%~Y-XlAlLdI+TG)FUeG8q5o)4sCTtv8R6J)Fklp$Z2@J^K$fO{|*X-2U(}}pLtlF zr8~lom_XyEK3fULc#Y0j=u}t0V7yq{YW5WX_qFaIsdhH`vwg<>< z>9_;bolu_#od1_wfm5K3Bz2|e$zxt9hZmd+9}4a-rEHVih!)>}yfSS*j5?Yc{H1*9 zi=(9B5~pyF5X{~b+iXVk8hnx0AJM^hO(Gv4S3?-}@aE6nzL}O|jD2qg&=P-sa34gp zcQ!_*d0o+E^ylXR!CE?6o^)mMf5ifwyQ17k@Jh?pVn+&XEnv`3(a%dol7d zGKPDUrcM!A&58|nYfiO{1>2snAGo*|Zi(9dytb~oywo134f~& zb|Ff9I%gxN4?&a;_^ttwcNAQJ-fQ=5Vz7Wyf+Qmc_IzKB&1CHh$aBX+dw7DS$uero z#)xIClmqR$k`0pK@wSwky(ll9x7D5=6sMx-V@qv|mRR(4lkf;uL$T?Gf_S>mlA(0K z&uNj*wQF|n!Vxb>vlw62Jj%I*u_0();280fgh;sFQVZ*r23 zeT#a~7T+|A@zb4GB-=znyHbvZvPWOo&uKOO%)kK?>^pGC;A1F-5bo`C4{QX}utgsV zU|c;3bYB3LTw3}28|Ko8th^G6?SWP>`ow?vSc5{>#9>U~hT)i+LN< zC3XJBoRlP0;lNX{!~Z7mx0iDtkV-x%rAn7DeApd}iABQ^epjkXBl5dUE&MO)l$RyM z3i~iTgb|-*zKpN=l=X|ItQ^Enhl@&ne^K*u{320DZ>#e=+g2studJVjkp_?+#^LplDJ14DVvU9RFJ{2UY)n-~qI@_%mT0U3gaS z=k8=mNA?L?1FE5T&v|Z98uouj0>|2h+_K4R00PozEyU4~?$QxS!|bx8Cb+!mt|k17 znI7mlEh7Q!Nd{8+j0qdBQw1w@{!x-+Uype z2?>U5F@{n(2EpyMRzf^Ctm(uOyU%qG z%%Dp3A^fR}Q!b^d>wm~vBm{R4owJ{+NCksU_WO9} z%KG=1Nd%GAe3~oab?TB3y>#e-_P#9Z{Or=j(X*=NM%$$3^hx}#AE`yb+j;)xb?Uwr zv(IQ(99zq%wGgd&ziqbAq-|Pxysbzfp=_=g!BakU^SH_O9|KtB>ymf^fhN)hpgaG3 z;bqxeicX2}{7Jq$JyDCDDrzw~WgqmRMe3a}&8K5oW79b!0t>jd`Q%NoR<+5!8q;!* zcv?)xgvMzYEf}Wb2Gx^R^*de-!kK709bK)5YeHuo1kLVR;-cx!t>O%5F3V
  • a z1BA{WCn}`1EVB~BD8({k15rlf|3Z&V%dx|z0mdM5r8pF_FWdz(8yNh?^53;O_-&*F z3RQ4Agyx)>MsJ5!HP7TR%DizCF?ULnJ2iQUl&L!A^@?4KwwPGdJp-m5V zHcGWuIJ$;i_j0r75(yb2M1XzZeKbmY^GzJuxL9Na@=EB~Spyh>;73S;sFJ%L zZ?zz-cS`jHZltb<;2w3%Gb4k?e;({tTC6?A zs9$xob5J$rSP2}27+#zPCXFVYhJWBWirD<5HF{4dr4Ia26UIPd{B_auc8K72rhnGd zCf-`E@s{$*Q&Unur67 zGV^(PX~MQg0ual~`^B5DGhrrcxHCh4#wlAlc})_C6U*hWD444M|*2!Y~TLivLmi)2de$Ptc$+s(q9g zyC8Ca*2|b-S9;;%b?=+c)0}!bbxR;@XFHisEGaaD*I=LxY<(uymbErszJer8@Apo% zaIHok#kZmD0dvDc`jG0ZbUM-dPyQ_*EzHgYU%~8m4Dvcg>n7|&^&))CO~eZ5|9RaT z5Yt`|1w;=h*ag@@tL6f$b2J_#p*$c)iY82yRXn1XTH3Xa6ttbY7fJSO28+;EU3tT4 zFT*PjpwLyjGr}_fgr=j|B=f2xsG->JKKbM`!Hr2E%;(zthEeZ;JtqX`m|Q)h_Ly@r zzd%iERQ9pu)1i=`!D8uW+9sAybA=N3L}|=Yv$?1*Ft=o@LKi=dg* z6!4q(Vp={6SPqS)ZfF)BGQ$8oLhP`?-0@^B)D10$IgcUQg5ISCYQl^A4^KBJyAjgT zJYfaZ+2syBF0*6qu7d2Je9Jg>*`!JP0s2M#y{fAdU}A{Ioa@QK7SN#SUGB$}uXR~X z#>Qu@kI=s#X@VxcA8!&Yaf)Bab5WC%Ul)?KL?O6)Ozj5|7vZrWH3ASzN*C}UmlT;>(1lC&=bEb@KX7!sdZ5sj1Tt~9=i zar{&8stITxj${y7~f6CGcxp#(o2ZAaj(j(${ zL#ZO@e_%m{=&yPE|H-%s5vZ8rbKktc&oRyj$ikV-8<{|XCqPOA$Z=N63**#-_Mnme6Vic|9o~~Hbe!#Nj69b-3w7~I4)dPVdUjO+|m~Ii# zp)k>;vrm7sgeM+@unca-)RN5bD3yQY08&P9$xie4U{YCan-%=VT{d`D{rF03 zDY_#A-<)5~CfjQR;l9=f$ptdrg>Um?970zaq5BRGrRn85FAa#r)Rc^|hrzWhMhD|9->mHkA(_u*0Is?vaSKcyWr#LJ?nM zZq^h1nu)|$Qe}tX;n`UaR87ibKv!D-Ty$%+@EK$-qY9xFR)5^UZV*J@ZkxS4w)A=g z76)t##0C$;Mn9|`1pFXZmYM-3zyT|Y$khX3>^x5Tix#fGfLz=6lBpvLQnAU5&!u|n z#=;JR#)vj*acTPpZ&aBWiY~3~)&L`Q=5N zTZ?Y+I5hD3G5GO~ULV=^m&9<;mEH%jXi(`tQc`wnFTC>e)oIaHIso0F`S-i4a{oaq;zigx zeG;s;Z6$8pb+~gOxsPE@+iXpp1<91NaPLMR`1rR=9L2snU%gb&ts&N^{E~JnyD~mH6>>69CNj3`lyptp1zX#QUajhCXFsP<%+et7>gmj?VT_PwE{OsXhZ2q z^AQ7`mi)ks#G(5BSMS}w|`dL4ss+^>HvUKiSZ)rAIjIN8b- z5nQU1A;P79s8o?7am>=-vh%@;1{v=?uGMY9VgL?YB*a`^icJ^;eYMtB+q~t$sP+J2 zMzM=ja(;8J21njBA&I-Hh&6qK6i~nFjD?WfQAppgLSMa>7q)KqR7}5@EVNB#bEY=^ zF+v&nXC}Z-movOP9tTZ$ZC6p%K#vP7tzHCNDS`Adb(+KIU&n3}~(7!A4nr1?+L1d!5uRh>{%sRV6w1(G5q z;E;I*#YOz)@2obk+XhnNl+!3%(pS#I{3PwfWk_Bw=Vj6}*7o6Ac^&(GR$lG}m2@O` zjimX|*#n=8rJ-+9AAQPQ*-&LajjBDy=7Pz>l$_lGDq5r2<2`yHs$)w}861$k+VNgL zG4Sh*HbpCJ-_UYxR4owesJ2^YXK7bI*i|+29!c#Io4gA0JuPbukRbi%S`FI!&l+HL zYrJIMDOG&FWO;3TJY?(?uku$5RF=nv&kg(7k0o}z+@G}MRCNw9qhOgmnnBqSCs=W@ zfvN2{ko%zr^MfT_uJLs;PIDMGJ0g~KqI&IS{GP^8fMpdA(;*ECa#T@Qg1*4d_-TFU z@>ArGCmAvZ#mO6m)Fw#&QToo@?9c@ff42Ry@2yzg#0U8WY0_q-KUqZZi5EHUz%wA|Vm(uNzv3$(7Y z&ewE+>~FkpH?V!!dAnTg>-6#A{`sDVKgXJ#fB?qB4DfPK;{uB;A6(_LwQdA!p9-P! zdFV01&XlqRF@;u!ysi}j8KZAU9jO)p$Cpx?-(o}Ta~4w*{EB0 zhA)1jLR`6$?EXjsvAGR5Kd$>;?ELt#L4j{6l{K>7Z?9TxARl#_ViESzw7d|=4FJY# z@YvSZ#%a~#-l%2F9&5>1+#hDDzj#?s4gPQIsHig3unlbndnq^2`g(%S$JM)7@~wHd zKF3e3?xgyeJ7gzp?l<)-KKDj(+97R{w6YSzPu{$HkV&iHThCAa*ZO%&4+ulqJxofY z-tqMDO?-U*rf~fyH;1T10)sfEid#Rc0sf%n^rd6k{eEk(1KPje)iZRLZy{6#rB>ck6BZYJ@73X*=}PFyvy_Ij%*&;scF?ou)7ONX^6c8u zx1v;Nquo}^Q}sav5ffsy3&)mGX#Quzo4Z)+J6*gfuff0PjJ%%DzXkoUdRHIumIW&> zNu8oVjgX|mXh?mwJ`_wnp{eSi20K=)Q;iZs$K*@C;$X8$)r?lsuu&z3HhnxZWf}My zVQC@kVL29wQX+iPueb?{v)lBy2$r1^nmO-tt1 z!hkXgdMFGBHg(mV;lyVlFP<~sz%z4bi_Q5r>NK$7ZLfX~G+eh7)jz^+Tb(z$y1FJ9 zg2)^uy>+XW(NVcnQZ(@~F%v}j>6m;qQ0?e+hg$14^1cxV|4$H~BJR$u=dHd$%F$S~ zjMaIVj7s8_h@&3Fv>RFu3M9450}-88AG_fAC~n|BB7CoOg( z?tFO!;m|{_Alfwii3qe&t1fWHMciV2u&ij4`f^qCc>E|A*ShOe)+a86x}F6|P%C72 zAZ1@u#YT*fDe9BNCr*$0{KL%WPMiZa!tJpZ@<(efuQ=S0!8w0OH}A4N4Nu5tN_0PU zyzBV+ftzXR{@7uEyd-Bs#W6!l7rnS`m}|$b1a8<3M;HyU~>CK zFd>YGWgA#s-N$fSvg$KQU6qDXE#srzhVJ09+gjVF6;8DbuDjYT2hD(z^N^Aha zAJb^9`^0zInH;wWYzx8*N*V_$t6x@JD*)*+!EL~8y^k^?+T%w&v0q9;CaeVvo>%h( z;<$*%jP+C3Fx7HRH>d#e#Qo$LX^&4IM_JinGjPuetD6(LJXdeH-LII5vVZrCHTJgT zE5~Nv5j~whacK=Vo@3%7oLJ|KTg%d(NGM)^Uv^hv+}}`rZ!CP5!^v z5WM-jj=L?(F0b*gG;!I2J{Id@&5xLLEpYxr>B7|cEle`k=Lf@%kshnE%m)xrrvnBlrxuQ?YAiX z2-pVr6X=RO1B_LfPVU`O-&XD^|7;}%&2O9_T$@Ig-H=x%<1>Ii=%kd?f#y}{f;3&? ze@tT$@O2vNJ^_DYnpYb)J}Kj}_*+Ks+L`g?veIiTwC8QrzH2KYXV+%Aj^53(7Z4; zp~G;tQ~t@k+NcdOKyjqw6z32a=JA&1!}|PL0e)|lt*hVDytoqcVLL4T0A3s5FT&Kt zJP40aV2BY_Vgi3E6EvjKT>24de%f^Fx5<8OLG;fnb`ej`}?`yCA_Uqh>?%SAd*|jpVZ0#c#zc&%~ z^SUiV`oPuifI&hH#alcdJ|i4oE5jLGtiIlNalQ%maRa(Rs4WrS6qFxiXKhclvri*K zSy|CA|Bk8B+RlK7;f5{8F10?p!=hD*vHDWuT%$f#sr>Sn|0P<_)0W@STo_{JB=R*S z;BnvSrQTymcb*Lh_yfh#(oz87whZq#?|S;_FD>2;oL-G}Tz~|ntDzi9N@9$vPrs-Z ze*i-aHt1u#32z9%LIA;}tdlr_boTMhGIi^Z0*t;YQ_FYD#JUcMU@tP2O$5Y^wambY zxxvpi1|!#HD)6_uS$+@j_n|EQ?mjMe0Vu?fFu|}V;^2-sEe)L)aCl*1ro1JP;w>!) zee=TUa&aM-GM*M-u`oSRw6&bd==cHwFPxB?mVWS7dBBg0w8~@WlZG>YH5^gV3a|hW z+ZLF#CBSL()P(^4)-QdxtS?@X_1USiJ*7h_goPx~R0j}1hpy~@rg?DX0L%8&&EO>R zf{*6MJiwj8L>Xuu=!eyx;<*NtSN@<=m%qBd9y&Rr6L>GMl=PzZ;uG+Cc6Pj+mh9&NjRee2 zsPp%=l=SzXYR^WUH2aY(1y=?UmB;9CkL#o&7LYNiUZjaR-?l7yZ#e3AM#;Xaj3Th^sWi)yZd-m2X@G!PbdA} zd%RgTG>Il<8A;#MGEqyw)y|v*eo-eVUpX&pP0gos+M97sx)Y`w`w_;xp@ZSvW{uiY zooN|5srjHi6;Gd!Juf#de@8$#^FdaZ0{&9&Eb~R?IS)b)5wCinPU8HdYt~o9v;8RJ zwi~}qPo3_;Z&T(~1kwMf7bmwxKCb20c_;phNg(E2m8$_&()f`0AXG{EOQ3@X5p4k z(+0oF=2exj%Y+^zcfNZV<2b^fe#(6K`-uPBfBV;k13#p;kS}TP^j~64^ZY z6=p@POIU@%0xbgg(_Uc$ie{E?m+8Bolt}@9;}36@$+gFEvTpzsQN5eMHz)WGXWja3 z9E~N-6YcSLQzyj&{QdV2?*#C7PnL))BH7Ulnwiw{Pn}MBPL^V4bzRmTes5otm6!k| zEd0(WZCaoTr4P;{ngQ^Dxya8kw^UL%3Nw2nA5fPS)W65zBYz-e37Wt(TO zm9_IrW$o1EvM!)wTNZyDVwxa_N&zy(rSdVD1~=W9^i9)b6OHtK^AS&CxbYxE#qkfl zseb|P2#HG2DbpATfP1rBI+a;~)8y@s%cPe4PDr0q(&vowCIE6PNJvw8V;V1a9&eQ2 zeepmCK*-u}Re-8c>oqpP~SxtC!A}vjSpgCHJW@fmXV4CI31+VtK86{N?@fg+RaS zkF}&+gYSa&UVNhhe;4Lw!h(~f*pmTxB~TlKP-$>5aM|ya4yhdaG9Cv?tk3BLU-ntl zp&nxw-YUDN1U~6tk8LeI1^DAYmI(`V3)_ybUn zG2a4#Qbt$_(wM^0oc)H4%&u|>Qgk|q_efu96#X0cg9pDjk#5(9opxCKy8Ywq$DFJ3 z^%839!N4CM61+I!EPwl>`u~NIQ=G+p8}}B^{Ysu6*Eq{PD-#2lff@_xiNNJ;xXCBctYp_2m20>*Ma# zwshG2p?%Aio|+%h{N6-*ANVuqXL@Kxxo72%D)VhgLpHwXGcxCL8e!%G7EbIz3gFQ{ zUG`~N`MuUY&vjiL@YjD2hmJ4H^a-a+KUd0<>vHy!Dn1J%NV>|%t0g0qFPtnI^*q{IyP7q}*Vu8f_UAmS*pk zH`wb>doFs9IqIR7zVBMl=ZV{20={3^-;WwV{2%_|A7akTRfU6#79*ocj`B(w?yDf{q4{t7)fBf*Stiv9c z2Lc{h<|{*`a#qU^-@SM`_JX^zI4=voX`NI$F2HYG)?%{oQxj?3my>>QQ=vC4Pftgo z2xq<=58pgGQ4I;8*b>mO4)7869LWe^J1nmQQPsKVg*>_{*E?kd>2U z!ax{Y)SrAtnqv0d@}L`4o|KRb<6rf$)U<^eepsB5hpgo$D)2YGaz`inqR%e^c$!*y zSmtC6$kJ%@5e0P9WQprzfwG+Xy1Xu6P9V;-mgz3YT5MiRsuu*hVquwk({V6Gm6^(| z=){S;4_3+}m0O?CLTy<>&PEvy0vQhrPAu^z)QiqCQ+_5CSN&QHT-F6R ztuJVKsZNmH67aWs_KmVVe@@`5cBzvd*rRX&{8b=HWhrkkwnn4NF?Psq+p1CtDe4C< zD1$?`fO~X1rVxP^_|pr1>V#y0rUL#ZbZE}B0QHI0``X`6*0frBJ*^Xdr=Muqwe&Cq zsJqedYoo~l&CAuake9+@Y*V^l)oC41Hnv0dtFrjhDr*6M$uEHPl$KP_O|#G9gbrAd zC9UQemVW3jbV$|FrrU5k#O){m5I!kAXmRlTV%gOJD_a6#*Uw+mvfm4JK5$42FBO9^ zA2leAajwjPE(FrrIxy!4lxRcDKwq1Vay1+j)KguS8^oRdy8QM9))oXYS7V&yeDs`j zKMtGc*Cm@*(T-(H-3I;$w;y!<2Q~TM2IukhI{QkSd_dsP4FE@bdgjv7Qsj;LIShVB z@$sy*L~Bh zwK7#|_DIQ8(JE}piVH?9!#}PgQ%!Fg>UDjj?Yf~#Fa-RG5V=B6>wtdo%^0*+_UO4UB8VNi4QdH(lHnmsW}+c$P$eel4Jkx&wmz&d&CE|@&PBH zgCP!s2;h&Up#mvp*6wSczw6qI?5nbK=ZiA=Noe|PBGqw|l zc4!B;W-l@~PWw$b8_HiN+Yc7ut0ii}(XSeZcY%H^FI^F!v@O7C{E`4C9qzGmTFV+| z&zB7Vr^zXOfC4h*i(Xnaf#_4drbUwu(|Enrkxz5>Yt!Kc&yibG4LWf<$uKXJ2{h@3 zfF8v^|8V14o;@QVcUpkc%%dA|$j7#pnocd>D+@YpmVNbPY@Bs>ZRtTE{XEnjjO5PD z&B|JAN+@Z!84>yQQVq+d5!kM<@LP z{0XU4$7xgYS2^nhz-mYrYQ`;PlU*#DPwfztVDvv|s%&97rw@5m-nRI&K0-7CMz?k7 z#*XHWto|mozvAR$fv~dpo4NaCnU)?VwcjGk=%bNnE9)F^2M_Sp@&`k@aAFKzWB)_> z+PP6nvjvhWJAl8)mENQTmQ`cnrz1b&AdlD!lg`wthTDkB2T5+LTKl1g?S*r)xO`Ld z;c8jaGT-$%0kWD8y8?ZM?FI0c@}~(Uh}U@Fks117DX{d!#lOgRKWSQwkrv$?q$ewb zc)uL^ufy@6_GYlW#CkK>c5`GuZ2Vw=SKMLo{5s_Fs@t$kkztIVDpNk_3^+Xt=y=sU z9#;JxU$3+MRu8spI;b8FgWngC&2izg?VCTWNqg3OIF9{m`+8KvmMizH6X5UgwB+Y6 zzUKwHG2qnd$+U;Z?aOQVsPx71bxk#T3h<$=I=UIBUjI4{UwL;a_n2c|V1N@es?fAqpQNYud}Z3nZ(jn#GVAA} zx73+)SnA7RfgFN^B`n`{?DfZCfd>BCKX_BWUB9lEshdG7wKdvh?9@5K0OU|jR$L1B zlf~csoCX*~iPtj&)pYpResLSJGFu*>iT(Yi zw5QxQz~92fvNofWWCb_@bWAkXO#x&eeD|Mfi1RPfbC3nw!5%r!a3Q}I_(O+vsc(Qy zHC%5VkOTZp0py}jS^Z7O(ro+IXJzuy?Xs|;z5fLChUFbXiu#ia8DEAK88_o`A;&Dg z46H`kbSZ$pZVU`$2oAUn_((r7-DKcJzZDdHSeK82;@4+g2QKFex_#Qe)&a;-(Up`)A^}qN;_t74N(Tv-o3BtODl4wIfIHy~) zx8>;zW&Gl`vUTQ-vNA6ad}dJxelQ={V^MQeYKx`2A@rEJ5;=*C3tjjTW?m@FzotDn zM;oJVnmM-+kY^${Im}QGt}lg?ZiL01dwT8hJJCSmi8}n2e0+$ zQ1<(FbU1sO6L|Ft5cfX-4(}P{4{OhXe!u$hr)xhNDaVD+R$2x)NIL=kTFD$vc+|Ww zC&zJonRk58?>6lyhT)TW(OUfR?6&;LKQ4WF9{IlRKDj;16<*sg`L=KZ07NJJ;q)gz z`AK|Wx8*6bqRCRX!sRVp4sch7wpO7y}$Xz6HiN@87KwoO&7u+EJxgO069me?J;r&?p z`^jfHFTw&-OMg`zmBx2w)~eDpD%a{VQ%-*S64>uP;WcAt~xfqQ# z!yrNs%A!oj(gW>Fc0-2|e0qI34k$Q#Zc6*e&FS!gMJ-3v@={rd<;lLehac5NZSHu~ zNoz`QhW(C-%npJm7X$--dy_lCj#?-5Qa+&Gy7rEHJUL&s7B9sqvOBVFTA4i?2YYM* z{BfAX5b(!j)Qzw*&BV6lSquVI-S=sAz*xrG6m&&jbD8Ntce&hG3I}jPm-tYs?J-U{ z2Kd`pE_3S-%EY6a1&hB)9riJ|`k+j2$l6SD4p6I;Co-~}s!!8)ktAjSjlu_ZTW*^-uvvyS9+N-iMY83esnMzECz8 zjQL=`@tv0yo3Q7rnB=()5U%CzYqIX!)&VO4{GGm3R%T9@bshGx!->8D7ANp$0G1n3 z$UJ<;2fC>ie+t8Y{Ok1M$8z3ChxG+{*SQF{@vb|sI56r(iF+yTF!*`J-956^^8xYT z!GqYV2J`&Z^76rmVI3KYz4&q>6>PG+4k?ag-6W` z_u)8>FY}J?`Q4@+#V~SiEzP{AnfKD7AIGIH&m-U0-6yx#AJ>kza%Nr_h<*S4+!K~} zXB_mt+WxwJr}g7bKk;*JTHcnEWomsOr}huo9E^75%9V2V413J!ojzV`^W7HOVT(7t ziw^;RP}osMR|k~Ucx1c2{9eg7ey3qR;xNSdzVEMsC?089HYwo4IWC*Nfx3*jE|+p0 zE-$JE8whHBAM=lIJ{lSBewgH_S_aJ##{(Yc5|JK&l z%R5W&mMd7C$?|VTmVYrnMAz!iI*mF`emV(w%#+Z{t0U+Ipz$BFDcgTuVEMPWxEMg7 z>+}5TRTWX|#k8Yn4xGloh|v-wM&TS)yTT6`HM!!G0hN34kNqr8^_|N>rOsg070d6*#yYO;6|>9ei$%vkoKiy>z@53U6NGVXo;68Ni#ujpfAM*)B1vg(`G0UvXlj|DQ_ zExQ7oCLYM*Ox9-8vOt>>*gG!y2d~kHTeUoE+{wuajYp`Hd5w07wO<);e<7@u4V7tV zsGEyASgS7iZfU9Yrhug_og&N9(ydE6OhTvmuIMCRECCbvLkECK75M9PLfxt>@TDsA zV4?D%JnO-{bq}H7QL*YXPMBb!3)KqPr`e`}!B^%|-niqmY>jhU{sF?y3H+OVa<|NB zkH0DDVeEk{YvYg)=}MC~E&q~T^P*VK!Hh3w(HC9rQWt=(b&kt-u*>cWE2RxXkcX>m zYP@e~Y4yfwovJJVmOU@G7S5Md0plA2V0W~yBVg^g1QsVBpUZRQ#jP-$CSLJwR(c>{afY(BHlKc2v^8 z$-tjwe3b9AjBzghP;~F!z4)MGj@Z%+pu_yzcfXFi|GN9*_IzIMTuL;*a55a<3h|Av z_xN!Bb}*Gn#s?HN_=1oyrJ?tgY26B_pvWInXUz2J=l2=mtjTrTeR|ZJy(#Iqdo3dC^+_J+%jB)VBYR+uon*8M&eI z95vYkhFuyR;e!pS1NxlShF&t38v8lGpAPqkQ+<^e;89=}30P2QOv@4{1q87?bXI$k zO=u6YZSC>LUVn44Qkr3@qQInyu-8RtWc3NlnZ=Ch zS90(`#82_yD_u9`0Gj}xba9K0ZYvD%2jDa_;} zFEeRLoAOT!zy$sP|2S-APD|!zrH45k^1V1`afJ>N z^cw(w)StlLm~Kw!E62a*1^k+4wQRjLET{f5VN`xY`qG1~3AjHTYy!@Bz_t9nbOuf; z9FhPZ4(v^X`#1mQ-*l(>qJ#D?ch=2N;UgM3F5}01de0N$=)+5W-+wQWp58mmM!g0QR+p<}I`wd{qEN9v*HE2IM zXj>;7Wevm)GL`P~5K(7SKBEH`di*81xe~F0E<%KGf_~5#FjRYzyImKmWvw65^IJ&) zo3U^}qe=f;DF1ILxuE&HA%W-3Gq%2)FGM$F=#HGMdhL$H8y=)Q0^%U^$TI zF#U3vbYD&f5NFRn?o;T%d;alhHg*L3ZI#(wS=6pS)?q7mG_P)yo!dG*M*#c0tTLx$Z43DB z$Hb5<-EKEAlAU0yVL9SMKegafG&P~Cw@1)KkqwWsO@VrAvVKMOTNjoB_}fvK!&Nr< z3j>!dG(DCB43{qQbYH+fRjMm*e)7qa?s&+N7XQMBDKnNg<}5SlSR0SB)cqP9ZTZE> zFRHO5LMHe;0Q^Gx8d&*OHqq+c0s!FfQXwpxcqrTXK|grzIp=8mqxyLiIX0j99+7jE z4{BR*{LSC|O<7u6ig|$!On(&n((-g%_-uLZhfjdNzC;c$&Uj*8aH=o!;Qb1Sdz{%n zJPuz@%k=FiI^TQR=K=cgA1HWkaG%0i7nC`w{Ru{&p}qcG*7ezUUCuwK|Dxp%TL1IX^*^`T@-d^n#_KJ8_0`sE`S;U!uZ^u!8hx<$ zB1=tkwV625_lzCi2AVa^MNZxa29|NeGp+CQ-VY!UK1IWcXXvBf3ROSzL>UQ`BPBAM z@@^-p%_908q-HovWp)=fQI|lzBFTX2s2PpI2Aq@U3iK@=|0qu=%X!=?AzY>^KR&ya zSnr?ReM(f!iC_NmAH;@$zrP0fd%OG2;M)q<>bKQvn+~1x@SSJh`Sv?rNjT!J&ntbh zbN|}DJI{Vw-t_oR=lz!Z)T2j_;`@(h2Ydeg;0Hg5CGivb?uE8(*LA;Czm7x3T=p=> zjMnhxDAPAJMl}MZl%ntIu=vv+e@2QK%z#H&B4q~|d9wUs=_lYHV9}bEhiXaage?9h zZhu;4bjZiN@}>X?5eiLPz%k~N6(tVR>wu@dr8&RMRDL|2s*gWtWJ1;Wu)>bil!&;^r%ISk5&00XlI5;f90NU)3jf6zQ@E+?!yTsrLKh zP>Jb#xyRh3tj#7jWZkJ!0KXa#s+kLCfhpL@w@L1@mD%MxpiBp;YRGj3YpUXr#1DmZ zNoL4)Q!?JrfgY=}?%O_dsZ3mWOG~XU>L3XntRmfzAK)v+s@&OEZc-C5_m`tC@~F0k zqkiik(|lu2V$s^AkX0fne80~Lj!qC+m3!z1xzkiyV`2%jEgfttkEQFf5!K#`+AmWl zWsg6&6{luTXb;VKo%qWVd%(e5@*4s%7pk)#A7n*{K8|!vIn#7WPU!opsCG0C43XTn z1*Ec<;`*%iSX`8qAHd(D_F9~iUZe-CV|O$USRRj@WBg<77dolHo|?&dL4Y)Xzh>@8 z%BU!vnUvgXea^x6{BgLAw{$N%OgsLdW(@d)!R>pFzU+2S>KiSARv(1Dq%r5Graj|P z?zrj2<7srSk4`FlTGsY?DLMiE4qr#UPr-@j#a>(;m+`h2|3^I?`7$pI{Pmw3-xT@# z9&l9k(LN8*2Nr+u?D=6m;JYvOk7}O|!q;K-!SZzb_ML8@bnaKS-0u#TsGTF93wmE< zxxRzQprv`ya%~+iGtBF@Uw!@N+ty#d_uHfchb_BN1uTE(IZm0-M_q#b{`+aU-+gB) zKR$G#VE1+8YN{`tMW@^&#Um$w-QOgUUONf6nnC&DdL%0YAe~@bo4KlOYP{eE-*?VO z-sYc#{OFRrry=O2;lD*|K;!EaF1PW?iU@agDm$W1FRr@OW2xb<1tt%tI9kA8NE2taCKlhIsBRxc>)HqtP-7Wzbl+o z1wohRw8nQ^PnCnFSJ3?8M?Y#l0ESQ^gvMbKTk~hih7K{t&zD8Cm_!JiIQw-YjGHZfJex@llzz~{tPPBwqu;p9QD&R{DB?@4+f`^xH) zJtdJR`zywtesKfx*iJcntOwvH{bXFe{)M$Hp>CX+Ny)s?Q`g;&j%M3(rg$|zZSlc? zr2x9-gW{i|vFuZD|nZ>`9c%i{!}7gPgH{(!UmP1l#0^ZV&XCB7HmM}@!r z_+WnY^|2rQamYK4`Zxjpj?T#9e#5+Ifu^OUrS7?LbU6KboE(+=>OtnK?^E#H?kz{z zetGxHen0=~N$u5_Hs8e7WI%s0OF2Y+A(1((Kl)^7-eV$CB$G{pg2rx@^c*w0vu}Ws;%Mzx_GnaxFD9 z$I12ib)WDZra#NjV96D0%8kiso!Tp_KFNJYmVUcub)bX}lGu^e*|tEx zZ5=d$RbcJ~XzMamqUFBGzv?(t9KfIIue?O_%E*b;-u8n4?!!e+<&SVj8M+XO@{s*t zF4Y7jax+HmSo;C|L5Ni)`)E#U>Gj0wqcYBtUoE}Hs&-0xm}SW?Ag$=a0+Y%^$dxam z5g&NjC(=i`D4-1c!$Ao^3A!Y&bhRC&1Ln#8P^WHh z&cza6YDbm;f8zrE0{lbfIHh;GJ^g z=Eom>^ii04vjpPm)vFzk-P{blz0B6XopqsG+$gzPAN&Q5m(>1gzAocBEJ5PVbJ|h! z`#c{t{zmcBEfH$;(Y_FkDsx=Yj-x(KfWMFO z<@;)X4*Rr5EH~P{<*?j7%({ojr3V^r4y1 z`=qGvX>PoGiBEpoUz6ZN7NjGAzov;Kszu#LzNa!tp$t@S&|XbYen(Sl87?`<&9Z}X z&<)a@UQ^ODLEaz4RLCcORWJ7vzI*g7W#?M5V%pA>^!awg_@e? zx43w^Oi$0KT?}@_MxB3zX}7Oqr}uSD`f+u8^~HV1cQ|w*xg69{&h^`;EcYUwA3jvj z&kr9e*tY4m+q$Tut&h0r2;=tVl~H0OLIaTgVdSOXIO`ztz_IjA{foc*g@C_>0HPRd z>^l|!U2LZI0)jXcVw!#7WR=8eu;sq?hZA72Aj_mFK%y9+su1A7@>HGa z><3RzB}IbEWN!VfiA`}jHK1=YnqcOStgzM#am{a)A9Wx+z>ZvAx{5WKto?Sw(oBa* z=p@-q_V(ixSq_t+eC@MQRvMx905&wyCsbD;%mM%-C)&*Rt@MKcf5~1BUI3<4ba+Ey zdXRh0pWtQF&*ag= z?1IAZLfR--Gdfz)#JC`#SFVzRQq%CZtjjjEuOHTA8`8nn;-ylwx8L^Z3tINOP__j& z6@jl|btxH3;3}pIU)3k@H;7lI1YH1d!LA5{H~a|HPPAc?DzC^-VNbWv0esi&w6?VT zshT;(4P2LQ%G;vjW>Hwmt2x7Rc`Rxt*8u-+m$7?a>J;r;np;}(i&dudhaSS>GUQg- z>pU9oxjyS%c1v3s?(zsAgE~edoN@L}To;hXzJBWq=i)T$@$*;XaGUj+(_wXqwI4t& za)>?sIM@R)9DV4@x~nb>lG~Tu>6&sw1*ty(K)d8S(+8>Kdj2@v#$Ebl`)oqZjh+vM zYuB#DgST(uO`H82_{-+wn_Qn|XPsNGq;olr?+>^3L;8$fOaTCK(8ru>1lIqHUz4?O z(0uJn^b#}O&zD%`OR1_a2lGif`tXOFUxd!qy)RAoQkXb|N{$=<@M{Y*#MN1BykyxO zH@Upz?jN{1<_FJ>*gH!A2fFbeDq2f{16O!N3H$el*Ue_zejA35_(Obs_u#pJK3dBS z06z}t;tzSy;{5z*d2*WY{_ekx}u;h_D3u1||h+i`Av#2;3DzmjDW z`bb9|4(0p#(*UJthBzFKP%27_C~L^yq{?uXcRDdH)*^L<6e8bWXIWw(G14urBC zXFy9{rIkEz(PGGp9MZD>u0}T()Z{9m1OGBHFoGycJZs6ET2~ch(_&<&@ru5Q^nJF5 z;lTsVk6ZbNZsx}ifB1v=4#`>uI&Jl6J)>V=+4kVq^U1V>oTC*opM9?ON{7y49iRKT z``DL7TL)p6qYlfHFphfo?%;mKcOjOTJkQyi^z!A)T^mWA^wj4z?K>ae?LCVwXg!t~ zm-+|ZfHM}w?BKM3vH$e{{HNWismVC)l)<&FCBH3L0XSjM$cGYe(7?0~`IwQ_-z?yt z4k4IczFQU)KRc!qN@Z1s)n7DPCrPv(KXo>Q$4?Gv=7c9skol)(57Rjlzt%VE&RDbD zM3(9*Y%3Xr&9BQUCxpfF(y^)XP=|Ls(cuxB3j&*DWwxOujvE3yHe*?1KGdRxT2Brd zCRR>s1`5`G_*Mpuqav5fqFKf_Omm&xtg%q;U|=AMWSfbeVFpXoAILwtl*ONP1HcRD zhn85f$`b8qfl9N|>!d)YFo{r$FN>9;OGc1O#9 zi!1^;5jFs;5PHfnmW--Oz`wX@nyv6PnXA6w7nxgc9bXY}Au}ysGRRc}2rvR|e^zKPZQVSPEha<9zl;Ez)}QCqNDkxirQPFZ-~IF;?{ zw~Wa)%MED+ogO?lj1SR4q0ui^)WdCd zImK5S15g8^jd5Q=SQ0|q{HVUT+3`Xh>B@_?2CS#A3>Z`BGvOFx_-M)JYA5ODRUYkzbz#r+c`Ls;!+ddHXha2>`ydOV3 zo-%ju-?rYpsa{@A+wYfG>&vUj@-Uyo4gApxAJBsjgwb>O<#F@vsL8TEXm33~phq77 zOegMeB;ff%>*$3&f^Y_!o>#X~_z3>A{d`&M9aJ`L+YZ~O4ldvSN$1(XWy>b=`}*+n zgK{{^`FdIXd)4(=1~1ai^OiOJivWMtkLL$&Z#f6HJI>GhO|ls6V6lZpkyu z7XglMko3bNwfjKk3q{{iy5Of4P>7OQT0P4=yiBTr0gV!>%a+vPCN8=dU+G6}?BhSY3X$PQT-h*z)^6%Hb`E}?hfF|wv zmrm`~ezfz0G{=1(s|7mG`7YmO9Fu_gZ`pNPj8VzJ_xrYw(D>S`Ea|SxH0^VN@4|o9 z9*npa_-o}3z2j|ruGc)8H>dk~<#zEsQc~41cp^1MRUNm?jxEiZv48&`{{8Ois!nj# z2RJS)kr>P>4dBN=hg}ti46xjHM#~a8byW6l<>JIvxjeC5-k91cXU4Y$5^2dVU=v)> zayO4w{mVRr}!DcM)#o{tggN?eP-V|fhi2Mg)uWct0((O1x z?nAOq(x@|n)>xJZIaHF`WKt;`3M^ zm2=};<-+84xhOrHnJi^Nx|o7ZT0*wcUFt$%>!9C{7h?qTiQ0=;b-OhhHBsC`hLHjHqKvoSn7+zvW&mDwfUq!tA1$qbN%}EqdiF8 zv-qJsx7pIRVcIdxLE0QexOC5m)o)5);%h%%_rRQ zZ~FGR-k&F?aXH8P^&aJT%d`9Oy!^Ix9Hgwx;Fkg!tSg6gS6SnME%D3)i>UUYX#9ihpXQaI?e~k0bI*l8>XmvX??=$YpD+j zTJOD!xzsn>lk97oQHDO$4%BSrn<9PpFWQT;nbQ7tm2{P9TsTa9{>H7}Kdu=+!s0VR zk?$7yX3y~z%|?BGN38UWrOXW4;G^mVdk*JPEwz#r-}zA{+ew;AFep*$gD~kVV`LgG zJpF*Bs2tyjDb8rAlBMwkmVXcQ9YPU*hXi-_@RCIN*t;%##tRY=ssOH z`h@++xKE|W{@s80ce`sVD=N=W6=`5~;N}b#fF*#xh(#R?y)nfnWF0oGJ;&yD*2@_H zKN(wH7D%LHF3RHWdYO&G2xL?!TALe217-#eaKX2J%wwiL{p(YcPH#HY))DHfFf zQt(v6YN+y*(`-CWh+Wfx9so_ZcBcdQ1N3;fGf}kjT7phkH~~7LpxU0B3PmAbC4}`7 zw}qN%>hNjWh0Irt8%ff73px-u!svv*KRzj3NkOU(1 z6~J0H6D=oKaXXFXJI+JyZ7o6G{6J~#WpaJqbTmPs{?g^Nn#J#0h_Dg=&<}ayjeRsZ zL3?I*vuG#7vN*O?&Q0#byjs{?E@#HJ%ek3}GB5BCa2*}Q9*pQA>Zom41oq7tjGB#Z z9+2ro1=atww$yPxl53n~E%19)a>m;4{?>T81MsH{y=-vcjq))g&I3IFU?o3YG3Fyo zz5I`#>Jv7Dt-L8qR_57<%hvVN`|*}`RM`5kKZ?d_)b0AA_lE&#?NU%4yYes#DE{$6zb z`r0yIH%yzp+>ZU{sk<%H_G8q2tEF`t{j|0Y(|i;Ce!utYDL&v(Cfc^sGr zc=P2n`_T4z|GNCSZv1}Td!@Byo(hY{&N0qw1fQ=JzpC@y(7d$=)$mtI7IgVq%~Ree zo}VI8g5?|>QK=eVi>(UoN59XUIU7qG;VHUc-bHIZ2OJMl%%AQcg>Hs=m}hq6=@tU>tDw_g3o3_6m`fAB=SBp@pQ5Ec_~nhxDq#~$m}B@H;OHulmy zxB1d4{F)WLC_nqj=b&}^4;OS{)O(lfu|KM-<|A|mL5#xz<)G~Fh>cOF!NGXdC@N$B z*Z=(=cc&&N^>OYYo0Twt!ZJ*jT~y`@V~`6miW7bX0!?gf2n<>;rv&ybtUoIA%eQ0s z@03m=o!Znv1u8Eapcu3{F{z&sOA7=&)a_?-%#b8-!m#g=zaLFoBIx<4?bPOnin~sP zDS5E3AE(0tYOL!(kJY)eW%cyMvNE$+o(OPSV_Bns5SEyZvA-WDm+Bu|m}M)95zr67 zYJyIHehE$mRS*ttPFC!I^<>nFPCaMsh|m^&*3Uq$-L0l}F>f~sKqZh%`K&|3L8oKM z3^2eyKwXxbKEC}``TSr1IY7W4EWKH-EKHZl6+v%0#06j%;CE67gRnPUwhOPx@4z4Q zB+??=G&L{etv>&C6xr5QRdFD zp3oKi-~;?|aZ|T0IYfs8S0(^q6$Sugj&0w+RUUr!2c7);sJwZ4uAG(0AC|Z5&&b|@ z%(bxmvkvM*A{dHJz)|BO+I70g5N{F|n}BMDYZ?1=+0=>Eo0ODZZf#CW3?-xpvd-G2Dl9!=Z$Eh8umUe(G>`VpgL!rwe^lCj>HRt#x9|Gww{1OdxL@af z|S}Ui+sY=)m}NCavZrG{8398p>-V{*e+T-^4j*C-uDke(=YQParfs% z${wW5tLTU8g!j0oi4oFbNzex@2`Vv9ytEXZcs}_)=zhB{%CuqPN6Eb^-YkcM^mRWT zoJW1WtPk?`Tk3ld9$f!H_%w~n*mwHN@(;rI*KO;dZCK`Rk3RRuz3bw>^-urwPeJO# zp`h(M)7y7`KmMxZOM7iwwByUXmpZNmb!Y#ed>m8;d(pW){Fa8e^+NhydU1L4J1Xup>Tw(PU9KN@y35*kIzDN>T;9Iv zy7=G~B(wB-8%flm7vJvlSh>9UDy4o#yC8JwpigJNM&)(w5gsHzGc>Ay@owIg)Zr_d zCm(z;m?u2n%~RW0a$0i?V5y(A$3Z&aO`+&~;u5YeWa73}wxf^0fGSClmYqV;rsd_5 zxsB0YQpwd^)RGsaqD}>9oz+n00=duxGGEJZbAhkDkBwhXmh@ABK!a_z(?)q>d-HH5>cc&;P$T+#`pZN_7Jci!d%7=%GOt zj8K-z$mj&D04(C9Q7!qM*_7>@_Jo_#K_62(j9}ui!a5XUN`S?LfQcdyBL;2MukzFp zS0q%X%&O9y49zI#dLnNRnxS&8lY+Wj#6Gn3W`tk>{jeh26zB)wv7rMzwm8XGhk9%P z#Xvg0>Og}HEo%gHVlT5XE(W%|7Y(#9IU#Le1A0^fhOlBU4qFrIE-f;hw;va_kQosef!?-+nI5| zX~tuZF&G6b0w8ZrBao2?or*6)Fq=X`sM`M&Ozx{ zeE>tSdw0?jD#xxI7qNnyhz69GTN#2z@$i%JXi!ExnT%y@(!PCj=B3fO^Hb{8$+2@6 zDy@C}w7hrF_L4*X`ZYsk>?CEAKk{`Mn^;vfAvP%6-wy*+Aw$a)A0}17{ficU0XAjr zfaYfmE`Ja=;mu|`M(D=Jl8-6FQ5EEkXiv>B#@ghUv1a;kZ&{XLBi|0m`u6$L>BND* zr&)Jyq|GZ9rKPhwWQ3Io6g^;sm$49op&1UXk}POzPW}?gO(R>?>jL1wjA2GUbV2{e z+Y+PSP*1OnuR2hLla$r}lg7hHH+qo4FB|=IY_H1~Q7p&24Ot_mkgMwy&`oFM9=Y}A8pfMcit#^%%~w6XE0pMGla_uqftP5_Mh zN*Vzx=|z6fFL6q|Iy}k+yq*sDcyuFwy2B^MN7)YIWtuwCN7Nm8=;f17KCvdEmqw#u zeGdRQ@#R{|AZP@vo}LUI`O_6fTYd?>@!If9Xx7UHpJiRZN;s#;mipj;53VqPP&PJu zk8)8@NjG4>B%JB=qHT3K1pHCMXm6>L7$4+uxCi5-eoeLhpkFUPS^9CyO-A=gGLOt<45_JX+-zC51EA&Vk%lKq%j(+gCcu`k`rM&q* z*|%?>=_&M5;H1{4CAA%^`=6KK{UGb!}#{&xtzpRYfSYBgOWzN`myjmau77wP zs>FyI2hjGUQPG=-(S#FdbMfgn3w0-pPN27D*%n@crw2tPOFfgnRW`;k$;DlnHfeNkT7)&;AdHrz` zDV|8(I^?6{woW6xd0F0JI`|_SCNTcBwTXst0WFB+IxPtHs9W(!R(v^6&Cgsm8raNu zI2N>wD2WPSZL$Id$UL3!_LJcW&!%BcF4YOLLpnWnP=|RukP&1+#tsZ4ZSC39FB|<3 ztSLG|1fPvf{&1i+a5P|*$8B+-7I#KGZk*{uZ7t-W5>=~tELnDj*h5CR_E#12ZosFV z+MEr!{s6)7Bt+@L3{KMNl`EIhPlta@gAe*spB@@Z7xbq2U9)t+hfemrcf$_l{$(HofDBJ=Tt%ixNtZt0f!h!EpbuLP zxyp825GdmXJjcssS%>_=BYR9knvIHF!$1$Z>E`A=tB8#oD-Q`z`$O0bfW$d`Wdx(T z^5Kc)yd5&^T|Ij;{rLAUQo9VVdp504ee-*y1D(Pw1AE(pyJ^;d>%o`(`W}q#8t(jA zOEUi=Z5Lmz^h^5!Q=c3`7n0+Mye)^(L6ofwd9)iam@SsCFCThT9oDh#P#Gm$6Z`X9y zKV5X|at!_gUau$Mfj3czK0f~VW0U`QhQEo*Pgh>O4UbFrQQA%&k5g}}GE=D+oT=dP z9a1;^ZP>7(`eCCLjgodN{%C87L;6v#pc`SGk4Q&;oqpuk;ZHjq`~^RxBTmQ-EPhDh zdjfqhPPpo)Uzg=4YD?5H5zf=di}pud!B@Z|9r+QC2ao(G9a29$hP>kkR}6n#d-v{b zIf0&xukqRy@@Q4Q`Ib*E@1ugycM9ZqORdv?n68(q-g|Swphf7n`l;GaDsXv^=jMuV zYzq8lPVf|=6*LTDb*Sgo`8Q}DCsxXM^0KGK`C-raR~chGx51=k^G|+A$E>Gpg;4Ta ze5;6`HNd<{PB>-&RIcUU zj32}B@|xSiQ?iw8$VBC+KUPmF4UJhg|5d~oaSZleym{-UPL&;d$}cOD;s>Yrp%oS; zx}x6_MjZT>{bM3RGc2!cOUYWjUG;Rm9Qh?q8HaAjjWFK3z^T6n2X63EuP5Mj`qm{P z(};KI4stg3FFTBiK+#H4*~1&3Zu*@ z+o8G9>kSA;{l0Wc~E*7+?bxkkKyMs#wd8k zv~wK;F6ffQ6!v zxuMTa?#1|uA+JO7?bI30GWw0m_==GaT?}=}@G5W1VR^fb;Elb-2kq`lIseSBYQ7OFU@s#Tf=B z@R%5^Ter@>1jq+Q$Q2=R;Bk|FaZM}%WEVG>$gT{@3wg$#Ot{paI(5qSn&C7pmYzhp zpcTKA0uNY(K`+W!h0ploQF(b(eA?dXs?!O)dI%nOz@uD@lkm`p33T95XOwMK|C53R zf74BWy6BejnT$tp>-fP($Tspx^W6IAqmPX2e`mvA$Ye74k{|M%3T}xLbwn6>kq-S3 zwle(Ld!_QmyGlBB9P;9>=S?LYZ4MqO6ZO^Ob$TUUJ#QwYX;bhRG6Gf_{#a7VDa(AX z;GMzuNUOb>CX>ZXX>Z9#v^{hj=@O@GSKy78Ux!au8osDI>JP(Tc#xORufQQ3uRX!n zc=o!k{Ou^jvXE_;49Nf5^kVAnr zb4bDQs|3h z+XchOW|v^YS^;(MUVplF{YJWT=U#d+IFyElnLBA-tvPv@=7n>6du<%fp3|f8swoHr z=qCzn?yVS_a&6%mr}|aTz~ErId$&K`zH?WHF5FHWhT+XoNzFry_PqJ2cW!U$?VYRn zZ->^MVfb?=iU$w0{ng#O>GthAqH)I#n_*sOhZt%u)H8c-nm2#3_?xG9&)KP~14k6i zz0|Hzt(>IIBBs8hG76E!$k345dpBLbb}jX*-O#gE$f>AjjvQ_lE=jW$+H(n0f$_tf z&S{vDk@>HSz~GA7c)56qtqS&QPt5z8o2)gxEMB}whp_Zm-KGnxj}l(SW6oO%L*M1t zu)Yw;&tX`$rDVU}u6nv&u9RUb+!8;wSmFDGxnlW!LRoOj8@_^Oge9+4ycpu<$3r># zye^w}Tkinq3&KUN-|^rQ}CaNpP zEhym7h$l4!O*)yd1^Q4sIK*I3h77#T2D)^t0!tgUr{9P?{Sr$YWq`scHKYg7knnkQ z@zgyfQq2KRPt18v`H@UvGy!sCZJ#xXLo=B!izBno47n9!yE{Pcl3u zJ?K-H9#j~ckh`7U%j1}*AhOq;bzmV6!7<)tstWa*%!!A5U8;OV_`io0qZaXUCZgQW zTtCWe)$b?+a$Jg|C3KZ-tDYTj$sEr<^Y9~XW6JTXUx0*r$5hDKaWOWLP~7IQS`wnJ&;rtGp7g%s2hz@e~FljI*WTk6&=Y@E3Ix zg2x37uAoc!-}#!X{UNWAQQ+6%ktVYIK`KTwts4vow8;(c+ap^sca;036L&zfHgn>gyAFltx z4~*y5haY}u<;#il(`ZA~F;nCpG7P>Z3Lll{iD;L)qE2XI`1|vp|7?2s!yo>T8hVBS zk9s4Vh{wo-{zUZ$-eh4}f8b7qZs63zXhVcSGs3`+bRDmrA9&-1;76HOZHaQ=L|qZa z4@npRj~_p7KP0g?)2dagtQdGfKk5j25eBVDKX2i9?Rwhn2sy$JtiBs(s(GO}~pp(XGky<5?T$CBRkWkAy@@iNq1&=0OB^@D47cXxV4Ke(<~xkBGT z&QCZsI0t;X;jhCCe`IWZP>UeZEUPhOBT&fowHcQrunPrU%hrc9X)n39X);`9Xobh z2Qgg}STj+5r*?F8r==@arA=FRrFD%>diPwF=FjU@`Rw&4JhP$X2{%$1*8F%tbGNf+ zPN)6<_%@w8cPUi) zetcgm_HJm)F8?9?q@G{hY1b~_i#*1|*l{qnUpQg^1V6?UkSJf`JWuiQ_I9d|=y(LMJpMlY zv}yRuliM%~LCFfpSYR-9emDI21Aq#!*8{`5h~=J~M%u3Z-#XaePX@nEE&avwZ`Pgb z@=nrG05bluY>~alVox|@&A5jmL~}?yGfuSSWvB(dF%4z`vzFS2z&Qj(wB7S8ALJpU zpPf#Mryolj<>5EjyVREYj>^+-6b~pFpEzwc4?pM66oI0{$d^MYr}AjBc0^~OZdaUh z=?_O|$)sV*$t+qNwR#RvZ(Y5tK}{FRF(Z-%l_W6g@+T9MvZJ)90$2L<>C@@UFTOAX z)Ng+Cn}qR?4n`js!GnzDyzJE|{h?>P%Gw4M$`II=jZYZg8Bn|`SRtayRzP>FT$W1VbuBGEu5_VAur_8N}j;MDe>^~!xI4f(v=?E z`W5vDjR?Vu`U0n3_F1N%Hc$2XN_n@E1NoGxzBlwv!9;B$!yk0&_0-c**JSkv-elo; z^d~F#Ec4+x_%8cv8Hc~XLkAstwv*5Eix5K~`goRxzi2~*b(zBFqg>Wjyl73+r@ByfW`mXx4G-Y3e9xlYU$r%8qwI zv!qL%WxWv(oCr%i^n!;hd3*QnO^rrlOm)EHE;C9RCH#4chdgEy&lqC&>#!)^!%9y~ zPQfnq*^2kjQ{)A{x`kbl9^2k{2d#(secF)o`)V#Y_U&{mHBW)hoX*3*P*1X`?{9~B zOlBU z;nHPa5vCT(5m0q#o<7npqgr3u^XjW<(@Qe2ty-3Pb({JEy*={U z6OH@#?xj;_&ZTemA4peaFtUO50@3 z?rxXyk4Bp&g(*S8tHS$oGs#oi3}rvvIf(=l%Bw)568e)3#l&ru7?N zk`Z;4JPNyXV(*;%9cjL{!otvsU8B@!EQMyaf9e!l-|Vwz)I0CIt1+`K zzn@79*)hTURFguhaS&sN*0jn8{=8h{@gL8HM{P&FT+ojYIfFwQ2P+PR^l`!-jCjbp z9{HXxuP7JvDbHqqlSJ3Y=$l)LFli^QptyWMu;qgat5YTRBxJiJ0Ng1e}#&O2P1y)0H<9DiF+XSa1b9=OzT_ zOP^eZS2Y@lFe}X&1|MEO4A_-%GOii-GKhN6F@Aph`r`WZdK`T;ojG+neetCXf6~Qo zfBU8ke``Q+{WEdUuNJr(W8`&%o(xa?;vpmMES>U;0jfhGCj#3(a~OA34&Cyg6EUNQ z(a83Z!p?QHyc}97^i#n{(`7BW zK6K~@b17f5x-TtRf*bi9^T4#;hcQa7;uz79H-~`uUW*Db&SGFUqo48_yW+|1nrMUm zue;sH05UfnU|dBn+53;Z{?Ns!bmoTbyoZI!M>10AdQhK7=6W7DET_Q(hX~HzJ=FD7rk$^f;21I`-k6MW5}`-R)ji92aI<-?eF5k4^#}Mk zWdGZOCzC(&=8AAUT}D13o=kNEQ(eG;KN);7{_5qQRQhrG7_Z!T?H`Z-I-MwA!UIMa z@Cbp0UZ|sPkPW=?>aWA2t~z|W(~rv6bk{!~z2K`ZhcX>Fgb}yzdlBWi6dr%n@hm+4 zf~N?}wwCP(_(ZU1W6+9_vXqNEXw}1@U6!lk{E~FgpNK}_U|@>97cu-{)Cj%B64byA zdcimFxFe4+@=I75pD4e~tJho7sK-m(k_LFKc&wK%)2+&v`BRCv;wR`v7<>h8z@g80 z!SDxc?_S?iF7U}O<7K%r4&F?-f~RO_gaNPfSkI4i9q(zTnJ{B`i634u_~ALj(z$r= zD*0>`4_LF^{=U(=9lS&4cVy6|+EsZF z&e4+Fm$q$9ixw}j_FukqE&cezPcqUyNK2QmNSiiqOuJv(E#uz`wTbzS=&8|~J?h2- zP;;Xsqn`|H*KXWQhkrVjKK}eGEhE02R`#t)ee&F0)2Fg(3Yx-8&>Z?Jmt~#Z;^BEZv&tJKd z7A;$u-hSu3^pXsdi{{Od@lW$uJpZybOe>m0-@I`xojh?YojrXrotL*?S7&E>Y4c0^ zajr|AljqVM)zd8-#EQPPY3ugwsYeFB3l~nOtCugz!}5BXC;4pKwk<7Rx=d}*916{- zE$GJjxAhIJOp@Vm->3Tk+Md_VLnSc$HFew^3+Sl%?qFnxzGuW3)cesY<|!eT3y=X z&kcVRtSSLB2-OUKW^kx*g_cphEXE8CI2ju{M+e;ar=`Cg+UGCbxt4~mUrrCMUeL1N zJE>Rhx!o*P6fVXi4lux_w(?AZvT+@(M+c2G6&s_?kfdb?E&wh85t0p!{K%0ZV?@7x zW7rsyN7DltJ2)+NM9X_w*4s9JNg7uCfew=xWSOaO@Hq1a9kg=WjlAf~=wXHoGd`gl zH)bei@K9KU@B?4Qsl{Q@n1`Y_BZuD1sL`^mJyza|l;tuW`s07htp_ZB0@{ElQ#En= z&n-O|*$fn~zpk#Xv|SIHrOTEY4adi0fCsn!^pGBru?bH;9=7O>hd17U?fP}3U1{!F z!sAA#(Vv`WH#T8V!q{XUlxBEhxi$KcTokHz>z{oRWNcDsUS{Z!Jju#sNt8Gt#wH9? zN~^5F#BY453d8fj;|@7jGL$^BC`(;riBBysft%RWWX2R@!iy5b7&Grn^6bIOm$%w1 zL|gW2G-QaCTl$xO{i_jsQ(r`VGX9y%Jn~1T`m#kAW?VIyqXTrojj<2?cp5$NZsE<- zr~cjBRS$m&YDDs|ldKsRlHsTsV6zccdB_}zSsynlE^`REya}^hk-xOCvByjpGD5FGC+Z%rzMvQQ z|J}mzh+c7 z>v_*AUGfxsM_A^S{MGX#UE(~Ac+?wwB7eT`;}EZS53>oe7z+I0Ez%JNycx#ZW`vQ$ z`y=x-e~i280Fr24=z{lm zF83%`zP{J_zUMuR>%I5iO>5V$^?3_pOXx_GSsunY41YM33~4XFqw>W2^GBbh)8{V8 z=r>4;zrNMlC++<|{5~}{ZqW15J^k8MM+diz zei;6=TfaOBZ;Iymbl}iW>Ekc|k%mS))0@A0EA806Ev;Xz121HUxFDnBp&t&XPe1=# z8r1ewuf4h_y}W&M+Okp0`sK)S>p(E+9-yBM_WJh@S{ofn?Rm&HrdGbi?P#uVhwp(A(yzI)Ai|OzW-=_=b&ZK_r z9k_JK64m>vy!5-%4~KtF=Pq1LcLqk&!lf(IE4yDcZ~enR9+GF^McW&2ndaxO?An!9 z$OvlFEK$ztP!(uib*X<`yy$!Vu_Sx_I`&{(ZhJ7Y*I!%`S#_b;xC0pD?xB7W2(@sk zc(r0rJsItqYQ<%{h;xUmN?NV(s3X3|iPs%S_~D|yH4)FbsE0CKR-eWhm#M8(oo#s5AGG_Rjmp%UK6+ks$&Hx4+4O9x|%IIH2!;oPH35*RI%y@rw;Q^+lzbx~; zcj;WZaP)^X>)!3uw{TwS?G!6ohu*Gbidsx)`~P*Ap#q}0G~)cLWxDbl!@G>rV~4ee+;ETfG2@g{4d_uV@x}Nz%3%`h^QS%KhS^t61}cn7 z=E0YTFVsh(E{!}hiYWAsK+XA2^@pLuI!7K@&Rdg5*t9E}qXZyJn!L*la`YIf3Q;oh z(GO`|deRbgJ-WfjbtNeOx-VCI``u5g`}%xuKY1{9b<5b9J0ALva%T9GexYduM97zI zW4zTZU6OV$GwBiImho>@iW_xWIxYq#h35UIcF-1#ex@&BVLbAspcsbS)6A9$S2!VS zl`*;dWYUaIB5xAPf^abfe#R4q>qC`QvLjC2InR^c)(p>}F@ebOxdL zI40GM8*NjK$ecfuyRu13=6F|{p;d-)JpH1NNg`A)?YV3$ZQnSa;~tmjN*H+@z+JP? zN8P!6mT_eyG(nJOth!7l`83)EPMNOj5VU}WjEkaUqLEJ+HwZkq$Gq5NLq-%vH(XIq zz+Z%8B~a>VY>uZ&`2(2@ADq%4yLa#2)MzxSu@v;ca*qlNz8jIffFZh|eQmr=dL>J8gc z9(ufq+bk0~5jJsZWbM7(VPfBE&`Z49!aQqO@Ao6=;^nL9#~+WT6DQB6i-Y_6CEI-`I*mZc_+`Dg@H~);c7(lALEYapwdmga@`(0^y%^_z(KbFA@|Dg zCw(Ae-sS!M_*2z4s_*-E(pnuXLEQdwTix*I4k9C(|Kr8?!{KA;|NPg->DtYE^7PxD zwrt&!wrts$mT0-~sOB@*v=sJ;jB`K#^m96%=0E?%lneemZhA z{pI7&$XWc`I>WJxyS73X)tPiw3x1Ym4F6;1(AHM%i%Z|@! z7p(!!yO*ThFTWzgU#EE|o;iOxUB5GsdKWHBJ6_(SJrIY|SAYFVhk)Emn>TGt4K3Ma zCD?qk-!R8(_EPJ2k_CnU4(+@l{x0I!qcPJh53`qdX%9xNREqBvbcfDeht2Ps7;lBz zrxcxdyiJM3Q$eb?ubwWMa2eTXGH{uW_u0UY_6H6jw8L{BJUo|8FSWx6LobwxEn0#u zG=fJsVN7ueYMo1;c9r#8pJPr=M3?dM$tUvoo99b?0Ym{u;U(S?@kDa(B{w8E1*2ki z2FhXN&|}N+0OI+F<$bvSPU^pYCG}sul=`onPqSq~U$syt=V&mD$Oy>c1l{r!>(T&g zSDtwRVz8i5bY9W*hS9(bj!tgvjt;N9-0~2I88dh+%E)BP8QbL9rzN{X+Pe(H-Vmpj z>cmnr`swfv_VOFClS_Mqr)8)-Mr0_&;KW1CjC&?PRisd@^*R-|fvpcS@);{xik64M zvhV>L4FXGe=;+GS0X81dE z`iy(}$#s}RJ*=|8mEkV*YoVp3X+p2q@hv5Y=_~6k>n{-DgSPw9PmD~uX^Z~7EkV)c zh&#LO<7cu%et7=TCdy=)y5N;0?Rf;|=||{Q<~-Ly;5xn#f7y^#)Z)jXfv$x z3w&U9S1^w_Tsp{d%}|%IzCh6nr%tid_q1Hd@xa`+eTREss(uWwLuUBnMS<2Ka{@vi ze>Pt2%h>hcb+{~CbZVoOR2d?1A!q5tJSR;zSwE_P67;K(o%M5*z2#&$WnFgySQ!sh z0cpFX_8fOu=p^GPpgH4RO`SQ$MCn#}z(QZ+)e-rwD>u~Q8GBos4YNlBljokAi#E8W z;cqg7p;(+aP@KfiFY>31G4p_h13igM7Y({9DvRB&3AdsJBP^{C}$Dt^d~cFh#S z-*m`oGCf7RC#oxGOa*r$I#bP~zNj<4FBlIj{rTpbZ!`(+PmM;y4w2v#*;ad(1+PIX z=#@MKP6?Z8{FjuSY8|cc>h;#!RnKolW2&&pXh&W3J>{5~m8bjG>6G=WPO*pC+O=yEOMMqC)K)mNbugf?;jA+JY0f`n?d_LG-p}cO|G!Vtod+ZG z$a_2O*ttEeTdR|_( z!=G?FWKY28*O?xe$J@6D4yEsZKAV2Na3?KTzBYaE&;OdXZr+gQc4DI#lx=Sy9XobB z{pG_?b;!mA8Pn#ZO&eCHx8B%ghQH6X^6Kd6OX<$Y+_Y-#X6fPmv|)W;>P~mH;_ANI za6cVBd^G)^|M*19l<#O6GDgeIT8g_lEnluZ*`;5mQz0)5e^=%4_me#M&YwG-Zr{3* z7Rs>u^3EMH4t1s@KOapOuiQ-cM>^7+d5crunho0bZyfe*p3@J7Hs|ByDKoXX;jdQ-?;IsVK19j#2`!x!g907NI)ex(YLyU$ z2_==rC={MXBk8&<+dmyTklN%D`;uI1S1y>F=F0W8L;C24?&jy+P-qua19!mwwkGzM)3e~h}!KJp%RD#F16UvPV2QLrCK{bqEmTCWbhl2 z!EcyDJmlFojPXzL5uIQ z-uMIN1`$&ZhzN|(@)RoWmhP41*l9bE$!hKFa=V_)y3)Ce2v!v}I)a8OH)>#2xi`KFH*a zca?c%Jn&n=rjiFv=rQmE2E2UHj0ZF?noP{RUokGE!=|E3GB4tV1SZl^$h<(eX!P%T zK6+uZTnvDXMx&YlV3_5atS&>Ep&!qh_j>)&w?h|%^!<3DL5#o{2TYjbg{GXCg&`wo z69(P!)G%Itz=PI!0hOp6c)?k$#$WO~!xl60#0_|AE~1 zWa5V<_VSG%FaoDuCgAlj>Zrq?b$T+s>g}5hf4bY#sy^GINGG-O{U77yWt}EF(IIQW z*TeLx7vw-GLZ44MfcH|;ae2(&R-4e~+iMfnEH9Y;gA&v*4B2E_jxslIX=$pKwI0;c z)Gz+JUun$)WT@FH&$d@zeuQKc-2NN5&kFh*qhV- zz_umhpvsdnDt_|mU$x!U8Ix^e?TYm7Z+B~+HkkH({zW==_G%jJT9W!2Thm+b=#UH@ z{?V20$XQ8;Dysa?KOay3@t>c_@OdMx(*F3HH|vm)Jv-9M6>_98qb_=8{>dC+SlesK zka_wdW4kj2GsVcJW;jdR3UU zZ~e*XH2YWmncxKcv)O-2=*)}P+fYx}+fk-VdBpc_y@e$Xc_n?~l;b%To`3NJInOZ+ zfKgwR3wjZnf}n$aNugb)@1~xVF;2 z83L8psg8`tAOniM5 zB?zWgR2K?!rBPz+^$;Wjn&lnPOcQH9;1L%ba9NII*Du%K>)JdO0~4pk_UHkybH|Rf zY}qo2)(sa`D17e&gisMJh1MS|o#`qE{k!hzO}e}Q5tjil%JUy>hBXJ}T<0BKBPTrm z2o2v5d2kv)F!UkAU)BY9mS>bGQ{D`+QqGElZAiI55x71Iz$8&*#0AZ=?O8-7Lqi}R zT;1e_oWrsY&S~l73!SbE+V6g+CBFI+u_7vA##SrNhY|CTXwG*Wr7{XMO@~CRkO3_2 zGJp^d50{6_x`<0g1|tO1(mobUP8n{Q`T#b@qfce3Jc~OWAy#zlm$0066l!|-vib_J z^U@l(K&ztl@{tkxi*!9CpNDenDZ`RQjDJyo&^0+D_!rlN5(s&Xhtx_RA=@&Kcr5wh zOO!p!&`a}s%=_4Q^~`kmWO91a{MYLb*_XNihtp#NmptUpB)Qt_r?w;>+_8AI%d_0MAzc$0)FOgAQ&(WWL3C+hXOWoX|A9&llcW-Jm8WqXlw|rk9 z6FASm$PZdo!5JEPR`Q;x-jE?-;1NeJALY}1A9ruepf}UhF&SSWli+(Y{J@*8uvLBV z6nZI_V)OkU_%S9(2MnIdxbs-Pv&H*lz&sr@ll(FZ6)#$SdOAu!oNqH&!)ES^ONqOu z$VEl-tP#B5h90EzGW;Jn_(MAI!%^)kcQUni^`_U~cr)$VwL`|F_1X(=f!?oiYk`Je z(6ct_dzUL@V~!zWDB9cPz{}NJ;Ls+1)z%ht1?BjhOi{xl}|M%}{ zuRrwSRs!?*GXtHUn0xiwEw%Sp`oAA)kG;{Z^xobN(oPxvRxV$V=FjPn6Oi!k+)URm zvpn`-`pZY3*cM#x{mcKCw(i=U7A{(n=ISsJ&EC!1uYLGIW%xU%J@mf#>L2OHlb6$_ z`(0`2n$79m-+z!cHrAv$ZT)8WV^4HeSAC{E{!X1dt)1iD8mot zT%^N+fghT}v841Y2Pbf2ej|me?r@yRZOJ@=i@wV%+Sc|dhQE39ERW6sK{dr10+71g zjW-N`K5#9AOe)bI|9Bd?w~<$M`LaBhemG>7<~6HVrRCbZa8CGA z41O4YyE-KY<>QHlLg{F3M9Q#C%hfJe)<5*ga-*Ne4OJi3H$c!8UkKG$6Wi7i1@IO` zOFRV6jdkFeM5_>iT8BsP5%+4mCZp~2q2oA|aZUo&>W@Sb*5UPZpvGWqna=G8XAB;4 z)5Rx-Ka*Q_>4iZKSo!Sp&#lZ`Z@s0x{bcyV!_P|aNLNV>!%F@}&g%%HU(hGy$|zpe zQx(ueA{>`dgviQs433;D9M1!84;I6-8mOw!a}$rk6}_x&gMqE`mY2h*$B2#d5wxs6 ztKShz_&7xk9C)FZ2%}6qFiSWu{_%qO?z{TMPhXnQ30hJ1MfhYSfG$EG$UM@#V1D-5 zXVw?PARAwd=rM4g3|CK<>a*@!_4-5pw7QIg7dLqrCd%=`M49mtWlCJ|qn^kI_AIa9 z=UMXbB3r&CS!dY`v`GM+4GNBw!m_e@;mbJPB~ zBX9hWH&CwTJFTaA_l`V=G(Q~|jOG<_FOz3AmW{y=;}-@ema*dC@<8+5yLa!TpN}3( zpM3VW^wWv+TK3vu#-DfP0k=(i(k)#yM+Pn#!n7pV=f3`49`iOrJpW9;YPTW5va<6OUo|>yWXN zgDoy!xgo>f@$~;b`8o}?^`!Ur{*xR2bgJ$=GyDz6M@WXhOXsyp?O^)zhaaUOt;&1% zkN-1mk>PK#_WPTwl{aDd>j=Z2minGMtNGMlzfM1%x}2^I%udVJyp-PE`-ik~{hBm8 zx#5qq1=#NDi!Z-Ye>y4CLw{N;!{6`UeogN(13Gl%lXU9R&D6bkeOmX@&h+|k-n9I# zQLR=Sk)2{_FdaR5BK=8*zjNoW*h$2jHf>CAyzy%4)5*cM*E(&Nh^!Y$Nh8wvucMw-U0CV$Fm&Izj8hUJ=c%)EPYWn z>PAl`Pxbjvh4pcOQWB>_eL>hh2gJ59)F6PA&@-005K5CU}%R-VC+M1q9;izrVHBQ+5{*e z`ymquIt)>P229m^5sRBbRN6`9(C7tSuP4`}y7;eBPPqQ5>^zinP7~ksrcBqLMWjRO zq8W~d;g1bIKbPw=*Sqh$W4|EKk*qUe^h2loW!;)F$sQ<1%4lM+;sNd#xD-?W5y0X( zBp(*IOdhn~SaHT&Mr0a_2YQg@q!}#Z;iE)uhoo$Dgk>RmL2_QINz?1{dcA(HCD-MQ zlpu?PU%y(xz@g3M)hZowtngGON<|(MW#8M+U9mA{bai*@%WtRc?N_;C2azmfGtwHp ztgmde%|Z@r3%v+6=h`jm@n~NutALq|;{l`6j)QDi$`)#*e!=tO-l!s(Gf z`2~p1NSB5`Hu+w=Rxg->haRap^gKOWJUuF9e|mbgHfyTaUzcM&9lv1mJUdZ%{IxRt zQA^N|uuiYZ$)%;?tnks#`^nXepk+jJ~J5)hupFFUd&8A76pUSZusMH3+B87n$ixWTQ_f{ zvuDqy?++c8q3WA->BfV!XyvA~dHe44=5OE9o^tX~(_s?b?HJBk&)VLf-!`=`e}!4(zuTW*qRbY{jyC zYH62@leAs?>tXoQeukH?Tu}8 z((<)i$JQbJ{BY_nri zhZ$`pJ9PM<|DFtSSJSmCS9H?v74?OYG=G5(G|}#ZH*fW)E7xwO^A|6txpK~VWsml* zUZr`5o=3cE;jDvwrCW!aw2P?C%T0P<{1a3df?%QXu_uhXmH5v`0 z3&3mvDj#$2W=TVz^uz0&6m7;J#Pi@$`F>P<8XRRJEQJ6c;rWLlkRLJd$c(*9`5xkm zc~H#1frXBs8?*yI($Kg2A;X`HIe`=e2;J+C#{)Oas}tM9M3rcg3fxMNLELp0(E z9RrBEbNw{gx;A_ANiZD7VSDvy;Sw%9H$EYYz-5s5uP|_w%jeLP0xb$~S==fagX@{&f5wBliBVC^AXmCRO*~Pr zF)4YWOD4*nfBu>9+tNF4zikuc@H`_lvF7s9tn`~{DkEyM2aF-23sm9tAwRo;RUCPQ z)+4L9Jnk@)X_Y}lrIC^FEl+x_M@20CDGDDo@P$a>3?wWqS~-thFuEkgFiXoL=b2lmQ+! z*#{B3gz30SS&p&5M=2}fx+!5qa#|g`gj>FJQaxC}uQbk!a>j?2(NhWjGfl9)4#L3k ze8&M}{Hqm?)noL>FBdsczSK|Xg*I`61FYQK8>12rVm4pp7nza{xRIuwG9LBT!>QoZ z%lw+t6Uig=L;C|SJj=r4uhmlD=UHCS&Y9eXQZHfn1I9!-JY>W07ww3#Li@@#0stRD z;J%*;SIN^%;Ac8{C_T#1OQX@4PVz5kJ%$8gJn+54xWVuTEDV3dV{8O&Sxw{x?0MF>d1d75EVb|Dgv$^6L44R}Z6H9bQjQm0rDEJw07?>U5t* zy1qviKg{mhwab2(E#Kop{)C~ohxxO&(gHm8`=~hs3cNC(T+$^BJfLOB5?wdmVbBW0 z-&r}yeErqm(}C}QOoxx1N$s;2r(JLCP1|06U57<%)gJ5%Q}- z(*YIVnaAIt=I|K)w(Q((OKb7?>yWJgns%@Ud;F#QX87ADPrk$Q_`5zlH!WMcCB6Ip zSi>K@oYlUHU&=G^q`cq;bRNN48UEhK@F%0*pXBj(`r?f=dub!B+bqN1Z+;_>zvVjI zIl&gAU=?ZH7OySs;H2NRI-)tyeJj8`M7g_jNz8 z5W^p<7cXAAswKHU$oO|x9)!!%q9u#dLfx}E+RZbxU8nypm2G9=!bLjlrPqvq*i_K7 zJ5c234b`enQ;j|dNuNCF?`L!!R?4hzG<1fk<~_;}+;|QFE3an%D4{RnQ;|R`*_E*H z{9{Qrwi@P{vFBgVH^ZNl7=~F_uxZV{V=BWSiq=)>G15)LADu+DIP>E2I0Z29Ve|{b zpO^CvWz4FO;|$wCzjNn~pGKAuqfSK#vdMe?Cm$AFKU+j4r>6J5fB)L!5nI2 znP(r*Gaiz$6gJDn3Elg=>WRl2~d;L=O3Ei~t}O2eNZM#e&? zM>SlOHu@G6^#Y&ZYNa3JnTn=xfon1pZapL~UKr66FZ}FP2HrdGyi@J%7dRo;dbO>1 zd>ov5nO}2yBAJzP1`h){;|7B{%i}pTg3XHg#sAlGO(c(*)W&$8m4-k2MfsCYj7=uW zu{1vPNZaC$wvaayuIEMWk0UD#OL+Xz#utXa$C2Rlm!aRI557~-Pb?`7!yn@-#zuY2 zz)j>u_`LMr;CK2Z`pYSnydh7%XYedz1pv=7JpLCiUR*7?1HWD-^gvk8pNPXKHxUkb zWqp(3)@hby%lKq;W@0{Vi|-rS5?iq_p14B(F^)nO5jNXYe}5eNeU#svo9Gq`9CDj+ zM}i*E2s1zOFl(3bu06To509}^GQ@nYEla-B{(eVKT}ZPRtW2-J`)_H-D{rRt8?>jJ z_QvmOyDvYm2Qr+=IYu<}4J!J1uBECg?u`wlBp16Z9o%OgWrQM@Q;wHEoBbimSCq%% z6<~{+fshz==}+?j41eG5|5k@p+_!!HR<2x@7B85W=636V5-rKSpO^aXm*MX}KK#3u z@Xk&j{PABkH{GFCg7eZmTiWb~zpIzz5h;(qzvzb%mioT^M|u3o@VAJizCCXE!;7$! z6MZYgpZ4aKC*Khn{;tX655wO(@9#Aa%JBFz!=F6zTQ@?`(u(2oZ?9Od@yJL&id8G^swFS!k-hV(yAC%iwq`fYO|hlPqF$h%2Rg#etBeSufO%$f05_eqWnA? zqh!HI@aJ=yRV_t(J5Qf0GN_=2JC*H>cuY3*yYm=vh z4)>U6eZvd6#}^&b`iwr}VM)GU&ZMOUv(BU}+tcrm_Vkk>qmR=_wWnXNJpDL!+bPL!ym&c!?OV| zHa#^8DrOHULN(lkS;e!F&qk^Nm7k4)Rv%S{!H*X=FE31|V-;k&IUa%6nd<|e46Da6 zkOnY9K0UO=gdZkFSDwV>rEm$QBON&4$40MTCl}IX%hi$QX;aVciq|mk8V%JLMknhV z@L=Thf!_0-flZz~yP39zHIu}m!&=+{*48FmL|h<-TN(ZUqNAdWr?VW<1@yBXKr62% z{SrEsA9Ct=^>maD`Hq(c-U`RYl;jEBi!#K1r&CFJpRFkH#lkW42<9{n5$=(J5%|t^Hm>5cNOCnjxtVfdRa2~Qs#^n+&^`e|kOf-9-^Af-VfcgpvhC<8zN_H3%ya&my7F{>?^YteH9NTa z1R6LVcM1U`#mv@bB{>9wGYf`4U+T-ru@`mv>~}K6>_6~*+JEqf3|n*4);;g0?K1rB ze0fh=wQ_0dnx)ffWh|UUIhyV3UI@|+~zkmPpU$um{ z$2|UaV)$D!KlQT5U*++4HXS;2Fn##R$7xtwb-nk`+T%}#KMwbpBZEkX^oz5Q8~!*X z^j8DYwx^kY3cG636H?342JIxR!w=`$D8pms)Ex?+`WNp?x6z7MI)0vQ2^ zp`&JZ|l zpMCn-Xs_Hvy@Sv#qHAdIX69Jx83v$czT;WN6xMZy(@4M6X{5q`^UXKS_-BNb2V!wp%23IKd!l+`6^ z=?{^5XtEY04A_P1VvN4guJi&dO5}11G8bbrfEUPR zJP=#KBCiYsFZ2{)9Uf)Kk3Hmog~wmyQ!dH|>_zza5|~Vu=p%H-i$0#1l)-?(NmwlX zk_B&7Z5G^4+vr@G+}@3PPzc;(${yaeu}bMf>`wBrBibMbJEp^wN3J_#}U zg<b{h32rI?06+jqL_t(TSCKC10ISy%c+(x$`G7vW1V7`|H(CC8 z<(>t+H2lROU%?0S8`@Gg&^|1e+DoawHRn&LHS_H~+9143`};JZ&t<{o0^jGKya~Gj z5C|*S@*aOO0BWtMj4)TzsT0Sw$KMa>%fIhWS8ok!kH44FrfqxD8`|Tq(O9cJ{*vwS z*Cs<4<(;zX%+>q*v+B%CbJf9≫BtI3gZs9?J!d*XBo4@6p~I26}*11kgkE2dThQ zctY<3AF%>JClc>{|DCjP-70zfX^E@$xVv%Vj-BfJzyIqCd9`)esk=L5_*=PrQJObb zhAg$W|IUqc`NC;4{O$Yf)0Db;(%yg7slGd3(W$hH((LYTZ3(8G@oc3a9)I_>2VZ}> zaPD;a>YHzMs_(^g{&rhh+_zDOhkTGWN}gRD?tvjy&P5z_@$tSd&ESUTTtoc5^V?T! zDefnqevwYrnPJeE`rg+Wr1#U2pN^;h{PSn&k`5~A>szZ+eK(}t zySB+-yF@kt>02_em4XUOeP9yqXqTSk%{QR44KAE#IrBm7dw5mzFgZ=JJ(*T2_74oD z>)H>oQ=W~h*RD$g1B2=C;lrZamUivfo;Gi6Xy3tAX@TrHz!1H};d)luE(-vLO=UD) zlHo5r%NmXKS~0WI_hOVhL)}GTkG}Z)MG`>&%`ujxi_Y>Ld4$YA`9Xtt{GbtryugD( ze3t+#Z}I}4I9Hnpj`nKPNG{=zxky(8FvR6<5PitYfW-f(8UDWf^2;wJ#y9nXGoQKvInR$rzHvsSx8;?!rM)3+=LWx@ESrh*!i&L?roaGBvG*X@6l;zCcE zL*;Q<8){4kZ-xL)v@rur7Qr_##XVVuq6|FeTVSZ*7!;7j$IvVC$cLA}j}UlVtzhJh z2aj^~HU>PxkfDW=TU_)!4qN$DhClLt_tx)he?QfzIs?o37J>s5pa;?wUFiY+gpTUv zDd@$mFe&?|T~t%HkGPK$XCU$%4}+icW?r)pR)*nZS`HwCSd&&oM|fi{%0om~EoTg0 zmTz^}v8?EnK7t42R$e7M@G0q%0~Hsy$Byq0u#wG^Z{k?!hk_K41e)! ze*KFMoagbHNFL9!J;7ImrEY?+Qa@q%3;j?o%0?LFWupOTAlrhLLCf5B&j&TV`mAJ55jjJD?n#8S25 z&V%DwmgrCvIiJux=VLoeVkG_kJsnoEuFpL4hSl!dI=S}14@c9#|G&?4lJRJI z#F+sdI^d&A%YD1s`qSl$=d{%LKst2vOgef|`{k`zpZ@7z{w=+-)6FpAI3_ z9)E*c<@lpc-u=J-wNHm}+)f)ey_B|Y*_3u}+oS_Z7P_8H4$PnOa~#0;G~9V6?^`<^OLJxl^kvkFO4_k-{(!}Cw43$v8eJpW_>^nRcc zrcCfD_2QZi3B)r9TEvlU++|*A_zTCAx*noj(26kVl=tNh!=I@= zbZ`Aur_yLmI;UP23kGC88o=4IN#{FfBWpu7Tq9v^%tW!~ zu6nu1BaCt-Y$ABzL3gstWSaZGDzYWwQ41l+)C=GSDAQOmYhhQHiTgIXAf;h)P|t+@3caEm@noW5>#c!swph$(EM z=dwnyiBR%X(rIEmS}f>=z9Jn|0!|pN*5xLvY#JSV$dzTwc+h$gKDq=ZlB4%`?;sfV z!hk_77%=dR36H-QhQCLb{iBo!Jw;fK8|aWOCt?#BW`o9~)c>S$XChD2(dN+03&Y=Z zNOO8<(ARigaq)g!8vepCTlU8oYtvKvv!(Jpv;`hZJ~8~o_zA;ong47h`gpZJ@BA}9 z*!qJ#%fi9I_AJYXu!RmMZ>PW4Hl^5nA@x|9&z#c@DE=l)yov8L!1voRBki~xSm}H9 zDZ~IJBh&fw=hHvFJ!l?qKOQ}wI(inSSKoM3bAz2SD6P|8fAjRd?M6QgVtA`juTdW5 zIYJDM1of!qZw|2xeKh&3^XnKUFN3SLc`j#(AOBc@3^5wR4?_R$d&hVJKdgET&_|n$&(v~f0>sA>%mn;&sk#zOy<#go8 z;dJEikHS5i7A#tr{`jx|nzn4)E@Rbf;b_Oi`vWq>aq_X8^V)~goQ}bCLPVwurSIIiZQgz-Paanr4{Ixdp7hplf2;3?j`a0E zzD?I<99^_xP3l|MNE>w63x>aMzWIkv0={g^d;3%P7y#pH*6J~IgH$Rb61oCnaB`ILf5WrPAVz5TlpyZG zWS_yW=|RZ#Fv_=rm#~O~AMpr-MuY*6FyIl62ao*m!jMzFeDwJ$6oDAfwt1&qtl8VI zcW$pvzwWHad+(r+3smVKXCv!;S4-$4D=3%_S|~!GrtX{aq8Pl#9b^o*=&O;2GI95m zRm^ZK_aPlb8PCm>gJx7zfyZDOw9Zql$dr5;%>GDSCm!;cv;0Sm)Y82-Qsyy@ZW*-)9OZ5WTQcpi}-6J#V8`iZd>->X3=IGHilv8*VDS^uO;Xq`WyW}41dH!Kjn-4Oc^87A?cakmf$Z!+8jSP zp)>Yiv zzV&8WyKZ&rkp0M(k7_SE-!CvIyGNm?RD-JXRa@{<^5tCBVPJ8YyetO4Tw_CbXo)sE zMoB%etz=I0$I*1?@XzTV2ajs0?L2w>y_dGj19RoF1*-49JmpTO zgFpO~KL6@KYHOdZQ*z%=yS8t&eGKQ@Qsr#;%cAtYC@o27#A)A!yyTX%5<2ul&?=pN z{L0R4X;6oG{Pk~NrAyiev3Jq(v|`PMw0Y}})c;^G{q65xr>j@A&!3j}uIXEucF35y zeCZ)N9yuc<e5Yp}$hWc#*|sw{a*z`GQgrD=Kl_WX+(HxItDt zE@I?mHUq5YW}GH!GcT97me&ea@-jsr&#?%Ru7?n}vXkIfOyo!_Iwelzm$0eCOZk`h zl^nAS5Kp-9g7>bLCal%wtc)wCAq@SOQZTs6m!bt0Mn5tl&%=ys35Nu|vHjUOE!!Lq z9?!}71oYP&I#Bgo;%aq6Z}O; z%VPYXv%2B0)Z^5p@Z>Q|{>$2CD!(OB`j`X||kHw#v(K zG4=#C$d)chE0)Z$ zgF&ueyQ;in>C-P{D7$_;E!Q&EJ}r%1r=`U0vZ7wnAsMI6UeNODb7{`p`RT3S{Z>Y_ zM(SHSH?_;~clpxAboj_o8DjU#qi-NJHg1yPu}{l*7s=K!m`HtV ztFmOfMH`DZo!=?AfCL~(V{;h>1(#ON>5jT9Zc{r20ozhBS^JfowEqD@q4 zaq7)=yS{{}G#8&1Q`)&Quzfg2kOzhXp#*f7P2dK(9F&{5}xbKYpL=r2@a8f zBLA!d%lD5`4iS&AKy!Ub-j#+TPFUPgrcPtB^myff2mQc#5@G0v5W{R79#J=3Jc+tr z&~zQQl0)>H&<{Agpm2BuSG?dye&Ac?bNunVwWE}Oj2~e9@PuJD#&Cpn)kOI^{8^=+ zH~Ehzr?MT48$4yXUKswyli1URhkoe)=;tGy>dUov@7~mCG%WsW{FrIuy_JmNvE;LE zSVBLMA9@Tr0gv=d4WAc2TgeaJV?M)#neUzYdjTr}z(YTE9krr48Las>9hl6892%kL zL@M5xn`y9P28H2|rM`HVal-HL&~Un{C8x)ZpOxY7d^&snlFqW2leTCppmpkRD`eQ} zoikfTKY9FVZq8nROyM!(#AWoAbdNt$%{+gDAIq<$^g-x3P->PT73qf!e_kTWSt)%O zKMEy!UhXtU#xSezAD(aG{rB&^ofDO@_06<-L?%+O$5sw6Ra#e?3|P ztkZo(`@4fbrlayK#Jdj1rJmWcRfx5IEt{RyIXlf?yh293&FOV{{H>SKZC*F01P|Jw z8=SKH)i>XzqsLFnbMa;x8XD4a+)nFPcU6Da?0IQUAQ(Krf%+eG^8?T+G(Qa&tm4WE)nJ#&PO(r}23G<3&qJvB^(VMnJB!7P^y+288QVa+MlBt zPM$-?lLdqWrylo8{qs?A%CeKi>oRSH&(cwrB$(^2yvoV}JO)4HE762LO8Vt;?6RDR zQvesMr%V@$ngsPx$zFJ4N5wMWy{zWXtv5U_xQtjrmt3eN9TPX{+N$jSTP&#@YHKL z&QkuADDCnfcq>sH=7ztrtzIG*_j!U)eGfU+1Y!H$pC!*WJp1%~(`mkV`>m7_bFud8 z>(sl!y?gi4nbT)v_`}ojj2X5#&2~gau8!_GY3{s5S{b!I?SAFuv{r_>xjoG5hvXI4 zuLCen%R};8GoWqMbCXkhIe=r){JC~wE_1Har_afw`lO7DKWka=6?xhXo3qoX=J@j$ zElcY*zLYk|@V9B>#(=db zN`}Y%2M?$7m#>RXM;g^>zZgYV_4TFKUVAOAlLzA5?#|RHVQ zmurprd^?PAV(3LU}PZ0#nCi;4*BlZP5cKflA9FBq{Z!8LN3fD&Vbn<-V~jc)z`muQ3* z&mXx!C38b-(guqw@~IPr6QXcB2Ae^mAG|Cu__3Uu39_{}mo*~!!(?t^%=$670O+H@ zkG7bkEYD&lD~d#_8AqR_bVaCW&@p)R;SbS=GDAj$`Hmvdo=8U+@CXAQ;dt<=<_F$* zVcCblDbu_-GJY^HtHjccu{8R5*Sa%0Y_hwW9Mluy_}DQ=TXYP`wV1A(%1p`>mG)1~#8SvVkbi zjfdrQ!+vx3wU=AJ4$uUnv%AN()aq8)!H;NayHklU8<>P$8T~3g^bT##Gr=KqJO6VO zhX-#}u`w;mxgO-4oG=cXrED&cs|pOHx~O^TsguW3kLIPX$dI=}^HkYkXkm3C9Qa{Nwo+IOw_5b;QF?)TX7NI^08h{1rpkyQmtX!hR7lVEe5?It0r| z8L%(E?4EvfR;}bzl;+bD+;T!UI<9Of@6P- zMkhxIzVks)QD`s^Aqlp3rBe7j&~N(XyfMmq$EZ z0j+-ja4Z*zH#X{yFesG@jShi+!cz(TFflgyn~vvKtHa(R7aVs-ri3iu*8nAD{s=NB|s>#3H>Bt3)iC zAr_sBWv0=xpPB#NEj%M~sm!d(EM#<7xV!Cc=I-I)=@DV{@YhOM-v0-2sZoTeda>vT z(kNJ7H6{&i#jVhbz>8M!|0S*ZF=aqln1}FHXewjMOz|a>h1u%QM5P!I8y>;t_^mwx z_oOW@xjyQXeO-9P=l(ZX_>9#4`IVv&CVD|ctFk;cRX^~eA=aKB@pI5bpUCvmQy5FV z3|i_Xy-F*6$&A5)jlp}~RmzHsN{rRzSy>o9l0J% z=8up1uH(J)r==e-PtYTa&)d6}@^xt6`pH>6bSU-c?W8|3>V)FTVJq$A^UrXw~0( zzO(vi*L;U!=ae60fA%}$ocfRA1HWjeWStEjGwpo8H zde)e{J%PdYqRFXrkIdabP{$*lad%*66Q+9rlVXcxu_GvS8ji&wD2iFqUI9Xg!Sz_7 z2t{WcN-JSxsBe)Cz|1djd&fERY+lu3K;{Xv@+uGr=tuuy3tl|-%1$`!Iw`d~KON9sL^e_Gfk(94)TX<~FCNwitWG-s$Htv$X>w4j)CuIeX4*i%5q5BOh9g z#CYt_c*FK6bFYUlZrj#R7B{sR>UNvW)R#p+=fPh7VK090IG7~>@?qr$p&lSf<15*3 z`&Y8t&N6m3U&bHUvrG0lukj5VS@`4Qt?c|`ZlDb+Z1D1NqQqKxcTg(fygIC5Yqqee%@kyk*$Q)aRWg*4MjUQWUL zkrkrd|1*FL5QTLN7L{sVG}1&iQsp8Gzu3_c!0Pob@azL8w|b8qJ)LOQg^O>UH2WHT z(kVC-Mn1X%oQ0))W9+UnUn`Yf@v7X?t~VItc&vg$wlw|%FMx)7F`mtQ zEEJwJ$MxbYKD%b>a7c%Ij^7#QUV7;zH=l*2nZ-xrAb9=`rGAHE=c;Xm`izZpeSbN7 zy~o?_(uF_Gmo-fuh!N0gS+WCkt-K)}F`Rwty>5|0V*jd0GDhzJ0S#|{;-4X0db@8E zO{BG6H52qvjC?gOXPn(mMO^OgK2Ip`Xs$nO6f5XQS{p#R+r=7%Ev(t8jC(+NG&U&Q z3d8wPQcCexY&2TrhI}ZI#kxQ&7`kldkXCevxA?RaU61EOL$odAIi~83VlZ(QyZjyz zFsM7TFjEZcJPln2)TFWB4$LEQLej$dY-wC7OH%-HweDAgurI8RvXgzY3sntOi3e|=k z)in46-}suZ#X0AgN^F^$x2*hJ8Hbrg_$k~Jd?SIYYqZK7o7FV! zCzaagep=VY0$qo&(t%0Bs-GI{=pPhR-r2M*%GAsX>-X2tHg55>+Y zPvrPOLw)ovEar9e9Ug_#j-^b0wz~H-+OVvyi&-&dBAN@Ad5M!*euxa_3N)UAkGo&c zp-*g~N2S7UG_mL>+w7jrNknJu)&MGTM;CP$UC8M)Ij}D9iCHszBW`zmvLneU`mMXz zVU#W$y|IyqjVdf)@a0%OSn}Xi`#9)5_Q4J7N7(1<3dYPo?%nVBj>XUzrcmdwSU!^# zK;@@UZxA;?^+u{T1F=4!1I;>01fl|kKXC3zR~nXxgH*P)xD^{KhO+4~16`X^7vho) zO&XFSHCw7-)Y|@RT?3FTxH4GyLqm9{_l>Jr@x;zd?VQzot{>-C6m=w9!2|S3jY<7= zME5~i%-GI9ZTNytvdF{lGGBS!7XJS81J?YlX|Xs)=i(n*Nv#plbXf3v@4a}ZpYQau zXYqN4o|ksJ5T}ANl+-kOxk2-R+$ehm(M3fKBm+Hln%2-;M{>d{Bl=@BZg2hS0Y((i_pyC^ihbbF_*NDiO0z|-M;#?|w zdxXRQZ~2zX^kXudlJ-Bw;{75^80N?1K_TA_sn1rDkEi5LO%(a1YwTDiZ;a;%JDUe` z`(WXse-!(;@OL)9ZpuYm)DK80YvGT)u0!BBl!DXWrZ()79~&>jk?TSKdHE;u)!0Lg z9sPuUlpo2ycJ12ST;ovdC%ZKssJu@pw#hz?RVrhr#yRpD=g1%8k?VDc_K(@jf}cLp zMy&F?GBqCN7>A60yw{|<*C4pkj@!T?soa~E(%b?}rQ@Evzo2j1bY2*x$C&0#8l2OvVr2C4zu zqM(>agF$R_@sb=TfIc=9xpafMWiGBts4^{+Yz1##KP`{swiP|d422M4RZ@v_q$_Z| z+6G|P?F)aAk5&M*`75m)x}=4tGX80tBZgB8f9g+?cNxbM)os^l9+U8^{?JPvyw(@E z@1Y<4+rRyrZzy8(7vr2ZtW3q_^rkKRJ=iV$p#b6E+B^Ne`ZDiOD)02OM||so6U26S zGd7-@_e^W8o=bRB5ImffPiYlonP||GY^k$^Y&yQ0dGrx=3ZVSs+4sm5NidMLKRMMQ zbyB5n(j-9&Z7@cH%=1k$+c)3h1%v4CS=0Iat zwr!4SO+faoWCP=%+}~*Rk0|!)#^m)h$MSYOKztbI^fhc^ML*KkcJTT&3ynE8+p*wc zq)@LzIQo91N9CC)@+t!k(WpMuZQtv+@Ak=;%hFtr%FAL!j5dRB^;ZtQW9h?HqDeolc|*t4N-UQ;tHeC z#w}45G*BjN0d~ct+^yC1$EVvyD{@=6u!TR~Ri>|$>J?&q4D23%;?Pb$?y>M^pR#4S z!1?h+ahIo(=@!Y+L!hC;e~}u$;k|xF@2Q={LW&rbU9O!PJvlA>2@77{OnxnTLyO>+ zPA>c*N3yZgwKgS|^O_{EN6g!YECvFBQiJymZXmHMm@MvNHO|G(%y@-Z{z|sS#>_qJ zQyFv2FY|!LCFtZ^rNFelK%RRZ4tTWlFUP6>D5Yed-u(S7Tll+bFQKGKnvl|ycm($| z`>gZ3@7iab?ZOs2{mN&Z?S{*nmNzoj8|BE>d=9?oWu&K0Z;juO-W7t#D^Wz1Ugrb` zasp4F_hM=I1w$LJb%+|p!e7V>VrV^Qb@c(sQWggTNK&NjscP#{3(NBLLZX6H$COWrkG_Ja#x<4K2w&##a7xqXkZnC=R(=Y2WL& z@AfrMF3#n8^b1O}*=#ZM5qlvXAWnJ5A8}F~bHBR~!a|-p>yL6A{iJqohF$0cCslqp@Af&e-B$-T z^R4wGHW>ZQV|DMnd`0$IfAm*cf(?G|mxeygi&>&`Z&zn4reNa_i2qr!F8)cG zAu46bXGg$ScjT2TFaF|C^}2%(9nW( zxQ(c$6(&Wlvgk$T$dLo&{1bFyT}F@Z@=h`)9@I(+yt|IrEcF%Rv4VWE#hEB5Oy{5i9o z>a`7koYy*#$R^XVdeyj1a!vbrOrDEb5|=Sm>-v36Mh{avmz|V#VPj#53tOJRD^8;C zZe?fQma209W7TNy*os>X6o_47bq~9ZKI7n>S~Xt+TJqz z%5S{F#kyCS-#zKEfyeob(Rcm1FT+3CcEHts(-o$3j$D`wMNs*EIuq;*f0?9EIHkdZ zBM9o*fM}pz(iHMJm;1j4sJY-*)GW0ff3l}GhA_|ILEX|S#xzK)(t-;|l>+?w0~9rJ zq(pmR{FM6!;~n=$d4my8tntpw`|i6hL=w1i4EvOz$8?t-P`vUEO>K}MPI)K#>8mXK z-T$C{2HKX#th4a77-xL<9s5N~TiE|Q-=QQ%59*+S4Xabzt$}j`$a&{TGQ3Gz*?CDL zGvEi3z`(@IGQnAgFpw|)IjJ~H3R0ccL8Su$4l4$_qJxLrhA6VoM%GWRte)}( z2w-2Xgk2`nx$YucJ_M$neq7MB(@*b=>%ki9$9TqI+4p1kMKFBE!Vx#Zw{G3?*y~*|*`MU~w@6-(^Z3jGN1;8{M&)Sg z^shzH4i&Oy724jYO?=sl1y_}^# zU0ltkHLHHp6c>xh{Yn1khYofsfn&Vm+9ce?TD!jXefR&WHOlokF8rtFxc zUxh@yhjs7gw3@;8brgJT9p~qTmZJyx>oD zM0|qB@BZDNStv5fx`C4wTy-?%MlVW1^A1W;i3WX$2@Qem7u>2GbaMdE{aghEZ!JPn zq)IwE=3|@qoVi#guo>sunrdC0D4l{(ZK3IOWr=P&i~s3M{ISl!$0=DzXO72u(A2x+ zrX?OR+w?#lyP~hOjVyWR-`oz(*WP$N7XECBjHdUat^D~y#p}1+z8g2L+r<6x`Y57| zc7@hj)dnlvGwM3@0h)9>ayjz~?wt%C{yVS9Dk7XdGnv?2bY2G(2D*in)$qd#01%Zw zk|M<+UIr2}0$n7~0Sax%if#)iUucAL$*!wGrsx_)DVk;Y%(sYk5iZN<^YF3tcIqp>qE}qp z$4mSxo<*tqaSL)5>7Z`@H$|j|V8$q}tN3w@W(+o^b``k%?e>>?a1ql^vKu#U_=H1` zU@I=-TSdo_W_uox--(wN{*bN(bhVE@72ozOxfn^R*TraGu2p`rP;1nk$?R#Cu zYI}$_FRRCK;cv`C`v;>R9T)!gFD}_4#<(0O?f5&iaYN&HuG=B!$NW#6^iiX{ur#cv zCa;2O2CK5t3|HQlrbJ+=$*PMoA-5JqWvsnMM**~Js!O($G!!X@Z1>n9${C72?ovzH zk>WNUU-*-q2u{L7(BLf2aU+d%u0jKLt3#C#hylIf{A|7TSCrouHZ1Z1Bm@EJk`l?G z8wR99KoDt$M!Gu&K{|#G>5}fQp}V`gyJ2Rihwro2v)22=`!Ae*&c64)?kgzVP7vW5 z;ceGZ&?_BRGyS@B`Fbw3+d-_5fakF2CS|(0(Yu+n&`qXYBmx_(#QHA_jsB`noV#ZdSd7=`i-+ zO~1E73bq)LI<0h8b1A$Vr%LrF>9(1Wls^@pp^OZG^ zHa*{bJ`b;|`wop`Yi!K_;%o_%0D<9J2-yduSPFT;4lgQxiHD>J<7Oz@&i!NIZ9f(G zgorcG;`h(k?DmL$=zPh!a*x4@v}V=fJz_v9KiI6|w^GzB&$fMW5cke&ZX+gWbysvz{L{(WoT#rj zX>cjWa`D>}MR3M#%T`zJf08Pm(ll)yazQ44t~$x`=+|>!lPyO7YQnbByB}kQyv_|} z7Auq~>lo~nhFfm-3N~Y@ZB#!p-ak4>lFs;Rwtf3Vnfos?$Kzcv8l*BWX5YK_5hJj2 z!co#2>j()==gS+Ez)W=-){od4JN_a3Nt&smuv~pyyDRuMRqT(C&Y>(U8!AhaENs;q z{W5or?YnECGCsF4BDW0r;q(+$Ef;=$qDHw?*gR`;>xbv-p4(%{_rQ)Qo#pHqQSjI| zLQJ{w3)^-XDncKNi8@VED`u~nYBh_0?+u#<`&2xgAotb7vB^`v6t+}&bWLWI)DOzA z1O-FQPd=^+vriD@$eXT8f7%b~E5r(6iO$fT8&yF{qj2<$U-H0U3zKr6k6gRzM^O}t zzZv7-834=Ed&T{zmaSRVhzYeKoW&#=z9=~uB7n#oA1(Wytzo+-jNA4qX30!R|3k!;*@;I=+M_Cn9m39^sPi5li)zmrNFI22`?tyrgSD8NnM6MWt$Go8YPCI}gOw>y3dU z4rU*e&zc_2mTpWeety#YR_3!?{sm@Yd~uh|uX;|X?1wR``@rf4#nsXJBpB?GmmI6M z;g|i(pW20z1TZG%tRktfM?QpP-m3<7zs?PAuKHT}(~-U%UNURCl7s%MIOt(T$vmDr zJL`A%DfbMjj(W;bD*yaYS9?)}6h^27C2^DAB)m2{n_o^EMCiThOy-!_o9fER)hkIcR?t)utch8|s$mG;%(NyarW7!Q3VH*aY;;Im@TR z@Y3(v^qYW#r*K4`%=(|@|DS%t(m=K$w2SJ#H?L<@gLYp-7+xl5vaDXSl6f^Y zqT4_YxI8ufYqKWvFlLE=OQUoG+dimJSgER);9B6&%nj51cj(Z>l0q^^7h!a`ADw)f z0c!#hJV7szT^?uibA5l09;KW+>D7mR`5SwY!-e(59)NZ2(#g0@_irK5=lE`9yKOb) z9bzz;3Jc`Go;n(leKPD6la^Ppz!<|r0DUXXm5d)xEhEV^d*t#XR_X7P7M$Fc0soV> zeJq0@azd{3$go7JGmdT19|9&<1iYO($FmiA`D^x#%b}QUFte0V-sNw8hxHy*x+}zQ zzUc@Bfv;|-NP1RRV~TyEZE-Ou9n(5?kDFs6ZtG50w@IK(Z(AKc;Nt}?2-oCzj}{_K zj!AH5g}&@?{o9^#;G(FNbc7trEorx8>W3ehdzB^A&6Q^|S~n{oCd;YT=9Jti<*cOB zkCkWPr(fGE+HdL}lb1JzIg$T*Ei~M<{5I(8Jk81DzOKi>N4TCNeA>mRsa(uh0NNBz z2`-abWA4%z@Wlm!glwd3$D~&lEOXX{ZCAT2Z{x~lNE{SzxaC8L!gE|HSHHqr)#j>F z(hxf5Xx3+)uk*PN8HrM7oRnG+?*LJR+FG>|c&df7H@BWfv=ef8CLHZE_Eo@P3-?1? zX`;-ohZZYjtYr1eYPvcRt;hOtzVGjJ(tCHf6XkvKuY-mE?^VJ1{QIPEgZ~WX#CNhA z>U*;fd|7-*Sj)eekidcGs)sQ=Df`$1n5%jUCF=FmX_Y*0$6g_*qcMysVFA1&7+^2uPr6sR=Qu4pzXIwWU$6qUPcly?KgS;(3J$iqMBRP%loJK*O;+XhQ^3D)N#e;5ip44YI$pHcvaF~j!7Cws% z5%3>dM1C3r&QU9YY69EOUyj|N)8}3*+b28mtMK7Lk zrc;N0vvbME|2v(uPXCxM@HVbHzfHzi%U)WYXPDn^yqNbge;K-AMocDwd=Ek2>C9Rc zeH=}cFU`QZqG29J)6qxLaec2R z-clC`RPV5Px45{U+$jz;TzP1T^vcu%8)=X@7_E5SO!ixgy#0D9gsHpR-bxSi=MEjv zB}n_NrAYrvEJkn$BSmsH=ySJ@_usU%xDh`_M|raRt$%Khp~}skB8!xHA-1!7qcE`u z?lT7;Bj2%G#(RcH+NZ_>$C6HthW9uo?OR??)Ts{24zGTmPk@&P;41vA-Ph}?>h#7~ z>Pc%^P8_Xf0nzCXdN+s(w$vA&9;+kaQ5h_v9-$T#`#06@E0hA@c~2u0cNLYC0glO(6iT`)Po`ZE$(jR;VlgvU za7yzNZb}c#zlEa=i@J@84MY)rKKlDcsn-|-Dtk$jA=N0wNztJ6c&My^f{GO1a`O;o z#-H*SAky>eq(tU;KxoPqXP|!i|9JtdBlk$32D;-iP%>_8%%avTj$EfX3Nv5eneGJp zl&RizJaD;L>#TwLflRw_W+DxR@HVR zG%N?iKKR+Z{c~^2pqaYg!Cf2l!4~9l@HgcIJjzgL<+an$zNw;BqnmHVl<_Iac|t&0 zz^d2-SN%=AG_!kr7z=Ini%p8GqjS+mgR;~!_JqYs!KGeE&^RFJ_X8nlR()4_#1#f=rew8(MXfgBi}!>#9?hu z|50z?nfSzz`k!^xe>CqSEms49gJl-@>f+&?i|b2r!*B7OoP00-x3v3Et0>c4?O@C7 z>CnA|=!_#TRzz5N=4-x^k9&gX<`|V;`d{GSW~cG-GXak&x9EhjaTf*Fk`_a;<;#Y` zz(R4}+$23&!p%mHtJJl4Om%x;p(5ny3t7@haJbAib zuYj2CyS<9*$>$|181Afufj!Oa&xg34tdB*aVR1tb+U-6K=cT^G&kRb4CDZl`BIgyi zoY1(>J@QFf6Vs9FSf; zPg438LVjU*>jeoFpMo&KB6aYx9&ztjP5jDx1z&@&qEYiMs-c9OtYywuP*Q{9KAWz4qGfCokOu9PBwHh z?D=x>rn#$~<4>{nF^13cdj#H*@S;v1fRDnHLK<^Hn}E6-gZS)0hmXTXR789R9Vkmt zS~P|(eqF1;aaiz)6ccPe=gL)Hihl0s;r%Id803A~JJ@m#J%%J6&B|GOZ$8V{<^Y{q z1-+trFWx-I+wEGhkF2dzK*E7^S@!lFBTe0fo9uSa=W_nMDiwTZ>({q=GC!X}z}LxlIqGpi`C2jW znB&g3fv%q^+#Xr4SK!;TG7}@PB)3OKeNrkX-SPFQQ>!0s^#Bh(JX63m5J7-h+floX zQ|2S=W<2Pc_nLSTQ=h2{+e~tMazGy8IbQREZ{E*8^AFSG+CqkgBigm3=f< zC_zN6mVFtJs`4uv(v)5}TxjGs$_yBZvQ$%bB)q<8dj61LECzr5HOl|L7%T5p8icy_ zkEtLG*C&g85GDSm2<7snSQHN4u6ce3^i|svH~pGOu#G)Fy4?JU9rK?^_$ks|4hNGB z-<7ipV~CPWfc@F0`hRnLVg8x|TB%g2;m(TKEi4)*pnv=aN#DP1YwQLqfo0W1QuyDD zQv{54D-mt1TvW?aQ(g*e#HLk)u(RcR{D7`zmS`k#?T>i2y-u$u6qRfJcd7v+jo;eS zTB7eCui|A1XtSg>np+C|C$k+bB$ATaAUn}5wR*b={Kp`3d6Bo(RrWR)R0rD2yvHFk z1Xj)P%W8p_FUHGF$zxxL;57f6k{Sloh#gZ7`$1B^4b$#XSk(X@n ziRts0%aJk|5x1^+DIrqfIf--YllFt~1v=xgezKSd`cZM>*4MdGQLdK?uR~w*Zo?q^ znT~(&Jbmgx%2nzDaPZ@y?rISxK$R>Z+9^m7AY}U1H{0SwCp29ccJOQyCDy8$H9J2_ z@}McZ6^wX3u39LEMPY#6q}6{(uJvsiX;UBL>_VweLs$Q3UWd&oR>z1w=8WFT9uB@m zGd#ER9;b4;EpiE8sTd@4o1igVq4ZGi z{}OZ)MSjrb%V+C*W5J20*?P=!KVjuEXpJo$j14hJ^ud1P5@W-WlL^20T`Qnrf-%S| zhh0_nIbKe@M6R(pzrlR}2hazG{*FriHmh*C_LG9ohANmez~wQC=*#Q8aqNEPZE-7$ zjd?s@u6K=|3EdN#%^aKWTD21T<7qjP1*(dR;E-(}2^cm`JIZywrxZ>N@@cSJ)!s#r z6Ftw}uED2YdmhDBK8lNoT$U((^L2wgAE|o9s_c5%kG8+T@K45@t8VLh;KHvpMpDJX zx2pw$=W(pd5s63i?X*IWfTe7U>`V8aTqthMNX@s@=(-anI146s>cSVG4UKV{o7T4g z%%{8chhRjg>#wN_cSJxW!Ku{qW5n10uan?^_*?cR6w8h1>BQ zD`Yd0j87?}@?7S|+dOpAy+!cr{H33fGol~(OjW;qZuy=RvV#@y@mmnmWV7*PHn-ra z3dfBP7n$nLl!`{*2`_jq$nB@7C0Flq_v=A^{_td84Hz;nk?4Z_o-vJENH16)&tX3QWc;=h5afZjXj=ZD_2@Dw+yrWaZG}Svtk?UY zHV-Esmgsn|x(P0)a$i@mltdLyH0moyNv42+l-N+EYeBkI(>DD_(y(}+ia_LCOT|{YjH&6@!nQV6xUbhb~(>S z_in)gjRe093=0NdP?&hTLfb#tFcZoM9D9Ab$6pnr&TrpL*ii&5n9Ad1`;zk2X7v!~ zg?iYv56R#2{Cu!oFZLxXL30>_G>)G9yLUe+Ks!(n(1({mHyphSY!8;Ky@AKcWjRX0 z-XCzbczF~-pRp0bym2D+S^E{;Owb84(IG+3NQ2b8 z)S=XBC;U{lSdHf_eGh6mp#g4-H{iu1-xyzD$r(BF|K2Yv9b-mp<{?Up;vw~{@>4kR z<+~?q-qd5YnO6?D^DE_bYOMb#hA8$XWSOZtihKVU34sd^BdSW%hUvJ1lFWDab;56J zZ?_*jS02Q_wbouFJtQG$imt*geKmdE?=6=v$S$XZ1Kf8tm>8Ah8?x;(O;2=Qy3ecS zDt>Hv`lbOwqe`zIFE!kt3^Stdqz;eG=WF75DXl?bB+aUw?nM z)ZcL_EMgRS2$T$BQqNUkifoZDxEY{49CaQtC*AG5?C;7Xe9?5Cpt?Hv0(V+)j(>DC zfW5i-9){*0KZ9jRtXk)-0BeF@IdIT6C|kA06Ow zez_{Xf7Yu1E49!r|Dw8bR|b7B8@JR43K87S;zaaF0@-PB$)6y|X-0c~3Z6>^u;KkM zWHQzp++JVfk$PxKnp5(Zz8AcxVq!V^p*LYD@5WFQ?91scPQbMger z`5ln{J<4b*<@LwzRJXHxh}WM9G4_Fk-^w8Pt*O|1U)(>JDw-R5KP-L|>Qb;W3^*72 z-GAh44Yq4x5s^2AsNSH@?=zYU4v|mn2LgZnf-MRBE30z;uqM*imASJ+_NDXd(Q{f6 z=x*>?vmQ#{#OC2Z*jUebY+57Cgt(bje(1`Cy{^rXvj|E7tf&(=@9|7!VkjK3b3MK^ z=cJGQ7{WS3D*hv)-iuhhb>=4?aO-wA353wV1HyOkGudypsg+bp0W}iX*-<^m=irx? z{_xa7FB@U+KE%B7T>GO8TX+%nQTI9&5+1za26z50_!FW|_?d7}c+2%1=@v(|Eyv%Z z-@315fbv?SeTRxz2ZyY|CcWvt@z3?|;i;K6SPfGvG zE&zP#A@alw=1F|u!q#heU5!F&A3lQNSkL~y1mG4<3yu+{&N3J(sLOARZOV?H5dK;BG$jI zUv^E9(*-i=TR$o;eMI^&+G;*?AH6N1By3!i_fnabM5jAHCJ>Xt6|9ZZd9g} zB|L@xi7^fv!+*wE65ykE5=9T+Vcph*23C z6(onbIWhYR;>}Sodya2hGvD=RgJMJaSCq7MqTMfkqbZ#+>WuC0-1r&8SA?_N4{?#c zo!qcVlf;7G;hu2j1@qg^1fsY2!rceDBo9GrWD1#dqLV_wF-x`UIQcdO&LIxOC2&m< zL?95cK)jmVN_*lh(&0YP8m$pFF&;v}r`Qf3wev=*9OL60pC7S%w zm@Gj5l)(QvNn3O^&8_NUee=t6!)QY2={ zLEk>K(w4($6LO!(spNBWDZ^0FhWLx4$7d_d2OC<8U-5NL%@OKq_+KZEL#Di>&k*Ju zf>0l6{8CGkn?0|$>g|=wRSI_Xh9R9BwH}&X7tXvk^t7yAZ+~KJtER|jV0@$2;fHPZ zpW9WQuj5>wa9t*Qq=Tl+in|-RjPE?v?n-(*s6e?)A{?qm5wVZvmApN>e)h=ky>k!e zRQ_RoR~LnL`ohJp{uB;JxyJV4N%TOw_M`w3w4WG@RLQyG0-kUIZOt;5c2PzWM(gpmdQ_kG_YdA`>e}%A&eZ&0$tPznY&mOjdWOgx$((A z(`-V1vNV`DC>VCtN||O7okV`sZ(M~oBSWgLYtuE(+fWEWaN>@u`Q`@1V-g1!WX$f$ z7v)CQ>yD~2DT#HV-g;|Y_$cg(@hC1bG!6}`PSOSozZbUqZK~Rzn`8Z&E((Y#O0ai_ z4O1AVjMZ$J9&5q)HbugrHrE5ba4m=Set$==55W3BXNeh}_A<3DGm} zN3i|L10lFqI%>upP4_%%x<&a~!`I6*0di>j3KPa{|B)W@lp>_+_TCC*c!X+E0TR@= zXibxyJxn`Bwo48mhmB}E{Z(?jqNjwgO9{tvW>0s_w%>5JGb?#c_EVX5O83}e#b!jJP!zuDRrgJ- z2qi)$0w8_XCvBwkJfH@>5uP|Yi(E8bHN&bOFvyfla=;WcDgZg!tyatUl+~;?I=u3Y zSg5La*{BYJmUQQ6Ol4Mnie&i)sffrci?$>Du1u*ixt~?$SIL`9_q~7V*la5M(5n*0 zHX2r!yIs8nQS8p5^}zwcme(wyFtKA%S&erg`67<=686(AlKOOBnb((Bsxg2jST+d=h3$2GvveF zGPn?u4e4N1Op&QH_T-?PXyNwIuvz1e;}hJ~w$x4GtEH$L$k^z1qe7^F@gX6g?#$ZodeV5sxSDWVE{;@T_ONk2cwL z-!_N;ZTuzvHo2Y&nF#0h;}i9)2bFdD0q=2YqU}Qa!`X5i_@M!|RH%$~RulT$$0wx% z?x|yLFm0klYdpE&c6|F@z_D~2>6UEkD{vZceq=sym5dAOwWdHp``Yr*Tx7~jA@~{a z7^xPLp|gBY_e!hB1mENnc_htR?`>xp7a#~6B;y5rzyHfowODppns?D~;J^2byh*4+ z3Dui*n|Ej_y&}O0m3#JjdAjG*hYgzykA! z3{Okm4}1m`25jZ_ukR$bq>v9&7EwqX?h6sV8bGHy-DbWO6^)9>*HLZ1H)1Q+yYX~M zf6GRGEwwf}kPWA46m~sp3jn12UVQoS?UKfH69O@=#?FDoo;6dTAX|ialLh2rz!SxY=Jy;R$tr)foJcZi5DU?C=@;ymC8Xk)I)Ey?1TC% z(-Z<8$=6keJd%E_=X)mcRI1APcV&Ns|3CCo$1Q3WGvdi8JCF{?Y%@^C)fA>mHcvO; zIcL(wz0;OSz{mP{OO&jjc8OUoONn1^ET1~ybDyqfkUX&H53*)$@BhJa))8K{Ty^oq zbOl)(mV16k@v5qv0rm^vP&Gdw{#Olzbz30NJy?i7!wcH>QO`$^+u^-JGgeA?6yuvq z#&5bpgJX+^+O2IiaylRgw3VJG*QjqPj*!lPU-U@msJ`tjQ&3MN1(=+ra@?#&5D?#K zY@^kW;0|ROH!e6y7&FjW5 zcMa{g1yz6c3BHk6x9=0Ja;#>cUGRWm+F)5C;q#dhp_iMX(v?w5x2w8n8oREU5k6p3 znt`CE{mjo(!MXhr9n{3}+%gRuY)el>AJtl8cLk|51ymIy<=URK(YgGJ+4S%$Zjp^iCm3;z|*-un^%ek;i?`a0;pSkhM> z&sRK%(F-FJaL1!``@b`a<1(C;HgJ|5m-fd_7MKTdY$SzNKoLV!x4Sf4_4$u}C9Qn_ zN~qFjvsPXX+^7~?p1iZ?mg;=bb){SrYcQT-%!DXafZIuKwvM-BYM=ijO?7-(iJE(g zt$wYd3p2$W5b*e(qiM#o*o75ry-na{QKMJ6wJo5$sE{h2*S(!IWFq52q7x@N;&!6L zh+Sq)Q?SJ@wa(w~)TE?xv+Gbknr(cWWw+YuF}+U&kC_~;qo6;TLhku?4)dC%ENbUX zeLur$mD)5q>plJh7kP63=YZ3ilUlQs6qeW7SD~j-!szG60$}=u60>Xlh3v8f5PYx$ z^*Ue9={pS*bbhhxCZkG#u+j{JiK`%;@U}NGdQ-r&nfDhp|u$N;39Um}%cn3Q>Q*1k^k zSu%5lm{P$PV*U29$J;Yww(PR9(ZR4ti2KP3ddjT2Z!!ISz7cK4{D7qAlqnx~6pmNqg(MORw*Ts{1ZR=r$ez=zNW^B3Bi>(b9=fa}I)u4@zDXLlKwc z$4>L7+X5>)&FON1CrVk3rI11`*K6)BPIjwVf9vnf@#E+|iM8>y3!PYLMUf&o9td0n>)n$=7}krP0Dru)cCiZRd8oqsoDpe zVFY$Hp#A2dww0sXEn2)`uS&H4F9w@H69S!a`;!%^_T$5Mp8@ZVw=K{svg=m-lQF#ISbAv?3`3@ z`NwV3>~sYE>P=YIFcmNx+d$gt8{_ct@vx<_M@^AQJoOSY{zo?*AbR6g*E-}qMtK?O zd$)ahV9xS*d7ODa&iU__lkS+afHZSVUq&imW;N@00AZ>)jR#a2a z1+Pg-uUd-(cbRRP^&7r9D> zN0$>TS_x8(WW&M7`c=t3LoLtlXe1RODT_+q^l`5@0({&1XjgnnEm>Hnx9e@!Q7~6L z9yIqlwoZ^zdLyo6cyU6h5W&i@2_k}Ar1iI;FkhrWT%Jv&C0SdB*GWvb;dLoVfTzcu zTg%*R?=rXJJU#9|OQxSy_|X2CGe*+=m`b`XC8@Rcd&jB`l~(bp=H1A=!^9r#`Iqzq zOw_1A;4-0tJvry*JDfa}AHh8(t&u-CQwdQ#LI&LrNAXEI3I92L%|k9vD@Y4f5REah ze%nn<@oGZgq^J|?;la`_EBuS-BPGQsMK6hlNYhs>gTVMxsdp&42x~2#Vk=pyPgdQB zO<+>fbF^L{ECfghaS#5lk?i?b{V91(65qq-GeGoD1?rnpT1>5Bp$+$?6tr52X}72Z z-@akv>-lQ8e~(|>>2Y?d1_T$;@!x*7tyog{d&ub7K*f)E^|{h2erBY%f;<=rPt?9X z#@Pw}yxOE_S_#o4A#Di@?-Qz`^V2kDx11m3HI_sEjEyGW@~5($!)!m=&ihGu4_j;h zIo~Z_xt7#g2$^^^ZP{n4G%9;@Nq~K@>5<2m{tl2?t&Z(o9G=Wkm&-RuEy=+S zd_RNgWM;%=HTW-8>`To#@8CW^UcmWjXaJ!7vH0Xu_$$7DeNw{!5xpwx=Y9Bsuv$?x z?)Jvor%qk)oNR46)2X9xV(h0qmZf9(d*39|*P))GS68w0R_OJ+3${{@tPF^N5(|w* zW3mkoUOD*=1t~g>D0_*W{)rdeddiCky}{dP^-6cMysE+}wzysUxvVq>z z6K{#0$_yX)XBX~5`l{CjD#Yws;U)f-?=NZIFTHfFOYcCVMjihaeboS0+T(S%4hlU} zhPXX;a=SDd#OE3R6~rw|*3+1qz$@`$$m%!l^D~JO)68$%H2Pw(%Eq@sHR*(#d=7oG zy@=v}r4?-|>lo15JFN^O%|?A?l5w7mzEz2lp`u%3L}8(*HAZ=e6S}}TH=AsE5`Bi@ zgUx%m#uqdUZG!)~@wXa{UD>K3u)P=OEnSZO00m?+oC492A(WPw0+_P5lM*$%BTpx3 z#}13LyP{h@eTc~QPi=R_E=6iyB+b2}u2FEq9?}BmP4kGaK|w8_S|814Uru;t56Za} zNF{qeoNX$qTq{{HeExVcVgWI|pa^34R%Kq&p6&bZKZKw9vr*YWS-GEmp=xs;d)fdBKi*YA z|NFo-<*Ey!l|P#|qkL;OGCr#*sD)7q@`KF=L~GQZXv*lCU31}w1N&jBxy~#T1WAny zw?BfFzn#!W&X6bn$C_rHGEN*_I}PcV)Z!1T2w&47s}lTbJ2Q9!FFj8BR+MhuUFmGF z@9izl7kludOt|8XQ(`4`S5oce(P{bWCCWx>uV(v%yax1mq+!?wAdV4G@IhPW7b@cH zZ7C4=uo%iL)Pgax!q{G&)l(C2!pW6XRBQPs1S+cLuX8?akhCuFFR(p(iBU_U*s!R< zJVYch(aRuZKIPYXEg7A#-g=oarh=fK*T*Fbc4+7sX94po6)=5cERF$R{kq1}KoNgv zY)?||XE&9uC&62dF|zuJFJT1RKimG=j{j2sPg@Hxkj|5s%BVc+N|5>iBQ+ zGP0k=+ghPm#sH06{f@})l%O900;$T$+uAO=uvDyGY+U2-6va*$cA%Wd`ab31p4XUB zpA^*y$Q?0FaG}l(3dvBx4~vMrJMSxGU z$D~5fW=@HPYg;L_{0x34{0uHc<Y3C8b*_$_<=%WWZ^ zQ)uLU|E2ALd4}&&W~mUp5?cW}!Flo+hvv5MUQPkaUBIIPQ6c;zu=<8NV`Qo%MYKvI zYgK10@aX(kEp!Khc08+H*B)p~6l{O)e(m|!=zw6>@*8qsqmu{&bFBVivRH;XPUVcO zcT38VO%Wo$opy5H(}J~s2*xlVXLI5i9thMSxX(Qx=lX)$hpT9}|4t5sG9NJze&e--O0&*^Iy_Ky z6{*)ST`^YxGB`SkA1x$QR$!H(mE#9I{--nxNHqL}n9?UaJ~w*& z!A~!@A22=R&CHQ$Vdv&EwFQOq1*#2aG?6!{BLgYe3JiC}#V4n2BG@#`kSw*SbJJsPnU?n@PE&`r5 zqdzXQY^mL+OATU_ik+U^7p&5qU-Nwc_yRBDSrM0G{B2t@d21T#jUCQZPhhsQi>fJZ zEqR$Ns;eR5mxW}Js@uHNJ7a2pFH^$!M|RRv*mZSP{Xq%Am-mTqC&)OfWdfbTHpyXTr)%}*OC8uuE>>}*5`-!s5Xwl2vJH9+sbRAU*rEI|=8=@L;P<8+N zsm7dia0Ist`WJHDo&jJ?GbCKrq%vfP*bM=&d%hfdx+?_idLIN~ppa8GD*gyGE#K)^ zT8n0yybU23R`=d7u$QhP(Lx7#6i10+kCkl&)(P;Zm4Em+PF%C&$@TAhvy<`(b3$f% z>;0J*Gg={a> znHwUXEy3{cZ!^SxW?W=`OY>3{7pC8@4SGhFf&`dal%TF2dnX}5>1}#}8oSGLu_Nto zm728)zh-%x4Z-E8TO^Hm4` zA*21gQ2!=mT?9i~Rxp`GQ>)u0F*DbUF6n4sKBPunaqT-3<5d=d*fdRFH6|fy@V_mt z2l3-{xAj{Y?u^?0>ZkNN$_CAlXw)f=mejrvY@YH%%h8VsX>~1pq)|d?l}+ ziTNn z_U^>px)b?qm4;z|UkZ&kT_lL57HkESeSX@p%X|jjEu4dVvY+@`@dqg*Ew>GHNobeS z!qevLbq!fboA=)1&kX*HP~6Zn z=vbrJub8WT|AwVe8I&9|8Rd~mdZxO+Qm0nOXClRjDj%#rsB(2F^D(z!qWzKT3Tu!) z$|2V6x$4b<5br5k8Axk|n8CtrAUT5S?WbrTr4uZ4SpljK1Ya*rZ?LatTlItCrf2L% zbzs)VO`LywXELhBT_~sQAy4LQ{#ZsaxKH!$FS}(xMDDA=)0E{8laNGWgs>25bE$5} z^}7Pw0{M9{tKH%?B^7;`gaOoEBjfkK4^1s{NVK3r{9iZ3CuFGY zmv7gf?{-2NGB3nTZ*fDgs#@K`u+-?kMVs$i2G*aj=+Dao-)*F`B!Zs<7q%+guojez?};##xUY_QG5sFqvt9j%(kLz~ZT2Ytzz+%~f>mJu zu!#(0^K;bl;xT;3EbQj~AUv3njWV30nEJ?duF+{V4ZyX&uFC=>8>01kG8Jui&1%;! z-}TRqxBqfE(C8B)YtYNdr;jSN1u`)cta9k}Bex}O5=4XxpPTgDKC@BiNH(j9X5>OV z#T5TD>Y8xp$&gF5ZZ4fX>bID6yXE$hhVQ*HnmnBC1sj7HFeVG!8FFtMbi5-1-5wHT zybnRW$!UT={QQ%C zdDH2AY1;ufYYi2gFEyC3)t8GFy!MdFC1i`ofDuQ0hjdb4!0;Hp_lBE8#8|Lf_AjZF zt8rq1n3E^%)qHjhu~x3J_95%4(u(RY{`iZ@#ZCdIsW0PYTVJXhVNuD&Gll&?&{A$!fBX6QhugUUqk1A z|4H1?r=;T&0LimtJMZZk6&@FymD!~@{WC;W1ukCcCqd~?(50x7t}Hf*y=e8@BxVK1uB)yGYQ3zXGpzoCXokAN zK?(3E7ljVkfqpRLla8-gZ#;vTyL0P;;{@3IF~9w+MM{Y5CxdgJFI3W7D$@_?NU=I= z2NS+83TjMGLY3ArG&TNlJl2KI{^NHw8LdvphMw_FF;ND%)AdP2{f~Xh@1f@d;XGUA zc+7u8NFQNcCrop8&!jq*8^JwH;Hq;v8(lkS|E=U!1TZbnoyqesY?g8&-S9?>_#jzJ)@zgJuo%_|Cn<9 z)C@0|vC{Js`0dU8El8?@TXK|e9`KDrvDN`$Br#{yHrmk>>}CNqqq^-_#%(BInJ*Wc z;+Ea^|A{ihoBv62{gpM-%pqLqT`IG#rl49cTPaHb8M4UZ0n$Z!5|{w00O9J@@fd6X zixumOSf}5S!{Jh|h}6RE=(-*O<_9jX(jY6neoh9*k18fVb=9=Q)lxEC!fe+!tbTB$ zlrJ%TD{Qhpk|-}#oNKZrc|fCjtYdlX?bkA^Ns(hG?e_4h)a?3KfYqw3MBMhv_ass2 zVl<_d-mmY8W$bjoFYMnxs({j?&luz~NuRkP?PsJJ1!m~Y^1SuSp7qVNbP)|Pg zhb7)(^ZNN1RIpbicW&yOelOV)s50%Q<+^RSj(5!5{F!MFA9s9kVLkAGzReIhnzyPdMBgj z=J#E0^obP)iM)tf{?Ch4noio^KNpw_xQ%27bpJ9AhiN>Y(V|kV;ogtb+?~;a=aU=5 zCx-O7sIhAU!t}&MPy;KRkpSp3n(+Zv_CHh?^_;OnN+-0qG|mp)ekM-mi*>4aaF+2< zs4DtVU%mEVw@3#yFNh6~Z=zdd!gzSUeczkFXyU@wgoMWbejHsGz-t8azJz5dM7Fqj z%HZ}w-!gMV%4=ikDwl)!M{%xo(N(KsxZStqiLk8xPXM(bO5dMeQ%;psK8hIlZ%F>q zSIS)I*@0wV7qx$UWPq>2%3E<^rxbrxWTn6xf-220^3#X(G>R;vL8o%-Q70+A;z>b0 zVUpq5NyeVg%gdyVGIc=7@P$8{pmFFz&oA#-#Mjv3wakw8*hVhS8XhD|wNRRA$MfP8 zc6Cm1Y?iL4e|lm%ZpFCtsXAtA^7iNBZG%TtPVFmeEd1F{&DUXusL0HiDM@Z;LiTp|WsxeC3Z)T? zak~a)b=OQS{K4sQvmdrRUKlW?4C1k4%IGoL1nb!n>L9Y~x~a9&T=SeCR$G_|9opiL zxcZL2mtS%i?`Y(QNv>}`7D7;iZ&3|k=_8T~Yt+Ec2|To-sGS4u4iMMrCV!D>jcT1- z)O(7fVvFKht_*>YU7jW)WtEB!c6QqOjz7yUTKI!j{N&H`=>30wy89Yu&+W>JUZ?dT z19@L6D9U`~<5gRTV2oq|iT974Ub)L}rgbOoJT+=C>o07NE?I;Qs?)<%Z>0m`s$mFi zrE#u?pU+L{pP*!%nMalJ#SlW8A<9BdKHFCFhNyW6{RoI_vTVrdr3K~OHL#3pF!7G| zci&C#jC(XbsyTRPT+!&du*Fr+TQp{6VI3yfOfX}joTDckis>2GqwZxbD31!BGCC30 zc_FX_PZiEk^0DKOT)Z38ea-cWHdW#luWYhc$dq^eJ!wx#@{aZgu3q)~@u`~7H+4u> zm}PKNl<}f-yX)L2TMI>#*XTFN4do9@tH~7)sp^B3QF?kCy)XQ+ zHI^H!ECdB~2v1XRFjE3RN+`J!KSyG`66wDy`o*k2Exvqm)np}aAT zvIah0!W>`meR4MQca8BfUtK6p&F8p`?a21u<$CJurJrP7PGx;+tZ_Skv&@S&2qAyH zV~ioycT|}0Ju=J6`JQg1Ts!`h?95}bUA&ztdFacn93uCs(a5{O#|}T_!E6|G+kZZw zbL-aY-uC@bU;CxVN3;;_v_IMoK@C!XE6Vb%6i}p(2gEU8>k*JFE$1uQWM(~T6O&93 zZvwTdRE@$a6++xf1z()@QlRc(%Or~aL!Vg3!XFC}ybqO_!rw3aWvk$q48f&Sso?Wz z&)HKfm(X*pS3aZuG(fCk;h2`5Z&0oUIQ5rmX8MT?@p-@O9OIf1H?lK>+w{)ZfN8-N zk-Dx(yzJ^zX%d}M!9}mK(pBlk=_OUEsB${g0A-9VLpY6gN{Ul<$l&gPRc*U23skS; z0>pzJ)xQ;Ng2O(^ju8~R7XH9I|9siOV(|)Fs)WUvLM-Vbt}=Rr2ufP%I{2X!msD@0 z8mh5UNFpy;^BAKrq{GQrpX1*LAHH7}kZi}FJ*v%z2Y$3yULfbnU9liRJ|YS?xhx$~ z<+|xykPPtx8|GY(+`c=Dx*D9tEWE;@bgWchbIP+16VgPfgjCtDR5+yaZq2;#H=E4> zPaa|A(AK7Hl5Hb|?A}PoTFkkA%FAngieS;KrKA!Mo4NWxMc0gV5053kE62{USoo{+ zN`F+*u5gxe=(>k}{0lpqt>iS8C z%eOvoW~rVxV1{LO*Hn<<(}eZ0P~|Ma^2NmOzb_xxktUvG9k3 zj4`T=k}!~S)g|;+aZ=UetYxjbVS!ACz!YN3hb|>IFy= z8`dZVtU}9JR?CqYk~Il!USqOcdHC76j7fYoj?P*}P{-R&O%`llx#`3#w9jTUA1C3- z@;j4;#bT2530c6+5Fxs>(k1v9ETLD<_BKs1uBvZL-WY63Pr#*3DbV?Ags_oX+bD`u zCX)2Ko3Fg=Vq?MmNuQta8XA5m@x=&>CI2)&qN}zEW@YeS0Cxt-Pi zvMDI<%j+AYi1lem5|oniq^`G|!hdm(6d3#${Pm1akx>w`n=;oqU-+}wyiodG<(tTa zw2YL*4BK8_c5hGOGD+EiEw53LHav`eqgf_-3~#P4N63l#svkt334++w&dzo=a=iQA zd;al($N5SuA0K=0AzMhgFZ!A>+%Y<2g?y9k@kfXKna+UI2ayhKq?~iVY;~=MLQ>nL z7s|;+Sbj(u$T3*v9haCXh7zO;!)rc~Yn*Bz=uE~?jPqs?e7Rit3vf&qlGRSVeMmsP z*9|Gbd#5bi#v{M{&=s$eDf1NRiGUcRgvk<>l?vXa#n7Ir+TSCp7b`^(C_<$H?x{NM zb5{5Gx$=a)&`ERFne((AXrd*6DSyt$iFPh2RxA=l8AXpANbd`JhrZaLWgW$L{@F+W z*!kxlkFyO__wp5cZ-dON31P9ef5o3?>uln3x9VtASCu5=fz+aT4eM zvFrc{NH8c6$Oqqa1XXP`CN3OQq+20w)X@`%&~{DYl3eEw-PR2Cwhu-!&9)CV4jhUzMytRrM}8&nok!bF$l zP)7_FW4%@9PN!OlKD2lVcO)>ZDwE1zTG+5C1ht5unFmQ?N)v-alMRWgX%}#cPE#Zf zApigsmPtfGRCu@2Dp=AAjsd$mOLhxCNJGcK!g6tFu%H3V#O#$or1z!Dwd>p~2lF|lM zeNtUSlu}U%)RzUHOpC(C7l3L>U3GaxLuZd83hGKFu`$%R;l1hGmSH>b;?pK?@BVP zNbf;ahpbXs5%ssW25Ekvazl=yAOj7Q zbkppJotm@R?Bp(Xiixg9K-xg0JlP_C0z6MY&OU$^kptLS3%y;voON~e^7^v;(ez9> zXh1l;MmUF^JoSK@G)ukD3T`P2e=oiC5=j3l^HZ~UCn}MKmuub?@2@Og#QZw!V*Y_3 z`;&Z^Qo|W!-FdFA9e$fdwR`HJBj*KMKUFPAl^;qG6hB6PF+A?_lb!8HDCXntKUj@H z^Eirbr}jyH<6L(!^t2knbzwVPGvr`74a*t3>1racvn$nLm1% zxJ22P1#fAS(Arq$%K64c&N;C?9Wk!}8SsjwK8PX>Mo%QYrj-F&$ODtXQir|X?+h9D z;RVB_(qNSbKifa<>t3^0k|5F-{+_b&(w_W*&b4qVOrh7IMX2&h3%F0j-@&UbbL{eZ zrC3j2r>FYAgHypN4UmrU$<*L8J0}HzW96W=bNP?d^UmC^bI^vk&=P&YY&1IOvHNS{ z#QpYnwqx__ufDcNw)x7h?flbMetpMgsVKxI5H;%ifWnUE43k=d-B+fSJ%=1;Gx~D0 zoFF4<6Ej2_bD%_^G?N)D{yWg^H+%a!C=TJ$&MGT5$h;1JTG1$CmSy43_3M{a zBmdr3q`xX#QyFCZ^WnBNm0yOSMS?eQa`d#K!!?yWG_B%}abBO`ONtA^|4vWqOLn3wp_i@yM=edNkWN?4SQkVK{6ir|zAg3plazViSFpP$P} zMYuVtU!&ybpz~~1Q^*Y{M(}84fU)>}{nZJN`ZB4$=id8Hp8fT&?ZW<;VXZb+Y1%QI zcQNmSi-utEF+UjEh=MQtg%tZ|u;^pvDd#U2E@v=XAm)&Xmdd9NH*`UPaGB`g@b(F? z9AQ_b7PzFMBNYwyfyVA2bKhElwAC|klq*aOaGMNCgiG0VM_ZiyMNl zXa|*u8z6_`%g9y9M()up!Sx}pR>;}hP3@hUpW0)i@7uU(k76*P_Hi@lRDZP&DoPAv z!dKd==?N3m&qBXc7LB#ds2uoeb&(el3jn4~nMJN++ zuPQ1^9Z*ucRMluwjJ!yy&}Og6Oh}iB9{@WX{zgDve`0Jrvai|U9z~x0BYq#+g008R zl(J*&+O?T46rsXni?I0bwpPu_hNy%~j%+zs+GfT8-xn%<=FfWE?w;%H<Nd9SJmO7!5C12||iznXLO!QsAd{W7HP@>|Jp$#>dBM+~D(t zzgRF~-r_%cArZjOXWmw281)mmcFxEF8D}&xi!8*2DM(GGiw#*dejrUo#Lq~qTya=Y z6;q)6qu)>b_vwgp`_UD-usw~{A;0MvZDX<>G3juy%T7Sc zHVNQlfA;z=`UmVzC*$~DEr`3W5Y*BbDAZos%6zD<^j|0{3 zz#FXay048i`Uh%GW5=z%^X~_{Pxp--9>1&h2=Kjzj~2wd#)F^az&jtS&@Q-<)Wb1| z5kwhe3O1TX-5O&dDohg7Bm)t&@B%4~7j4+?zL35`UfVZy6V5~wRR*h2$2uI4F)}vk z@AReL-?T@4uiAnJ?*=g^qRdCV|9?nBC?=;`NKlz!H+Aq*T(10f~ka-IjV5Xu*5KbK43Zd6ORt zwdMiW8rw)msZXxB2D9 z`KltPb>A3=<4|J$ffX$@`S5mG07YzYs&j_$%u@5z8@ac=T~lR) zKwnbH)`SYd#VX4XhY&?In2_DFk9v^5e*L!|!=$M28KlY}OEm4D9!->f7|DY-dStTr zp#=}rqC4UqGLaVEbY_nYd~r}O%enj#HkWCqLgdQaUj~%`#}=( z6%iCfpuzfI@Pz+=v}f4~fe!iIZN>`_+aES^L|cfw?1VjbZaan7!~J9Ri+3uP_V4nV zoalG&Sik%B0CX@~fWVA8aXlQIqp-TT~(_WG#dose+WuF12Zfv38_5 z8Vg)5&vcQZUwoOz^FtK{Z9rq}QB6PX*a%#Su@pj2ylq6Cp<(>+I%7Mejz>*jS732C z9n_LbE zP(56_ofaIeenI4ZvaH~krlXpjfkKj20?V2Wcu;Z_|L`irA%q3-@Ox<>1`d~pUkC?f z$${2w1i=A5a#45A1y#U>KvWf)&-Df2JKI^Xwfyrh zv`2kSFba}>sKacZ6Gm}R57l3&TImWH&xkK}P#I0JTXoa*o$*7vv&SW^0ac6&3pV%- zq^0O}-K3q!pmQ%8#_&G>uy%pJIPh7jxJQ(e%LD##Wml$m9Y#ofe!P7f1KgLv>&6bncs+95;N(yR$s?mc92_=B{6!jmLml?u-)Nr} z0YpkHfy`!S(gXszwKtSnpvrp4zaR+en5DJ81vDd(mp=J~usnjcKK#$CUD-TK{A<(--= z5_+v*v%~s{%TsLv<|yDs>+KG@+K*&tq|)tHMI*pi=gm?>X0|#*vfh9@#DvRU>R&2d z2*PqVUo5$8!7I3>q1iG9tai(u$4f6zE(##KgTiX}z^ z?RPf6{OYUdcOQSu$2RXi`QHSXq*8O0#vG!n@WDfHi(V?O5f6yj#AQ>J5#{@s~ zWsayE50ZZ2V!GjA_~o>qj3y=;iK8?LG>6Y}5UF5iy^LF<~53%uwCkSH=I3MqDie41gO# zys3)n030Moz|g|J|;JY2~0dXWEL{TH&$ zvK$^5WXlO|vf*LprEAe=oR%yyY%R{^F)4E$CiT?pKVjlPT4WVv&fq)VOq>rvMYq#g z{)*~(1?$2Vuj_xn5ECa9f&Jq1FHYY3zuxnDJ@f3dClA}#gIpbT@IMv~SfDb0VkZ;F z|73o)RE_XXn&9|AV=-XT;T_Xt;6D~A;#Xj7FsseRD?j_0r#@g=J%9WU(_yK9P{QkE zeltBZ6mKl1-Vc0lncF4@8z6OmyW!zZ_ag|S^$C#EGtn^+%+6&A=5R7v*6U7fTb%5^ z?e-uaJ8ZJ(Tjty_W5QM@_Te8FWa4OtKl|C;ruK@3kGh+5ljC(Zm`}W2jx8K%0QEXT zf-$BK`z%%4jJjhWy4~8Sr15=j1IoL$@CVD&zkJ#Ul&B0oD-(R=LV-T}<6Txra=hiV za0!(kCKp{sZ3+H!4@8?RZ6fRhZX#WNusXooiNTR$dG|l+S*Y?phaD!@`xwofxS-AI zZo0Ja=k{dTMFokGaV~$YEMH;MZQ9)gKinK4CnNb8Bpg(LA>ChTFurKQ5>~5%+jovRXRe#9z`h)_X2*ko4 z{ziYu(nKI2p(h3+ClRUH;mTcSU_@)2h1u)wg5yLP`Q!eN`ioihtQD?u8bzfsT=}WP zbI51hu;wUYD(9lyKbT(Rg$#{Xr9_|e_7@Ax(Fa_F*>5x^S2u37U$1BJE4n}X{8N92 zhqc_3r=O0An2(93)!UrWU`_CO4r_*o+Z*;|L_mszGs5y-Z>|Y;xSfUF)Y&mF%jp~} zoaCx(sX!2?!++$l@&N5V5B**@$BUxKEJfO)eBh=TT$EA+z8(eX*F>Xiw2?E|o)mdDKBWHMQ^;{krHRM*N|rq?UC#q&id&S?y`5 z0DN&^f8!Oj%7}`4(OKg{<$3`khq`(F3`cw8K$q(506#HqTf4>bVn@(Wkem`nu5GmK zWKguHV00M?*K~~MTu;&IY<3F&ME$)aM6p#idW?%$ub1UXIsX4b&ILDWAPAxoaEIIh zB*Ohq0XY%%s=8)+cTunud$xa7-Se}ZO(-M%#=l0u{pb7q58}qx)x4=uePqcz3BJRe zQ*A65zDM~kS4QXB+ zS&0v*k9iw^PSC(6>+uz)KUN0rx+R?1<5QB>S6$Pe&aR z7p3Q)`j39fi@!JVP#j~%{d!RgWc3ek-`66QxHZFsm>l(&HCC3Pv))b?9Xo%LDK$x- z+$*|Mf9D+Eo)bNvX1P7LLYGIab#>j>{^!0P&IE(UFdN1%H6WUEp|OtQBQo|TXS?K; zdEfnij2;}qpct%Ee8Gcnj!~Z<^PKSI>$lWqaV9^|^VcZ`EgNwLpXZ&sZzMT!Som(% zm8;ZniM-mwZd+oyj@n+4$Nj-~;K7c~%#`b(*7F!dS#-A+Oz{!@@BW9i^sF2Kt4h?eXoMa`La+;4us$}j%>mnG~!jW3O#qYpmJg5C8F2}kBgYT(o-f5(c+ zbmu5WR^QwIVV==O;IM9d?91=g8)2}~yY&hq`9ziNgPQ!N|GN*Q)PO%&9=}^(143#V z%f2FzC(fCVqg&RBT?buh>c@Kd?)8xTslVT|=s6vZ-}RjL#*06{aG3o?&e)!?hdop; z@*e;B1*2yrMuQJTY8P6n{JQ@+sUM&ccZhY`^)J4z&M%)kUi`_JBUkLC0t2NKF)fnx q555%}ss6*=j%s_{$k6vyL;f#r4t5KB&S`A`0000}Nr2$)4nYTZw*e-&1-BjYfA`~C zwY7VzrUvfx?LK|3syHXR|^YAH)|*NGx%;%7?}4ka#9~P zymOA%z5L1N3vVtqGc(sywURC5Ps4XYUEu9&n2=`W6yzj&LjEGi_9;^TWY|?~m6MeP z8_GI5vdPH?6QJOrjDIDKq2Qn(!{xF;`x!0-cmw2|Md(X%||1Sk~e69dRAj6=s@EKD(3xsQT|?w{+P-N*Q382Kh?}I5=FRe+XI~sEOJibVG0#lB zLv~x$Ji{h>sI+`_{CL?dgWHN|0qL$w8K;47SRf(ns12CVpEYl%^LVKH;Zyv3g2M-M zPT(G|^L7P%%lVX?ls()LLqVl5IWpLnM~E%R#{<2&7vmA{kk1%|9iP8C|X)`?RlNBV?jeIskn!b zgfH}cL6s-J43!%XK7&$0Z7uGqVgc76$JLZ1BP*-LJa_r83gT8H&_+Ru_H2(fk<#AJ z3yUQY-n;b_2uZ(8u_lMW;l-8J=Jz^Rjda$;g;1-?lO|KB9GRx2=JS$RfLHz#UwC4} zhEj2BIS;)$#=DKYll>^ajGxMypZA%)D^ZA@7weObNP2i!9~1tIGZ;@MX=X;#X~3K; zOG_+f!V)=_(VOkmHS$Z92C1{-cAR)Tc@*a*uWdsQRnIg>LuV|a^vC^U@x${de9giK zV2o_uMRuuUUaw4-A5)1URy{jenu@@lN&@Th1dW%lOaM?yT@wB}9u+SHk-S6pYaOoY zX9=X$hHTcx@yFaOMaI#VT2%>z-=1ehCQj(Au)r!A7adfZAC#8eZpD*%WwtlOk+M9a z!??H-CxqzM8?(bzo#PF6#`=lYHmG}al%%w@$@x1M2!k#ed?&_PSy?j^s)~xDvz7|r z@n*iM89b*mywkFdNUFe}Lv>0b*C~`BW=>d$GSk3j?k8&n+vtlf_)%|Tb%)5yWCC(& z+DQbS6E5J7x&#N#^{)WLvef$^0^L=H!=|hN~(uXr;`mAb1kyf73vd zVMy}5)K)}!(@TiIdP#2N7s}x}(TJF0t!1%7riAe6H(A<;mL`+Ylo9*&I>bpgKbEr` zw~5obukB}D$eYR&-RmAcR*B5i1gr8>GizNNw?+Zqyp+j7CVNFN9UXSqL7Q#goW`?O zx)hdlmB_S51Lnt1_ULr%E~eHIrD=^2Sb2z8cN>0;ax`Vm2R-u!`B#NcTNK5yqFR>* z##?y;rGDUsrhUSj{`{enh}70p>XR17-udjEyG5Lnq077M?4#u-2O((~$CS}pnkZuV zimJ3uQ3ahFx+b#tIw-MI~oO@ zBqaP1HI%)|t}mC~2%AdyW9fVWsb)YVP20$5(Ltaq|4(g4|7grP*{yiZ84^2WJagbS z&o`o4G50HkIPh-Jvg(UF!AJT2u26gzEM{~U$bz?@&*KMdhuI58ff(7-dKapoCniDdSl4V9wte>+g3_>;D){_yuEA$DhRw-w#FC^bw5@D|OJ5 zvAXkgVW*H@26u#vh$C0`56cqJj}&XCQ#&web`)ROW8A9s=3Z?-_m++=aEN74N^RkS zh9I08C8jj)frsjWTGVUbT%wl$4m2NR?y)u?U{0#uk7QPS)thfHgsg7JN-Prb*=~9L zB}y3pOGndx?0f375OmCem8f7mO6=|USED!rqsfFfv0`O>nA5~oOL(B1Di756=i?YL zRZa1P+FG-ZzclR;#)UVz-TF;Iv+aDnNL8)%v}&at>FfeUZdUgVJNBPiGU0oDuRX+Q z;KHB~f=qimR?s3_95^`q_r&;}V~MjZxj%TyL$txxg&;|I2bfWIa(vGEqw``cS0uDs z4EION+_9JM6_!x`WDa+BU8mD|Vz+Q#cQ)1*1(hFieP1x_(a^7W^8R=10%@ERY_#9MP3P|nW`&^ z`_}CXE0d<<`ErHy;v~)5#W@FLvjoxe-4AihGSldH#t2cZC}5nA4swjz{Kjt24K))t zlZ+w(C0IqEH<{2JmG|&fLdNf0#+b8*m|{OUpTro%34w_%eV_m>>3S8TkWmmhb~p1s zh^n5Ryo-yfUvPP4rJ|j|VtCeypzx&K>#>(6r8r&rUN3gGjPap4y*`$c=R+C$p7^~Bw%vOogf zr_=}+>z(=b*IwP~sN_!NtLDf_;{~Ci`n!5D%U)?0iD`hauJ_f;qYrhIN{lYK^ra%> zac#h((jZh4I6uXN6feme&4!d>Vq;hI{WSeEmQj`{}gnTV<4N0ymrVc((V` zwDvC#c_u2=&vL57i3p0A^Y;EHbT8L`N%@@obG1F=jc2~rDrE2^MVoy#R_4v#@DA5h zt}gPqQJcsU!W#m9{ZW*X+W3-^1>JZLsN-eEt%H==L}5?%Q);@Jc~-y?JQ6xM<7qC1zT;dQ_W?< z=0!KC8INsNKLKz*%o*V={85;)q@sdg^HxsDX=yf*Gh#fu883E#G3Ki;i_^p31BE={ z*46yt;$lkBYIe|m# zEXi+@x-BD0dcwc^ouwN!5a8ckIZ%5dS|vRVh!K_tER1b@36+Y3hC2avhGhp%^m%nIrZDwXp!Hgw@ z>Wi}hKpOYEbd|&pSxR&`(1u97LJm(-5)H^NH*Ls;{P57L*5OF&^XKnCrJ+yly^Pf^ z$~5_;^S_g=)gx_u+SsP{rUy*})s5CHd@3!FGG>)Eoe7|*{(yP&*2X@D(^doVhm3ZE z7X?FmmilW|RaIeAQ(kg1V9n8W(KuysjsToHO+UfDDv#^1&AE)Yu4Rak-hIln{US0= z2|^EraXVyUU=6^F{h;Jd&;-TVw40dSW z83!Uwx||DR51r^Oj1F9ezMtwWlZIv@NTa|A6`+*Y)%`86-JYq>f-a&Abbq)9271nO zJPB{9%?!7lD%6_aXq;%;a8*(KpS$RGdQJkwf1U9i-p1p?oJEglE?0%UjoXD)-1?Ul z*{J^GR#L`_)13Jsx)(z2rcn_}?n`~S`3vU%;6^%g7Y zqO*CIt(Nr^4U3#Np`~Hkz8^VMxNwC`@KU4;OOcwo!%Y5D1c342CXk}DUeC**A4b=U%ddvKaF`d;OV zYa&2wC}3Ad*1SA{VwowncA|5+DgwHHf?u$RLwy#;yD3K<;F2ztS|b;34FHdrBqYz1ATFUh_e$b!kc$J)r(Ixe4lQpVFi z4-9p&FlOO#>}kDyYystmJad`gj=hpcWBU^eH4z+Bj)8)DI$vHnu5)!i4Ryo6(iqWZ z2-IG4m3s5;m%a{k-fJoR!21bhoBPkLrA(5@To0VzhP^&E>YED`tuR7`Xl{$FEqb=^ z1*5kz5^-|^Fkhl3cb;$ZD?xO8CX{WIv#oTkmjt0+l$hJQ@FvGL-Lw};;H_~X=jtGY zdMkvRCHZsqJItmhb?>0SHg$@$9V0HRt8-1D({aS|JDiRyE<7W)zQ^AAj4!LMVD|SH zl}={;PCIK?24jOj@{5m8-(J4`hBdpWdf4l-c+*}L=QSg9I8P0Pn~rdsKSi<4_1e{a zk4i&YBDa~y&Z4f|(F0V}Emxd5w&fdg-Rw|v~Qvq1O^6P zZjDucFE10i8Z8(O5os^H;$=q;Nc)|hRuo5qvGt<7v);14Pl7vVJd%b_ zNKb4;4XANc;!Adz=?U#;uepfh8AL&wb#G$4x-=Ec3pMvLHVmZLAEO7l3QjC6w&~S? z^QG%i6M!&=_gJU7*v0M_f-0OzO*ef6G&K-|*dTj?D@fwDXnVc-J?F2okR8?Y2UcM9 zX_5AV#QoO=FJ4};PlKj1UrmOZ7KnZq=VlNi5Q1wX64s{&@N4#Pm%1b?&ay<7e%>AFseK%7RB^MuMY%YqsiDXpo^FGR42^G?%kL$wh&$8 z=|ge^T;yh!iAgj(sWcMMAcAuWFECggiqrKiYrvX_3BEnVTea-3yZ#dhnzKIf08P{oS+r65Kc3F0)ks6E2_Qds)#7&(tvkT!j;S&vYyJdID z^RqLm_ShS_%YT9GrA{>tc%R_2{jR0FcqhmdbwB-VFrbNOKOpk=yEGHIM(m{UJFz>~-n7@j05D^yoAO`; z#rxnB?5&qew4C^OCidOFj>+VfJMhw|teyzo`MyI-cNdyfyBahs%XSf$9e5Lv&u*vn z3{Nj51ES{54$G)F#-B^$k&D2(LjtoL4Cp#{9}JsJ7o2=P}A zRl-UuL!=Jrrjf{z?N{5j(T@L2Pu1b8t8YG6A}A7npf`!7uwDwanX1@?vgjTffhpWZ z9?X!eI>5pI0}ISIRS;zi$ln5VGDNLpi)8G;dv53d0~r5jzPR)p?vGVb4Vu%J}$r_z(TeA3l6< z#cBE#nxIHsepFS(EtZAY;vRI@)p5WK3=BN$b~iK-u;XFfw!`4!l8`1j69b;@=x}gh z8QHL)Rfs4lz_Wfg@#K|o-?no^IXwW7x$8se{VcQ`8wDc;pw`vZMG2R9))#vNTglkE zVP>yNHvj<4wsVFvaLrfr0P>Ir1_Bd`-3V|;EE2%MV9Rz=K=P3OqQ(2xNf&ZqvpA@D zpn1(;@WecT3ua^rSg?iSz(5PF>ADDN$I8Bvm?5Ry$8lD&CcMGD)^TEZ={WPruW>o>i@c(+!61z(VsCZc|4KbB*7L}{tI{>0MB)zL#jVtRu6oqOh9_hwUr zd5P`18WbBdaX2|*e&Gax*VV}bHOOk(XRn5oImwssoTc@Mz4zl0ASJ4fRl8J@c2SDA z7cXr5|FvPvKRoY!#pFi4^U$0G#gl@awal##d5*tQynu1imEV!XXwlxCHJyJ^J9Pz_ zrkk0HvY-C-DG+F%KURRk>z_SK^dKrPUB`?q=ckq6y^9nE8Z0VutEG;0NKzB~&+tg^ zr(0ssp7OmgxLI_cP{98lC0$;IECvqbmhE4)vN{k;0^AW#q#EZSS2gEA1=VKZ$)_3jiT>g7>(G>6J2COo&@f+xA8>v`O?_Ruz&y6Rx(?1p)k zeR6p{g7r<UC$r^xCBm*1d`)LWJLt$SDdzC^6MU+$NR9IRdd8S z>!x?^?;*Tur(+~Vpuh9hHx1~joj*?%z>@!rsoX^jc~Z=b&1_n}oWfc)lfN3{imd0l zi3wxY-*=8cZ7HE%<&{&H@6paz=((WOX1j6LroW?L3lg2!`;#$=oHy1vh4QA~h{Kmt z^q?EL2<&)Xmd!eLdj-lfXV<065=Ged6-qani2m=Mn+0Bz=apt6U0(>!W9LO*qk5x} z+n;{HDU{sQe%p^|3HVT^V-u>LkM_k0cJX|CfVxZ7_P)Oy^`!}! zh;sMxTAH%nNY;7#ll=E=R#XlJR_+e3D)e^vz`O5sl%WV5mK{SsWP~y(M74$OmQ69v zat~Z*Q6rRv)3&M|qW{*AP*Y~uE!8bUVyh93IU;<_$cYG=8}9@nl&SD{N>bDGj17Si z-CI|#a7vl`mte4@hA0VSv~6JzARQq|!}iKe^m1K1S#s0&>(nzD#`&q2Z4)lf+h?;j z_sHH&&s+caB7f*>3r_!B)6`ueIYxW|)G?|3cUTU8x^h%&A7ipZ1k!>r1G>dXs)kLD zd#qOr`Fsa4fLOZ&xq1obD-%Vu95@*wfLwIIPoLVJ&W-!Ou@4EnvdWVeplKcR3cFN* zAfJ%+4H3UFwEFx0+-oCr>6%*LeK=Q=A9tay$~$n~SwO%Zx-B0Rtuj%7;!8sXRD`N+ z88`BnCOY6jX7ISfyl=yTnt$?8IyT>0gq27~P%0oQYyG;@-#cceJ$ME1>7)@CAdrD?( z{*K&ZFn@$ay}|y;g}{+qzSXL(dH%23V*~P?dT#Q-_7BF$l_5=a7=h2;IaKbXuk?>@ z^7>t_1=}1)&b<%8M{Twgld4SuTaWAyGq);i|ZL65f_byy4ga%QfIHYU=3PbaVdEDXhx2O33pl@Ryz0zNdS-lz|cdm@Trx!DrcOQKA?Y1485>&?Om%mO^rNQK0+btJYm+YaqpK(vK zkhcWpY{61Tf{KOW{&>W%sj8h`rkfe;A7i$-Rd16G`Ra>utu`L!y@gSg+4H0@slAYl|MMOgQ4uNK859JxY3=c;hLCXcE{Wq9EtF16Z%slBip4H5-WU z`hP_g3Lt6bj;^jFv}44f-qumW+MmwBsS|K&2u6@Zh64-LTL*)?K`Qp|2{;Lm)8a)M zw&G%f9ct~52#U$FSu{iXGn_~1SPbUq@c2?-^-L+K7_e6HI0{dc8O({#`Z{c=Up&rV zJRGCRM#&2*DHX@lbPdMVm`i?dgTCp#Cc$wy#PlONAw1Dz>r%*%8aRq{c_@G*wI81P z1@#+SJjQ64-i__zL5nI$aD+}Mcj}d(TY7=9Wn$-E+Ww8hXLj;~3Z`IZRlO)VREwgd z1$32UQ&EI**nD5w-gSdJrkS(<-3u^AV#@jjLs3-fyGjyX42%TZS5}^4PS0w$z|VJS zM0Tw{nmLoSkDfx6I56Mv(^@#=j<;9Y_QS}y;#`Crt05A#wLA|LMggyF;%nj-5SU|$ z@b+rkg-H4>BRggaPw#~iIJsn@2VbtEvqhqfqSiehYP>SN^j5uAIVvq;P z-$NR%ehKU+<7XcP=pBz=uCkFign|Yp4Ttq!RvHSn+h)2Ij!Z4lp=U*&R3)Y2_+0iMYM6AZ1MfYI4OMBeTk|Z>z5VIT8`@Z1FFyxIWzZ`H(BBtxdAQzX=usWB$-b5mHe#1qKy^7-UYF&t6)#(b4rMm_mNp zeQ~ZC3R2|kXkyx;%5C?aohCp3cAe$|4K~|2kztaR)dr-TETTPoqwu=@QlP3}DyLd< zeh~PODPo$9z=xx8X8TeO33;i3cdO}BzqE|EzcE5e3x{9KP<1hBlhbu;WwY@r!Fl<3 z+JU-ARgO8MSK;@y?UH(ohK2|U7=MsQH6l;Kb<4eTWIv$NBOwAKGSRE`5GV4I(nwa2 z%m^dMN1&H((&NELprCMg*ME3f^WFKEcSAuq^=tWI>vIKFwzx@sMCdIx?R&ZE7*6(> z-ruv?_R>;>NqCU-AL1s*Wm;K+N@5#TjHu4@opic*xh)2IF3U^6vaf=#d$}yyrOrCkS1d&=gcY&g#s_B1>Q+R9wia?ih9q6 zo5@>G?`{pwXVeWS^>eq5q$xLzh(QHOW!KL?!W;1GXwaL>k_6Mo|7 za0Y@6!Op(@o9F5|V4u%mb;>KeyujS$XXkwx;N6}sc$%>MOn-7JZ$O&OdZad3jwr&? z&1|_mugKqdVq#>~w?Pl$Mhlz4Zrylhe@n0hB>rCt$p7bQ;QvqgdI02!2rXoZ1hL;+ zHI=^y_?*PSroW+>WQNhv(K-V}T$25_3izdzkB`sWfc~5}50Iw9vM%IgBB4|tQjC$^e&Ykv z`)DcCVO_XNC?ySBk1zjqBSrNtwesg1~k;9^Ba9$!n*w*R{wb<_sc9O{EQ zzCjEh6~d%rwari{<+7d1?u-Ng6gbn`rGj-aK@w7t$yt#yi{U?~Qp<02CtJ;++KwD} zA<+nvnlXO(aJWby27sTQudUz^X!vJG!HrFmupG-4>oYSFfTUqr5#dQ1yy!n4Y)42+ z^U=eHd;d+-KZ6;&&YGTMRNLB`2{nSV1sOApe`Suiqqf7mw2D8h#Po^sh{L@<-c}9s zMYjwIZQy>Yj7xUN4KsFHpF{gE^B-w6 zZRnN;A{*%zLfnH}K87o-QE1RHBU_8=v1ZED)4Jv78PspG7kIz^era`6B$X~XF^+Q` zX|Sr#)Qehmo0I#E4|OcL=Zp7cho^yO2b@X%vj*13a*|Lnyw1A zcSj#sJh7r}eNrUm*5`yuVL7jF=O!f&3DnS{GK=0=jd-BXx;_sal%<^!?fyRO40#mo zI-6ZvTcegj`dDMcT%=3EE&1m9K)y$=N-q@AQYexA%fG(MDt&&I(QtEfdj#iJ4=#8Q zjlFGv#8hN_c}alh^r#HVYQVZ|XOM4Qd0YE=#^;Z9XF2xT;!@^7`P&b+cJNTsaBQhs z4SZDi^Vm_6Ec#}k2u7b9*qsMXUX}g6Zx5^`=Y7;oE?e8!J2MO`GMEpB8HiI zb7O^P5s!_bkhM*Nn}4iJ&eN4r>xO}P)v5Gs*~Aqw=5+;=`FqX-s<*mjvcd-cN7jer4=(xPgH|(-Ad*i^YAOV%bfb-B`(3nL$BI%-jkIjg_5oeqbSx*a|K5n~X3G z@}NA*@MrM|6vREy)&91J{IMX`j7xzP>Wwtma>TEgFfeak4i7&cVyR#4PIuvrM9gh1 z&9fl3I!`bo^nU;z79{DXD}VfeA92Z@dGyF9&{bQqDNQTVx$YqMvF>$FlQmh=^|?Od zXuF&ttkns*&8W@RM&Wr~7u~1hOgchB`LklZ^EbLRfS{WQzCusN(L6M7zbWl= zrJylscrc{18;u+u6y;V)vzqHkL*UbVNt{4rRBO(GkgS)7=ILt z%r)%$noa;f?yzja4ehyAxwpUx=_q4j{Fb@RmxTKBeG1cGu^x0OP7pt6I+g7 zsT|oXwQad`18^O6oN-L7f2t{yLep+a_|vkeV|J4o$b zL8mi55)s=AG8Btp53G$ds`htairL4NdI|3_HG}@}pOUj3P4$lrKFE4@CM(F*`-?`vtR$v(&LvMOvFE*V^6U9*VC~MQz}(7l zqNF&Nf=A|iu4@`V|E#l6{%(I0wCl53WE6iN&(U}5W7_5`&h68#LQGy~9&?uq`UV|; z%@fsa?Ne|2{YWNV$N7+0O`T}tS70@(k=)*1&~}&K%it!Je=wOSf8 z>jf;J%Ux^%ffoZGS{1vFKqieVU|rqwV`VonRyh+|9|ovrbodhH*UnriT0%}2{nup% ziN~VgGm=+I$l0tk<}7}vFr|2Td(*0}N>m8QGWD9w{k4fxa`23z>?uS}b3Pi3*LYMh zym~Lz{y09qY5#D3h9wg{39i;muiat!t!e1919 z_!Cf0E|KJ1a{3`rc4^=N74E41WrNJ8ZI?sI=+!FFS928*Up;G$Zy#{SuYY}spwxQz zgJq^d7~mr_dl5DK-{{;u{pz;ed%?4?xo)A?JU@dY)Wc>+EB1Qg{x(a_Fu$#u-2iDrvr*=&Ji&5cRkmjRg}OvfO?@QQnwnItn6sF37j1KVYZx zW<9Fy`4zQ!7>q43P;Z6_+R8X#cTTb=t^gZ`xO=0fCt7K!HrY`FmXpYb5#X{6g)TJWILopN3JOP=7dI+b= z|87(u%ODCTZJV@g77e)MV67%SiCn*yigle?73Bc{A_s2H8dLa5g=y7ZHY8Ez<;9I! z;3;WZEAIjhMnHI}7^KM`D;od^V?8pMhaPbKtTs{q2weyN4NbtROc5k)OF_YlIf@4% zk2;n7OBJ;gAUT$Ryh!^2j!f7#AUTiNY$Zra$~7d^jB+|%W}Bq!Rs&X3N{Z`aFK0i& zDeXHOJSSWx^M_Lk!G2NTp)tPPrnne8S{{IlSbuTclQ1H_1In5Jz`gX<2duH-B%1nv zDP|ohIpI@8vwzSlp>;$=aXa)tjshMn;r?YnZ0*nUXodb#KAPO)5$N&zGXr3TzirPL zYx?nhKi4ozor8Li81GcRuoV(78%2zRpU-Gc?q1kSrD?RX#HdAEfHsBljWBGq@ z8b%n+oY8H21yQ?ManMk;g%o*H{&RHqLInl3oVlOXJSGYwoHFc3-)Bo}vCnL?h@1x} zVG_$)xJe;X?!q=xFSrLQ&Ta2Mz3YU=(kbGh-r{qHWHPi)be+m{fZFgS7w`i@3M zDVLCwHl)1l%0^Gh+a5bU~CLNh0N%Goe4a zFMl_7n`eB&ShWUv58A(kjTQ`eWS(O#K$cg&En9fOP0}ygiV7_lR#6{5&aJ8-O48T( zuUC~}x$i%xGq5uzFii1X8AgO<*`nw`Ogdk!kZ|7e5cv@9x6jUktQKU==WAf)OI?Qy zIT;p{3-_fCN9OoFWKJvB6oYI-@QKKPLQWtD;r1MFz#;#0_PAe6CP%=BR1;_>ysPLu z){LWS-SFzipYkaCv6LnpBxqGD_RT25JAV*VuciRaANE*Eqh`x3bs;J``f(9U)9 z5buBULu~gVLTyl)WvKcYm$0NOo9Xp|dsWn%q1iw%%y|9mZa1i6KPUTahYUUDrt{OW zMb+aRa;x19@7ncM>GHA?E(t;IYly&4L9cV~dW(FgWh? zbz)yE-2|H>Q8oV2SITXPjyw$v>13*&xtlRyF%rw7I}^={q2Bz2OQH~lM}EDRDu9N} zMeMHNQMuLJeL;8H6(mBV+?@kb%AVq*T1D9pdWy~AZ%jz_5*@*Mf3Xk0_M8lweism< z&d}hYAZ_LPQUr1SFI&xU8E)e_0e<;mi=tvB)xRdh>dg1+33ASaUjjL2iXH<%vH_AAtBVsgPG+)ULHApx7P`e^mF^N<;kM9K(|>pX0K;`x9(j zg80Z!coOj3<-XoE#e&oF3zE}W2v+TE_5{gUmW=)0iSW}65oPzI&J!Y}&fV7K@{ETq@)s^1y{l*bEI$Gr zCu?A+D~Lon;HgC4{cuy@JXn>s%#KmOl1ZNaDYZ;V5zBH%F2`$avh}H$%w)Ip>FKB3 zpJNua3|Btj2Z9(`dP3WpV`i^Wzt;VY>HtxGwP}2R>gOA(Tp}fOqp#MqM{>wg7E_O zvpT0*u7djKlm#IrCg)w+PWEJn00AU75tO~Gxq$M?wy53MoX)Z~l>>AMG)=*wrap@^ zG?%>3xJ=||2_)a~+hxxP*q~L?>`*gy0u?}Fi+U_LDP;U3YV;^6+Ot%)*m6k@YI=08(UqP^cvDmRfi4lJI^8?z2 zpSfIbWmY+G8xZ>58awVI&eY6I-_>N*;jCSB6b4dB2?O+f*p{=dM;NY4i)Poo&wLIm zbCjg**`9#h0|qVQW`DCNsE>9^OEYI#Qv(Pnvm6jQ5L>H z01w8mo?UEgELH^`9vwXfuwWFsfCp8zwbPU8K7alU9eKL=a`43MdHm&5BBi3H=6vuG zujLpqbgqffRAyv-Ef*I~`81a81wE&6Ssmzh&F(Mvpv7U#mI`$xf$(@T{-)P{fI;qU z01v6fa-9WC09$#vZ?5}{9L&@GWDw=KCln$yIfj`*<=mZ2K|Vm)SVrw!%t?S>!w6=agiSqElP_zD9`iJaZ? zMkomS{-#cyIqI}E4-Iv7TU%DG+0c#MdT$DbUnWlcCvKt}nEkQLe(p)(S;*9KDpUYh zQ1P4pbVR0b$N3?XNa_45G~pvp_I7P~9dxS+oDtcMZP8y?7S6!kEiD-WZu`!IBv#H) z@z;2stiaAIN||$bkdQA{==49|Zcg4q@;B`=4o~Dikc?SQ=H(`xc43n7o!@~It$ylZ z>gpk51Gj?X8vlsAK3$R637 z3LN$62MIH~`uAzZ)g}kf7awFw@ApRwl^|Iiv!Miw>%;i~EI)(J&1vftd}U#m?)NK3 z4Eg?ClVY#_gQ0&y5z)C8VthuKO3t6ICaq|NCvt_FI~_-iS2ri;{!IT6xLtGeIVei^ zzMj`c*5HRC@fm7hv8Q6tT|bp0HVgcLQrFFjolc9h$)~|y3qc2_8oa78T(&Wo0p_`1IyKD|$JcHag-O@sx4}dCht` zN#k8_maVLKqTnc+8oOVIp~obaPzxnFutZvc*DY?FO=s0hOFGY}Se+@7Z@pg7^AlE@ zS@wdq$#pZfxX|QV>9@jHiGpilGjHv58)=< ztrY@cE!sRd)WOL4KKmpS!dGLk%^36|FLz*am*2P~rDWz!;m&6ponslCG&B}_Z3&9i7aiP^hAOOG@j2 zzMoQD9O1CqWYO4>hjn^*XbY9}V295Ymulw?r!Q0ywR{l2Y#h#)XL6WGd;)=XYZq5* z*V69^-L~t6{<{=(vV$=BKwBtl7u3|%`)^KGGerXg_bllAuaC6Nf93(g|1>Td(vV}> zV+-y7?_L0WwD7kVM_il@n)_elIZs~C)?m2xC9I(Cj9IJV&thBbJ9fw11gp7Us{SW- zMj+Yn!)HaUXIL*Jf+JWdDa zY`jC?8$(6daWP1CY%@GI{|pHKaNoIl|L9d<)>K4;JUsl))YX3%now~sJZEFXXMSKO zx#Z%+;`DjXX4I7v%iiVPT^{>r2i;+g$AS(CdOR7Qz46~a(1J?*)CwTA^gm=3ZEYDj zIk~}6P(yNZa-8DGHx_nvZClCx_U<3kjOauxTLbTm#=iJ4lE$4c z%@Z!JACyg$uA0Wd1{_5H{dHwk+&-C#F%}#Kec+%-KHak6h-g7MWZBpI)=JvyWZ8?*d5ZlmS4Ct(`x0(dt zMOWPGa8BA)4nSW51!r|y;vjq^&P@LLV-t|;m%761e%-I<^PKZIkH_OY@2Fagdjxx3BE|Rb-{%$R(K2@W;$;j^ZwP8j{(gI118`KIC#DtAlR&$naf18EXQ4vWbm9Rem z7|SY}D5d4!jh;g@GZB7%ewh>UVvpSyyND1!3cse6?77tmiXrmz^L@K9C>7)hDGcN^ zXbvMS#h4X^z8wraOhh7w`qW~IuuYED*}i`5`z?=8CG<%v#YUN3W&x(^zpQB~ROODF z6TO+K%c-56pP#2+Utj0b`*7o-%VzVhUn!&3+C>^dsZaZpv`4M2?tSt#iGRMqKRq?| z{MDxjkgeP&*Dsl0+e>_~8-tC}Yke^e902lYq?p$k9LR{rvYLkn@ zSN|$=k6EJsCVD}6<=gsf)=#FLmWqpUjhup_1waX(4lih~{erV?UrN4d|1f@#U|2OS zo-Db~%`Yrmuyzo4`p{~LtU$k_zFw!I$%pY)%i+dES!wC>AC3=3W<&Jep6;85M?}m) z_K^l~CUWqmGQpUQwDrc$tM}a|-!CpiH8eB;@$Bu+JqE3r`R0|P`+ zQBjX+fRedFCqxfy_Yg_iPm_+4Gq;PzBpCa0%^|b^(~K}`XjFZBdnt0YmVU*uqd9V! zdMgA&iHR7#iadNc^y7!`-OE+ElRk6tcVeDLg|)?#HX6kQjLF77F>sl9SXo&=HnDpe zN3o-EE?3EIwhlX?Ldym*F)>&$Erxx?_BlJ|2*FMJ z=$%>i4}YEymW}glz<8>EcejFaCsp}!yiwkmiFQR%5gy{^t*C~g?SV`o1gk#zWDB&GR^VJ)IKv_a81A;1arFI@IOmhETa5$RxmL1m@|>8wP%S; z=W{&yGC}W`kEa!Y3a>EhiQ*zw(*%!|il^r6$r|)ASY$)wSQuOa0=e!XE=ER=4g$$( zEl*~KhGHh1aZVq4h|+j%=*&J4DEvy^9vW0;+Di)CUO9jvN{K1@ZwOoN*R(C}GUp9c zNGi+Fl#0wh|AI?bTIH$pMYTp_o_nV5^71k?=ee9*XA*A|+q98Da-87fu=eupmBO#o zVeP}APyD&)H}B?-B1f!<3P{5gZulRXTJ>;Q$;r-j)umLDDv3%nAlkpEJfX`a&C4! z+kx}()^rdg?98Gf_N|2s@-m}J?L9!W)(`f5O#~bb4W$lLg^2re%xK1r)t#OB^}Y6F zberB%|AROTSV{B5-*eOL{t6C&rGB->KyALHelu{G@Mo%CB5A{=t>U9iNstC6a=fGd zDyhhqK1KTXN5rMCG<_>wbs_S8{2(N=?|j0CkBj@MwpQz)!e4ZN|MSGyJf7-h^?^sD zkjrM`@-qyY5hKKc<{lTMywaMQ{L?yA(i{8olAkO)h~VyW)i#vWVezO6v7>Tq@}O3~ z?QPqo+Kk)U!J=a0rdKg+S*Ioc&Pq-iXV1l6sH+zV_oaJm4;hse5`A1hh+rfSagb!c z&=gRaVejX7@-p}7eQ^cm_<^Kwh7Brl`}y~|^x@Uy*S|{mbZzJw(-JmcTzE;ni98km z;U4$FFPnCz`c3-sM&Khl4*xhZh`QFUuHfaU5U3vWo0Anu5`voJF%xz5E?dLd1wq&; zRaF9geSH@CH_fdZ&$sK7MDX(4jk%Gk@y;)N%qaT7s+4}Qc;C7$tNZI26GepVN5Mfi z(PAt`CPqJX>%0D34+>^}tlJo^*SaD)o}HIOa{t>O z6-CV0gZvTxwzxAyT4LfK)u)&z{H43MvK#(5)5N^2oieMi7ye*TF=_XARRtGP>{7xj z4tKGmpVgB#J?@x#=Kv$4;1c?cmgI zW1PL8w+`{grG98=D5F3Rcj4jeX(SWHmltl-ya?aBSGz$;cjD2#a62d(t^()mG`qiA zdiy9TDbbSLT)Ipgc*$Hgk+ZyP#?h(M(a~}9t)AljqfvS;s4j96XECau&CDsG5Pl~@ zAbp8Vr9@g16hzB6vd;v?KNB0d8KQmNNm*v6)Kbv19ug80!$VvT>F~Pyo{U4cIpc8< zA6bOtuzy}&p4@@6-(oTy0r$eeDXwXI>mS2z^j+3>=xcZ_mCa@qElUojHgPNgu$@R> zXb+fFrG`!|s608p`{|_I*(%6+eMul0kMr9JJ(D<<&IoO*0aEUWpJC*ezCYKkH5(^Y z-jKC{N97xNp08>5G%4McBUv!?@dRvM)2wh!PUQjRV9}`7gU(Kf)x5Cxhx2NlGgO~p zdg|cdKo^6hVs0)VrqGRCl+7LSc7@9CZ{Q#877UuG17yz41|_4|giC_wNp2>4WjkXL zyaLI}L=j4ipYL~NUx|PG9O6K)=IXSLlsj}Djv)0KeKM+@vDTE`AhUpq`5`QW{;9R$ zxg0JY9)CEU%7SF=tdiiac%SKOeF4#iiDhigCp5H{7hZ?!>bBNV;o%nFiu=tL>W=1G zgKn>2up11n6zNnySion92{zk6SJ?YGGo!aVRZzl<6p>VWsHmnKGnT&gPCWc7X00rB z$}shes{1H~Uh#27I0JEnXn>xhW5sgTU*AOvE?P_8Onyj~h?*24z<0kCyM6cS(hhwS z?h!N(ipw<$L=_raTeC9Vzdv_y%IA|(T~##?MYqOo&VTv%34Di?jLiOMbJE%T^^^Xe zTQl`!m6es(&1w404w5QD*87atCCb*y!`C+%q~h+Z6*`Z;;%!MhI~YwT%E<_^TV$uK z+_mcaYt*CID4N8F`17mQF=_fbH-}zbTT$HR!D-DvjKF8+C3n&o^V+0TxzQ=Yl$M?z z(JLvV5i2-@itkl=V{Z1%5wAfdvv=xxp+r&ZvI$N>7bBC~`6Y5WR+%YXE>F2fBwnoV ztfjNOX3_G$aSg3Fvy8l?!|O@^oEufDg*qC$qMDfX!Co1>$ zY$#-poUIf%D@WqQSF?1*%f+fH#N_1p_A?mgx_bFixVgFg47d{2e|~hJu?Miy8A-ix z%TtIdaC&Q*Y16Gg$}BuG(rBVsPj?(2*5u-!TkG~4nroQy@!#M4s%bHO&9wb<54&ix z`pw-2ea>rszRT7X2a)E3X-nltF${9MYkBDpG@hPD?`%YBi;_CbX6s0N_{3Nye>bW} zF1ORCZUrkuR-A;L$~~+@lGeAZtc*WXr8oC>n!ZmnJnVa$Kf46=PcGluB8MNkZa1$v zIcVt+B;F$+DAZtOVq&Vn9`QauLOlT8akKeIxh&jh(GNAIz488Sdf&MAghWKN|DH|i zrzg63L4$FVbbReMiQ|?W;gWoAr>Gd&-~XjWFQ-Efsiro^Gk^V!gFd&Rv#;Vs&o-WPZ zmt5jvj-a-9&@l-oTJ&X47LioRp}YA9_mV-!&~W_?YyM7==`&HLafH|X`TPk9kG~dD z2Q_lPAC`D2zlm$hx+!+luJ*h@n{_CWrKnH;xqGN=^>qK1E<-fQZJjEcxvIBN_uASp z1c$COCfmAc5_c=rb(-WxK{AG7M)LPzKy!s-auI=Vua>mIm|cpT0JgZGah6$z}pMRuwuL=mS~b3uWDe;jISLPdOE;FyR=39&QDiv32Ye~T_0rW&5h+6H2f_i6cTm)! z_E3KN9br$yWp3_w++19~FJF0oOwKo!ofoY@LTUK3UWCP1;m4NT`YtEu9-n}K;(bh< zoG)L(k`2&&kB(d*EJ!cUPfhq!pWYWVyis^2yI+^?7S5<-x-yUoz3IyQGwi~fe{AMs zXt5qKmEY`i%2e49bU!lc-uNUQO_D1bQRBA==tFiMH!W}$mp#0;0z1C8R`{{b-s<%o z$6&;dnHjv2iC*P~4Z2ND1!P|7boHB8Ei_R9+ft}&W<{$AJ$?3UA=UMF%TSga3gL20 zeuC#YG^A3T8H1!g=rb!9bGxY~Hb7G@w%@W!(W=`0LUH_7-blAI!I!a{L9H?4gt}jv z*bnp#hxT1je5-Z zLFo8FS&QD~*otY6g%lof?MO*#a&pwmv@!H1g=cB=?b8E#IG_C|?kd$uY3sI4goW{E z&#flD#m|JPG%M@z2*29wA3z1Qg1-^n=i%nHdYpd=oeSgoJnyEBi*D|<52)?`&9iy^ zdQAP({-*qW)H^8D^c};zZFax)pnV-S9URit25H;={OGmqIe?i}2c4tsncmBGZzH2? zkkkLv5wM0tMnySJqst4->ejnNY|u3H*5fwK4qjeei;Z{*Zu4K`1Obo8@7@iXv0brh zU$hef4224%Ei}gDE`(k6M-k5>wu$L^Cy_aqdZL>FHM6Atw836wi03vEZj?{ZyB$5A z=BXWQB9q$NWn>TsY$3nvoN*8}ze#D4uSK0!pZ~7T`MK{vOX%CX^av29N>e%k4h|07 z`eNM;#Lq1kc&OXwPR`DBBscBFDkg`9{M7QE+Iy#rjgQa&EHfsjrj~j2>Tb2Sh=>T6 zurPAMTVwOr5-diFko`44HOps|b|<@rOO=5W8%*`=n_jDsRBJZjEK?OM(xdBx`+U)T zX10^%0iIe3A+l+2LlHHC1l&*4#UtK$Z|G3;)@!Fc21a4`{Bm`D{egRt&54&dbaKU* z%aW>}#>d9&XU!cPZq>W)EMJksPpIa0?*ijx;N%o{?hQH>di8X~yBh?ge?0?kDlpZ! zH5H?E`_Q|8D}Fsw_i-BI4m_(z+~^lF3=bXKMqFEe*}U5FcqpT@u2unamOpc+CAY zbv-r!Gx{Y7^%kS8#JA)Hj%#LYw`G4x?qf;0x(d2RNyiH>C^M7H>x++nn3~eo8&DGv z5LhpN=IZLIFk*FcvUB4Q-U>;htoWl?q}729$8fJt85Ly@mOnE=%}rG51h#8!f0n1> zc&;C?+=Tn+I){1QNP!aJT=&U|(D5cqG?lp~zJ@4nqitBf*+>rd{bahD@$&CVB-gq2}UIP8cctx9Bn|6{LkjA&>lh;koA^4#|@MZ-aoW?f&3 z6CP@fy&->-{dYwfMF6Eg*%KhvCxpj0PrpL`snO-Y#ly3o49Wk84L1>EX_Q z?JU(A<111w^;rm@TUtV_)!6H!jDjDCG+VeQ)xzqRJBt4Z+i8pVK*P2e@Qm9C629- zE1-4l08vsw^cIFnyafjpRKQZ>PJF#`Q|M<0G@ggY$Hs1MHQBOAFN2i_Bc?)?E)OhTzYgeK zqQ{~3r|r1~427r4c$UqkOTBYh8`^%dT+!H_!Jj`9ZO!q`&CQ)FI#~o+X=EK8c}Yo0 zou;2e4cClW!LNTG9gVZ~w47xAfX%e(poM0+r~4b4L0t~AiM=2UDMI=mNPG*T zPaG6at6qN7Th9^gJlu7I!GIrkl;1D3wY}%ikC5EQHKj9MP^F-tP>~JYJ5n>D9`N9g zUY#t=oX}DvT6I49F=yAjbG$L$UDSE{xay^xTo6YD&)UGlBtji${TA9lK|>QbvNpQ(HYGJx2IN`}Pc(%XkF6eZ*3sO!UN%0d61l(>|D02!YeLb+-uwhcd_MSJ^nuaHRF6F z^+OUB-KXNY7*e81n!eeR4=^>m-uev!KcerO(;Y#z7?2u6_pY$i)*B zz?|N3#4T{>UQOet1H>qJ|t{b9-K4c}w587K!ezR^=kIvW&4?SU8cWZQi z1mYE+TI4jrs0pqh~e8 zAkc2tN+!Ncd)Im%+lGgSuU6fC9CZn-8T<~EVtd=cht5n6v){ahpiTfot{O+&*6!+4 zU}^z(B%?A)(P<|X4y@BU6D2aEW}M+VZ>m$nsvjE=!F8stF`dt z(m5~}*DnWBgj>BiKXku`#yhr?L5eUi*I;hdr5>JbN!Uw@2*Mh&vsIS&`sCtujc6NR|t@W5Y^l*Oo1RDX`0(7t+ug6r+za~S8R0+Rw-vf!JJ;o)1bx3+&bhAl0b!o7f2ZOKGCIs2?cmE)6- zyY92cc9^{D5G2k*RDi+Bsi;OxB`PW0KT9$ZDF8-VB#HEsL_lIqa^*8;NOz3TZp!D$ z_?#DfhlZwOd#2ubn!vYsX4+Sr`WL({t@; z86&%O?nkAX#?HPF0ubh^6;|;Il{My_mICwKgOj}lt=>gOT5SL5kizfWgjmc=MvXny z@bb3RcjO|ew2pc8{{>V8k~ez&^UeM=T+dcqjTeQIO%nUNgB21?pSP5uyI%n!#i9)1H%ggN)cZcv-CajL1m*85?Wqt?o^Szcz71 zjd^KuG+6$$H}7THQBhKU2l3A7b_BfLr+LKqL658VaUWLXtZa==?i=J>DQhqhe6!9iVjGg*=r0U-?OZQUbnWwbzT z6(Zub1Q7W}u7Mvub{vYfVy`l2Y^<+?N*49`^Me;JUN9#lD>1>}z`Yr|yHmiEukk$Q zK;0^!C0Oe}1$k-T_xE|kPZx<%t5f}ER)dAc&iVhm0E$01sZ7Kp_~-|yLYZGy^d;&C z{t3UjdaF11@>(}fZQX_zL1O2^^qZ!l=`_^xls*+I-w)TvoRu7wU4qWw+xE3ccjk5E zYmC^y*-gT4`h5cfH!05Zf^H9j4aEz)m>)lWZV!E;Kc(eg(S@!b)A2Vn`7tJlm+uvr zV?J+lmorcoU3b@k7~OBbCb@>$=(KhV^4T7+J@z|%kJq{khYpX?8-mQJpBe zirxgT4Dd8+Np^pKO>7)ymXti35Nn;|qP%mbb_W^76(O5d0}2$Bx-z&w$hdI)Cn+#w zrP@VMP=(xfX>Dh}MG%OeAY6BTx92J+L(`4g6p+?mynNYeRcQo%DiGDAg{brogluhW z-Vd&f%xrqOxoIBzNGAr5jJ$J#;DpNIcCpv#+!&?DLH5g5F!HWM@pRheYU{~K&9;vY z0B)Pa-&ZXQFOXg|I!)tBgd9vvPoiE2P67PtS()byUfo8RGQXC82? zEb~9CDj(4Ek>k$4Y&yFQ@|Or&cX5I|Be+|{Kq53WG@Oe$n-;e^FE1?a@=pIX7C8Iw ztha9a8KLwkbVYV^-vct=9yj};cZV+kj70VO3HlxiYi8rIO6H`4WT&ifmIe9!0)*Fh+w*wxly5e?({9OY@2%8*+RlK*2QK z2}6fph(+vxSl!-+esxT&zE||#;n!8e^II5FU6KP@W3|kq z`40)Ppuc<}AChD$d`PMSU?6x-khWL}Z`HW{11G9P9t=uEm3VJiyW@1BPy8znm8 z=%(}frZDq#Z_==^FjOSw=H=a%kY}RZfs6)iM4J&eBstFR^~Pje*i3HW@V*%w~)Bou5a&aB5oN>&D%vD1F>eMnADAfRM(z|*UD@{ zhf5b)_+1631*`Ck|LFKQp+SQ?I8m;joQ8(fs0E#I%SSr(4Q{}r??+ENAp@3Q>EfVu z%Tj#4z6c|TrvF8FQIR@NBp3~PlXIJMBZ4KfO>ytwYRbLx) zq57U%{B&B?VBy3myF`nnkccND^2-mTqP1*SQ&Y?8)vuK{q$6RaMG`P>6q;QdhNi_v zfK_jdH0-)deQKB+iD@r-F#E>}$9Q97<3~r^8ym!`9QU#O3H|7)DoMj|VM*#|IHX0d zUqf>frJ-B0r$z2p)aE71*yJ-VJfyYq~dc4cM79yU1}8=CG8t zW)&2W=*L9OVo;gJKdf{aO=D0iv}Ow|4S?H(e6AX{J&7@-RwF37X1~@y*SuemAL9sM zMaX?WJGv3w&-X`oy8Im)NeVg6m!_3=+=B?Y{B~*97N;goJ`8^gWe-o{FpdC!okB zTA02`$>ezp!3KHg(b2LpXy#z$@qP35AQ@CiB}tD){mrRL955zhVO+DW`!Z%8>gc`r zZq>p0@#A;VAso0d$|9K+sQu{i>GF@Rr0@nqIg50gs8t78Y6H?Zbu~2!*E4ELOMSuk zWq58aBT!~mscrwK8O>{%H@&6A=W-)_Wg2D3fg*NsAn~ulK?{0KP^i>Or97(KMu{yG z*`tCxo1m{BS!;vVKbqlzjZfo>Ca<=R4)?={tTsNdqkdbY*`pXRkH+tcqx35(ybby# zKQ86u<5Awk&!6N8v7iCIo89SzUVzNANH>@d!~FdC@DSVjR=IYO(Ax{4 zz@Q*YMmi}%)BpLH$VKD?ZoRiJ$j|R$2?x)MQCZ?sqI+eU4(S+krkGFT?#kicZQJp= zG#xS|#4xl2M9QIC^L%uNM#zrVy<=~B_R6K(59*JxnVGCb)!tV1EUDQM9%DtshYuef z?Yx5sTL9Z2*?1y4!sqa%PfoY-gI92c=mUk_KHkB_&A{>4ri=sgiw^pmrR zrUBD`K%;>tbUuJgziZ=coi|n+cvK*`88%P5m^2#qdsrVG-H1Jw0-2JD1ARwt*Mg7; zWCTkK)zA1~bfTud{UEWUvoqkSC0ZNhTV7F`s2@D`!rFTzk0BpgSy}OTNC@!r&(*G^ zEmZkrsF}FMeU1yPq2g)=$5x%mwZebX@g_1^Y{;BQS=Za2|V?S#;0m5zWo{?na=?{| zspKhb!}u;RH3kJk1M}QI3b!(|!n=h+wOsD<%_j=1Dj9)`zCVS>aVap^V2ula$C$Ad z1cJ`4#btezCF39;O&GVy&qS_z^&p~wE7QOv>c$Wr(KGQ=#^YG`;-)Bz$992T!sFrp zHABVW3=g1Mo8%eHbq$b&rnUAgONEh^pmuEMIk&W{6S@LX(UO)L!%bO!;2^>DV1erq z-&b+j2m$;)OyH2pI_7J2H3K>BusgsYTm`A`DuFTnlBx}0d77L57-BIruO83CkLWLS z3uhyzD6G(CY#0zWV@UNiNej&!Ja%?s2e1gmZvfU(6VPv@9>Yh`JXbB-dZ-z(B2hj(?pUMF~riH1XB z-mdmE#}a9%W+FW@KF;)ukV;?mtN1v~yU zT3x7zOEsFVRn#hw%?MB4>{L3;1Cf}V%*uSgqRqD&fEzC=S+2wucG+7oC?1xPL5DE9 zd!tZF#tD>auLxjBhA$$ZTjz;U5rX;&30hGlGv1VjKe|tV$C_xU%cNBeD=O3iW08eO zr$_^280^8~GR;wQ4jG!42IdZ?HLw1cMHpn*;C_%@%&=ptNivC|jR6*dFhWgDo!N?@ zjlv^{_F;>PwTO%O{aatR!A-@995LKUKVQ~DX=+m1uF^^0x`zq9nN#-dNFWP15}qU# zQqum$#F96=XHxbDEf!BiwtUW=L?(;P90$$4uEEcQt@%tTJ-8F=3vJhPCYS%?dPt~m zLg;9ZW6L22_^)-lkAk}n?f{{rtgK)tir+Q%34O6@9xlW{o1pmt4poHD(@NBpUQ1GT zh@l&q`28Cnp^Bvick+U*d5Vk~m)VZW=+oP$a-0858ig@ zMf*HbA^m3MYA1L=_`9H}aB( z{ZNkcrOe`Dd^j)*8re2aGI?nb-D!ABty~><|40q(A)>#~Vaj(bIEmyCMaY)UxxX0X z%Y97xgeI_cE}DtPWt(TBORRA~tg5PN`F524|8kMyhkHy|{#@wMX4$llfbx5NQp z@S}66Uxw*2ZY2^{tG0H+cqicADQ*(=Vh<7>@#;iUXMe@H>uA#&7 zk4EFAeWoCED+HWU@@hOc7I`i(7unRnPt%_8?7c;}Y*yWl7FIbnKhnmXJT*1-I`YH8 z+mvpe&LsFi#86NHrc6@Riv%GX4xcbyQ=nu00R5Y}*3X?|sG1Hwyw4bK!9m4~Y$&kuk4s-mYmVH|1FR<(Z=1Hy&0taP6$NE7gAp&TV*K>`!5-5Hl{G*%WVEbM zxgai5dI~_@3v&s-U$WC4#8?>c2`OEsTbgWDxyb@FQLWGfwFcq=byTX!hT?8TX$EUG zpg#swHNSU4xd)!ZgR@K37}KYGS>U;a%;`jaQ{&5RU@loS`}Rqqc>2p=F`}))1$rcC%uBg`u zAv6O+79=nhA}J#yGvLfliu3u)7ej$$6%`dfn1}$@uhm8X{w%-+lG@&on6SMBb3VyE zGxrcV2V^1KpaoxOPmf|TQf?Be!l{vw zG7B*=@%4WkoO`SP39#Mx5Vi9@gd9}BuK?Ku8kbB^dEnff;hIrWN=jT0DVBU>gqrIM zGDXH)D&^jVPJJ9|=68{+I$B!rW(Y`z65e!_!L5vqjr{~FCCR~6MkYXY|0(0Gjid2U zV8063><|XvB^_>Gbg13EI^Q8XtZ!&Dc6F`hb1Z}!BF&&HgpZGpk}OqCk4$(k%mAi7 z`S|gAtT{&*QKXHnle+rH{W5T%YqF8v8_6FK=NWpbqLN`k*KfwlM*2jbLe3@E-rZg6 z6jzcc3yjgQ9jxbpF5x(FG0h~g@5h;}YxKLoYdL(+-vdln2z~&_%R-L=7&bEFOr2;R zcl4!&3y9*H0rdc0q~o1gIrM;#5-i#eSXtrdI|Cl1fk5)@7^FO7+$IBYQagQx{0H{pN4PC&b03{eRya-T zOCW*$mCd)KqM(Q=wnm0%P4am1OzkEr<@zT(Yr6k5tDvKdcwo8?-dR{Tpfd`Edo^Jf z!CWSP&N7@U$e%6)LA5rYklvK15i z_UY$kW_*H0uIC_CiCW*t*6L*##RLhzOQhUcY)E_A)nBpzELs~5#QVHU#?@N{l zX&BItXd%+q?g-lI-oJpH0efB5ANEjiyAf*81XiOwX7d-_!+%}xf!8$E-z)dlGE<>O z-zYXi%8z^ZW61MSs?UdXE+`@!pM#4L=ZZS5OS_n(gHZG~+(my`t}KN=EsgqntWH#` z13Klf=^ZWIa#W8f^8V{0E7eO4ja`_6$dQuv{vGX|n&bz!r-&qPuB!;zw07C%PABg( zs~C=WU8V_3TxP!@o5PsKLTp*48AsqkT28JqJUmRFYKO5{v4j@u@AB{JQdPMcE!MtP zm*am=T*h?{O!(Q!a{aq*qQhFdh;E)rC42565?oA27aZU$VJ^bxV7Xth3g0*O(%96Z z@(}-_YreqM)BY=NqArmlM-?rt0xXqy;TO+xRTA2?blFH6lfRt59kEAAZ`X8|5En_}nBSSHtE_&ZBA5rttg)bFMwVn2>VgtpH4&h8{U z#j-T*&#H6-ZgO>X^^@>8l!e&U2UL@Hd~M9J{Ich&ZAe9Zy#z$p1?P12zL#m@npJ37 zDk`c-%@D%W9v^@~>O6k*eV~BWX>!%l6&s z3K@y(5&Kqs3XLTuHifHOTOZ5A^*{3yaKeDrFf;gW_Lwu0?c(hJfA~;7taBk|An-<) zZ9AL<7#Db(sr2WhBol^~LSjhsC@wAW`+|Fx%OzL_5w!i+iG7r?%5h(a*e9{Gb{iQj zt&J*a6dy$X*TD#tBpymH+gQALQ^KVGK~!-ZM5mR(^a&?DR8bs~5$X|%qLjZ$OTi9! zVLsy4)}JFo+CN2xm@@eNiV!KkDMxGB%aDAD7fn(L=pw1DgJI+6#DrV~ z>h*Z+$Rf)Jvdn;xW2uPn)g3WXowcjb+T%LdhKz_B$XK#+E)Y@o&3S7kVSac0P%XfK zLz9V1J>_#ngwp%mFa~~_!^?~`rVmeqdaSz9EsT9yaRgYk!wxbUC{39+P<)r~^*_@T zLZYI$(DRxeqfB>ob#>X{c=9gngZ=#>_~^}Nf;uG=Ver3SkE!plCJrR(cymO17m1&D zeKXUKP+H`kl{qvm)LH_ko$$gdeSKLjayAi~@vk4)Y2uyx;#GhG1x{>Od>Qell|VvT zPcLqomb-jqfbEtkclLqD|ssRNe zRZ8Fa)O3;awLbseYJ8z@nvDWdec7IKBkDhN&7ATyZ}s{3oRi4MmBPXl5$8}HuiI0e zC@PC2{5qnVg#+Y=lBTP=IP*JN3nAgeHVEcP9EzURHAPSO4vf+(O>IER`c?1xjD?|M zz|*u5>I;EWH17j>jw`vp z=gR6;*XW=X-4{~i=EjSEa`7#Fj8D~K#-Kd~J!t7duB{zA;$V31j zaWbhImJ%X2K5=qMNs~LHT_h2WS+8How~WmcfZkMY{Ai!4z)$BfdiB(z7oD*WlqOBB z47=uysw0Z}+Z?JAf%%A2(?-<3c1O75wNQWxZ8G?nP+F^1Mkq2o{0~4L(fDx;Bpx&X zuiX%Tmiv<_?vRXr=hh44s&pzE;QJgv+j~(~Xi{Zk`YoF{K#8!NfRvb(_e*<;2rrUD zr+dDnu&|HvCDR=St<}xV(KfqeGVPAe-n34z?$mKWqre7UEUoJN!pR1CMtWxo^62Tn z`(%A@&4E{oKp4|MW4~GPF?7Tf3t4LX3cbtI0k=MF>Q?ZKxHFs8bgC0Qzs`8<9*kd` zM97$-h8Q>*96Q3>?^}nX7;YgdRo4O3mI+(_z6XM|Dg-UyD}_`%(>DU;X?WMmadf~M z0VWd@Qr-|w#0I7MPt)~s?$QSrqe!Wv3NN-W)x0)~+aE-%yN$dy%R0+D=+A{8P4gwt+dhge2PD8(sPsNyb}nHh^*Z*mq8yH6eb?!^!V}@}bf#z>KQ!npxe9nBDMW{6$?Cs{Dx4W&XR@+yVk@+F>IG9rs!fJ> zCIjX0dOJ|FA9sCZyorVW&kJy2FGa7!E;6PiY4CcP2VgLauhh8h8R;K{sU7z*y?`Up z^o;R|GYZVvL9}|632gaFgO%i!YU!92IM7~>?}cQ>T(U7q{ug8td_@11Z6L4|aA+ng zBFaI2oGfx9?=$d(jt=-A9o{F}?B9GVjkpfWM|sN6cxYKL^Kx?uL!^I9O@-#AdEA6( zf&jV!E%P5cp@XEQqnDnFS%~x zr2o5E+3S6E#bdn8b(lg|`WC~m&W85<;!g`YY&eus3}PW(v0i;3px8g)TmYJ*M`?Xj ziRoPXQdsBU$!7!Qhy|z@`9($jI$mA2-RNDjmv~)ou<#j;vr%BCCm{B{G2<;iaPdQT zq_Jmb2u3e&Z|}_3u23RMSKn-`LAhV$4$h$FfD5`l7hNEg>xGZTD^4AX(}|`l=W%jP zGdn<@J;$4lpDp@Gto>Yf~7?1A!XIIsbjU3okr}`ej~$f&4PPGZ^ggwc=-Y)mv&|n_ zU!pA1mDn=Mxv@N9JJ5=09cv_Xs&zBr9^8(%+4}hLHp<*(Z%-s>`>Poosg76T2q66w z()+Egtv^h063K^_U!EV|dGse%i~z{kJc~KzbKo8UzkQ3tUrg^NRuD(MY3e@cBu~~~ zHig0&CM?L#N9{%rPBmvygM`e6iInfo-nqwru1JNsap((y>ri!lLKdphGbT$^19qJ( z)N{ zyR>pKpZ}fIsI>TdehK2!+YGGlHs_xoHaoVkxtsXVP|!VPvhx;CAMI4tvGqab}@$vCL zCMOH9&b^Y%eonwiMZ(A7oeS4H>!AT;eOXK*X09nFz)c1dDK%hpQ8{1j2Gs$owT#Sa z@6C#37WHUTUbhK12gR1}Ls$p-ekP<*m#&--A(#RQYrxC^{JzOh zQwgcB&yl%L;J=fof6XY5$H2f-Cl?nhBBK^S02iC)5^CkEIk6=c7_r~EUwJabkY}J% zX4PA?JPW~mZB)+dM*I&9F&$x!2c^7eq(yFC9#%V>Pbr&uG z)wu_!Lj~jCV}<+z);qp7Z$(0kj9l6|As!z3OHnIY7Q67+cHU4tg62HGPNT9v5rV&) zqkJxmp#ia(sk;r+u{~#IX9wy3L`y1Nx26Jiymve`H8p=c&{gIRMK#ACnd@nd|NZRZ z=mH`PT>rQuCh~+BEnW3rrr_yO0AUZ04b?dz|GaMeJ67`c_N&vLm!RGI`doDSv>|!T zd7f%$>FW3+VV7Hv|JyvC@!6RA@^s8#4Bv#nT8VWI&bSt9Iqzjl`hL^Y?&? ziREBM6~Pmg1oW;|z9vZR>>}X}kX7>w3WmI2g|+*0dd=aSfGq6TaIxR3YC?sY|9<1O za7VaAP(&o@Km=~0S2H#NkD-0tp*C9(!@N{@T()Z&rGE7N$2mbP1~TWJ{WlQtxa}rm zva(6v@9f@n_eOp2;-L){#=bdCP>uuDmD&ASa(^ID|6WHG>DLi3FLy)Ya_!k(AGjz$x+|xB51nCO5IT71h?(rc9tVOEifP90m@viNiQ@pPU}s{g(Y> z1!O5CK^AX8IHq1&17+mJyVv&rUHL||al8P*+{vigv$;Pl?|y>I!*{W(8CAPZ5`0b* zVkf@An8CmX*ON2=gcn!+H?n}h?cfH1D(W4$nqa`90TkQJRv?MHC8x4 z-#~_J*(hn^fF=0z8mO|nV2$p!Zh)iIP-hnGdqdrVp9s49R&#%<-6)$aEruuC*Z$(Z zpL)haadD3Jg9utIdTNRQ;8_L2OGBjT1Gzy->>ZUQyy<&IJ%(id+xG_yVP!u5uK535 zfHAcJ4z&TQL_6pu-~S}lz?1v^@@gi&CfIHk7F}F><-+3-qJi$-Kwu8h7ulKIv&w3) zgU@87kmbA9!K&6vOSLoGlz!}-?zt@ttd$Xrv>|*UouiZsc{vyHdjPj0{8en=D3%{$ zFi(XN>{{ENpa4oV#mKaT8|&WC*oHL+N5;&7D0?Z; zzFi*F6x*|pKDnKK?|7cuaj{q|aB(&9iWH@EFM-1GJphL+^lSzUM2x(V;1qkwK}AI+ z4c05Vjz4JK17qM5{(F2JhJWwP)z!|wxBcE6cM4oYVfd#5hqK{R9~x8-B9!Z+pJhm60tO55%FrULoayUL`c|M;XznIz$dv$RQ5s#w6z`JI_8!ljKZ{570P>>`rW#uk?BFazhU64tWbR$m-cbBeCXcOMU;cXT;f~{ zK4GNf964siZuym(I9#@D5zQCQD!WC-ssCairYCYJ$-{R{mf}_cD?1Yznu8ODn)|+SO$k#*bsEu=t7KuJNnh_d7B2@`LXcT5{2SKhov z$mG&GXV=mM_3IrfGlN$*5O_AF&XO4JVG;^iK#?lrqV!->W2AxzyXLt4r7M8Qi*N)E zeX*=T-v%4t&))%Q#}7UJGG8q|yTX7tgA3FI9a27_VK8jF^{_XNXI2}CFnS-{WBiAr zqBcTkn2fL8!s9-o#g4E_n=0TSmGKypX~OX<7P)W1VFG|a;6Wt9vxc#%rG~Us9)4(w zZO9dcAm_KMw#t)_1(&;!Lys^FYXTpup= zvSU54<%89HK4nl=yGpaa4{-m%L+HIoGE{^Cu)`c42HEViBKT9D(|drUoua@A#hkQy zSwXWS4YhpMwuMrJYyzpUNv1r|3<3uj=oD=6vT$Hx6u+A9xnKE$-!KIyo3ix3Jt$7} z|HM=OI9EVUpag+G-`k`6M+B+hNRKbCcKYjSf0m<2;d(AZ_@u?Rklh5>^7lMi^uvg< zLFGd6dOx%veiA7GRoMl{^l|mquQAXDcH3b**+?0x0j03t;8xyJbvSdCLwJq#iAc!_ z+CYkn_)$HOsmI2D=`JNr0fQ^-@HOHYFC1us*KE8lAK~0drpas=DLK6%Kr2EHJAV8~ zTDY{ev*VY^7X>RjXQeZjtrnly|6ZN4;eW4w&*4Fi@xkxtf@YmFR=P8g)5QGLLLG=w zRbs}#!@7{vecsfg*nxGpO#$_b!-0;r_7K!ZdR)>9P?v=Bz?+vd#Z}Hq$;rW6e)11F zw+Y<@iY?%Qq7jJBXFvOqCPq#^7KsQ0)^Nc5fD3vK9|HRsq03pdMIeUBfD&9jj)$r+ zd&7JKTfOfjBmcuQR6?96<1vWAk`UsjEs6N`)&Hr^-SMTs zD%7usD7>!sEUBYk)tsMcDlq}b5K32!_KqoF`Ubt20L(!1|HS# z2=|_;y(NKyl@m5eol}gr?dIQ_n(zR!>5dPc`ZPtdv$-a|^u#>DY8WEhk>4NJ?!6SD zPp86|!x*4nQwpoT8Uz|fV5p2hD|j1i4{k!gFEFf~3F{<$=^jb}Iz`%i6>u;Q;23@a z0^^?opirCvV!egw4>bIeR8~;H_n0(+ZvGBG%au+mkpk33eLjVlu>d&dy2wnS9D5DP#f4?QVuHrYTfs>@H74 z?oAZ!Xg9OA=D7Ht541<PaS0R-&#h!WN1ayx%2`Fa=l`*w=%aYMUp8X3V_`<>y;P^nqv0G2gMxVyl_aQ-~Z3dt^MyVsgmpS)rDadSRIUj zx}2PmRL3|F*wQHZ5~czD&<|iMFovV=5$5x)U1og}~W1ArQp0MsBS*ZwDq0ncwa7?CcQGh?aJYcH$d5fFL3sopV`qlx=2 z6EyS$+aJM_b0S{qoRyK$Gn_~(7544bwrVjABWVjAA_VEJgZFcF^n8N=oFgNHsB;c@ zkRh`d)iYTX4XEBfW=FRU*pV5t6NuXUZt%VtmPG19J6ObG5dP&djK0p+V zH=woN`ygiu>TKW;WQgi|-{N%~1KPHxp5p?d&U)A1fW#!=u72h6p_Fal$pPpB`QN|* zXU6XgWVdW9`3G;xc-cF_eHOsi0Gjw2yZihcz6Ho@{?CB$W6NC7nwzos`J4_mI%A+r zqSvUPTYYEh<3sqIAN%Y=v1(W9Oc$6U5C(^g9o2q~+`~UN0cLb?G}>aDXAQVI;5hyX zz1;XWIOT@fy6Mi>-{!itgBdtTjC}Vz1QCGRd!4jkabbYYYE$ILzZ$R?=ZKdje-lMd z1~^avT!`uE5dp$?zB2xAo*}D8%&dQ1f6|dai=!J2d)D7`5LjFQ#!L-#Cz$X968E<0 zFl^G`TjEbB-C%}$Z5#WZc9G*%6G&R}D||czI~9QJja<&=vw=6z8CDQi?f6J@nnpk2 z7vjQ0k^a{$Wp(6Zw!U3Sl!4RGPkp74?gT_SGCk6NFX#0`hl<$EVqCQ*@vldDnmn#E zxI&UIP#_E0ky2f{_J$ML261 zy?~*HvS_7-sC9J$i%};4ZSt1`QRf9k7I%tGGIQT;t0E=G--%HM;bxLB&Uqj?*+@6% z!N*rsA@LsS&uD;rw4~#u1t1`akQBcqj_Usaqz!%jtwD1O!|sAh9y1m^1mJ#yyAJxO zU4Sw(+}vI1rWJePQFhs#UYwF8V5xv3vAw!NOF_~*8&y5EB1R9<9Hddk`$`@JDS%>0{uf zTx>c#cCfRY&eoU&)zevTYrm6V1%d?g!{* z^6^ZBWWy)*!A!z9A6Au(spD&+0CP$TQ7}T9{qGvpO)D110(^Z1fh(1&F9WDg#Bm7Z z=lUb1J<8IOv!FGGk~2@&ft$(-BK94R@1&>FVk46gy$%nMmIJSz^8b`Pp&!&3s?WoJ zt(VMVnRj=oADvEaQJd7H!FmOz3%=|L?p-#u(e3@#PPNJ4Vnzd~;y=J1)a_U;CZ?VG zb+OOb1kld13ZN(gxEPEMkPd$~I$XM|DHa?#n1 z4+g4QPf8*LQaL(6_B=#D2gS90p!%c&_|^e{?EE)3SEM2d zRvOntp3OA+l{6nq_H1kOUF0gy;;H*lHS6{ZPDM$of(-}qf(B3l z4nvl^1)ah$(>$w%Jf{jE+N3D}+BE&qx5Vy5Ww4v$TbU`h+Q(FKZSN*x&~U)0_keVU zy$@XPK4wyYvbu_%ZZoYqI+I}$z{cgfe%77N2v_N^#$he_syo9+wxxdYITOpHR>?K8 z&v?tsGxeHU<<1d^HI&MGD%HE5lG-}yhk4lJPrgm5-9PIxF{As0=%IJ=ZHHZ`bUo}p zY!dCosfgr^@n=3R!`>-z_(!n|Z9^HYUP_WyN?fHEk}$yM`=7OjK=CSoqX-O+016)f zzA{Py9B_F@Kv|hy7ZW{OZPV~yUC7Q9m%vXAE{;P^Z0)l0?wHTC7*#8E#it?3p>x!S z>Ul$sQLWz81~hdCM~e0>LMV5a?COC&b_T>m66cHf8HkRG-R$0I@|TK8jUHy5_2{E< z4qAPbQ9!c0-&b&mPp?T;@36x2tn@tKpA03JFKO0H_ivzRM%nfR7n8HaT_Irbp7)YN zv)JFy9wxTp_%zxZ6?}r6)&_Z?GL?-p9J;ku+SnGvv_dRK`^a?z{&xL$6C_w=tsrw* z(geOFVitWcTI66)oBAn~8y``2LTBa+7CbI4>rR$D)H)>QD!Rcl7J^`GxYJUAAz5Ox zlx@%g=B3uIt7o2()Uejl9Eyuh+ICgJU0Z6VKs%<|mZvuPZeY`etMl6I$9?W`!Td2Z zL$z)fUe(j?oweWbpiO-})4=R`s*i-Gkn6Ks>G}>#n)G07-s}~`NrvYU{F^)r#DP<* z43!#YUctkJKyY+A*m89yRQ1%E01O3V9bIiaJuX56H^FJ{$x_Z@+o@*%En2oRjwC6} zxXp<8+)B*2vh)G*`dD4na$I!ovppc?*V2hd0C|C49sLgy#qheKj&uJC_iY7DvccJ! znU2M}vGi5XSC=znwj@Stv&w;A6v>`^6cub$1uK^<$_Rb}nu{6xv)6{!Q=9wL&<)w? z(8&BgN7jLts@a6Q-j8qijHJPI$*xRVfEYx^?FB=~=PUPSnsQ^jzkR0*JybeE8zomV zKTXB|m+mmrCsGl8-_>+k98WWX8Z?+ip>s$^ns(*By^HGTz@d+Zr;{mki~o-#6%}dt z<{4Z0(b||bVRiV2t)RoxWY}%<;ofIYj3aio8!0lA76l$(?66y!_s)~*mBODwOBd)|m4c?wz&GHX1##v$ zBw@uuw_Ax8bIfR!y5~tza~RLHh1>x9N+4uEgLgJ{>E#T345s=#-RW+bdZo}OX145F zxGZRvnUpo@<&)acPUyp5dH`N`U zi%^x=tt^eIfIP(oTyS{m2e(~>Ct0_j`IRl4_0@1yj&d))AMM&xjuk6c|0LX6>99rp zTf3jgNMNM{d;3bZY7GW92*#c#lg1A7o{m?Z^qbHm|I6V@s^^kYrFtvbMg2+0V19~6 zw3oiUr*<`4hju{KOxaVKGhWtsW}FdRhK^Ndd6>PU3kP@oMTT{6r zn5{hvTercEux&jI3j=Vl)}^z(WL&GKFUgtYKhK|=vQUD&OF?4Tnjh>T4~Uo!J?nFG5qC8%x^CDc(OHN8$Xlh$FD;Hyqj!C2u4y!noC%|Ti=?cc?-@@xm@0>9t1SRGk= zBIAQb4d>U)R0kWXp(rI(dr2(`+7G>Me8fPeEbSn~Za|`!FrI)|e2<=3g}r3Xp<-ab zT@||ivzXr36qWy4cNnBQhK?vtthplL%%4q`=khuXXkiK0bOp2b~TcR=O4oiCd zHqaKjX;!n`a(P4dXICXs#3k$h>wrg5v~>^$LJ#z9;*yc@*WjQ^Tw8EiuZ|6Zb)}6{43s~IGOYbS-5jS zc-XGW-`;0#qN>V@|IeinZNw;Oth=?XsMF8dA^~}e!vJ5Y+uU^!#>3CguR;RiQOsmG zbkD?Gb5e)Rf#fv-V5oh9IG~jN!mtavic)Q?m6VpBWKT0aZzYTEPpeQWW};F0*LQsL zSqePk^0dnR+$D6hiHiOENfoy!FU)pclK)348&PLYzWhd5sU#6tdrM>KzmV``#>B?P zdWBro(MR(Akk=jQw#Pkg^>eNM;~FL&u0>$VWL}r%2YLw{JUkhH{df6k^BL8my@e$gdUheAQYsV9y*>sDEr#1feFs+%GVhXfiUjAHFa`PpoF<4516-gA znc$j{DX^?BHP~tCn_(cq1zTgyt2Yq8|8MBnYdTMvm`u!S>i$z(?T}QOs@Q?M!1~n# zwFb)WG7i;2i>U_vbL)K4jgt_Zphz$<_J_#R5C+iJm7z&Igv9*--Nk2pd>M) ze*qIPdy1ye>0@|yv}}sda7sF?cH2j0-|M3oPka>_{9t6bU~?*aNa@E+5t}7nE1Gn+ z5UNbm(L#0-Efx6RMqQ;i775x(P9+Oa0^VIW+ei4v&j%>#mW=S57p+B0kXO>LWTa3x zcl}~V?yvwSq--P{s8ANV_#6X-(AXwBqweJqB2WPr> z^h&H>YLKR0Jm7Mp=-~Y|J+D$jlB%-s>Bz|`_dwA$bIV=o_KvD$wL4jj(!KpUSRvWM zq#Dmpq$w0}7AKfKG&5WA97rde9!@>G6JyEM1v`_dOL@)dom7NAqm z%jm7tX@dr|nt*}&n|G%Nm+o3sW^cQ=$kFIEnQMuVO-=d>!Z6~dsC7cABo|U>;{%RC z@HIHq2J>HQ=|AKK3G>F3>lf=+&+L1Fn8xPYoy`5~BnVy2z+aR4gP`g2GcODI8-i*J z`ABci_ludE;ADxe`~hVYhE1)U@E^y~rvm+jS2&hO3X={vgGMwrX}8gRU)9hH z0?*QMG3^yj3A!96=4`A?r;_5AY(AG@VC4jX0BK_*1D%yY!#|?&!zw1sbq8i^>x+e7 zeYQB+da3xx#LP<=^P{FS5|1W|YC_28(nr@$R7u8wO1famlgYcODZ?0r+k=F@wr)d( zD!xv1SgcOTTP{X7KF5givGaY{Z{Y4bMUw(aS(M^xxHfZZ!(_f!hk12%uD0YIIcib! z|EV>wT&XbbmFW(aN!hXCqjYM|78fL^ixgQWDeHjzuo;zwAxHynmgo59ClAccC| z>GVrgY@vL-Fqfpbbk|zp^D(2rJMjN#z1M7XbP|)(* zPQj(R`QKwLBcsVq|2shVp&Z8mkzz0$l^9=ngw(CTrboh>VT-vPYoDn-B-Qe2=C}wVGeOjmN~|so9^Ydt>Z=qgc7kJ3~LOZ!A-* zGB@Jwc9Xd+Jg`m+q)WVO%&FyMITO9*6aCdFK3Cwe)$#Ou^!iWH&9v=6;3LkY{v}e} z>h~mfnCn-Dw~!g)UpE+JlPJHmS}oDSsdyHY!5B1+wj5Bw`kK(30GF@;Evl-D0jCro zDm0ALdsgSa))jSS-b}X~S-CRJ;v-7_L_5QAJ@1zDaE&JgfX2Cb8Fb!vz@v^x(iep!Hj}>jLKB9?)E%-vrw4TSYf~8Si##R z7uJ-ECG4xU&R*g@jyl&F={JQh_L_}nE|Ye$Aitr3CK%sNu&VDaWQrxJK23~8j+2>r z`;d{)hH+WR)R(H+!^IfJUUn$8=kXSH~b~sFK`9_Soz?1{F z$TwAq3y2J0?%{i5)MulID@BWD_Hcr6-Wq3|MU2k)^Szls$%y6#T}__TBYd+WzesmE zjwKuO%j8q}$!UokdH_{-9_IH#p2>>(rNdF4k^1P773PsZGz%6MBNlEPn^!B^)62_p z0I^qy!$bi+D%yHI$EnhdHg5F+_G+K#=3vvvtlr^cyX1?LW*6Vf!Xibo8S}=ksTNz- zcGw+>sqrOe^xFqQ($`)hsmVIx#6QRT7WuG`>QRXANLY_Z%$9apiX{=f?)ZFe-Y$(+ zTOJ1H8V^2^ZYub&@+B1H}Gx%3GDaSn)=7PZT>Z>>9-f2^8S+Kevl;m*jq#!~ux+cP*8{I9 zNU=ZX^@{GU`R3+zT+H}EjT&84x|t%S#k9VMP{a2gdP9Yk0^OVo!g7dCddBij?C1Ydj`Zd(yfRUO-$(CItZx{fnYMNez#Y zB)*Kzr|X)DYwH7The>yO|(2#OzIZ_wsl5-0DbpHHut0tGUY2VWc!nouyqmbJYc*<7~3qBkiem7xQt_6?OgZGVT~MuB#>LO3pn2Z#GHK zV`}#Oo{Z;71NQn(n^8MPBAUAZdTfws=ii66CEFQTz2^VU(EYZXSnGBe^LFp^H<8$p=vAQe>aMdGE&ixJ{QX77Jg2JvH?DrB8pNapjFBcqd3m)} zE&fjZ=wZ&#k?j$ByW7U;zd!<}rmtTqfLpzwys9A``TmcNZjI)8DK+6-@y%z0R9V1# zSpXrh3K1(-NYmymmCl)DSWd#Y=XuSOb{sUYb6AV?9yWVw-y~B7<(#D}GxzaEM5N16 z!&#D#Lmz#)jyduWU^<{xS;5T72aDr(!$;hww}IJwZJOcn|9 zdev1XjUFyPI(Ge`;bG-dR6EBgsvu&!$gbEXw%ZQ%J=$vNM*Verg4e=#?DxpxjvtNS zo@f@`^1|SSJY&>JGlGkvf)lsM)%j ziX8!bqW?u)*|BYdZYV{w7hu;G%oU*#fl#B0P=bf2=(M1 z0SZEweZeyRh==V=-`PU9Kw6OlNNb>DWz}+UjgJzqvM*fb8F5Lvj61v5`QsnQ1B@U^ z$;ndwzhp5s*w^ss%GW10<5m?cj^D+i`G_B5aRdMDuISY4rn$Rm@DwoT_#D16Jg?p@ zo;2*vy*>)9z4qSE6ufEK#Ol1bw4-y&{st1rK_TvgP(;%fVCcIQW#9F5ec@GN*!6H0 z==RO-)70s!fx)Z`;(J_CuTy-2(FN6P#IM73iduDrPZ~M521LE2=-42*{8Iidy|gvD z!6HwD)PUIUG1a~1?&U(&5Zo9}Y9{~c{4fUF>{PIDK~e&_XG9W8H#}I;tAAIxBrQDB zKgENv7Z+gjsct=B5bd=qo4_p2lu8;c3d7pIIct?@>B|41z${ThjUW*r&75=@OXhbH zRMV-_Y1m`T28YY<>Oy#^Kii0jWEnheX$FLCz>OtoBT2He&Fj4WIm%{!y!h)i$JAdA z&(%u|s}2|+1!SJH?eMN1i*q5Nt|w(SuP;p*lWgp_0_(SbbBnLtiF906(7o;xi}qk9 zomqveZJNU3sk(OZ$es{4Nzo1C@M>5{pa+@FyF_|)BGM1RPWHTKTxoisZS8)=()@>l1!>xx zdDU0{e-m!7ky~_zHQaOT4bU_dtn=7zsMP(4&yb$YkS{#lCK=WpXaDB-wd(3aB+vH6 z_a6%00n@Eum;eDKd*=9ym%5}~_xhhPV~y2)nMHTCF`O7lnI%&%$G$XD$4L&{$Fa3_ zks!QTy?M)Ov>I0sh|i=MiL5Ac?f{I`5}xenT^BAw47rLvW`Fr}2gIwJuT$-R%7z{N zg0|&aY%UTgU88TfmL%$N#rY+^cv|P6vdDZ)&$Yjy>?lD<8)7Of913RNs>u%@Zb$Wd zU?+;Q;5Fe`IXe?b*B|_!LN=>rTF(xqPTZYuvP!WoYo#$d%C$mO!=O!fR4J9mat@OCW zO|?(0Df%|Y01kbMMj^K+TaTk+OaEHC-WejUl;dj5+!)Ga^B>U+Y-=iNdW-g`>nrME zcLM&!oyjdnIUgo!`44|4*>%&jNR@UcaKO=-Aj#?3?-uf~f&=!g5irU5_k;eRhjy{( zbHAgR>>RekPtKmRMWwNw=N`H29#H+uJz`{MahtTEP%;BzRDnNOZIloI3OpxtC8Kk; zxD5w*X3T^jLxzr?K4PDpQfgK(EF6G%fCbnmVg%e5IHA^2^~n(28So(aoqvn9OFVD5 zzLqlJg0r1~F9)cbub8!b5j=VwnC(c5P7*z-N88F9;0pZgw@16S`Bp zL(B=jv&H@kdvbB1FiVqJCT}dfngw|f{f?zLT0zANhX)!VNn@P>1)z(#+YJ zZH=N2Wq(ux9O?k-P?uPmE2L+{kPVORB_Q@WjYE4OC;p=gBad{)m&CS2ReyrH2d$Zr zX+|vTP{lxwA8@}B^SerN4p?JO9-4x0P*YO_edQo?*pgVr{Ndi-7bkLdX@N-~*k|+4 zvCUN*4g)!?LX$oB>0HOp=!HF7&n&M2H8?q>u(oz;K_PEmsxoZ)ql_Iu;x`)&3a@pQS#%LQ6|8@?Edvuj1Ty@>rHyYzL_!*6Qw(IIPYe*AbVzh zV86P$LRdU`%Lx1%U;FDIwk16~KE z8-yZ|9kam!Xca~jvbeSuJ7=5iQv09~YQpCc93PFx0`NAsMji8FFuEpM91o0XFL54@e-@^nbAf-N@Hy9zW{8dq zjKveX%S9P!ND6M|Q!lDGf?=&}?m;)v?(yE0#@X zzJ%o`mL!N@9cL<&H)V$sm<8Q-^r`yIIf|10|6l*=@b%O`c-Vl1f_9^QO(Njq2I4Vq zZ|_qys-40*F9r8}>LWFWR$Z)-GS^OUhfb$p+X4PcuW`Jvx+=UYjB3^MkIg7^$z4&$ ziHmR?#{OfMz|bhf<}gn6Tot^_{}x_mZw3Z&(O$7+0E^|l9&-w zwrJ8Cz>AA;zg*dtmcSj8Q(U2G!<|%+wS3N<0BQ8GE2ma^S+u$-8sKTF!ke|jrYRQM z9H@_U7DeJJH_L9&%%>>VD;gS-vZOMyq?dUixwbIJ4Gn-Qx_b;LZ}^V=pU6Zj$dm(% SnR;Nr$9pLy$!c-q;Qt3LxtI(9 diff --git a/tutorials/video_recorder.md b/tutorials/video_recorder.md index ffd06943fb..a84b802adb 100644 --- a/tutorials/video_recorder.md +++ b/tutorials/video_recorder.md @@ -13,8 +13,9 @@ Gazebo that already has this plugin included in the GUI. gz sim -v 4 video_record_dbl_pendulum.sdf ``` -In this plugin, you should see a single button with a video recorder icon. -Clicking on the button gives you the video format options that are available. +In this demo world, you should see a video recorder icon positioned on the top. +left area of the window along with other buttons. Clicking on the video +recorder button gives you the video format options that are available. @image html files/video_recorder/video_recorder.png From d0524915fa590d96743bcad9322f5a15f101a81a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Wed, 13 Sep 2023 20:49:41 +0200 Subject: [PATCH 26/50] Fix multi_lrauv_race example (#2111) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- examples/standalone/multi_lrauv_race/multi_lrauv_race.cc | 2 +- examples/worlds/multi_lrauv_race.sdf | 5 ----- 2 files changed, 1 insertion(+), 6 deletions(-) diff --git a/examples/standalone/multi_lrauv_race/multi_lrauv_race.cc b/examples/standalone/multi_lrauv_race/multi_lrauv_race.cc index 03ec9eee98..be8dd072d0 100644 --- a/examples/standalone/multi_lrauv_race/multi_lrauv_race.cc +++ b/examples/standalone/multi_lrauv_race/multi_lrauv_race.cc @@ -74,7 +74,7 @@ int main(int argc, char** argv) rudderPubs[i] = node.Advertise(rudderTopics[i]); propellerTopics[i] = gz::transport::TopicUtils::AsValidTopic( - "/model/" + ns[i] + "/joint/propeller_joint/cmd_pos"); + "/model/" + ns[i] + "/joint/propeller_joint/cmd_thrust"); propellerPubs[i] = node.Advertise( propellerTopics[i]); } diff --git a/examples/worlds/multi_lrauv_race.sdf b/examples/worlds/multi_lrauv_race.sdf index f0827cd82c..902d89111a 100644 --- a/examples/worlds/multi_lrauv_race.sdf +++ b/examples/worlds/multi_lrauv_race.sdf @@ -57,11 +57,6 @@ -0.5 0.1 -0.9 - - -5 0 0 0 0 0 - https://fuel.gazebosim.org/1.0/mabelzhang/models/Turquoise turbidity generator - - 0 0 1 0 0 1.57 https://fuel.gazebosim.org/1.0/accurrent/models/MBARI Tethys LRAUV From 0bd0b66dab8b72d34a290f2343471a9322e3d69f Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Wed, 13 Sep 2023 15:00:52 -0500 Subject: [PATCH 27/50] Add note about Featherstone (#2143) I think this is helpful to demonstrate the alternative engines without having to write your own custom engine. Signed-off-by: Michael Carroll --- tutorials/physics.md | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/tutorials/physics.md b/tutorials/physics.md index a8e1c12217..ef7bf7999d 100644 --- a/tutorials/physics.md +++ b/tutorials/physics.md @@ -16,8 +16,10 @@ tutorials to learn how to integrate a new engine. ## How Gazebo finds engines Gazebo automatically looks for all physics engine plugins that are -installed with Gazebo Physics. At the moment, that's only DART -(`gz-physics-dartsim-plugin`). +installed with Gazebo Physics. At the moment, the primary implementation +is DART (`gz-physics-dartsim-plugin`). There is also preliminary support +for Bullet (`gz-physics-bullet-plugin`) and the Bullet Featherstone +implementation (`gz-physics-bullet-featherstone-plugin`) If you've created a custom engine plugin, you can tell Gazebo where to find it by setting the `GZ_SIM_PHYSICS_ENGINE_PATH` environment variable to the @@ -70,6 +72,10 @@ Alternatively, you can choose a plugin from the command line using the `gz sim --physics-engine CustomEngine` +To use an existing alternative engine (e.g. Bullet Featherstone) + +`gz sim --physics-engine gz-physics-bullet-featherstone-plugin` + ### From C++ API All features available through the command line are also available through From 5577b19f6e06fe2e2bb55631fd060c81e9e8ad71 Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Wed, 13 Sep 2023 16:42:21 -0500 Subject: [PATCH 28/50] Fix CMake warning in example (#2145) Signed-off-by: Addisu Z. Taddese --- examples/plugin/hello_world/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/plugin/hello_world/CMakeLists.txt b/examples/plugin/hello_world/CMakeLists.txt index ba90eedfff..135d6288ce 100644 --- a/examples/plugin/hello_world/CMakeLists.txt +++ b/examples/plugin/hello_world/CMakeLists.txt @@ -10,7 +10,7 @@ set(GZ_PLUGIN_VER ${gz-plugin2_VERSION_MAJOR}) gz_find_package(gz-sim8 REQUIRED) set(GZ_SIM_VER ${gz-sim8_VERSION_MAJOR}) -add_library(HelloWorld SHARED HelloWorld) +add_library(HelloWorld SHARED HelloWorld.cc) set_property(TARGET HelloWorld PROPERTY CXX_STANDARD 17) target_link_libraries(HelloWorld PRIVATE gz-plugin${GZ_PLUGIN_VER}::gz-plugin${GZ_PLUGIN_VER} From 23881936d93d335a2ad1086008416f1f36c3fdcc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 14 Sep 2023 14:45:35 +0200 Subject: [PATCH 29/50] Improve joint controller world visualization (#2144) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- examples/worlds/joint_controller.sdf | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/examples/worlds/joint_controller.sdf b/examples/worlds/joint_controller.sdf index 7152726bfa..65cf6fe938 100644 --- a/examples/worlds/joint_controller.sdf +++ b/examples/worlds/joint_controller.sdf @@ -39,7 +39,7 @@ -0.5 0.1 -0.9 - 0 0 0 0 1.57 0 + 0 0 0 0 -1.57 0 0.0 0.0 0.0 0 0 0 @@ -91,6 +91,8 @@ 0.2 0.8 0.2 1 + 0.2 0.8 0.2 1 + 0.2 0.8 0.2 1 @@ -125,7 +127,7 @@ - 0 0.5 0 0 1.57 0 + 0 0.5 0 0 -1.57 0 0.0 0.0 0.0 0 0 0 @@ -177,6 +179,8 @@ 0.2 0.8 0.2 1 + 0.2 0.8 0.2 1 + 0.2 0.8 0.2 1 From 839282ae44715e63b52e62a438745098b8d05d06 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Thu, 14 Sep 2023 15:42:36 -0700 Subject: [PATCH 30/50] Update logging tutorial (#2148) Signed-off-by: Ian Chen --- tutorials/log.md | 5 ----- 1 file changed, 5 deletions(-) diff --git a/tutorials/log.md b/tutorials/log.md index 6f88370656..8c3b8b8011 100644 --- a/tutorials/log.md +++ b/tutorials/log.md @@ -103,11 +103,6 @@ Please use the command line argument. ## Known issues -* When using command-line playback there is currently a small caveat. -In the case that the recorded file uses `ogre2`, the playback appears -brighter, because the default SDF that is loaded by Server.cc for playback -uses `ogre`. - * Currently, specifying record and playback at the same time is not allowed. We may support this in the future, to support cropping a recording or changing the encoding. From 2bef470a01ba580f3472ffe011ddfdc289975041 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Thu, 14 Sep 2023 15:57:56 -0700 Subject: [PATCH 31/50] Update Reset simulation tutorial (#2147) --------- Signed-off-by: Ian Chen --- tutorials/reset_simulation.md | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/tutorials/reset_simulation.md b/tutorials/reset_simulation.md index a2f21d671c..7a62a3fa3d 100644 --- a/tutorials/reset_simulation.md +++ b/tutorials/reset_simulation.md @@ -9,18 +9,19 @@ In addition to the API, we have also expanded the simulation system API with a R System authors may now choose to implement the Reset interface to have a more intelligent reset process (avoiding reloading assets or regenerating scene graphs being the motivating examples). Since this interface is opt-in, systems that don't implement the API will still be reset via destruction and reconstruction. -The [physics](https://github.com/gazebosim/gz-sim/blob/gz-sim8/src/systems/physics/Physics.cc#L928-L937) and [rendering systems](https://github.com/gazebosim/gz-sim/blob/gz-sim8/src/systems/scene_broadcaster/SceneBroadcaster.cc#L452-L458) are the first two to implement this optimized reset functionality, with more to come as it makes sense to. +The [physics](https://github.com/gazebosim/gz-sim/blob/23881936d93d335a2ad1086008416f1f36c3fdcc/src/systems/physics/Physics.cc#L919-L928) and [scene_broadcaster](https://github.com/gazebosim/gz-sim/blob/23881936d93d335a2ad1086008416f1f36c3fdcc/src/systems/scene_broadcaster/SceneBroadcaster.cc#L489-L495) systems are the first two to implement this optimized reset functionality, with more to come as it makes sense. -Following the tutorial \subpage createsystemplugins we should implement `ISystemReset` interface. +Follow the tutorial \subpage createsystemplugins to see how to support Reset by implementng the `ISystemReset` interface. ## Transport API -To call the reset transport API we should call the service `/world/default/control` and fill the request message type -`gz.msgs.WorldControl`, this service return a `gz.msgs.Boolean` with the status of the reset (true is everything was fine, false otherwise) +To invoke reset over transport API, we should call the service `/world//control` and fill the request message type +`gz.msgs.WorldControl`. This service returns a `gz.msgs.Boolean` with the status of the reset (true means everything was fine, false otherwise) -The `WorldControl` message now contains a reset field that we should filled if we want to reset the world: +The `WorldControl` message now contains a `reset` field for resetting the world: ```bash +# the world name is `default` in this example gz service -s /world/default/control --reqtype gz.msgs.WorldControl --reptype gz.msgs.Boolean --timeout 3000 --req 'reset: {all: true}' ``` From 294fddc765e93a233a438cda21d02e4171b17b33 Mon Sep 17 00:00:00 2001 From: Mabel Zhang Date: Thu, 14 Sep 2023 19:08:48 -0400 Subject: [PATCH 32/50] Fix broken / update ign links in tutorials (Harmonic) (#2107) * fix broken link to API * use \ref for links. Revert common::Event link * make links local so that version updates automatically * update URLs to latest release versions, and ignition->gz namespace * fix migration tutorial titles * ref link for gz::gui::plugins, dependent on gz-gui PR#571 --------- Signed-off-by: Mabel Zhang --- CMakeLists.txt | 1 + tutorials/entity_creation.md | 8 ++++---- tutorials/gui_config.md | 2 +- tutorials/light_config.md | 2 +- tutorials/log.md | 4 ++-- tutorials/migrating_ardupilot_plugin.md | 4 +--- tutorials/migration_actor_api.md | 17 ++++++----------- tutorials/migration_joint_api.md | 16 ++++++---------- tutorials/migration_light_api.md | 16 ++++++---------- tutorials/migration_link_api.md | 17 +++++++---------- tutorials/migration_model_api.md | 17 +++++++---------- tutorials/migration_plugins.md | 4 +--- tutorials/migration_sdf.md | 4 +--- tutorials/migration_sensor_api.md | 16 ++++++---------- tutorials/migration_world_api.md | 16 +++++++--------- tutorials/physics.md | 4 ++-- tutorials/rendering_plugins.md | 8 +++----- tutorials/resources.md | 17 ++++++++--------- tutorials/terminology.md | 14 +++++++------- 19 files changed, 77 insertions(+), 110 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c1cafd64d1..e28d8dece1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -272,6 +272,7 @@ if (NOT APPLE) "${GZ-TRANSPORT_DOXYGEN_TAGFILE} = ${GZ-TRANSPORT_API_URL}" "${GZ-SENSORS_DOXYGEN_TAGFILE} = ${GZ-SENSORS_API_URL}" "${GZ-COMMON_DOXYGEN_TAGFILE} = ${GZ-COMMON_API_URL}" + "${GZ-GUI_DOXYGEN_TAGFILE} = ${GZ-GUI_API_URL}" ) endif() diff --git a/tutorials/entity_creation.md b/tutorials/entity_creation.md index 0e5b9c8824..6772fb1538 100644 --- a/tutorials/entity_creation.md +++ b/tutorials/entity_creation.md @@ -58,11 +58,11 @@ gz service --list # Factory message To create new entities in the world we need to use the -[gz::msgs::EntityFactory](https://gazebosim.org/api/msgs/6.0/classignition_1_1msgs_1_1EntityFactory__V.html) +[gz::msgs::EntityFactory](https://gazebosim.org/api/msgs/9/classgz_1_1msgs_1_1EntityFactory.html) message to send a request to the create service. This message allows us to create entities from strings, files, -[Models](https://gazebosim.org/api/msgs/6.0/classignition_1_1msgs_1_1Model.html), -[Lights](https://gazebosim.org/api/msgs/6.0/classignition_1_1msgs_1_1Light.html) or even clone models. +[Models](https://gazebosim.org/api/msgs/9/classgz_1_1msgs_1_1Model.html), +[Lights](https://gazebosim.org/api/msgs/9/classgz_1_1msgs_1_1Light.html) or even clone models. This tutorial introduces how to create entities from SDF strings and light messages. ## Insert an entity based on a string @@ -103,7 +103,7 @@ Or we can create an SDF string: \snippet examples/standalone/entity_creation/entity_creation.cc create light str Please check the API to know which fields are available in the -[Light message](https://gazebosim.org/api/msgs/6.2/classignition_1_1msgs_1_1Light.html). +[Light message](https://gazebosim.org/api/msgs/9/classgz_1_1msgs_1_1Light.html). There are three types of lights: Point, Directional and Spot. Finally we should call the same service `/world//create`: diff --git a/tutorials/gui_config.md b/tutorials/gui_config.md index a1a8679450..9cc42fa1e0 100644 --- a/tutorials/gui_config.md +++ b/tutorials/gui_config.md @@ -3,7 +3,7 @@ Gazebo Sim's graphical user interface is powered by [Gazebo GUI](https://gazebosim.org/libs/gui). Therefore, Gazebo Sim's GUI layout can be defined in -[Gazebo GUI configuration files](https://gazebosim.org/api/gui/2.1/config.html). +[Gazebo GUI configuration files](https://gazebosim.org/api/gui/8/config.html). These are XML files that describe what plugins to be loaded and with what settings. diff --git a/tutorials/light_config.md b/tutorials/light_config.md index 24378aa798..eea79a3237 100644 --- a/tutorials/light_config.md +++ b/tutorials/light_config.md @@ -6,7 +6,7 @@ This service will allow to modify lights in the scene. ## Modifying lights To modify lights inside the scene we need to use the service `/world//light_config` and -fill the message [`gz::msgs::Light`](https://gazebosim.org/api/msgs/6.0/classignition_1_1msgs_1_1Light.html). +fill the message [`gz::msgs::Light`](https://gazebosim.org/api/msgs/9/classgz_1_1msgs_1_1Light.html). In particular this example modifies the point light that we introduced with the function `createLight()`. \snippet examples/standalone/light_control/light_control.cc create light diff --git a/tutorials/log.md b/tutorials/log.md index 8c3b8b8011..c8aaa379b6 100644 --- a/tutorials/log.md +++ b/tutorials/log.md @@ -8,7 +8,7 @@ Gazebo records two types of information to files: * Always recorded * Simulation state * Entity poses, insertion and deletion - * Logged to an [Gazebo Transport `state.tlog` file](https://gazebosim.org/api/transport/7.0/logging.html) + * Logged to an [Gazebo Transport `state.tlog` file](https://gazebosim.org/api/transport/13/logging.html) * Recording must be enabled from the command line or the C++ API * Can be played back using the command line or the C++ API @@ -42,7 +42,7 @@ Other options for recording: ### From C++ API All features available through the command line are also available through -[gz::sim::ServerConfig](https://gazebosim.org/api/gazebo/7/classignition_1_1gazebo_1_1ServerConfig.html). +\ref gz::sim::ServerConfig. When instantiating a server programmatically, logging options can be passed to the constructor, for example: diff --git a/tutorials/migrating_ardupilot_plugin.md b/tutorials/migrating_ardupilot_plugin.md index 66676d9cd1..e58dd764b2 100644 --- a/tutorials/migrating_ardupilot_plugin.md +++ b/tutorials/migrating_ardupilot_plugin.md @@ -1,6 +1,4 @@ -\page ardupilot - -# Case study: migrating the ArduPilot ModelPlugin from Gazebo classic to Gazebo +\page ardupilot Case study: migrating the ArduPilot ModelPlugin from Gazebo classic to Gazebo A variety of changes are required when migrating a plugin from Gazebo classic to Gazebo. In this tutorial we offer as a case diff --git a/tutorials/migration_actor_api.md b/tutorials/migration_actor_api.md index 065a0b19d8..5bbc743198 100644 --- a/tutorials/migration_actor_api.md +++ b/tutorials/migration_actor_api.md @@ -1,6 +1,4 @@ -\page migrationactorapi - -# Migration from Gazebo-classic: Actor API +\page migrationactorapi Migration from Gazebo-classic: Actor API When migrating plugins from Gazebo-classic to Gazebo, developers will notice that the C++ APIs for both simulators are quite different. Be sure to @@ -34,16 +32,13 @@ can be divided in these categories: You'll find the Gazebo APIs below on the following headers: -* [gz/sim/Actor.hh](https://gazebosim.org/api/gazebo/7/Actor_8hh.html) -* [gz/sim/Util.hh](https://gazebosim.org/api/gazebo/7/Util_8hh.html) -* [gz/sim/SdfEntityCreator.hh](https://gazebosim.org/api/gazebo/7/SdfEntityCreator_8hh.html) -* [gz/sim/EntityComponentManager.hh](https://gazebosim.org/api/gazebo/7/classignition_1_1gazebo_1_1EntityComponentManager.html) +* \ref gz/sim/Actor.hh +* \ref gz/sim/Util.hh +* \ref gz/sim/SdfEntityCreator.hh +* \ref gz/sim/EntityComponentManager.hh It's worth remembering that most of this functionality can be performed using -the -[EntityComponentManager](https://gazebosim.org/api/gazebo/7/classignition_1_1gazebo_1_1EntityComponentManager.html) -directly. - +the \ref gz::sim::EntityComponentManager "EntityComponentManager" directly. As an example the `Actor::Pose()` is a convienient function for querying the `Pose` component from the `EntityComponentManager`, i.e. diff --git a/tutorials/migration_joint_api.md b/tutorials/migration_joint_api.md index 8e33acd5e7..5cf035ce76 100644 --- a/tutorials/migration_joint_api.md +++ b/tutorials/migration_joint_api.md @@ -1,6 +1,4 @@ -\page migrationjointapi - -# Migration from Gazebo-classic: Joint API +\page migrationjointapi Migration from Gazebo-classic: Joint API When migrating plugins from Gazebo-classic to Gazebo, developers will notice that the C++ APIs for both simulators are quite different. Be sure to @@ -32,15 +30,13 @@ can be divided in these categories: You'll find the Gazebo APIs below on the following headers: -* [gz/sim/Joint.hh](https://gazebosim.org/api/gazebo/7/Joint_8hh.html) -* [gz/sim/Util.hh](https://gazebosim.org/api/gazebo/7/Util_8hh.html) -* [gz/sim/SdfEntityCreator.hh](https://gazebosim.org/api/gazebo/7/SdfEntityCreator_8hh.html) -* [gz/sim/EntityComponentManager.hh](https://gazebosim.org/api/gazebo/7/classignition_1_1gazebo_1_1EntityComponentManager.html) +* \ref gz/sim/Joint.hh +* \ref gz/sim/Util.hh +* \ref gz/sim/SdfEntityCreator.hh +* \ref gz/sim/EntityComponentManager.hh It's worth remembering that most of this functionality can be performed using -the -[EntityComponentManager](https://gazebosim.org/api/gazebo/7/classignition_1_1gazebo_1_1EntityComponentManager.html) -directly. +the \ref gz::sim::EntityComponentManager "EntityComponentManager" directly. As an example the `Join::Pose()` is a convienient function for querying the `Pose` component from the `EntityComponentManager`, i.e. diff --git a/tutorials/migration_light_api.md b/tutorials/migration_light_api.md index 86f1f508c6..818f521042 100644 --- a/tutorials/migration_light_api.md +++ b/tutorials/migration_light_api.md @@ -1,6 +1,4 @@ -\page migrationlightapi - -# Migration from Gazebo-classic: Light API +\page migrationlightapi Migration from Gazebo-classic: Light API When migrating plugins from Gazebo-classic to Gazebo, developers will notice that the C++ APIs for both simulators are quite different. Be sure to @@ -29,15 +27,13 @@ In Gazebo, the light APIs has been consolidated into a single Light class with some of generic functions available through other utility / core classes. You'll find the APIs below on the following headers: -* [gz/sim/Light.hh](https://gazebosim.org/api/gazebo/7/Light_8hh.html) -* [gz/sim/Util.hh](https://gazebosim.org/api/gazebo/7/Util_8hh.html) -* [gz/sim/SdfEntityCreator.hh](https://gazebosim.org/api/gazebo/7/SdfEntityCreator_8hh.html) -* [gz/sim/EntityComponentManager.hh](https://gazebosim.org/api/gazebo/7/classignition_1_1gazebo_1_1EntityComponentManager.html) +* \ref gz/sim/Light.hh +* \ref gz/sim/Util.hh +* \ref gz/sim/SdfEntityCreator.hh +* \ref gz/sim/EntityComponentManager.hh It's worth remembering that most of this functionality can be performed using -the -[EntityComponentManager](https://gazebosim.org/api/gazebo/7/classignition_1_1gazebo_1_1EntityComponentManager.html) -directly. +the \ref gz::sim::EntityComponentManager "EntityComponentManager" directly. As an example the `Light::Pose()` is a convienient function for querying the `Pose` component from the `EntityComponentManager`, i.e. diff --git a/tutorials/migration_link_api.md b/tutorials/migration_link_api.md index 57662d5b76..a6377969c8 100644 --- a/tutorials/migration_link_api.md +++ b/tutorials/migration_link_api.md @@ -1,6 +1,4 @@ -\page migrationlinkapi - -# Migration from Gazebo-classic: Link API +\page migrationlinkapi Migration from Gazebo-classic: Link API When migrating plugins from Gazebo-classic to Gazebo, developers will notice that the C++ APIs for both simulators are quite different. Be sure to @@ -34,15 +32,14 @@ can be divided in these categories: You'll find the Gazebo APIs below on the following headers: -* [gz/sim/Link.hh](https://gazebosim.org/api/gazebo/7/Link_8hh.html) -* [gz/sim/Util.hh](https://gazebosim.org/api/gazebo/7/Util_8hh.html) -* [gz/sim/SdfEntityCreator.hh](https://gazebosim.org/api/gazebo/7/SdfEntityCreator_8hh.html) -* [gz/sim/EntityComponentManager.hh](https://gazebosim.org/api/gazebo/7/classignition_1_1gazebo_1_1EntityComponentManager.html) +* \ref gz/sim/Link.hh +* \ref gz/sim/Util.hh +* \ref gz/sim/SdfEntityCreator.hh +* \ref gz/sim/EntityComponentManager.hh It's worth remembering that most of this functionality can be performed using -the -[EntityComponentManager](https://gazebosim.org/api/gazebo/7/classignition_1_1gazebo_1_1EntityComponentManager.html) -directly. The functions presented here exist for convenience and readability. +the \ref gz::sim::EntityComponentManager "EntityComponentManager" directly. +The functions presented here exist for convenience and readability. ### Properties diff --git a/tutorials/migration_model_api.md b/tutorials/migration_model_api.md index 837ac603d5..8c252f2b82 100644 --- a/tutorials/migration_model_api.md +++ b/tutorials/migration_model_api.md @@ -1,6 +1,4 @@ -\page migrationmodelapi - -# Migration from Gazebo-classic: Model API +\page migrationmodelapi Migration from Gazebo-classic: Model API When migrating plugins from Gazebo-classic to Gazebo, developers will notice that the C++ APIs for both simulators are quite different. Be sure to @@ -34,15 +32,14 @@ can be divided in these categories: You'll find the Gazebo APIs below on the following headers: -* [gz/sim/Model.hh](https://gazebosim.org/api/gazebo/3.3/Model_8hh.html) -* [gz/sim/Util.hh](https://gazebosim.org/api/gazebo/3.3/Util_8hh.html) -* [gz/sim/SdfEntityCreator.hh](https://gazebosim.org/api/gazebo/3.3/SdfEntityCreator_8hh.html) -* [gz/sim/EntityComponentManager.hh](https://gazebosim.org/api/gazebo/3.3/classignition_1_1gazebo_1_1EntityComponentManager.html) +* \ref gz/sim/Model.hh +* \ref gz/sim/Util.hh +* \ref gz/sim/SdfEntityCreator.hh +* \ref gz/sim/EntityComponentManager.hh It's worth remembering that most of this functionality can be performed using -the -[EntityComponentManager](https://gazebosim.org/api/gazebo/3.3/classignition_1_1gazebo_1_1EntityComponentManager.html) -directly. The functions presented here exist for convenience and readability. +the \ref gz::sim::EntityComponentManager "EntityComponentManager" directly. +The functions presented here exist for convenience and readability. ### Properties diff --git a/tutorials/migration_plugins.md b/tutorials/migration_plugins.md index 25104ee695..bad1919e6f 100644 --- a/tutorials/migration_plugins.md +++ b/tutorials/migration_plugins.md @@ -1,6 +1,4 @@ -\page migrationplugins - -# Migration from Gazebo Classic: Plugins +\page migrationplugins Migration from Gazebo Classic: Plugins Gazebo Classic supports [6 different C++ plugin types](http://gazebosim.org/tutorials?tut=plugins_hello_world&cat=write_plugin), diff --git a/tutorials/migration_sdf.md b/tutorials/migration_sdf.md index daece419ab..1909bd5b8c 100644 --- a/tutorials/migration_sdf.md +++ b/tutorials/migration_sdf.md @@ -1,6 +1,4 @@ -\page migrationsdf - -# Migration from Gazebo classic: SDF +\page migrationsdf Migration from Gazebo classic: SDF Both Gazebo classic and Gazebo support [SDF](http://sdformat.org/) files to describe the simulation to be loaded. An SDF file defines the world diff --git a/tutorials/migration_sensor_api.md b/tutorials/migration_sensor_api.md index 0616b2b012..de2c996104 100644 --- a/tutorials/migration_sensor_api.md +++ b/tutorials/migration_sensor_api.md @@ -1,6 +1,4 @@ -\page migrationsensorapi - -# Migration from Gazebo-classic: Sensor API +\page migrationsensorapi Migration from Gazebo-classic: Sensor API When migrating plugins from Gazebo-classic to Gazebo, developers will notice that the C++ APIs for both simulators are quite different. Be sure to @@ -32,15 +30,13 @@ can be divided in these categories: You'll find the Gazebo APIs below on the following headers: -* [ignition/gazebo/Sensor.hh](https://gazebosim.org/api/gazebo/6/Sensor_8hh.html) -* [ignition/gazebo/Util.hh](https://gazebosim.org/api/gazebo/6/Util_8hh.html) -* [ignition/gazebo/SdfEntityCreator.hh](https://gazebosim.org/api/gazebo/6/SdfEntityCreator_8hh.html) -* [ignition/gazebo/EntityComponentManager.hh](https://gazebosim.org/api/gazebo/6/classignition_1_1gazebo_1_1EntityComponentManager.html) +* \ref gz/sim/Sensor.hh +* \ref gz/sim/Util.hh +* \ref gz/sim/SdfEntityCreator.hh +* \ref gz/sim/EntityComponentManager.hh It's worth remembering that most of this functionality can be performed using -the -[EntityComponentManager](https://gazebosim.org/api/gazebo/6/classignition_1_1gazebo_1_1EntityComponentManager.html) -directly. +the \ref gz::sim::EntityComponentManager "EntityComponentManager" directly. As an example the `Sensor::Pose()` is a convienient function for querying the `Pose` component from the `EntityComponentManager`, i.e. diff --git a/tutorials/migration_world_api.md b/tutorials/migration_world_api.md index 4a28e28f37..e47a976ae6 100644 --- a/tutorials/migration_world_api.md +++ b/tutorials/migration_world_api.md @@ -1,6 +1,4 @@ -\page migrationworldapi - -# Migration from Gazebo-classic: World API +\page migrationworldapi Migration from Gazebo-classic: World API When migrating plugins from Gazebo-classic to Gazebo, developers will notice that the C++ APIs for both simulators are quite different. Be sure to @@ -34,14 +32,14 @@ can be divided in these categories: You'll find the Gazebo APIs below on the following headers: -* [gz/sim/World.hh](https://gazebosim.org/api/gazebo/3.3/World_8hh.html) -* [gz/sim/Util.hh](https://gazebosim.org/api/gazebo/3.3/Util_8hh.html) -* [gz/sim/SdfEntityCreator.hh](https://gazebosim.org/api/gazebo/3.3/SdfEntityCreator_8hh.html) +* \ref gz/sim/World.hh +* \ref gz/sim/Util.hh +* \ref gz/sim/SdfEntityCreator.hh +* \ref gz/sim/EntityComponentManager.hh It's worth remembering that most of this functionality can be performed using -the -[EntityComponentManager](https://gazebosim.org/api/gazebo/3.3/classignition_1_1gazebo_1_1EntityComponentManager.html) -directly. The functions presented here exist for convenience and readability. +the \ref gz::sim::EntityComponentManager "EntityComponentManager" directly. +The functions presented here exist for convenience and readability. ### Properties diff --git a/tutorials/physics.md b/tutorials/physics.md index ef7bf7999d..98a08b8a78 100644 --- a/tutorials/physics.md +++ b/tutorials/physics.md @@ -10,7 +10,7 @@ by default. Downstream developers may also integrate other physics engines by creating new Gazebo Physics engine plugins. See -[Gazebo Physics](https://gazebosim.org/api/physics/2.0/tutorials.html)'s +[Gazebo Physics](https://gazebosim.org/api/physics/7/tutorials.html)'s tutorials to learn how to integrate a new engine. ## How Gazebo finds engines @@ -79,7 +79,7 @@ To use an existing alternative engine (e.g. Bullet Featherstone) ### From C++ API All features available through the command line are also available through -[gz::sim::ServerConfig](https://gazebosim.org/api/gazebo/7/classignition_1_1gazebo_1_1ServerConfig.html). +\ref gz::sim::ServerConfig. When instantiating a server programmatically, a physics engine can be passed to the constructor, for example: diff --git a/tutorials/rendering_plugins.md b/tutorials/rendering_plugins.md index 0ba4e34003..9b54418c0e 100644 --- a/tutorials/rendering_plugins.md +++ b/tutorials/rendering_plugins.md @@ -4,7 +4,7 @@ This tutorial will go over how to write Gazebo plugins that alter the 3D scene's visual appearance using Gazebo Rendering APIs. This is not to be confused with integrating a new rendering engine. See -[How to write your own rendering engine plugin](https://gazebosim.org/api/rendering/4.2/renderingplugin.html) +[How to write your own rendering engine plugin](https://gazebosim.org/api/rendering/8/renderingplugin.html) for that. This tutorial will go over a couple of example plugins that are located at @@ -45,8 +45,7 @@ To interact with the server-side scene, you'll need to write an See [Create System Plugins](createsystemplugins.html). To interact with the client-side scene, you'll need to write an -[gz::gui::Plugin](https://gazebosim.org/api/gui/4.1/classignition_1_1gui_1_1Plugin.html), -or a more specialized `gz::sim::GuiSystem` +\ref gz::gui::Plugin, or a more specialized `gz::sim::GuiSystem` if you need to access entities and components. See the [GUI system plugin example](https://github.com/gazebosim/gz-sim/tree/main/examples/plugin/gui_system_plugin). @@ -71,8 +70,7 @@ different for each plugin type. ### Render events on the GUI -The GUI plugin will need to listen to -[gz::gui::events::Render](https://gazebosim.org/api/gui/4.1/classignition_1_1gui_1_1events_1_1Render.html) +The GUI plugin will need to listen to \ref gz::gui::events::Render events. Here's how to do it: 1. Include the GUI events header: diff --git a/tutorials/resources.md b/tutorials/resources.md index d1af43a991..f5b810df3f 100644 --- a/tutorials/resources.md +++ b/tutorials/resources.md @@ -31,16 +31,15 @@ System plugins may be loaded through: * Attached to a **model**: `` * Attached to a **sensor**: `` * Passing the shared library and class to be loaded through - [PluginInfo](https://gazebosim.org/api/gazebo/7/classignition_1_1gazebo_1_1ServerConfig_1_1PluginInfo.html) - (within [ServerConfig](https://gazebosim.org/api/gazebo/7/classignition_1_1gazebo_1_1ServerConfig.html)) - when instantiating the - [Server](https://gazebosim.org/api/gazebo/7/classignition_1_1gazebo_1_1Server.html#a084ef7616f5af42061a7aeded5651ab0). + \ref gz::sim::ServerConfig::PluginInfo "PluginInfo" + (within \ref gz::sim::ServerConfig "ServerConfig") + when instantiating the \ref gz::sim::Server "Server". Gazebo will look for system plugins on the following paths, in order: 1. All paths on the `GZ_SIM_SYSTEM_PLUGIN_PATH` environment variable 2. `$HOME/.gz/sim/plugins` -3. [Systems that are installed with Gazebo](https://gazebosim.org/api/gazebo/7/namespace gz_1_1gazebo_1_1systems.html) +3. \ref gz::sim::systems "Systems that are installed with Gazebo" ### Gazebo GUI plugins @@ -51,7 +50,7 @@ GUI plugins may be loaded through: * Tags in SDF world files, where `filename` is the shared library: * `` -* Tags in [GUI config files](https://gazebosim.org/api/gui/4.2/config.html), +* Tags in [GUI config files](https://gazebosim.org/api/gui/8/config.html), where `filename` is the shared library: * `` * The plugin menu on the top-right of the screen. @@ -62,7 +61,7 @@ Gazebo will look for GUI plugins on the following paths, in order: 2. [GUI plugins that are installed with Gazebo](https://github.com/gazebosim/gz-sim/tree/main/src/gui/plugins) 3. Other paths added by calling `gz::gui::App()->AddPluginPath` 4. `~/.gz/gui/plugins` -5. [Plugins which are installed with Gazebo GUI](https://gazebosim.org/api/gui/4/namespace gz_1_1gui_1_1plugins.html) +5. \ref gz::gui::plugins "Plugins which are installed with Gazebo GUI" ### Physics engines @@ -111,7 +110,7 @@ Top-level entities such as models, lights and actors may be loaded through: * Path / URL to SDF file * (TODO) `gz::msgs::Model`, `gz::msgs::Light` * Within a system, using - [SdfEntityCreator](https://gazebosim.org/api/gazebo/7/classignition_1_1gazebo_1_1SdfEntityCreator.html) + \ref gz::sim::SdfEntityCreator "SdfEntityCreator" or directly creating components and entities. Gazebo will look for URIs (path / URL) in the following, in order: @@ -155,7 +154,7 @@ call. ### GUI configuration Gazebo Sim's -[GUI configuration](https://gazebosim.org/api/gui/4.2/config.html) +[GUI configuration](https://gazebosim.org/api/gui/8/config.html) can come from the following, in order: 1. The command line option `--gui-config ` diff --git a/tutorials/terminology.md b/tutorials/terminology.md index b4e8df5e6c..81dc324c78 100644 --- a/tutorials/terminology.md +++ b/tutorials/terminology.md @@ -10,19 +10,19 @@ to developers touching the source code. * **Entity**: Every "object" in the world, such as models, links, collisions, visuals, lights, joints, etc. - An entity [is just a numeric ID](namespace gz_1_1gazebo.html#ad83694d867b0e3a9446b535b5dfd208d), + An entity \ref gz::sim::Entity "is just a numeric ID" and may have several components attached to it. Entity IDs are assigned at runtime. * **Component**: Adds a certain functionality or characteristic (e.g., pose, name, material, etc.) to an entity. Gazebo comes with various - [components](namespace gz_1_1gazebo_1_1components.html) + \ref gz::sim::components "components" ready to be used, such as `Pose` and `Inertial`, and downstream developers can also create their own by inheriting from the - [BaseComponent](classignition_1_1gazebo_1_1components_1_1BaseComponent.html) + \ref gz::sim::components::BaseComponent "BaseComponent" class or instantiating a template of - [Component](classignition_1_1gazebo_1_1components_1_1Component.html). + \ref gz::sim::components::Component "Component" * **System**: Logic that operates on all entities that have a given set of components. Systems are plugins that can be loaded at runtime. @@ -32,7 +32,7 @@ to developers touching the source code. * **Entity-component manager** (**ECM**): Provides functions for querying, creating, removing and updating entities and components. See the whole API - [here](classignition_1_1gazebo_1_1EntityComponentManager.html). + \ref gz::sim::EntityComponentManager "here". * **Level**: Part of a world, defined by a box volume and the static entities inside it. An entity can be present in more than one level, or in none of @@ -63,10 +63,10 @@ to developers touching the source code. the world, while the **primary** runner is keeping all secondaries in sync. Worlds that are not split across runners don't have a primary runner. -* **[Event manager](classignition_1_1gazebo_1_1EventManager.html)**: +* \ref gz::sim::EventManager "Event manager": Manages events that can be sent across systems and the server. Plugins can create and emit custom - [Event](https://gazebosim.org/api/common/3.0/classignition_1_1common_1_1Event.html)s + \ref gz::common::Event "Event"s and / or emit / listen to events from Gazebo. * **Simulation runner**: Runs a whole world or some levels of a world, but no From c8d16bfe78dcc0983cdf9ca3e47e671c81f91e77 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Thu, 14 Sep 2023 18:34:46 -0700 Subject: [PATCH 33/50] Update triggered publisher tutorial (#2150) --------- Signed-off-by: Ian Chen --- tutorials/triggered_publisher.md | 30 ++++++++---------------------- 1 file changed, 8 insertions(+), 22 deletions(-) diff --git a/tutorials/triggered_publisher.md b/tutorials/triggered_publisher.md index 56768e470b..5d497dda86 100644 --- a/tutorials/triggered_publisher.md +++ b/tutorials/triggered_publisher.md @@ -267,8 +267,11 @@ and publish the start message gz topic -t "/start" -m gz.msgs.Empty -p " " ``` +The vehicle will start moving forward and two boxes will eventually fall to +the ground. + Once both boxes have fallen, we can publish a message to invoke a service call -to reset the robot position as well as set the speed to 0. As shown below, the +to reset the vehicle position as well as set the speed to 0. As shown below, the `` sets the linear x speed to 0, and the `` tag contains metadata to invoke a service call to `/world/triggered_publisher/set_pose`. The `reqMsg` is expressed in the human-readable form of Google Protobuf meesages. @@ -291,26 +294,9 @@ Multiple `` tags can be used as well as with the `` tag. ``` -Once both boxes have fallen, we can publish a message to invoke a service call -to reset the robot position as well as set the speed to 0. As shown below, the -`` sets the linear x speed to 0, and the `` tag contains -metadata to invoke a service call to `/world/triggered_publisher/set_pose`. The -`reqMsg` is expressed in the human-readable form of Google Protobuf meesages. -Multiple `` tags can be used as well as with the `` tag. +Publish an empty message to the `/reset_robot` topic to reset the vehicle +back to its original position. -```xml - - - - linear: {x: 0} - - - - +```bash +gz topic -t "/reset_robot" -m gz.msgs.Empty -p " " ``` From b504e5c1837a10f800d3434b1883966ab2da0a7b Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 15 Sep 2023 01:03:33 -0700 Subject: [PATCH 34/50] Fix light_control example and update tutorial (#2149) Signed-off-by: Ian Chen --- examples/standalone/light_control/light_control.cc | 2 ++ tutorials/light_config.md | 9 ++++++--- 2 files changed, 8 insertions(+), 3 deletions(-) diff --git a/examples/standalone/light_control/light_control.cc b/examples/standalone/light_control/light_control.cc index 329a05862f..1d4abc3341 100644 --- a/examples/standalone/light_control/light_control.cc +++ b/examples/standalone/light_control/light_control.cc @@ -53,6 +53,7 @@ void createLight() entityFactoryRequest.mutable_light()->set_name("point"); entityFactoryRequest.mutable_light()->set_range(4); + entityFactoryRequest.mutable_light()->set_intensity(1); entityFactoryRequest.mutable_light()->set_attenuation_linear(0.5); entityFactoryRequest.mutable_light()->set_attenuation_constant(0.2); entityFactoryRequest.mutable_light()->set_attenuation_quadratic(0.01); @@ -149,6 +150,7 @@ int main(int argc, char **argv) //! [modify light] lightRequest.set_name("point"); lightRequest.set_range(4); + lightRequest.set_intensity(1); lightRequest.set_attenuation_linear(0.5); lightRequest.set_attenuation_constant(0.2); lightRequest.set_attenuation_quadratic(0.01); diff --git a/tutorials/light_config.md b/tutorials/light_config.md index eea79a3237..7d6d906386 100644 --- a/tutorials/light_config.md +++ b/tutorials/light_config.md @@ -7,17 +7,20 @@ This service will allow to modify lights in the scene. To modify lights inside the scene we need to use the service `/world//light_config` and fill the message [`gz::msgs::Light`](https://gazebosim.org/api/msgs/9/classgz_1_1msgs_1_1Light.html). -In particular this example modifies the point light that we introduced with the function `createLight()`. + +This tutorial describes the code in the `examples/standalone/light_control` example. + +First we create a point light with the function `createLight()`: \snippet examples/standalone/light_control/light_control.cc create light **NOTE:**: You can check the [entity creation](entity_creation.html) tutorial to learn how to include models and lights in the scene. -As you can see in the snippet we modify the specular and diffuse colors of the light in the scene. +As you can see in the snippet below, we then modify the specular and diffuse colors of the point light in the scene. \snippet examples/standalone/light_control/light_control.cc modify light -In this case we are creating random numbers to fill the diffuse and specular. +The `r`, `g`, `b` components of the light diffuse and specular colors are randomly generated and constantly changing: \snippet examples/standalone/light_control/light_control.cc random numbers From bb6753a50c9c924dedf1529787e3d3a7ab176d60 Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Fri, 15 Sep 2023 09:55:40 -0500 Subject: [PATCH 35/50] Fix reset button in examples (#2151) Signed-off-by: Addisu Z. Taddese --- examples/worlds/boundingbox_camera.sdf | 1 - examples/worlds/camera_sensor.sdf | 1 - examples/worlds/dem_monterey_bay.sdf | 1 - examples/worlds/dem_moon.sdf | 1 - examples/worlds/dem_volcano.sdf | 1 - examples/worlds/depth_camera_sensor.sdf | 1 - examples/worlds/fuel_textured_mesh.sdf | 1 - examples/worlds/grid.sdf | 1 - examples/worlds/lrauv_control_demo.sdf | 1 - examples/worlds/minimal_scene.sdf | 1 - examples/worlds/optical_tactile_sensor_plugin.sdf | 1 - examples/worlds/plot_3d.sdf | 1 - examples/worlds/projector.sdf | 1 - examples/worlds/resource_spawner.sdf | 1 - examples/worlds/segmentation_camera.sdf | 1 - examples/worlds/sensors_demo.sdf | 1 - examples/worlds/shader_param.sdf | 1 - examples/worlds/sky.sdf | 1 - examples/worlds/spherical_coordinates.sdf | 1 - examples/worlds/triggered_camera_sensor.sdf | 1 - examples/worlds/tunnel.sdf | 1 - examples/worlds/video_record_dbl_pendulum.sdf | 1 - examples/worlds/visibility.sdf | 1 - examples/worlds/visualize_contacts.sdf | 1 - examples/worlds/visualize_lidar.sdf | 1 - examples/worlds/wide_angle_camera.sdf | 1 - 26 files changed, 26 deletions(-) diff --git a/examples/worlds/boundingbox_camera.sdf b/examples/worlds/boundingbox_camera.sdf index 4aa95a96ae..7697d17684 100644 --- a/examples/worlds/boundingbox_camera.sdf +++ b/examples/worlds/boundingbox_camera.sdf @@ -82,7 +82,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/camera_sensor.sdf b/examples/worlds/camera_sensor.sdf index 89a71652a8..3d967d701e 100644 --- a/examples/worlds/camera_sensor.sdf +++ b/examples/worlds/camera_sensor.sdf @@ -92,7 +92,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/dem_monterey_bay.sdf b/examples/worlds/dem_monterey_bay.sdf index 953c7178c2..7f2d170121 100644 --- a/examples/worlds/dem_monterey_bay.sdf +++ b/examples/worlds/dem_monterey_bay.sdf @@ -71,7 +71,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/dem_moon.sdf b/examples/worlds/dem_moon.sdf index 8cbbe830f9..a1de71ad5e 100644 --- a/examples/worlds/dem_moon.sdf +++ b/examples/worlds/dem_moon.sdf @@ -78,7 +78,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/dem_volcano.sdf b/examples/worlds/dem_volcano.sdf index 979f0ca383..f48b2779a4 100644 --- a/examples/worlds/dem_volcano.sdf +++ b/examples/worlds/dem_volcano.sdf @@ -70,7 +70,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/depth_camera_sensor.sdf b/examples/worlds/depth_camera_sensor.sdf index 5f17082d60..e666d12f42 100644 --- a/examples/worlds/depth_camera_sensor.sdf +++ b/examples/worlds/depth_camera_sensor.sdf @@ -82,7 +82,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/fuel_textured_mesh.sdf b/examples/worlds/fuel_textured_mesh.sdf index 7ec952f40e..251e195810 100644 --- a/examples/worlds/fuel_textured_mesh.sdf +++ b/examples/worlds/fuel_textured_mesh.sdf @@ -95,7 +95,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/grid.sdf b/examples/worlds/grid.sdf index 62028f2f84..184a946f85 100644 --- a/examples/worlds/grid.sdf +++ b/examples/worlds/grid.sdf @@ -67,7 +67,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/lrauv_control_demo.sdf b/examples/worlds/lrauv_control_demo.sdf index 2be3dc543f..56e3900b2b 100644 --- a/examples/worlds/lrauv_control_demo.sdf +++ b/examples/worlds/lrauv_control_demo.sdf @@ -111,7 +111,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/minimal_scene.sdf b/examples/worlds/minimal_scene.sdf index ae6c78df09..59c67d10cd 100644 --- a/examples/worlds/minimal_scene.sdf +++ b/examples/worlds/minimal_scene.sdf @@ -134,7 +134,6 @@ Features: false false 72 - 121 1 floating diff --git a/examples/worlds/optical_tactile_sensor_plugin.sdf b/examples/worlds/optical_tactile_sensor_plugin.sdf index 2920a788ee..fcda4ad605 100644 --- a/examples/worlds/optical_tactile_sensor_plugin.sdf +++ b/examples/worlds/optical_tactile_sensor_plugin.sdf @@ -97,7 +97,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/plot_3d.sdf b/examples/worlds/plot_3d.sdf index 2f0ed9874c..8abbd11a16 100644 --- a/examples/worlds/plot_3d.sdf +++ b/examples/worlds/plot_3d.sdf @@ -71,7 +71,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/projector.sdf b/examples/worlds/projector.sdf index d2a601c348..00fa8747ce 100644 --- a/examples/worlds/projector.sdf +++ b/examples/worlds/projector.sdf @@ -97,7 +97,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/resource_spawner.sdf b/examples/worlds/resource_spawner.sdf index ec9eb90392..ab101d4b38 100644 --- a/examples/worlds/resource_spawner.sdf +++ b/examples/worlds/resource_spawner.sdf @@ -81,7 +81,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/segmentation_camera.sdf b/examples/worlds/segmentation_camera.sdf index c8644c42ae..c5f4df7def 100644 --- a/examples/worlds/segmentation_camera.sdf +++ b/examples/worlds/segmentation_camera.sdf @@ -85,7 +85,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/sensors_demo.sdf b/examples/worlds/sensors_demo.sdf index ad40dafc3a..9d842a0d76 100644 --- a/examples/worlds/sensors_demo.sdf +++ b/examples/worlds/sensors_demo.sdf @@ -87,7 +87,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/shader_param.sdf b/examples/worlds/shader_param.sdf index 1c47a001e1..ae76f08d71 100644 --- a/examples/worlds/shader_param.sdf +++ b/examples/worlds/shader_param.sdf @@ -87,7 +87,6 @@ ShaderParam visual plugin over time. false false 72 - 121 1 floating diff --git a/examples/worlds/sky.sdf b/examples/worlds/sky.sdf index c1e2c620d5..e001ae59e5 100644 --- a/examples/worlds/sky.sdf +++ b/examples/worlds/sky.sdf @@ -70,7 +70,6 @@ Currently only supported using ogre2 rendering engine plugin. false false 72 - 121 1 floating diff --git a/examples/worlds/spherical_coordinates.sdf b/examples/worlds/spherical_coordinates.sdf index 1519bd64d7..5f76fe3844 100644 --- a/examples/worlds/spherical_coordinates.sdf +++ b/examples/worlds/spherical_coordinates.sdf @@ -163,7 +163,6 @@ gz service -s /world/spherical_coordinates/set_spherical_coordinates \ false false 72 - 121 1 floating diff --git a/examples/worlds/triggered_camera_sensor.sdf b/examples/worlds/triggered_camera_sensor.sdf index 23e2a027d2..38c6af1d05 100644 --- a/examples/worlds/triggered_camera_sensor.sdf +++ b/examples/worlds/triggered_camera_sensor.sdf @@ -98,7 +98,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/tunnel.sdf b/examples/worlds/tunnel.sdf index 2b70a68648..a902e40f03 100644 --- a/examples/worlds/tunnel.sdf +++ b/examples/worlds/tunnel.sdf @@ -108,7 +108,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/video_record_dbl_pendulum.sdf b/examples/worlds/video_record_dbl_pendulum.sdf index aeebffde37..e5eed30f0d 100644 --- a/examples/worlds/video_record_dbl_pendulum.sdf +++ b/examples/worlds/video_record_dbl_pendulum.sdf @@ -164,7 +164,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/visibility.sdf b/examples/worlds/visibility.sdf index 3f0f184837..ed669970a2 100644 --- a/examples/worlds/visibility.sdf +++ b/examples/worlds/visibility.sdf @@ -99,7 +99,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/visualize_contacts.sdf b/examples/worlds/visualize_contacts.sdf index 4e78353353..e39092e014 100644 --- a/examples/worlds/visualize_contacts.sdf +++ b/examples/worlds/visualize_contacts.sdf @@ -89,7 +89,6 @@ Contacts will be visualized as blue spheres and green cylinders. false false 72 - 121 1 floating diff --git a/examples/worlds/visualize_lidar.sdf b/examples/worlds/visualize_lidar.sdf index 54dca0b06c..61f9397505 100644 --- a/examples/worlds/visualize_lidar.sdf +++ b/examples/worlds/visualize_lidar.sdf @@ -83,7 +83,6 @@ false false 72 - 121 1 floating diff --git a/examples/worlds/wide_angle_camera.sdf b/examples/worlds/wide_angle_camera.sdf index 0dc56149c4..8482ae695c 100644 --- a/examples/worlds/wide_angle_camera.sdf +++ b/examples/worlds/wide_angle_camera.sdf @@ -133,7 +133,6 @@ false false 72 - 121 1 floating From 509d01a614324381ac1826885d3bfe70545e7060 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Tue, 19 Sep 2023 17:55:01 -0700 Subject: [PATCH 36/50] Fix another deadlock in sensors system (#2141) Signed-off-by: Ian Chen --- src/systems/sensors/Sensors.cc | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index 3bee1711bd..d70dd6590a 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -390,9 +390,12 @@ void SensorsPrivate::RunOnce() this->activeSensors.clear(); } - this->updateAvailable = false; this->forceUpdate = false; - this->renderCv.notify_one(); + { + std::unique_lock cvLock(this->renderMutex); + this->updateAvailable = false; + this->renderCv.notify_one(); + } } ////////////////////////////////////////////////// @@ -746,9 +749,12 @@ void Sensors::PostUpdate(const UpdateInfo &_info, this->dataPtr->forceUpdate = (this->dataPtr->renderUtil.PendingSensors() > 0) || hasRenderConnections; + } + { + std::unique_lock cvLock(this->dataPtr->renderMutex); this->dataPtr->updateAvailable = true; + this->dataPtr->renderCv.notify_one(); } - this->dataPtr->renderCv.notify_one(); } } } From 4d4b680f8c8ad414946820da5fa9a67b7554359d Mon Sep 17 00:00:00 2001 From: Jasmeet Singh Date: Wed, 20 Sep 2023 23:16:35 +0530 Subject: [PATCH 37/50] Added tutorial for Automatic Inertia Calculator (#2119) Signed-off-by: Jasmeet Singh --- examples/worlds/auto_inertia_pendulum.sdf | 367 ++++++++++++++++++ .../worlds/auto_inertia_rolling_shapes.sdf | 187 +++++++++ tutorials.md.in | 1 + tutorials/auto_inertia_calculation.md | 166 ++++++++ .../auto_inertia/auto_inertia_pendulum.gif | Bin 0 -> 1921301 bytes .../auto_inertia/cylinder_inertia_demo.gif | Bin 0 -> 1888792 bytes .../auto_inertia/rolling_inertia_demo.gif | Bin 0 -> 438725 bytes 7 files changed, 721 insertions(+) create mode 100644 examples/worlds/auto_inertia_pendulum.sdf create mode 100644 examples/worlds/auto_inertia_rolling_shapes.sdf create mode 100644 tutorials/auto_inertia_calculation.md create mode 100644 tutorials/files/auto_inertia/auto_inertia_pendulum.gif create mode 100644 tutorials/files/auto_inertia/cylinder_inertia_demo.gif create mode 100644 tutorials/files/auto_inertia/rolling_inertia_demo.gif diff --git a/examples/worlds/auto_inertia_pendulum.sdf b/examples/worlds/auto_inertia_pendulum.sdf new file mode 100644 index 0000000000..3b9cef933e --- /dev/null +++ b/examples/worlds/auto_inertia_pendulum.sdf @@ -0,0 +1,367 @@ + + + + + + 0.001 + 1.0 + + + + + + + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + + + -0.188749 0 0.75813399999999997 -0.13567899999999999 0 1.5708 + 256.42500000000001 + + 154.202 + 0 + 0 + 152.286 + 0 + 28.8249 + + + + 0 0 0.01 0 0 0 + + + 0.8 + 0.02 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + -0.275 0 1.1 0 0 0 + + + 0.2 0.2 2.2 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0.01 0 0 0 + + + 0.8 + 0.02 + + + + + -0.275 0 1.1 0 0 0 + + + 0.2 0.2 2.2 + + + + + + + + 0 0 2.1 -1.5708 0 0 + 0 + + + -0.05 0 0 0 1.5708 0 + + + 0.1 + 0.3 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 1.0 0 1.5708 0 + + + 0.1 + 0.2 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 8000 + -0.05 0 0 0 1.5708 0 + + + 0.1 + 0.3 + + + + + 1000 + 0 0 1.0 0 1.5708 0 + + + 0.1 + 0.3 + + + + + 1000 + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + + + + + base + upper_link + + 1.0 0 0 + + + + + + 0 3 0 0 0 0 + + + -0.188749 0 0.75813399999999997 -0.13567899999999999 0 1.5708 + 256.42500000000001 + + 154.202 + 0 + 0 + 152.286 + 0 + 28.8249 + + + + 0 0 0.01 0 0 0 + + + 0.8 + 0.02 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + -0.275 0 1.1 0 0 0 + + + 0.2 0.2 2.2 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0.01 0 0 0 + + + 0.8 + 0.02 + + + + + -0.275 0 1.1 0 0 0 + + + 0.2 0.2 2.2 + + + + + + + + 0 0 2.1 -1.5708 0 0 + 0 + + + -0.05 0 0 0 1.5708 0 + + + 0.1 + 0.3 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 1.0 0 1.5708 0 + + + 0.1 + 0.2 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 100 + -0.05 0 0 0 1.5708 0 + + + 0.1 + 0.3 + + + + + 10000 + 0 0 1.0 0 1.5708 0 + + + 0.1 + 0.3 + + + + + 100 + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + + + + + base + upper_link + + 1.0 0 0 + + + + + + diff --git a/examples/worlds/auto_inertia_rolling_shapes.sdf b/examples/worlds/auto_inertia_rolling_shapes.sdf new file mode 100644 index 0000000000..dbf777fb03 --- /dev/null +++ b/examples/worlds/auto_inertia_rolling_shapes.sdf @@ -0,0 +1,187 @@ + + + + + + 0.001 + 1.0 + + + + + + + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + 0 0 3 0 -0.52 0 + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + true + 0 0 0 0 0 0 + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 0 0 3.6 1.57079632679 0 0 + + + + 7810.0 + + + 0.5 + 1.0 + + + + + + + + 0.5 + 1.0 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + + + hollow_cylinder + 0 -1.5 3.6 1.57079632679 0 0 + https://fuel.gazebosim.org/1.0/jasmeetsingh/models/Hollow Cylinder + + + + 0 1.5 3.6 0 0 0 + + + + 1000 + + + 0.5 + + + + + + + + 0.5 + + + + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 + + + + + + + 0 3.3 3.6 1.57079632679 0 0 + + + + 2710 + + + 0.5 + 0.7 + + + + + + + 0.5 + 0.7 + + + + 0 1 1 1 + 0 1 1 1 + 0 1 1 1 + + + + + + diff --git a/tutorials.md.in b/tutorials.md.in index 10ace242e8..0c6f51aab3 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -53,6 +53,7 @@ Gazebo @GZ_DESIGNATION_CAP@ library and how to use the library effectively. * \subpage spherical_coordinates "Spherical coordinates": Working with latitude and longitude * \subpage underwater_vehicles "Underwater Vehicles": Understand how to simulate underwater vehicles. * \subpage logicalaudiosensor "Logical Audio Sensor": Using the LogicalAudioSensor system to mimic logical audio emission and detection in simulation. +* \subpage auto_inertia_calculation "Automatic Inertia Calculation": Automatically compute inertia values(mass, mass matrix, center of mass) for SDFormat links. ## Advanced users diff --git a/tutorials/auto_inertia_calculation.md b/tutorials/auto_inertia_calculation.md new file mode 100644 index 0000000000..e9f1322ccd --- /dev/null +++ b/tutorials/auto_inertia_calculation.md @@ -0,0 +1,166 @@ +\page auto_inertia_calculation Automatic Inertia Calculation for Links + +## Automatic Inertia Calculation for SDFormat Links + +This feature enables automatic calculation for the Moments of Inertia, Mass, and +Inertial Pose (Center of Mass pose) of a link described using SDFormat. The following +geometry types are currently supported for this feature: + * Box + * Capsule + * Cylinder + * Ellipsoid + * Sphere + * Mesh + +Using this feature, a user can easily set up an accurate simulation with physically +plausible inertial values for a link. This also removes the dependency on manual calculations +or 3rd-party mesh processing software which can help lower the barrier of entry for beginners. + +This tutorial will focus on how this feature can be enabled and how the +inertia values for a link can be configured. Some limitations and recommendations +would also be discussed along the way that would allow users to more mindfully utilize this feature. + +## Basic Overview + +This feature introduced a new `auto` attribute for the `` tag which can be set + to enable or disable the automatic calculations. It'll be set to false by default. + +```xml + +``` + +In case, `auto` is set to true, the constituent **collision geometries** of the link are +considered for the calculations. The `` tag can be used to specify +the mass density value of the collision in kg/m^3. The density of water (1000 kg/m^3) is +utilized as the default value: + +```xml + + 2710.0 + + + 1 1 1 + + + +``` + +In case of multiple collision geometries in a link, a user is free to provide different +density values for each and the inertia values from each would be aggregated to calculate +the final inertia of the link. However, if there are no collisions present, +an `ELEMENT_MISSING` error would be thrown. + +It is **important** to note here that if `auto` is set to `true` and the user has +still provided values through the ``, `` and `` tags, they +would be **overwritten** by the automatically computed values. + +> **Note:** Use SDF Spec version 1.11 or greater to utilize the new tags and attributes of this feature. + +Here's an example snippet of a cylinder model that has automatic inertial calculations +enabled and has a density of 1240 kg/m^3: + +```xml + + + + + 1240.0 + + + 1 + 2 + + + + + + + 1 + 2 + + + + 1.0 1.0 0.0 1.0 + 1.0 1.0 0.0 1.0 + 1.0 1.0 0.0 1.0 + + + + +``` + +If you use the above snippet in an empty world and launch it with `gz-sim`, here's +how it would look: + +![Cylinder](files/auto_inertia/cylinder_inertia_demo.gif) + +## Links with Multiple Collisions & the Effect of Density + +To understand the inertia calculation in links with multiple collisions and the +effect of setting different density values, you can launch the `auto_inertia_pendulum.sdf` +example world using: + +```bash +gz sim auto_inertia_pendulum.sdf +``` + +After the gz-sim window opens up, you can right click on both the models and enable +the centre of mass visualization by selecting the `View > Center of Mass` option from +the menu. Once you play the simulation it should look this: + +![Pendulum](files/auto_inertia/auto_inertia_pendulum.gif) + +This example world has two structurally indentical models. The pendulum link of both +the models contain 3 cylindrical collision geometries: + - One on the top which forms the joint (pivot) + - A longer cylinder in middle + - One at the end which forms the bob of the cylinder. + +Even, though they are identical, the center of mass for both are different +as they use different density values for the different cylinder collisions. On one +hand, the upper joint collision of the pendulum on the left has the highest density +which causes the center of mass to shift closer to the axis. While on the other hand, +the bob collision of the pendulum on the right has the highest density which causes +the center of mass to shift towards the end of the pendulum. +This difference in mass distribution about the axis of rotation results in a difference +in the moment of inertia of the 2 setups and hence different angular velocities. + +## Mesh Inertia Calculation with Rolling Shapes Demo + +Let's try another example world, `auto_inertia_rolling_shapes.sdf`. This can be +launched with `gz sim` using the following command: + +```bash +gz sim auto_inertia_rolling_shapes.sdf +``` + +Once you launch and play the simulation, it should look something like this: + +![Rolling](files/auto_inertia/rolling_inertia_demo.gif) + +Here the right most shapes is a hollow cylinder (yellow). This model is loaded from +[Gazebo Fuel](https://app.gazebosim.org/jasmeetsingh/fuel/models/Hollow%20Cylinder) +and is made using a collada mesh of a hollow cylinder. Apart from this, we can +see there is a solid cylinder, a solid sphere and a solid capsule. All of these are +made using the `` tag and have automatic inertia calculations enabled. +Here, the moments of inertia for the hollow cylinder (which is a non-convex mesh shape) is +calculated and from the simulation we can see that it reaches the bottom of the +incline last. This is physically accurate as the mass distribution for the hollow +cylinder is concentrated at a distance from the axis of rotation (which passes through +the center of mass in this case). + +## Key Points on Mesh Inertia Calculator + +Here are some key points to consider when using automatic inertia calculation with 3D Meshes: + * Water-tight triangle meshes are required for the Mesh Inertia Calculator. + * Currently, the mesh inertia is calculated about the mesh origin. Since the link + inertia value needs to be about the Center of Mass, the mesh origin needs to be set + at the Center of Mass (Centroid). Functions to transform the inertia matrix to the mesh + centroid in case the mesh origin is set elsewhere are under development. Therefore, this + should hopefully be fixed in the future. + * Since the vertex data is used for inertia calculations, high vertex count would be + needed for near ideal values. However, it is recommended to use basic shapes with the + geometry tag (Box, Capsule, Cylinder, Ellipsoid and Sphere) as collision geometries get + a better overall simulation performance or RTF. + * Currently, the mesh inertia calculator does not work well with meshes having submeshes. + Therefore, they are not recommended for automatic computation. diff --git a/tutorials/files/auto_inertia/auto_inertia_pendulum.gif b/tutorials/files/auto_inertia/auto_inertia_pendulum.gif new file mode 100644 index 0000000000000000000000000000000000000000..b74d8e7a8f96e8a8dbbfff1af8574b6610d22346 GIT binary patch literal 1921301 zcmeEt`8O0^{Qj8LGBbvdy+QV+v1H%IAfXzOE%hE*QlY8rNwY8`S+gWjV=Gxl_9e|2 z%OoKoq#BWIX%MNDPoMwb`}6mF?z!jOd(J)go_p?jJ+JfJ=RWtyQAblVe>A8@;D>-d zfWHga0|*ERK-Yc=k{SeuR)mNTMRG^stQlzpT)KH!=EP-1d08bDO(olt%1Q?hY8j}j ztEsDNs~cHp@HREoHMP`KwKX)fHMO<1v~;v|bhNc~{x!rrorfKI%4j`pJ$+pb14_A( zfsv7w<6*3_nQxf6zPc68#m34SD+0z@TRXj)Kk9-%`q0Ulx9j>}_^~5)#~OxDxt;VP zKkzAQ@%8rgJ9pvinX`nm1b>46IYPj>fb-|Bkpj;J1_lNPUP}lL3=TOTaw*6^%+D=6 zH2lhC;5wa-%d$OU;Uernx2uHo{?9ac_%BgjG2{@m6em7HTx|) z^;ULPcFvvb-0a-E+`IXA?-k_VyMM3n{=>4O`-Md>XCD+kcu@3^aXXRmfKkFIDJ>~0 zFD-vm_NYQzu!2!k@#t~I$DJpSE1rD(Sy}O<>PcmFWp(w3?dp%~)gOOW^M2HP{83xq zP}|;C+rh1U$Ey9nul?|&_Ty&l$F16r+qJy!wY;rb-cDUjT^;X7y_0%A5S?i z8{*D4)HgJ|{@D1mp{b#<`6;uxvAOk8VQXDgTT5H}hxU%{#*Xf`&i2mEu8wCNozFU- zJ^QrzZ0XnYVCU!0p0l5`yI+iOy1F@R4yT*L;q-8N`g%FN|4Ls^-~ZOW-oF09{vLLJ zZ-0MZKevzjqMtj!9e6qL^5y)-;LBG-z0ZdRhen1*MmBdxN8XHw9Up%)KK^ceqN3pK z#N^wVPg8HFrY2|JO}+b9W~OI8yqozr^MRK~;(g%F`s#n0o%^)(ZDD?4X>n<3^XCfw zz{={{%GZt6<<-@%Yip~kYpZK(U%!4^S^W0(+j_Ly`nUCU{`d8bjrH$8HrF@5uP%Sz z*xcIO*xKCM+T7my{(Wa-b!U6$=P9M1KH5Kj{`$4^Yu7_*_t);9-9LXl4*dP|S7}e= zxPyl~4vTj%(8GWP004l}PcTFfAOKMMtBboDpGx5rPhiJAWZqFW_<*I_g4T z&}DSQW%QAwj_82P;ZZ?XBZ961bpA~S{4cKP|A(soL)HH)s{X%&)ZX5n;2z+xpu7{4 z!KMoC)AHjoi#c?ZigTe;eM#?aX~T1hi>cUEz{%o?E;*u!)n;Nq zaALL|HiU%sp9hKTV^p`|vpIq&`OM`prhn<1$M{m`BIl;c@hXHiiN%zxdRs@}q$s#Z zUFsK6P_ZRF)j3_UPt?(uiMex-o`sT4_37hrASf#tC!!F!M>=evqH)By=lmH#1&i0D()M3{^bV-njI}+r*CvD8Wj{Ums%5vJSdeNb36C68{{~BWG_c zp1P!#g7lM1*&cxxNB@^=pzFj+(NDaC)}ZhTon-HUmcQ{hxA$xipU7F-@TiD;gI&*l z|KQKPe0bt{*Pq`zn=2oOpFiK*13)!+q~HDo-Vu3M0M?k2YD59s3Z6^X(Cx&g*;tMN zZ)+|T@_jXS3bX7?n0VZvkhCqo$ND^j1rYwrL%Eo??@)!UBJ5FififW^0kSPrb3W5v z>cV`MliJY(f+ur|lS1YkG(YEfBs5`tR3ipt@Lea%&dPXl!%^f*8CqB$zPflOH`RD~u~g{F77PAZV;xYI zA6$7M*DDyn20cuE(~a1%)z6R$!yDQeR>YHnHSGoWl(34g%7_S6;~hhg#132)E281b zOw+tMjdDR778+7Dp2QRFph}pgrN%K&7tdJp3jJ;>2f9&XrBKarH&6%o%803REpW|-ls8QO<(1_8rQll5A#8MB_D z>%Bg+nUtf}gw^$a^npa|5pm*(orreDST|gy48?&Pma%Mw4XXh_A>AH4&h8Q~$mFmpy*GK!&7^u<_-KM6`7n0Z@XmHKegkSX6t+xca?)GHh-LUPckjFLK z)1fV2x8D&P5JoWZM1B@nDv-#A!K?SSZNWF`-)%wSe)v1S`|jrCKo3~)1)St9iCD0> z2j7GzAIOMZxDvhg^9zHn_iM52ZuqZBbL_LRvFerwOM!R7GTj%P+r|_Gz2fd#VC8q4 z#ugMDR_;LMnQx0$xaxJg8-pgI<0ln_B&@JGSSu^Lev7(4+cVMM{`}z44_TK!zI*xa z&&9`ee}ApEeEa*G-+yRt_j~F4!9P1+>h}Kb{`mGU0^tk*%!vh*<&y+m8NmHq7Sxq>P~E7Up_^8kO4K}vcVH`R5ZL;@Q72lcmY3A!?jr0i`y;L&QHRm7Q@dwab&0Y zG}FOiWHgtf_=``sg_ofA=uSP-kLHq{T+dnD;r6JRuiwI_mPkBy>ecdHPw^fsk!s=g z>cy?!CcsOj`3f5CYTuWu&a{G+iU#EOcE|ve{)Nek$o*pw;s`w+nKf05eL4uc| zVMn=kvKyJnu4T&mUvM4GH?lHQ%MPj^ec|l8aVLMUOwHuQi{o({*$jBO#*w1~Ckr-m zDqPF8yzV(gR#0=9spUH7kG}Ms-pFem{H&C_!;Re8xJ&vzCx1iJ)uMYYpPSlmu_%yX z+7+O{XY^}F9({Guce7w}@R4!Li({65#q;C7mzsXeLJ~iS-CH6ZG0ztgjjo{ivgeGaZ+OyL#anhL&T7&QrFVC-(e;dY~&3YoXomkzkKBKXl>k96#-G@ zy(ulKMBqv63RcL!m=!&E&=#nA>yqCSH&MIF0L2B{?g3wPVkk49Y%BSQIZrb~bO2Yx z=N_@*)n}Z~d2wJxP{T~bWiY7unvgyhE7Hx&FtqhQ@Rhh|nQoeqWGC??;8@K?ub0yk z6Ia1NZ|aFJG3htL`wTzLB4gs`WVd)n zjGOEI0)cOv07xbY=E}35n3D|UI$9~mrQbI zuDf#N#(f{2n#Io-cs~}^#qMMK|SxA;8d8cLuWFivqb6^6GBMqK~hY&12z1wr7wER&@ zmKmce^!LCrev$=+B2?fGglMT9{fwC3R9Rh8lGDTKZzXbn7Mt(NiNpt0O^L=^Mb zO8up?mvd&d0d^+J=@bke1kS4M7F@*Ml0bt#*^}&OEduG6j7W&T{2swpH@XCodcYV! zu~}`N>G4sb>v-=S#-Z0nqB~5{O_FPB`K8)2By{uGbB|NId@tmd%O>A>bL3L-)^W&T zH0&)B|>#?oUdcOitfxJ@%U=s(&~**~3*<^>{7#SV6@p zuN`Fcq}y|Q`o66r9iBeo5Wl>|BPmX|GA2`McTy@M?4!$Qx9ubHH0UEn$Das0V=>I?6*iI_By+VO&&6T^+Shhtpj zK2s)5)91a@s}J737jY{v>eg~d`r1x9U)uTdcL&hnjP00=%MwR+S~GShGyd*m>`G^} zHj09MG9fQS1@C1Fw`IboGLb(sQ8HQLW?2$GSyHiC()Y4tWwQPf$^T0*#|BX{(E-f2W-8<=Gq`D7c%W}EKa%QkPzww%hg{+VqnlVfL=V|qd4 zDF*%qg>Y`mah=LJ{xb(JlY7!E*TW~*Gd9=zUaoIjuHRJd*`K)tp}YYGd>o%QM$8Mj zmv^x(FLWv|{AV6f=I&LqyAeKjqhjyI+`AhWoA-v8_m+ro-j}b5%GV|VwTb!3_wrNP z@>8es(|_h?%G|qSb}z^0US90I{CoG(ZUHs%UqlmyZ#0O?Ja=*gBEn3o#)mKw*E zniiCrUo16cmRkQRwUsTiGcU7WE-@#7&XC~G0dUvpvg5zX@UrD6&C5M}%RS@Dy$i~H z+spl?%g_EQC&)fJ_pAIl9$tzTd5c2aXuBIa{V4p`Bckl%tHO_uwjsJOuvjK2uKjWR zGAQBKW0GtI#k?ZXw}KW|kz7!b(q56eH(inbt0L340!sj0z#zB`_>N&-LHm=!=_e0< zJz>aJmY7$T`BpxPtE?!ftZc8Wp02F@Raq&EsN;*wF#m(mi7f?H?d?^a(^Xx+s#vns z-R9LjzSVtk)!ewMB?3GaEoi|5#R=D3Uk2IWYe*Msl6-3>D{Cg5Yi0^+W`5PYkE@yW zt)2b#*oOCbsi0zEx_0eX?Sgp)-@I;Yxn^^^c3ZY$;$m&~0Q4;bKFrKHXTSuXWh-8Ud*y_f)In zsm{BndcU7yIn26oS+Knv*ct`?v0RH~JT_-M zw!c(&)S}V8qsCpX>9Z`@F0FnvIvsH~YfaWu&8=d58ovt^}m_G^6M7%;V z{bgFNTC_x*Zi%|y5_7-BKNitSfPX_F=K-y=800KUv_Dg5Xaw9Auocgl55T&i1G>9A&iT3kBDuRjZW2X`?;9DUNVef{~){pY_r zp6`m}#;>&85o!IxL%zq0C=vh)7|3@XvfwuYDUbZfXfIf4t2xb*d5;(8bK=2DkA0UX7u=b+%F|9CyIajB!x0Rwx$7d9LeDII}2 zkvc!ib=icpnD- zoG0>_1Tn{S&31rJV&GH6mv8Zix5SrR2E-iIYs!Lc@k9+;ZuDMZ` zZ6H_Cep?VYa~R4(tf0Af?~`+?xB{+i67g+!MV@9~w~v9pfGe;LXuo(O@)~ibUCW|f zJggn~r!6O5=uGA#=b!Lb%qLv*^CIG_j~yUa5_}4UP)dXM@3?0m7XlkP)q33nFX)5AP$uhtYz4+TiD_6HBR}^{Sljr{6~1cpFpnHtyNm`1fxU z{=6kAOj4{S6VFW2ZcHW@O{RoRzQzm(nXgkszK!J_$U5#qZGBFG2vhG-Mb?^(G1j6p=a$$U9B z0LQb>5j+a2E15 z1Fj^&Ihhk&mWUTi*VPvKmG>abjCFz_hA*wBZS4}Vuo znL+~u_}g%JUxG-xMc2o!HRV*06B;(aL?E}2_pC*HZEIGC)|7R?NAWN=V;~0&al|w) zBfmnwfzH?pv6)a@6)3=!4}JKpf-z884R2$C1N^{2BO;gZ{LXYxSSF%g4{`9n4Yiva z8V@(Lo^R-U+|b+Gz#P~#*t6L*`ft7}0`fQwQa)RPn)Ah;Wh4 zcXI?JkBHSS~F8ydMXcH9wwSVmoW-6VR|7P`Y@1q;5r_2vgxergw!cd>ReuIYKJvK)S85K9W?h{m7)c?VS-gg}40a)u>_oN)r;^ z_Tkz1ZBQgW@3-p4Mw&=7D!Y{leIEM86aX`~TC3U>Y36a>J?MISU1+X$;8~q;NNATC z8p0yJbU1UCxmOF1VUCSo|5W=J?3Ft)JOY`z4N|S`v>-y@L*V+|?s(Q}Y5Zt7Y4@TP z>?8wn6w?P#3Os_MK$3XG>>8iO3kU`4L}|BA_9>FOXM6J9<{Z-%tP;R7C+E2tuWM%w zw%6X7UHQ~kemXZ9BBHKSK)(JZz0j1%>$*{@zAPwpttTIV^*rH`tKBqt<&t}Ox_HQz zT@d-?%ZCcaJ6*XJ(Y1bNSA$+XaJcXJ)welxxQY5Z-LElXX}Uz=_niU_`}VkkYb`7L zG|sPjrmMb`y7D1-c2rgIepF~{d`aUD$M169{liY;Pu|=q6{&XXI5{;*SxncB{j|n9 zr=Bin;TEySU_o12L%V{>dXdH3I=&75tkeU0hh4`-7a&D)Jz|T#jiGOH5t~6TrE0ub zYdqA3UwkH&*nI3#aP=hfzvi=u25P|W?g1t{r3qD@eNPlZfS zs=z|7S8e7A79|Qp5p_<<55R8aEP;ib*ECA3g@mTbaLY!)b1?a4R*-~Ryi>iPlD+&o zObPIMSQ?+tEEd$M&74aiKd{g!PLfVhJF0p&@aa+YhlvKxnvct#I&0VU7`W)R%s+KG z^n7fiz%SG7Xd$uhHEmzPS;B16{z9U%Tx8dUC-T<@g(^ibl-U4;TEXj}WCE(qU(P!vaCZl`AFKAZc0cnTRZc4x%5gW6^s?N3Y_FX?tX3m9d1t< zu(-_LiYa!G+EJD;P5wnh9en5+v@ONLGQxdDJeeYsb zU7z`-nwEw3U(mgFsa&upY|kAvZnUH z{%~VKCCjZ%0c34vqJl;k%)yBwZfAcm(Y5B1Nsm7=vK6PejdC6Zlo-`sxm{Lg;}@!tLKpZ z`~j1}EmL!Ay{mTt5DiO#l;efU*Y5canhs#ohJHfiqs8I=d2~(J@ryb$T$ljYB%d$r9f`Pgd*%Rp+$1Jb*r$GgS1*$VkYdxyPgM&4-jpg6^hHlg0+k?gtBi*u`X}!^n#H9@jg=mNTo5f5v)7jaDb5JO#Gm1*0um&k zga!Z@SkP>7g{sbD^q*Q>za11BAUL4Whf2;$wtJE)OU!2<#*@JzrZ};=5S&c=XYr!U z(yYjyO5e4LBPU`?GH!Odpx@NrJvR2~(C0}9b;7Ckr;Xsu&rWo+%;K~N!HtLzA^J%g zL)ZarCr25vvu>?`pM(4F|CBsonVty?X~oGHv%2>-{FKwf{N`jG@I4!&v&cMvA*#E~ zk&@D&KX>qp#C}QCH4XpN{{qh!yy<})SU!RYtEAt5D(I-N5PM9n6)RO|`cTJ1K-gMP zpy{yiFfxjXE%|HSF5fC^E=TFC)$} zsn$5RvVNm{|4sdVJw5$)v%^UJQ@eeS`u1KU0}6{pPSE-=mSPzQ7mh;0BG3T8o)WuS z@{jnP6GQpuH`l6g5<(oU#>Avr?%>YcAF(@3!4*#Y?H=mW@6(K8xc({=6nZQTjSkdb z{I~&>*qvERCgNe?W6jckeuiOINrpF1CW}&75$Lr{m=4~z9qfPH;2y4ywrndLo7s)b z8A;+-W2Kyl-;$#kP<%DkJ{+H8a%)i0vK_Tr5ib^s<<`z!elfnqjjKEaaHY~H0qWSJI2x5 znml67Cuhes_Ixye#`sRJ!}px==~r`Dg$o~k-MI*VwEv@Nnc3CXLfy>qE2$AhzRH_- zZbZZ%Sn}?-{A868nH-?Fi-%eAl#sE!0L6EL5LBaE`oaGDs?1CMrluX*!)Hqb&+PO@ z(DdQwk)<}3JY4l}zhO53$iI#W(Mzbmwf{z)zr2T|ab2@J)yIcjuYkqlFjk5H0*in5Ea`6_<^UA!-zMHUq{Kk!81 z!t)Gz{Jg47?0{E-^01V$ZVnqMDop}_QP}1dU3W+f3#70U50ftTcTb`&Xum#c)~)}W zSU4xw@chjo4i-tQ*elh!bm z_N5?XIPt)zdE&EGh*|pk`zz`*#3R{huWQaM(c%dHx3)gYgB1kHh%P~zmT?x$Bw|+B zNu%ypZ1LemaK-hcW455bSESGG%iOyM!s8*QOq1MEU;_;BfS|>mK1F*3s7ojgltV|`cK#LL7r00pwg3Pb_t(kFq#o21gI$#&akA54-cW3;=L@0d*ums4(}pEk?0+g>-=$`E`(6)^-Wsy8 zQYGa42o$(TLaz#Vdeg&*KpCgRQw-S63V~q@5;B=u$jH_;>I<;%V>0amt4lQ_iikTx z5%(mG4~n?ndrsk#v8xTVN}1c0kKlzh_)P(c9KC%8#VwmX5sl`N;3iiIY;>w@!0F!D zvi`Wnesy+dXhl+4K2R0|068TFwC;-;feNa?Vg*fr7?K)_7Exh!g=iC;!@V^l5me^1 zN9xeJN#$O}?7v2~sc-Fi@cWUQd;uV^KimH3v4byiTwhQ_KyvN<`8hA{**9lVpdra+ zWdvBzq(hVjEPModZL)ghw4wtKe2u{g>ExCN4m7bikKm?h^SO`hZ(9W(6;SH08XKsY zAE=d=jxBq^lz3U+qjZ6F^b7_X$)kmnFliF>I=BKrb#OfJ)kMUx4S>tjoL5t2uk_4r@@cM)kpC0y@m=p zA@0>DqoKLb7n9YmJ_imh1m1ZUN`HU4tD`$7z4`&KXK2+=WGPf+ZP2=jTSbsm7 z)yYlb%t%}^T~c=hVr3$A*bV65wlDW}ly?gurRM--6fHTbq&lj6cvQt<^x&yc)u2(e z$WisAQRPe-GcI(NIHcV>I@Jk1jfW=0&|@;`7)keNkvFmVu$v5%_?NJ~mbu=aWQ-Gs8jJ_6H$|}pq=W2 z{K}9Ox%C#P3Fr)I8nDXh$rs=BQ=@`VDNEYm7rb+yw=@mS^ z_Au<`B+RV{W_*g?0D&0=(M!weQd}@)+#`V`G8mI2&3YTL=n%!DCv4K=7kdTgU?x^$ z(hlS43R7N1Q+<&${Yf+2+?f}-Qw7g_ih5@T9ULA6c}5&|kK@v`FccR)%)mDB1_N|( z5jbEDs*a)ldv&NjnMFPg>|Jx|+Og>p!5Ofoj zB;!q1#=sILsnVJ6;!z)it;RjdXZ9dGfD}(ajgZ;o_v&Asa5Ns;nu_JpM;vIXF*IWU zIAMfF%mm^|G$m4sG7oBiqF%)S&&1G_h%~cAI_A%N$>3S3vtB0UbQy0-Sh9dAAV~~Q zyX*v%!_bvblrU+5Wfy@U5=99^mtq0K0AxIxCgGICKkOc#Ox8ouBnY5@5P?`cJq%3~ zGNoxrQzAmhMisPuyh({g=-&FVS@+MA$51~19@|wi=gjf~>{ETR5I&Z9ey0$;Q(;q{ zX-a*%JghOn^VAf`lV|TaukdLqitqP6&GVu+g@~r<2!iYvX@9jTmPDu;pYFU3b1H6wsOkkw(o(;lVcnG$~t}6r)RuNK?-Q-V6b$ zI3-F6&d8vl@dTGR9!$%Kp*L*>LKZ11eArj`e&>We&Az^RF$8xxLc z^!Q0y*c9vDto3xMZ@@B*lX16^T?cl>$0>TtWw3Dv&hxS_Il8u9yZ>v@?Mw zd}gq1jdRun}6k2JKi(QrHgdykL3IrJ!WWEHR`@%!sw9<+8J8`dpw=6NDHrkofD+GI{8KmCLNZB>_w4i=O^ixFifu!?{ByHyRyQe77$6y~mWETg;?>t9d_EBR2TmA;9*n$R`_(4;8JPRJq zO1+>Fa>Em7M5G!MsqX4N9x$JStrS8HjW!8|)0O;92r5n>(@C&zE7+Mw^=hS>5h!pI z0-EE> zCP}aaRw^zD76VgE*ojUsHMt3h3Cb6cW07Tez&&L=m=rxfNQ#bs2a5r`yOk6jIr%YW z#5?^NScypeo|z<^1C)7vS!HCq-w}xQMg`#^3BlXF4wS1qk`FqoLG!Yu=DpqO zUa-ABN-4-t@~VT~1lSA;(xWi%!WdiUxm!8C76zHe za)TZ*>7oDUZ6qKzL-a$=qaOoaOS~eJYaz7rrsYDMw~)vY=`*`g{2j=dh*;ZrA_*4l z{ckAq5{7=60E(E2zQP4al31ltoi1{*~F9KLfBkEhLgK?wke*$9QxcR9~yKFS!V zwg|+>Ku^Sk+1URo`vwd^fz>ht)D~^l4uuvJt($GnJ;_IN&~4(cyc;gPGImrk zNx9XNDV8gJWz!)=;voCc;VLQJX=V=ch*W*{SJk0H^XQG$rA_q_h8nY%H(8+n=#~ znz^;TzH-0rgJq1zGuo?PlA)*eV!v)57HNFpB&Ndw%eqgv-ZQXpFqYG&*atct^q$uc z>pm}wR&tym=mTYq#PLrxw4S7aZ;2UD%3R}hue`XUb&6!z)*bjVcOG%W=HOAahtIFh z?*5#c82Z>1`g_;v_ijOnR4O<1g;p?J#$d1){QgOUkk5V zwSBn};!>{g(!p4c2QJ+J{mR7cn8`6ir6ft;7$us_#a1P{Lfnp0vQmnv@-5YZ808er z0_j(W8#Oq?7D@F@NQ<)yo|66nOUZMVA-%c#GqJ*Efv3Mo9}V>R*4Qwgb@fk$r=P{f zo5=u2!7DIIj#8=cJ_p;0dzbb;lD`P+`ubftYIyhHj}%>Bo&5v{_N3AQduNP4SiaY9 zJ(%Q*!GaJc0B*exPHK=(N(uVzYCy7hn^YSqoU;T-$F*ZA_Q{O9lUFYcwt&Y(8 zx04iCt0f(?uXk3evyshfh1ZUoeXiadGJAW@La%u_|GHk=LNoQNxr?*Q*N(5=F1pXQ zrmr9B`nlY3==q;+7d@7Mhz|eRQXvl6EkxfpWCrT*2=7WYoA42H>bw&abWL!!{O$w& zyYCJSNNkE=z95WbD1rQ=55@Kh?)WEG-$s@~D!T+=ivqA@Tig{d!n&b^t%mdH{_)UK zxWSYkbyU9_x8&08agE4(OltD}g=5>-Tr|{fuol5D=jq-fYve!n{=4W0R zO_4S}j(|Q4*y~^JD0^LJB=k~;M;5U*olTOn&S~iD+;_Y?E&BA3>AMFFe3J#@zF3Q& zwr7!M?-ge-raW84^wRmz`$)6dR4U)(W9q)xIiYAdi?2=Z5-ir*R=O;{)w}$);Il;z z#eNmJ)^N;NZ`R|O@yyIn>)P!6=3q~e(0Wo{pTxEPy9&QOKWYjNoP1!w=Gwg^mlEoq zI^EN{R!K$4u=_A8j}=D6_fG0CZHK@pz#WN3l!mRQztE4WY_So%=*_YK^YNpwvYlDc zpcs14KignTJ0D_GCLqGLm5m$nY}l@;xiH3p3s>p4L6BR3a8I z{l=`~bZE+)T#4Zk3rFm&I1*L9W+l(G=XHnKXnlHAr;6f*{Ybs=QkhnKuco7ZihF0b zwBwwzve*kIwRk9MwDfGQhMFMwCs1Wzu}9KluKwFW0U=jLk9Ix@jI~!m)w(6A%U@+> zc_fOTCQZ3s3`pE_>9org@a>kA;{Bs#EP%qIz&;8{!xnKq7kH9Ts(4D_Xjp*s6z@3X z-CKidp)#2qR=4A$;v{oRoK48@vkoO}ql@2DWXD3@39kfK?brG$yEfQo82HH~rn2I} zcBi`a=9A$Y8x0S)0>$(s&Ub{9=j1j4J^Sa`X?}hI2TDgM2LG%X|IBKNE2w_^AH{Gq ziIdX7!WuSWMb8P&%Kr1KdM)}RuP`|WD0q-{kG^Ppg^K)VQ~ILm-TtDD#>dt-KCCx` zx$YIfOlpLK>Xr&B&_hK&t>^uB;1wYZ)=}uWV4vg&CiOe_oXFXfV5f_Q`wTRc1Rt+c zQ91mi9nHOErH4zdklVJ<0Iq*xR~AJm>H-OZLW{Uas}0MZa}~JZFE?M&XV_Yi8VUxX zB2hiItjcB)VS5=0NyDI^{?+Y7{{1KIc81IaabX8sxPx@)HNX6--nf2POb~3L=yz_zcC>1{eQON`c1^c5-&31{1 zy@XbK#q>E?5DD0%vLpcChI!kb5fFq{%gKx?iO%aT$-YK`6?gD-m%)YWZw3o&oB0sJ z;H+>bU^b?U;ML^sFE`dIB&?51i@4Z&@Jws2c#43@wE?C~ec18D2eX{R4Q;Q&6B_Ug z<&kN&oBVfg8mc)fMJa-;;EQs=q@prZGnEd%*+~)wWI@ppoD}j1P@)i=VNo4E@40+X1 zWr%a~?z~~zqoTKd>%>e8w)%{G`KE)~q#fdJCVZd08YI%GSo&`!P>VMLy{V(p;Tg(N z1hZ*+2S16_^Epzx_36rECBi*?`hf`oTn_&UX&gec9IQ9@G<>#X^*+EjRiEoE(ppiO znN*WokVdsSRO$Y;sm`pg{+O|aP*DsNZQvJ`j3$ddXWCr?DRbg1h?j_Wdy zvYy5yp|jRS@O+>QxwRRhJ*Rczg>u8~6QW%=RKVk*RN7iK)MW2C)+Dr!jR>=)!pBpy zFF0YpA|9*vy4U?0Z|K^Rf7*(QoYuWIhC>AZ>XUC|C58i3MBbC^bog12bJb+TUkyi5 z*<%?-tHtuhgzqwrv-CqdR0RiOuXxmKhDGb_emiN1Mo8A#Yl~w`3pRW5ZCQvw*Bccc zk9%vw!@O$^rSA|v!vFSuxEFjom(!tXe9J6Rq7&}dCLJ0h4osPxjy%~LF&d^p)@G1V zWn^uBAK@rj3l747LI3m-44iXl2lxWaflUKB&u9-d1Z1nxBDG{M8OCX$WCgx};ut}3 zUf=*8{Af_BaEl@O7mb3Z7oPDW`iSXQv*dVGgPuLsK0Z!IhineO>a60#0Mm#ZJM;`` z;{sc82d9`yu?ZDWw5N);cFRe#O_*dcX^=!F+f+h8F}43j@d1U2Viko91Hef)ME>t0 zJKLrH7zxnfe^Qy{odBNWU)4`_0*n&Or)eQ6co!`?zOO|fS@%M|w^`45{HL%H1>q8~ z2CYQHSwQ51x46cqU>(LTUNXN?R1~VD(^sN1q>P6vtwr3nXvG;fk_|~-8Z0{#OR5G5 zq>KhxBm?z%IOPzw)I8a^5N81>kj%xISJ>&U;#**48Vg=&3?R_{{iUusk)-XDc-RJ^A4Az ze9MY=pDBv94!jmv;%!xCe>~9pnX+zhnPd3;eSz1y7hmuHj00T(SyyvRSUAfvYFjeM znnjha2U+l_Y!Z$TFJ_VmaxLJv&Vo#nab|;@vtuBWGMv?5QtcC!lO_M{3&I)hP_zV3 zqSGi^Bi#vp95L0=V-88hBIwUH!bAI=?^tejvcGH z&GAzU{`8q2s&+o=(fNcuwGi3@zYMwIXD^t-AZvmS%fJ2)IQZY_Lq6elPfWRe#JSTS z)WX%+;`3^kw;x@8pm^q=QwRCj{orw{Mo&n^${!CVt}ajplKL*yDsX z^_#!I9!`*}?U1v)Udv8Sn(3`9jq_eShdX{rS@_;8Oht?uE#0Fc>EDGbxPlh0L62HY zpGjhmA)7I`vSUKLTh9mhb>FD1(0ZhLyDKETt9<2^M%qM0+Jw~YNg$~pDe>v~QenCRKJ+sCW-Q^eNNu-5DTzY?LuX(utwq2q+)ZLHn@rjUD0l(j4NnARjYcc zr`=#&)nKjN=vdWwT)WA$>Yp8{LAHt#qtz0%;z(Kc@Jq5R1DVWoEz3AE9s&~8WMc`{ zs1cl1#j-Vbk7H4xm6f;b$(pZS(|*2Pm1)1E#(2y^>aeA%*@`;dYSrC(IvnF_jTPjK#6y?E|tDuT;v8D4m3r}kn!u9R| z_d-7;=q=J}7t{5Yj&na4)EMyW)VXBcPN2yc&N`Hesunna23dOuXzg%}CD?XKWT{Y& zc*wsmhge-6E{&+Sp>`++7`9|ww`qOoyW_X;qVQ9pM~qkkQ8TO7t81k_2Nehc)?hnH z63Air}w+-5X6gFF|_a}m2FXyrqV=vGeOyfr3 zj-FKaFZ+r(qW@)qDe6@(`JcYjZ9&w-UX*)?_ZXEduAj8+lxABm@o;@1E?lZkU#?|c z@^XFjhh^0M@>>)23IQ6j?tE|iB~^IMfjxaR>}pFh_x=RNj|)ixLbDd0q-W}T3Tk?e z@k!ek6}_&;9KYq!Rh9IbXlrpWAIs7S57j=;g(o4ucQU9@-LMVkiq6WqwBEIG0+go(XhKG%VGp~K7wkT zkAqiWt(g47gE)&E9L^ml?rLP|hcoAKw4JafB#;$}ExBl?Xe(kF3etCCn_&c`DLCt9 zBcHpGN)sU0w~fAahflX`orszLYC9wzBp?D~2aZ-S8sZgo}pDZ;3+Q-A1j5X_n*_RMlV_Ji$1!<-3ao&E|Yd)Mb+bU<5HY%L304_v1)8vE`+4l6b0^Db>bOLN$WC zCW|%9IlEti{7#d6w6@MH8HhY+w_gxwg97cdY|&k%8eenyd8&n?{yFk8Fxtj6@rY?p zZ1n2PT~l!#S0VP!k*#F!v6Y4+g|vfLQxxF@eQ1!OWpwHYHz zrLy50_v3mUo^QO;B0=+xUEEpioLBVq+rL_` z%XR0T)#<9}+!%kC&P(9IfwcIH^&|+~g&-NeK|wy?`9e@r4W3iqmMeBp(~7_$|6Qwt zVSoTR(wUY5(E@5fZH(K+LXJ4W?lMGlfRs)iU5Ci>r|V7J2a|6b>Bc&t)C*Mvy^b~= z6T15<|uEEoK~L&ySV+tsw|TNre9O+rCwe>-*eLT z{JmcPr{4ardIP`io^6IPTaziA`h)Lz(~gZKedV$6Rw3^Z-qqwtvxz*u#Nky7SHRWb zg;r?Zi0GZZu?PC&NqytD{puMM<6XQTSUdlFnDOd}K3NFL{B?)pzu z>(Bnu9|SEHKOONwj=G`rhXp@R^ZqRhPskV_7hCPi`PjFJXmcSqc6nc1_W$d6`f2`= zY2yqv@_=A!dYUz@U+yt79n^Pa&(wPwbg{uWYk2&{BsFq+an1bsqU({@biyTxaF@Nl zS(bj9zt-HHi(XL>jkO`QP^v)<$Tbx5T(RbMlW}b#lkXXPheV=4$4AC?9B9C8^o0YE0hVsCZRss!%rGDL0tkkEYVYra?e^Z! zTBP#4L20e+xB~vs#s*Hi!q&eTaLW8lQi48FjAq@A{&&!ago`=lR>0 z8{(Pyb@KxpNMCn~ri>tFT9JE!qd^7D?nK*{E!UQM9@2wco4p4U`Sl(JySMwleCpEs zD8#et=KAPEy@DH;dc&L79Xr2@&PIRRoT%@5VbKwFsi(%cQwgf0XLCP<_tuyj_pPWx z2_>WJ#n~p~JwC_}AK7JM{j1;`hdZyiFpDNvulo<%tLwX+9=`l=^X>cM{tRY8gOaGQ z4Q={NrMW#HJQj1WYt{9~&ZXT~t^Tk2OYh$K`hGA;FiYd>yQrfW=BBZbaUN-#ri3Xe zIp_uS&C{z3t+H7e-f>3<=3M7GeJT(SKGw<=pBVydGGZ|n@#Xp-F=lM{j}^AycM9i5 z%YzC5)i9T+v>h@pp3P>2-#z%{h@elpgPAb?&#pp@5&b%wSQJxUU=K>Q$ZT9PMR|T) zD#ylgLZ&EqenO6v?l`GX+b}<=)H>}rrP94OKXrC+?fm1QsB@ebON05+)qFdAlFF4= zLS<8~pJJ)yDUN97qUfKYRB@}7@sG)A9|z@%WjMYkm8*>&_-E-pa)=X;wVH@4lWtqD zMqJp8GAg{c0^}HRuvA%EEDi3HH;;_jb>2jL<<+I=FD~Qfrq(|7 zecwD6ksQKEcZ#Vj;}Tf{_ApfOsLmB80oNnEar#;ZmpK&W2V@byl?(;tT&&@)bkLxv z`9lqpQ!>P5mN8)D)oV~t`Ry3JrS}hj0yCqx59qHeA+i6$e~j72hODe7NoKlzNKt4y z{tx@YgumtSq@@fpdZqT0i2e!yjP%8=PazG40r6s2Q`gOfuY6>cg=0!QSh%%6;-ns5 z$zHD(x^nPZhTW-2AwewZ6qi&cgMBS1MhRwH*{N@}iz>~LXB8GJx%@1!uXRFob+7%U zo#&Tly;ADFWlSei;<0nZk1I2GCj7;!zdn@{$Ly}Nh{b9TRU@K~yAkF0%6v=2M*fog z#o_3mXe`sD<2jd>@WRTa=-cZ$C+~iKc`DSlvRtCM8;N^ zMr>MEm&Sa+S0kh5U-vePhQ#=n#{9fI_A7juj`tUhTrBcnxIWSTUn6Mfrv(EsC-u#D z#(%AyeoK*JG~aG2mVWuQp5^`T_vhyK|C%QAE^WN8`#3Nb^@oX4Yn$<)Vlw5=&(6xI zctssbYtD8qFDIxXD~`Xxfgbsx|0E=vAo`ugf`$$Str!WPCbJxX|9i&zXBf}kVOe9e zB^dR6>p_QaIV7ymxTHZ|%#dw<7bj#Q$&r(6D*d4_ptWH286m~iuVO#q)o{OdPU;sS zalphclOGqk(_U`8(tXpKsq)`pq+?jcpE(Ogc*{ZbDj18H`Zc_28kV6YT*><)%1qZW zEbUs~hR8Fhg)S2&%Ni^#elo-%J41~Q$)|tN6A&=6w9CzX*s&?|Hk{o|N=ZsInO8$ws*jde1^VjUl~IX{uRIx)$(X5=?{b6vCFj1-;Y!x8;{pVgAo3|U|JJTiWCgfZ8i@!_~N4nnpJf7BU5+q$Om=9huZwTBKfu#eP5 ze+WI%9u2d0$jwE5X!)cS%9<5J%qt@ypC}vFTDkvIFMChiQr>zwc}Xk}`Smzadz{-Y zW;wj%Usbi@?E2hIhIYDxy{c1a$=~XeTP36M+0sE|fIFP$QA@`s?NqspARM*mjXsNh zkT6GBXk}qn!2T>Ks*uR|Nm2(FPLZDM3}W+byhBeHlt zb3M7}`Nr|qB9)W4BBw=unRvMcgnWamF?qzr9u>=jq^Tw88Myb|Jjh3EcgPtpgk{(l z`XU2vZ|OAr!G!JIM%rzd>E1s~y%A49xQ*<{@237Yl1fFcX(wHJ;ow@`Lq+b?P*p1w z7lWS;3g=xMQ>+!{2zgA+8*+Z4w}yUws{tr{BteBAQ8GjCw}~xUeh$ki_S#bYrJ|H! z?uL$@j)>oYTVaO~J*14HDxMfM$VaE;*2z!Gw|eWUSkA=*Akuwk!7HI-JohCz?@WV{ zTZLc6QbQrKMN;?MeV+t3=;1@XWABX3Uoj%Fj z1$u~%Z6H67kKJmk1lpd~c z%$2%5s%ex1y)h@nj~h4B>PKfeMg$<%Rua#zNkXvl7JR9gG4*dGh<4uwk1=snbrg^m z!&M1Q#f-|e0a9J*HK5k{blHn9@L6ZF2gN_GP{lCWP~^oy;rF;C_IET64dS5ij!@$H zWfJ`A-W9N~1z5i#EYZG&TH9zdrWxbIab<5EKDuqD*M?5ikEle9%Tr}PW-~>}^dM@r z337XinLW8bdAzkpG+rI1s7O?bu5yj=YU4d`tqgLgY{y?nMP~)^ZHSyhnQ6uWv;4V? zk<HJ1T)2>yRGI<;%K*OV_EJ zOWbXv(g!2BOztP*;3j<}XcK0XqbEDn`Iy3PI!-7gSiUHJ!&{;H(VTmZ!ig9rLfIKn zlxqM8deK-|emwD98-*YcYYg=~NaAa1Nr$h|*oU>z+!mn_-i>y#kz`=^e`@ipLIi|5 z$_UnZkipj>0gndYxeORmcS|L^I|?nl5@Q#$C&^?kF__S!Mo=WuM6L<}c_c!UVr_*YSS7pA_UZEOR0bn2v_Y0-z}T zS`^2B>Dxd_H71!*CWSex(P05MwjPs-hwldYQvuLGyilUVg?t(>7{9}}kDwP)gij^; z%7}=cK8R2Wu52JPkB|7w6f+UUdYL4YPeWEo2-*2S(+4?kpb(3Av27xB5e214^y1J< z`FK|F9_y)(U>&9MzU`wH)>6uK#5SH~1uJBR6)oK3&!jMS0GU4nSk5E~@%S)h`>+xz z;&l=l9HZilVEQpoz>MVlZ3xFx#hqY#(EshJ)2^7BufS;m893=$R5ihY{~CIX-zDZ*EX0>?g_!8p;Qb@*l&q>Tu{0mRn=E0x2%90A;BL}=uk zP(KQal!2N7Ax2Lj*Iu%Jr7=%SGSi8J>^F#zo6QibL8Jvhpw5SJlfu`0VA=qVp8)3E zp=nARBFd^TW(J{gOI@d3{UWcm>YUI!H1gYyNHQLQS!c;cL%o0^H?Tqh>nxoMDo*mjVhy;hTuHaei)&;$6>-2YIfP>=iB*l-gtVmOa zBmm9EBMi_|4}4g6*xCaEIRkyf<$ZWBG|CcCY#l(RIS51*FS1R7{Ra@npb+!xU?Vir z3?N)age;Pvk0`79L^>oPH-O?L zFNNCBuv7pS-A+P$n5d)>G@osYSeAg4kRU{wP&!_$UjllHX2<1#CILtb)SQ_F)h_Z+rT?&C3h6 zt;Tsn+&x1iQ9nFu6@b;xh`$cY3SQS%C!U z=mtCjD{eN(+zI6S56kQU5T3!g+DpPyah031%r*ew4xghdIQFB#-9T7smCJ}hN z9(GC+PRAjtB)ERA!)X-paR9`F!qHEHete0<-ehN5XYCk-GB&UFQ;$9PbtcfF6$_#>=<;z%(RV)jQ$DRT zgOPvEicR~(P|y=Ze^IiJ_cpqCTax+6xpy0gJo0IN_fsJ|uaVx#j8q-s%M9V%!-@Qq zoO&0j(*bnu7$p6?dUJ^sRdz<9>J!fajpH4PZ=1p#moA!}C*HY^cq1Kth)1xQitYfr za*f1(`t;AEk)x(wYwIE1z+36TF^@p4J3h!qQY+xhMlm+^*4C>DccN0dqEtRI-JNQ? zz*VYm{jlV7;Mbi;@ zQj4|~3g;&B`V@<&*O5_y&1KhzANjDWe$f^_U+iUroJ;9&u5E8q577 z&hNlxJB5l4OWK@e2jx0)oC3|HK-*A!$GArAAf$YnK0R8csz7}9}eL= z3h#(+YL%Kz$C7>)fp0hnfAxDvvRS&2oDh|qBBVSiCEftd$ahO=t%>~uQ!Eoo^|wer zHob#NjBQEs25igL31!563W|t}jr2=@wT^p4j{P8i=N)NaF2H<;B(-=PS!JH_TqtAz zY3O*8=(U>ImhsGYl6O8@WZe9a`Soc!)$OiYfO$he`V;fJaCfmcz>CLGqKlGg|5hRw zS<>GF``XO!#a1caACEGP&bRE&r%Fez$;;z>O^HmY=#Pmvh90{3iD97x`GABsa=7>n zQ4H(D2;qX1D|axK>5ji|fu*AR$O!?TM2`o_smDchlFs7<)d#83@@_?@UhZ;!-R4+} zq`u$9_s*onbQd(r%NH_&nL4FQ(WPI~1)D+;b`!*#Mq)EMB+)wM0V9j13Xl6(;3_@+A*)%P+> zFP%K|xl1sUulO7H=&hgNeF>y?oJcaQr&E%>5Wu#`&XP~zzXCKg@qr3dh+U{IKYP+` z3CXP{3D@-YX!QyOFs`z=!_u?2Qt}x+rrKSvbE3EJg zmyTw0egY$-p%MGYN5**K$$<3}vGH}`hP&-rcZE>Jz1_u)4@p74wbSoy_sPT#DR}A4 z>-F9KaOcPe(Sc&Ck!0-v^0s4P^cw)aaG=C*G~XmehzJmGiPYKl@dd<=W>t#KlPL8F z;kb2vGxT8hUB3MFe6`cO^@gF0)A1aA71dL@IpaHjeGripp>%-z8x-sq&(4Gwn#>hv zT8Foxp>2cWn?5=}6Gvb4X-9dqharWz*2XM*$I91R6TJwzeKTK9XP#Y|SODe5FyabC z=o(hMg980YFw!rm$Y}*kxxnO&)Ba<^^Lt< z6R1Paob%GXPkwe7yX1ap=*OwtJX$0UC}Q;S>h?F0bRXeKp!gbExD$x9xg%bKw^h?w z$apIsGuF`V^SYTNLN5afN8uY+dpcau0%gEw&pYKXqRF1mSD*iV=3Oeslzh1yq;L#m znJA5ZlrDSi%FwBgIM3$F*4xLB$|sjZo;IU}{nq)9|ML6c<3DU5CyV5^PgmLh(bBZn z?w-N@Gh&>CqWymBkB@0(Ml)Qhl3xLLu)2sk#&a=T`)Sb9U;O?t50}A~i-9fw zyOPhZWy`e9B1NKRhV#zee>cXG!Fs(%KLnx6UfmnHX?edIc7H45-}Z)0-WiXogbxp{ zh?zzHDZ6W;wjI55{k~a?!S1vByWRgx4%br zN4x{$(&DXiwIzjG)d}uL?OM6n|GuH=9ni|EGeP6qA+g8fP))VSL`hDrLE&*9 zByMt{11AD75)_WS>9wS8ZvQwx`0aF&6wA4a;S@e4kG|w{m7^I*y_j^N%vBBFX1fes zogL?vYm05&)AUY;SRVdKV!5yI|3%T5Kc}o0YUW5LX(AU>FVxOIu_@NQ$EH!YSnFKx z@jO+de!0=LnbGQ3_0_)pGPUD62$|mO;K2wcwqKiCzarxFWXCz+Wwq79`9xif9sf1W<%Nm7 z`n}g3L96{4dR_Z(`|h6Xf97u(3E!e5)c>kYHhi!<$-c@ovS^^vTDKncp}JW2s&3V9 zDvRo+GU=;L-JWsE0({ZQaZ9`|kTmX))p_N?TesT({XISL-b1phG^PLNfv@Z1fd`H& zlZoeM$xrDEG6S|2J_!PslYJ6JZWMZkevMb>4&!>rYp454!eLn9LvXvvnL0in4uNWC z_4qR{kmf0Tdo}Is7x8?+G$GHb_W1M7YJ;47f&ysLkep-vV-9>x=gO&K*0+?#J#3z}-GrJhR!uw<|EYWaYA}oX3m3#;i`w_cv zwV`eD&1;KFE;o^;W;o$m;OeIT%i`A0mcgx~Vrju`<45i}$(ym?>SwG-rwgcfWr z><6^cr!>v{Kpa|M`0_v+$BXS*e6h!saL!eEhYX+7;KK z@9V3g^GyTHe<+n z@B6&H{kL>5D+ zQ60lD98G4?na2{&oDRk524B%#BxMRc&DOSSsNio-9#IYqOY^dk)FHQK1j>VKdHY5+J=BLK>79fW z_cfN_D&Uy*WLRcIL#61~+eBB%7(()wCk?ze3}{mq<-sG9R)1q?>%J0LZ3oG0(NeoOb= zxk;}_ZFxr&anEI7mTj(MVGr`@xrCHyUq$tzX|Jd1#jG#<6>o_~0)1_+TtSEBH;cWr zk(J$T<AwYg0Hd0^lYj_%H+{4UbLi<`i|ZH;759lv`Vd| zed>IEUBnaRkXmbRHm9|#vjThRau)Uz9G91+%75?qDQy6=lG+?=s@JM*Lwc+p^f(gD z?~NHD9^1QIK6>cLujqI)b*Ujxqn_E;2UV2nlCv-U)K8_}eKvKuqwaQNu*+wgAVr7L zKYV#*RXdnNch1Poh?+J1EtyvioUt_D=C7x<7q=v5qmL`aYLsPsqdza+o+hXy-`+Af zdYMVu(Gd6i(%^6C`7$}?zlKel>g)DtZx+J?;zJYU&n^veV0$3Q;{!>3eO6({$sIv( zF;}bQhTe$G6=(30)c+Z|#QZs5)^g#hQR$xyr;Z!_SI(FM2D#879 z#8;enJn}18+^9h(kWKI4!`*SBxk2K3qDKprH)JlsFai$&CKQD(dRxj?_6#ZTN{rP_(7kOA7948wn0k;_q#uq4{LAYzMG%b4`+) zc3={o&Co4deZ?zQ;sAfwne{`dEO)Zw7@^PvhvRkD1CyJzoSC5+Jz<1zA!MpJ$6>{y z*7Db3bIq!jVCMiyK@SNQo)SjJvP6=f{w|5937?=M0rDTmGWq@rOVm23RJj3UmQST* z=*A9-Uk8BC;c!=^PmQ?#@`FVv!1xf0b$(#On0h2V42%)lVAB~%l9&I>@nCU~a}^tB zIPDOBvty7Y2&=3g9=H-;f9cD926^>8$FD^@{iZ{Txkmn6rtUO_Z*JU3BRiY@LGTAy z`O46%hY}fz$v(VzH)ge_Y@gUYAY0mVWzo(S){-e8*XfF}yu}RXeLo<7J``lAn!|iU ze*IF*O1Q!!wN%BZD?)CxB;5nDx;bKow ztmY`5*K^Fbv)N6#Vh^h!Pb8ogbL@L_0u@WKDnfp_6vM>v{tzlVqu^bTq$W67Iz1a{q3FfsHj*x7~B^vxK z7jx=U-$`tcI}tWQgm@B}Kew=wX`D}SZ2zzc7!2&68e0mDvmd}l3uW1DXLbd!tfE*t z1>oNS%!EYF05Zf4z}Ad{t!J}rVL5IBI10GneOin~8ml^au?drlTsHE&r)qK2gK|$WMDua(f@9nx^5NILZl-b^~s59?cnk z$8b`Uubime`ebByBEk8OB5+FdJ*HeCRlDW$*-UYxPUj5&5jhs3?*1Th{LAK?baO8q z&)hNfSVFNM%4dDE$oiq3wS>z$2*^4a&-%Na^&6TERLBNdW<#zsxMkU_wb{R;*x5g4 zbF$`eE9CH6=I~$7;qPWpL30Era*##rqO7?Rzj>rAb7fe0<)U+6#pfzr&sF)HdzLlt zoI>9DLm7?hd0M|^R0p%!i?S9_?E2e$sNa4?E)IwBmd+5*f4&$Uu;&AyXUvx20G~}B zgmY((qvZ+afXm=JfG!Mw$gw+TxdAn$`B~lonik}9d_NG(m*Mo*$t*Rw=lD49`8UGy0xx+ZE5$MkKT!x3&dOlTHnddkS3mcH2roz} zdX!RBJW*8oxu~4=ap`LbxbfpB*B@UGe_Wd)J3@Kf`1x@&YjLX%yj`bwkPA-16?fJa z_f8b|Ma#A>Ffe*f3%IOTEqUkHdGsv{jSk_jP_RZBhbeQH2a?W;QI>lsXH6G-)QCV{ z!sXv!8|-U0n5n(X6Q_{~D+3qo=j-|HAFT=&E$yBZeCu|pl7Thj%76c6YdT=-q?OZI ziNHVxmksu-mR`=1N@T4g!X}CAJ48-45_cW34F%&5BnhUHgddY2lO)kPk~mw1q+*4X z2Z<@LLN2vJp{_z{vO*yhcJ@yNowZV(tx_eh@;qB*AF)!er;<#8U9hTDVPo*WE46fq z(y3KKJLMWNRhCu^{u8l-R^A7Icj^?6sKH?s@Yh#LjxBO|y4m{}GA%0X?|1vi5ogvP zF1866=ig4pe9q3FF)kYRYkt*t{QQvM=|17Y+E49A6u6_Vl{CuZ=fURLLwYZZF-mBO!mfA4bQ$O_wR=d+M`=()b zr=i)SZa%Q_m2M+xr*?I+@$F9Ing{89YE8CCt;l3O^`N-OoxL3g|A(<@kIZj&wrP$x zBww&v(r^w_bS?sydDq$}m|FFiqGFBRZ1rneKgovSo=Apc6IA^ji7d|w00fq z_5m8Kuddw?)`320Q!Q>Y^=wm4>#!{DFcfK1sv`kXt1zA<%pW$$A2u?Lbxwiq5U7Z; ze)6;}-^<%N|1{q6Alq1t&-qlk6DU&?vKm`1-|8~edds@&c2F1cPpjRV4rPx@<-2WG zFftxiWoF%G6hux+BWq8=Iu+{sCfZYA-8$Cfypzhf-OBuvE*k{Vrl+eEL9|B@2WYG> zLgOW#VTh1&&aKiLQ$3B=9y~E!txCP^)}-j-s{S#4haNZrAhOzS;Up6~uEgu6L=vLP!zTKgU|-`LuEO`TMEZX1&%9>;A2v)=s60 z<-3&wQ~mhW-bvWNp;E`i$CXEjKC{*S-}M8^_5EZ-m8}QqjdhPNjNT6kra9|ZNO1`UY9yR&-xguL2Kb_a7{&*jpG^sSzAuMG$) zQl8wUoKvRmLAw6Drf7NfbHWGz)^{wV4IcOQqS@fno`VXA0ST`m%V4tp6pYFRAHepV zTdkCC7*6!;RxBQJ-|JPH9$MZVT7^;7l}CL`Tz;ld{gJ)8@QO=)-Tfz(eJ2&|J(U-y z>Rsw|J22#_w7!Ynu`KHj5BNCVrj2sIhF4?jq`+*}D%E-ir#wf-cE@G!_T5w-;Z+`Y z4~EgFMs0&gXKg5c@JW)5!?pC$C$X)8ebnOg$`e=>sE*E731F*6kvdy6KW%MwV==K4dDhdn^v5)d2a)NpK{Yl@2F|sGx0uLwQHeooWi6OX?8m`6 zW2S#iRZ8u(b-Op@AZHLZ!wn5H1ND!UfY-aA;lE6;$|WnnbC@aj!-=TQR>p!(;{u;3{Oq5}G9p_WrUA1zHeTF) zrgX@3a`x2;?7(K${^D$T@~nR_>374dV-I~%_RW-hY@L3u?Mg);Ehr4rDd=WCM}*<2nsbiXd{iEjAxqWD<`%a^zBrY^D##*)A5 zt^Rm16Kn%}^46~A#ryLOZ|X00HI~x*TiJ=yyR&n!IU?7)Xxu6T8dAmuZ?}9$-I;qH zQ{3(GZY+ikKEpyTWf9F}3E_e|tPReGe2~kmKbr=lqFBus6k8&5h#JfE+jsDH?_#rA z@S)H4Pbtq}Y+^SyifmVAUJN3U9mE$)70*YOte<}ke)E@o3v&7%(BI1RkJR>d=I57w zGKJ+1_BFY2^~ODxzbWOSqFw%(<#m|X(OjFC%2;lon9XL!BGNzHzVRum_rrZG*op#X zpjN$c%;6MTu-$g>{wvVDMoQB*IZiEOf7^Fx`SSjCa{E_)r>!di{>l?P6-vhNM5 z?hWpmeCNiOSE}{4(=4W;^JpCS-aBT|%iHny zSwOa|YmG08iTk@v`vtW9uN+?wIlg|f`})J~>;2H(c+t%}YHXO2X`0RZwwceLPj}Au zRFLd;Sl@R(wcD!e-)U%?P^w$(Ryt5Rsq81RbzR;Nzp-)i3kz;;`M$&vUIHp(e-y_B z#Yr3~%^v0LAD!j=CeHbRedh2>2#Y5QHk9^7@4+YASQgW4up<{(mkW%ZgM8rF%)kHo zHijjV_T8TIhr`()PG7&<+@$}oF=TP~WHygLu=sNK-?a*8^FfgJ zPW+n#zLNv+e#KS8-DcEhgyD89jrj&f`|ej}|Mg#Z`Y(U`(h?(&m5`;!~Ak1zhM$D%f=`afN5eqDPo$orroaQ5fyYzq9rY}i26 zbotf=k%NiyN~XU**e~yUXD52LKs-?YHnSjG-v2%||MO`1=Zb^45+VDX^doWlS8uv2 z?bF7)t^G?ZbpS3(EdB6|+nfa2dw@^XZ)I-XIGJ0v$Wf6_u}XCG}q-l1~PT2>FVn87f*87*31*nSNoUxuC0Cv5(vms zrr;r*vR-60mEjcrv)9&E!Zw=RWb8*rG=k8RMH+fPmOjtS=|?3pZBb1uxFu`ttIghu zJPTZDy*m3SBXPcTF81_b{nn>k2by`FY?a&Eao8qDhKOfnYg#^1uc{qr!oyjX6W2-0 z?l(?iOmgT=8grl!r# zUmXmzR&F~AKR`pJ@@;rg2zu$RS7zo!t=h4u+&Ny?7xysw z;8J+`;q7JmBW&A`<$`=HQ;O2w_6rX0vpFO33TYZYR}yMWjHS+ZBscY*>B$Ch8R#BL za~d+O+ji;Tj|4ak!Q6Me!l(EPa;;Tg`(28B^?aDuMc2}m%SuxiQs4s~x@mv^h;KfmwUJv6U^6EB?a z95c9=p*dUpsjzm_^Hah2-}w%9(GXN6?(nxiksuHgP?4tjC!i|tXLR9N4@YCze()k1 zDr=@7TX-c^_^FU@+s{7?pee^)p|&YmJ)w>Tv(@0viJv-!r?K2nd+fpRf_GoB^Pz8l z^_yNAeNquL%G>%O=Tqn~uWM}BDB{j(*tk?dZ1|*7*J(JT_m2#_eas_GE!3zoePn6P z$?dy%?#t@zKn_!;AT}|Kv0mSRIbVndqbh|yR4kr7lg4K?{>hu`jDY)Q-dT=9Z0B4+ zh6*O+>@Nvt){pyrzYr@w;-Y5$o!me1x))p1V?{4}o?RymqKB9MpO!UpnGVWf0j(;Dn@?II@^y6ZRDcl}W;%kn-wl~{f zcWkkBcqZF1z*4kd?c!$|fc1GEHdJ830`sv^Ay)Ycj9XLw`-sECdOsNtX<6l=6^BRB zRa?{Jzs}*=;|1^-V{Wz;6Qml@uxgP{PBPlY4`?iq?;IyOP80pHf@1A6mc=DUzxa}H zaI8!6G!JiZL|@?rSiA_m7|a@gFy}NT$6cHlrNSh{4=`01 zPJR5&huw(ie<%0=;%Cv;cT*E^fwH-2UQaa@4NE*iV)F)sri7CNH;RO z#ojp=)aq4S?)TORI?z|r*HFT2`FulVkqW45 zrZVQpZsWOfo=6npd@T40b3<8J`$TR1zu9E>L#1DFJ=L#t9i!OrXFMO^JKyuLbaE&p z$`xYcmDW0;4uq%dG#nm953xEGW(K=rje#qzM`I~0_syjE`12{m&dtE;BzmXVont< zBZZSI^Ai5cI@YDErwrkg_k*@NS@oxvvTdgaIh}Kwz16a!C1elZy!rXD6GE>H_WJht z++M7|{;GSB*VL`@-bDZA9QI&>!1q$>f1m2R-Gf6T)p5RB=@;n1|U)K({Ur{z?Yl*Nl|vw5j__hx%F};Lsbx z?K(8IBzM*Gln?8?I68G%(^u<_AJ}wM05@1rWxOZ-&ykh%Z|Uaa*^dFd17E0AHRjd5 z({=MH_qpJymYxaQ&Zb605Td_xZSlo={K5XX7dl;q)d=QluG4X&@KekJuPB=4A<#tm zq2PQNT9RS(fw%m)A?QnrouAhRVph9%XQV0OQrzWyF0eSDwfHS2PK$mY)h)qvc*GbE z!KIp|BhG|oMU|9n^}haZ_G+f+yG`JQzKL#f%!Y~|tLO2MKnM1hN-&T;$W8D4 zOI+epOA>p~N-ttfB8k!L-VIiZ{qRJB(b8F$yN#nFX}GA-S)kkHS*lD;)w8mMDDtps z_^q==ohy^$uYno zSDk|B2|{@3*>$`}=Epig}=k(P#AXH0N{`w&P|C3DU%B**}>o5)YM<`)W^E zi2wmuux@=X0lN3-=`IDvr_1g~cv_6wt=HEpBxvG5{1@~Yf}i&GfX;z{a7U(o07zvn zV}qb`i#y&L0MTBFTm5!1-KpUAVf_1EvIB~6K|8^tQag!2zH~Rini8iQRg~lealMtm z;9$AFjAK+0rM2}84-zQb=ej2foX8+8GT1{XkXib!m5U&`L z`?a*Ag9+CT+Vy!&(8|nuQ05dqljIA`De(kXOk(olctZMk@Zq=~%rYT3(PxDn%VmhbHJT02~pGSGLW`>ndIpkyQfdd;sX_+G8JiA+|J=^D*ac)R_nknRE@y+bWBu z3Ae?yLcF2OhR(*<4+#uBTkOk%*j-C6j7}pg-XS!>JWUj^Yw0IcRM!BqI+z-8RuAJf zabW-hD#0#7R_!lEbUerZ$HxsNyhzvTwCwO98>`(SIJj9FOtm*mw1o45HEE1#Dia*) z9h@5?|D%wFLbBG33@AMFOq`>jge1O>7RlCjG&9LM|e87n+ev<}e^LroAw!9Q5a&qzJ9EPxOM&g&-Ad z++jNbh3VnW2k|fUu`M!5<9bz+`*hs;sGguvJ$+3I6N7Q5g*CaYR3^nlv|KCy<7nMq zJ4}tSmbv^(^$X$siY~bK{=`!0I= z8fnroOvO9#4wQ=-K?Q3{qt;}Q*QWKup#EEu-FX|Jup+`=;{xGz!tQolNg!oAS->=3 zcgomQFm|xXiEsf+P{qbIsSiA>?^RWE#{ONphK@T+)9bV*JeTUbP-xf`MCiE%LO>`8 zQ51i~AXVMjG@=K#_8+#0lX8NYSkQ;%>$9Dv0CSlPTKdbi(fp;lA z<2AP9G|2G|0UCD}hs2z?ya7&a#snPzWWt72iJIa)|NIc`*r{D2)A(8_(2{s1_3ojMWzT0ZWz zl#6C@1~$A+QeszYY{$_uRn%hzJYfvl;Q~jI$Wqfq?jUtCHBOTZ!qhmqCTphnjiUU8~k5KVts6t_cwK&;;A-tv)~@M;2_`i5yf<2?v;`S|G_x^3{F(rjiA1}seQ}RSN^?@ zye&s@dkfGTjZDzPf@CvGIeA(tu?yCyWxWHiWg8^%u12C~E`TRqg~7^2O|!4sG0%ue zX1GHiVZ-~~+1^Q>=3IQ2tD*)`*Iw!yfclw=i0QRMFcd;N|B`HE@gydhIk(ZLCBcD4 z(7+HLJcP`Gvulo__CJ- zLEVYVQZMzW)jGkA;6N6eI(mBadYwTuzieTC^VH01!%W!(baz5nZn#Jme#yhy2n}73 zaCS~_7x?`>KBhZfrG;R9Tkze~t~J2yjXTIN)Ir*UK(YWy&Pj+`FzrkcJ{@4&HVhmh z2*O(i`$2?yYbL20z0=(u&FwhvC%xY{f)94%sx$QdS%c0W_jcau{gc=8l{yFb8`sF| zwWH@z-AmAI>3!~d<+56$Ip6%vpMosRd_^k$A1;eWM~UASYjZT_*8UDr=+m$N26jF0 zF8uk?T#D*+074`X;)5g-XruyqSVBQ9++~I4$^L;lo%J%TNSW`e7-IX-6ZAqlIl{zz zSl;647RZI>=%w^FggXq}N@-+w(5jfVdJTjk&z% zHu$fykNWJ@8M5U=Jmn@NR>l~l}KxEmf8 z-5t~F+HKABZ6ve5)K{8o$cr~#2?a`e^33egtP@t-D=NYEcu9}ztL{Aw+?0`Pago!? zijHiIV-gIyLrZ%msTqn7j#N-_f7P#rU+S4c^l1WC#fRT; zXWSmCcR6wzI$G7!pfE{|_m1T~x^TSIJJs8}5ZCK#81Q~TX*^8BZ9vBUzi&=oU>|AEXTIxxfnKI27fg_gat`U%_*Om-;OrmE+{? z1K>dmP*yvXu|dj$A&+Ar^had5c%vJqaR}zIt^Z@_+~b-0|2S^!Vr+9an_+XE`~5C$ z?zi0UNpsD;5t5|MoraMRskuc$Zb_G~%yq7fB#D|!QmN48r&50YJ&(^H=kYn`eBS5r z`Mh7x=O%6hE0rMu_G->N_!Yt^(G|1=dsSu<8+6rk9w_zeh8^ZDN00-LOIjJT#w~NY z;X~P@^RpAyFM38YWZ9({c1C5O{mB6*7q0)-+%I%9oqJH(f8h?Hy!Wp-S9hU)<@5t} zd@~tS74YZxq}#g|ceCACnR;YbFS|Si{`)LfUOUrlLPX{)ZK}Jrwft|x+g`<0=`$WO zX-!?VGV3rqkL<$(^9dVsX|;V;W5w(>BZuZAUPH#i%&my;z!&OgsR*C}n_J(Aa}?YM zL2c)1SFS^ku&W@#euf5difgp#tjF6$A~=AxH56;bzM@xK(w1NfI`bp5Vl((?{qCBt zT66>ZaREbagW5k#S?EgE7=T?#nWp=o%D@NC|FUHc+lx(_8Q6U)mH?Mzb8i;vB2>Ze zj@hNEqFw4sPq27G@+Pcu9P%W<$Mkb9i)&Ii3S`c}>GnkqIxjlNA_o!wsw?}7ILc>$ zHyE=u`O@O_K>D3pPuk0SS=@$oP9GdONI8eao$;%XVktfU9#W@BOywBKyzpV^^Ubo( zpeGc#WN)|cT(EPdnB{FJaT&vk2$U)~=FIbkz)TeX-3gZ})0Uj<6IBb*9w97x&DxOS zGkkz^w>bYFgVvK_6SSH=xiPqc*Fev|-$`>XHLn%PSQe>W*t4PXs~?|gMIk$!r}zK6 zqLixlVeYm|y>nZt{-=fZ(?dn-7Y#ly)xZ9H7%jflqUPV54)1O(D3vrwnqNl!C_v7W zp7y4`n~XM+G>+M(tz}17u1#J$w)vycfi7uC#=mkv)9Tgzo)`trOh$`h3}S(Iy2NM| zR(b#a>Kaa|mNnGoNFKQjVOG8DImTIG?fqp{O4@3UlJtF~ka`yxKbax&*L_MgIZZoP z^-qvuNiw3%h^7+NuKzLS|C6&U#iAaXV%!1H1izvkxm}PEq*-1C8I!Yn{sQqv=$$W}O1lK4jmnN}b;2(+TVnJ9CZ672>3nB#|jv zb8^;CK})&Blje2di_a^|rP;j#^?QdAZa|T^VZG;0$=h4`YVA+<_;T;{%~fN?RGKD~ z>x&W!RN84R1ugYuA14$eW3+AW)F)cxx0MAXjJH)M%JR0SBr<`h^bK4dwsbUc%;~(= zD^ad$CdtNiGAs+g|Y4S#Bh-#bF zoWhLG6^KmQVoes@X?XCC>gA9YWlbu5ccM90E}ic#L+eeSQWHG|dhg-Ks80%`+`@UA z)jYDS;^g@tNaJ*d#_z2>5JCKOrjEXpgmWA%VF=)ht;I4(ii$T_j;t_m{8)|H-XE z!r%(Q9wqA38mIy{CF(b%?H+Qk75MxKu@Gi+avf9Fyvwx8v3iiag{u$XO z`%HnP?&|MOKDowIH~~sTCh98X##&i%%A7?ex+@zT^N`5zLl_ii?|?pmKJYhrTK@FE zlVdWKmHy)~k4zaUQ?@J@{;s%;}eh zh3lR{3Qqq{j*dOlBkvxYrPbnIqvBQX(1Av;7Q|KZZ0X!_Tz}|{h#r8_O9y~@eaxgy zSKs zP5DlT77%wg*g4{jciyPkiX|-U)mMTmrYNbn2A5afpf{VP`=n)Iq=5@IE5#{rH!$1L*4KK@+aB<(eQEYZJ z5fRdjTVqa-SAs-7IMCd#_SBJ{SRf*en%$O%Jd5$0$G8ELn!q52+y1Z(EZwCr4X5iO z3K3}Hat@PUyYi2VHT*OsJ7AHH2_!ekNr$q`i7f>uI%=;{T(cMceZM)ZW^>2kHZ1(m zb&Gznt)u0L5q$0La@F01o|;pkFYw{7-(|%+@}Exe71h;0dEs9hv2Q?t*AOS~M%;=x;FiQi7C(7f#5c#p2artGx>%{@5_MGb_zg{km-APj8;r- z%|9(4g(Ei`8YZ%RUhL@TjHN}?s4oe+l?8v`jZ7+zvN)pzgg0sNF><8tO$JOMRVAUt zk>77#YRS0ZLt5yndual^1aYO+ijWHce0uY%Vq9?=m+5O?m91k$&MG))AMtNLRDS3= zGwKS~&;X1(V{#&ePW1RNM9M1%0qwrE=u5S_vrn=2Qge$jT5`b z&Mb)HCk=o)DD-Uik4dqldlw{{cEr_l;)5pl{ju^xvu+>RIX*GLRUJ9EWje@?Uahv; z*X#0>M9+C1dRH?GQ90Nz1F`0xm47<4pc9YE@OMvThf?nepR{lo;V?0yffna5_~0(h zqX$WPTBmjDwWShESTM90pef?a`Not#|xkI}X zTa~B}e!Y|7G!DS<4k|a~PVI#<}} z7cSoX5@1U_%Q}X8sB%P0o)15I6@PO=*|kn}fGNhHCdBxetkzkq$zsjuQg%%7eZGTz zfN{C)?jitZ3=Ju%|9mhfMaP7VyR`mdA~^$yGLVr9zjy@oYM-;==8TrH;uc+QDUyjP zvvpd6=%b6#7y(){K(+9N*a1s9KO7lDRk`GjW^AI#n`l>IGzoy=x@KBcFC}sH%MLFv ziYQHBoDp(=?>f`g;}&^>eHa-;m85Vh+z|QKCL|+I6$)Sy{=WM>C5mU4w>0pHj)-%t zgf!LOpqIVtma+D&S?3v9%gS#s%eFOX!#DB@>u^2#IA1mbZXoNx0rm*~oI=f(H9ZHv>fMh{!%Fb}^Xi zT^-NuMxJtSY~GAGo?7{VeR6LT_+_nVpSU^COrp(+vjE>00Y2l*qPpUqZL#qeL^O$b zN|`Cvz(iLHqmEcHo&u3^%&Sq%t4mUSSb(z@QE4_rDRQzLQEd8A7#8k@?4f=)64}}) zqK*i6n=SQmaUUuOI$l|Gxv`{>vCC}20%W+j)jzwb&AN006%iZ)_$MF!2&H$hC~-$* zJ)o&YOGOlbM7sv(TD82nE=f6fsfo?RE>g8ym#WfkNhd>fSX513|BG(^H?TvB8vyo= zsJp4znknxcywEz7j2}S&x!pSrMo?R^)3;pF6a^4oOZ@iSNf&ml+&`$h#E>e7c;uI_ z!Ebe+g1x?T#g^9&RdYI(415&^wjtr-kN%^_2W@>}v_^l6otv7J45=O}nhhe02KMPk zWSTes*DPr39nt^slV{NN6_h}jyYTTS$I)X)HZVY|C{;L-iP_2PBzSxuaFHQ0WCmP- zv%`m)HK!xv-4ZmM|6O;em>pCGW}wrEk~E96S*_Qn7h=>Waw2lo4ssrKF_Fu}1}SN) z7~ZLL)?4*Y#k}19*Z}Xu>PawBs7H`$j7x7bBhR!6pXXxy6 z>i`E^(3r1oRTve}oi{Uf%~gdowu2~7BM{=zIoX*_YL3m&9%y@vA4N+zJ=Uspz_ZW| zp7-0O737J+5!4mJGo5MR?LMjuMf5((>!beKEjCnvLB#HGH>CpQEZXNVBWMFr>>^0C zntdFAnWciJkG( z?Ji{G^^@Mo%u-Ij&e?CHg5{U&pJ(NNuR>}OilkbpQj`q!4ePJ(a4#rJG$=P_Lk>?G zxw!*fXgC{kP%}l#_)4eF{CD)k-nbEP<6HT;B>-u?H&x8(*J`7$JHEEu8JyY!-09-a z)CO)R1JCRaDzaM>N2Yr;a(LhHW|c58c#zQV3{}@Q?dzuz94>5HR_-`$vPv*yU~Ge! zXV2nB_i?9TrJlfsFe%(l*Kqe^+no`aN--+-+hoCS9|y` zCo;oxp?bM@{oXQWPviYJHW6l+FV|!LBGX}i}AV`&!jE=X~BOrwpDz;(FwwYCMfcE&c@` zVwACc7OT^H_diI@fb&!m3o#Un7xbDZeeEa&(DTM%v1>-6bztcwdd?}Db~CsC!whXg zE#e}Up_aAwP+_G=>4WoU$n#S476GwkrPKg8V+C~UJ^ip#OM{j7sdcrsA-01FC>iN` z5Wl!w zkoTg|g3lCL8Tq>zq92}f>jFa|;ubkg*3!x8d0SA$ovPTE@ zA+5KH(mL3HDCsAINY3JjQ`y~{Dw?g#xpwGQ&iq7l{w6_kXZP=i7YPs4DnFxsNJ@B_i>{wL z2Z&1ml>8t{FV=s|ha8Lhu)ke@Kj7^N`i=dqQbo9pen$Nftm$-;$s`l^wb~+_L~~yXzPb^a<*lS?nW*pkc>l_+QLow42w6~C z5r)P)i08yzJP=n9leE`T%(L$OwUDGUM?7IPTM<;W(e11;`NpA5ZE1lRcXy;6bw6>_yp*ZjSbDXT+7qF8wZ;8R9A28> zE~y9*P9ru9_^)is-sHBBZeWT5EtG)V3R}g}_e(ai+<-zR_{stqJ1RQy`WnMy9Xr#S z_UDcs=E2dJ&0l|@$%x>*vs+MnS*}>_BI=7(p^vB|^cQQDsmPUiTGaZEP8)f0OzDct z%Noaf4?o-6C3w90(5 z`{x(DD#);&FW}B=;)(3Xu0v~*aE8Gu-@ND@jMX2F1dmOUbKR$4+R`(4BS0kYfB*WN z^KShfZAdjnL(o8eb?RYB5Z^qw)5}6S^R{4>}?}B?9eA3NKGGEf_Jz3;^kz|>o7S>=<0AJHU z%;m+N8;_^Y%Y$^(+I5P&4}y1Y_RQnP9;%Ck}{rVuf1?fS9%gTCHH z3tSC^Wi%E}8aDTuPO+;@`_gqnTr9I?Kf$(nxc=#tkn1YUR3TA-IQdGOp)x9Bvve=y zfs^B5jSwn;C^k9p^6 zo0_huBvHIq({@Dd#+8?%#bb`~xE|QQ!R#kI{BLsUbG>!~65SCr{I%k1`=- zl3Ch@Xy@*TgeK|fVFutFOwD)WG(8h8>HV05G6{v&R(y!o{14_fgqe{(Q% zPJ&pP<6_H9F_AQEM^?7zpLhS0V0K+IspHGrZ(guhl`5vuHu^;Zm-_ejQ;U!%#Z5;F z^?<95mG74diYg$NuE(g4JC|g_&78;K$dk=iT>Ak^4ediDS|_N?c(Ia4)KBH)CykFA zS7$07C-CQ#I}++P%1)dA0k!eIMwhZ=3(XSjB;o<1SHpi^P`Zh4yiq!#()L7nQtke7 z>7>Sg2f|ZYBbdW;Q|G5>O*NOQprKdQ7X**GI0MI{%1m53J+7Jk@Ej5A39Pk(>#+Ma z#7?G^SgZL9N;#Hy&8X1THa!8uaQ*$1?24e2T7?IboOU#!NntWTX z+Br6613bK|}HaWb%Yw z=$j1O&4TMKZ*3qSFBhh?{UW7(Iul?so(VVnBJs{BX9Yxl+xITV(Vj$z%#p#5FIRu< z|NBpJX8=^OSCh=A8F0eD8V)9eAy2~8HhrV%!e;%=nZf~ROhw$2iEPAik9XKi0hdR; zuUb={>-?|%TIOz;h+%)2cZJsQ=VY()=_#S>MFE4gm2)o1zm8g;LUf z)1^aS&4BH#;c(4!sMCRlj3Bj9AMS~xKPoF1zHIKHJuwKcoCt|FP5jr0Z6cQ%Kpq-V5!y`hQB{#NCgJLnpdnZE}5SG^j(L~ zXev%rWAY{Bc=KZpd|j-9&V$|?U=FA8WgmpR3eV9lAh3!A7+Wi0Y1%`3HM2*Vkz_$uN#E^q*eiaXn{Mj}bvDBzMpuO0Xv0 z<{+4^)=z?j%x`5Tbh|0(8QnC+GQmC(r+)=pm;Y3_#_#%Eezq$AX>KPO@pl%Lhi!IL zpHnq^`lPm`MOow11#Wm%YFO!LuN~=02F!`TEv)71w6_=}@;ra>q1i@({yg<6To-|o zL23wEHxn=HTPQj3J{|XL)2@943$;k8b377ykDfdc<==?%uCeiCQKl6m61q<2hkJ^| z`n501sWeVgL*L@CFg(nm^kx5C zaJSC}6&6FPo@NUhcc(h5znhrGdp^WIsHI>MEIE+0r+&DRJRl!!sC zeKr}EznBaYuCEMWbik7PBv>~iyZE}*=YaarD<*xxr-Vygp5A_;dI-y` z>>PYSw%1izEr`-h6U@>vPpz8k`PkQ&Ix9vS02*c~Xx_w@`hIbfQ>6+WbV!UEF@)rb=NrF~(EVWDIxGg4M+|Hs_8LuIco!pXdaKd$yf+LV`hY=V z{J00c=A6bDf#@twBn$jyC$81sJ*7V?LBU!I$b9d%brjVbkr*M+EBlbCLDrC=VY_#k2kYJZkbzDK%S-C|CCZ z6)I2UH>&+X_%ttP0FLhW8*_aB zF7DS1M!Oj_sQ=!? z!+QxYVscc?CSAGV=^cS`lCPqD^a@_4{!Ti)U`djzjC_j@Vv;%AL$DR zSdb)dtrC^X>gW~9jZ&3ZPiI+*ufkL8mlvAUQjnQpY<@6Yg8R7VldJZx3^SYaYVJ;3TH_HECf+G)q$ds4WF2us{+? z;L%ZAHE)998Hl#JkY=d|I87r-p!z-QzEj2#YmDI34!S1->}&dwY6i zfdOAAly?YTQ5;nKUI=Az5Ka~=+Z3E)Mx?uJ>=O1@YDr{20oqU5H-jM-D6k?SRI&CL zLiU%@=Zjw$KVlfXJ6ue)*(L6vS7n2*%DI(IsKSr2s$>n!u~ikTug?3SE_z>Y1F7%` zfYezPw`91R)-yK}zlZptV>u8Il_%#DP&jYZ_|TaLRK5C;_UWOyd)QPUzV!Bo>PA-tns2tb%m|^2~eDn zA+Sv1XOn&hZr^mbz;P&lzO=pBDTF=Z@Ke4XWg7V#7`z<>{!$KqsS6wog|i88ccHQ6 zSlq%r#3th(=I|=4Qqe5JLMes&uxDE7fbcU_c0+^O&_kKJDJyuuCCFhQvg(xfDat?j z-~YS2XoGX{Z50{j7WxL1mIJxvShX#H5|)A`LUX#7_ndph~F2HZ;mKA!jxx>DJOndw4#4!YS~bn*FOVIiAU;_9hY9E+Uj_dDA=4>C>s5U~L_hoo9tO$b5>NiVrzn#NR6P%{qyi|nEA53j`SolZ^rvP^$?R#s;q>1 zE-^$XxR4W!Mo}OLGY>8svKCGFAHH{RUuvB|JUnG8UXIR85Wnvd-pKX9`pS$ z&f?U!4waH&>T#e&`&~`Py_jfOW3LwF}A*M!8(CN1g~~}x?MmjI6lcHVPOk5Al_A8su*o|8nc6h z6$+zy*f})oZ<#ReTFQ(Z-|_DbV(Vg}Q#Tp${A2>JQ-aNvzSy=Qk@-VTZch_A8h;Kn z?2r1N*gv)0!W=)j1&MtU&)vPekDVcX`nN4@YKh4Q2G%P>j&y|t;K&5 zmL7&0o~u|Lki4c(a#FMf0a&oXfIH(@*xvX7*?^X7#*Ew1UApj=-YkmU#L|Mr%T@_b zoB(Sq;n3!mUXw^azZ$?1uur;#Yn}lkCO+BX{VX^hCm;}EC7x+Ni9gTv z;$_!_)MtwJV~Q}oCoAe#In}TIeO3FXrS`8?m$EOMP{~(xiM%z_7@hhB!6Lx-2yN|6 zN(#mwdn>LWKOz6g|AJjnxng@hcS8fwETT9lg5gQsI8?ds>6>+hD(*QhMrS66ruZKY zAq$9Yr-m&tqjgPR!Z(5u-evqP_er-b{WIUTps&Tb%L&U>Ej`-WMM5akU7ymAb?5MK4`X?y?gQO33C-o zu}v&IYaOAF4OmxvX+8TMmma>b+t*%Tg zx}=8p83}w4f81JbtPdoCAjr6XaaQSa4ig?Tasd~W!Dh8_%` z^fq5H&=^8&jmX5V&-v2(=&Qne0}@#a#wJ9&l@)LmFlefitU1z~^)rj7 zoo!ZMY9(lX#yY1>-`)T=O+^<+;jhI)MKvzKHwdUTf0pT+_2beTpA9Lus3+JO_Lrre1_oWtu6LU?RXxW4Dt}+s=5E@L=Wsu9Ga6cel%5vW{04h$!n+ffh-3>7^KvevjaC+@+tw!~pez((Medcn8>CC)k z!r0Jj9$WH`d&?(#YmY^tF9po6++SNHzdrZ)tUGuf{txnmSrxT(b+*X4KMWvXV7~EH z=J4BbR`&Ic8Zb5nI&4ixYMkuP*fsI8EtGWV%Yk=~Ojc-;ByvGRdGT@`B&K|UQ-o7F z)-b^a<>B30X%(WL%haWR4yAQ-TAEGKwdvG2y&v~V`k`_x+N;Gw^G>I= z{vGvX8uegDKanCDKcUK+kWQ!zL zGY5P_-K-V3<%ABks#(-Iyb3}Wr-d)FW0&A9n%D3wmgUSfV-+5Oa zko@6Y1t}-L(d2U|%Gvyx;Qy{zNAJni-p*rv~Gu}3myjc6;b}~yl_f#w$H!NNd|L7&AdPX}JLypPu zlkDhST?&h}tIZCLWl(d_5fPmrl)oMBwYX1OXLJ}MXfvmkIvqbI)%ykqX-L`~&6Rl> zd?Zgu11i}CoMk4BE5-`7SYvAfWLc>NE6iMs@gikZwcgIK#;3hc*2_n+b9Yj;XUp#e zQOW!Jl|w3Ve12~58?GKE(}cHtJFLfiUuyL=Ke5wp^hpAQ0^q|ZP$m8b?~RL#@#JDr z(lFY%!qFsZj4lTq^|O8-)sRk}s^!z_;o$3uwlfDSL~CRyzejQd&QZIsC(^T2x7@eR ztuM>U9+}+C;T8}=%`n=q*ZOk8uIKHO z8)|*aG160p>eYQEIZ})*-*q=_q*dLECorA@?XPC2na%1Wqfhyba~hjl4Ha>}KQy1c zfY6`LIyZCejJXI)@l@LE$mf$Coz}u#uT-iqm;_c%YsURfHHULMFCrr^?<$TVedwz; zhf;~B(2>$9W*2RLzWRFYO*fTS*8D-*fC5CsKPFf_poVU$QA;s+e?ukpzhBITm08 zf2Mh7zFN!z*9INb;VK3|C23S8-KyCba0yF!o5MUUI#fuH4n|D+mLdNIi^Lx8b7KQn zZ&p(6$Z2JAiURJ;U{;239DPGMea;q>&9X5!n9qZB0gTPW}#eu1`DF=r!3-M};d(m63)F<^ZO8)6OnE zJ0nWtJJ}Nbg(`hq5-E5coV=IDS ziBMx857GdQQM@8dGgyv+r=={Ue!=qk(FPGMeJ$S8ie7!QbrSaoJkkrHv&RQ%B{5Zg zpwj?|L3lGU`i08!?UV;k_E*K2>{_l^e6PHYL3pkwNSX%W3*-vR*Npa9jxsVly)i77 z!V#1S-Mxy|UMOqs!RRb$7sWpb7NDdIDbMf1&-8ymzb23AZx6s@Lo+eereiuoZYSgN zf&~V~GqF8@qUlTPlDFi>bjCW3Px^m*v^X92aV8#W7_*+_ZQ`LDjx2TCDTwbSJ zEI~>y{XA5lM~>17O_~s|PV>fKdCc8B?021K?R+SxFl!tFLVveY+({7H=D0 zMc-OY*w>Mh9U=K2lDl}^>fq*|<%X(_dV?v!h}*G=BNeF(w;iIL=&fIi-&6SXfJHM2 zLqgZuXkp1ovJ$)~kYq$H9slXT#*qgkX#luy)sP~gAfYD^$@-~`H(^ibJTiXAa)9CM+oQZCOe2T0%9Ien#uOw{G&0 zj8YUGlA*r`OYd=IYlPNI7|;i$8kmqMJ0fq4#E4WsQ6O{~fLSMxnH`isw2zwDCl)Q+ zdrBY*F}0{qoE*u@o$T0hxupd}|4y6oqZ0$G4{GY?9{9BKIT_|LtuZ~O`33_XQ&hJm z4#)I_@=gY%(i;FH!>@p5{e9o(7nSuo1c71Vf}ch42*&w)8{LB3FcWmx!xD{$Twa*6?aMhAA# z1Q((}1{fTg8QNDQCM0~G4sPLigbrO6Rnoiq+&0=B){a$$=w}rf*!%?MXNybeVyyeK%rulmg)<~eFrvJzDZkT?$iuHY%xuC&cf!_V`V z?BxZI*Yc%Nz)7y8iXW%zQDuieq#);@nX^Vt00VBwC0I^ju%)0D6cSD5i_h@lGY+-N zz}>O;NBZ2b93}m(2Q}zhM|1Oi?~_ow4Kx@4a^JB({2zZPSt()uhM;}2Krl@D`|+4C zn~!~-;`kurrZ{cgP$A-JyX-T@S^WMa=_GQAsV<*#LUJ_$JbQ=sA@?kwqOp~w&?p;v zii=nMN0oJg&B4AaaL&GI2Xvlf2hu6h{3gw_ri1Gi+P4$Q)PvL~UIWx=AHpm}{>|2j z4H>eyU@OHWnLbKDVRVi?>&E-uJ@iu#^z%98@#o<25J(jha;Fn~ z-yN7+3;Q4#Wz7b6?6fbFfDbqV8CcK(85HXZ&x}CSQ-CZE>^lLX&c(mag>YFz{2=6) zNAP)ZA@&LRuUz4eNr?MH@M$gBz=l)C(t|@vLF`~y+H3g$+EVi`t-xw*%T%6F&j2Kv z0nYwk4#&{2{ra8T`TQ9K@LaRpLH1eV!|FFaLZb}6NDg=w6~Tj|_VVG#+29Lw9I@P^ zJ*v%e4^+)%QEZ80GWcFZ)}&!utr@nqL@nSq{!=@iRXKV_C|P)t&xk`UZk0btPzYB` zfDaRnQ?>u_iJ%&^nOu=G~&xZnZ(z>wy zNaCho=XfWyo{*o(ja(JMBr_$`2b7aKRE}w1snhPE2SdnO>Q66%uDN$XpCI|o&}|vQ zRlDe7M^y1+)t%nk{&b){1$?+M56Y#2BT1;9E|erp`B^Yz!QFga&ODt0exk%nd<4Cz zg|Bh#oY)J1Z)9*>4=GM8SQM^+6}J@O23asDkT}K>-Vp5!;y|N|5YD*8qH%tiA0^Vn@AH@kr(+VdJT%x+4TzUBX`U+i*fY$BC+D; zRTzsHaWPZ;hK@N^koR?$dWN9+|E8Xud=8d9iCmnMOvZWZK0#KmA&noabq=aU)4`oW z$4)W^`$E(nm4Z(*fOc4r^w_cU1IoHINX!5*iHp~)Te6cS`3HkhgJaaBcsau6ZMsYA*gdQ^(nI@Ki`JhWEr~>t77~Ph1&d1f z&liSWR~5Fz)#>c=rDM?-zfBZ~8u)x`_WfZ|c2wQ`5Tl}wKd^`iE5uhVfz1xYsExo6 z4&v}Vm*WZp=11X8h4n3p3w$Fxe$sM$$2b}%@TbFZpN(Jv6Oz4Qd8_H(P*p9qUmM3Ht%86N_S0NA2xhk=Q_!R2Y=U?=#2=Q&WMPPY_ zLtxx5T>Q&oW@C1!afqbcCtZ=ek;u;8>B-qftBlRdf)7J@-qWaoU@$d7GEg}ZP5 z9YYJ==!#*hBsU#f3V}5J29@ndQn2RaPAE!pI4ii*{39lH@Oe9S$&CuGVY?q%h8eXS z0cFXckJ{cT?Eaj3A)T2*GQ0olA0Z>6wwlB898uDcW$wWJ9=i5<_qwc@$u{XMW(@5wx*y<1H(4RiQ(~gpCMRg>+ zjiQ6E#-r4iL80WOH#4{d2JjRY#DZTrT}b%}aX?Godn5ME1=mhn%TL*?+cz zkN^Bkxl$H;@}3By9Kl;bQP-HB8)QmSIgs;Q5O*vpgQ9+j{fsP|(>;j&a)i|ukSb80 z8a&mp=0x}sg?)=Z=o|XBKfw)YOW;hs(bb`;Ph>-mg81jj&%kEv)$V7t&pIpUos#LD zxfWlEseEM}pfoPnJ@(h%7Gk?6#g1pMqdi3am559bs(qlYU$1EQbMd}NgQT-TMp)oY zvfax+I*|j3(4i09gRdXf`1xClj*^g*Ri6K+=w95J{Qp0I?}RyQPQ$RVInH^6oYH2_ z=kp$-QpU$5um zIq!$Pfhtj_@e>a{zArDH<)Mszs-~C^@yF*QuN|Rqa}ais1BC0&+qRJCRcqTe)tCH$ z1a%}ns82+}dQ^DHiY_Gk`?t}=Yqa5wbl`oyO&Prm(Ib}2Os!fyLiA>(oOI5u)>6ge z3d_6C4mfR2akI+_Mw?glg3w3*y_M})!@G}eFqN-*YxE?p6d50XggC`ZUEZ^e*f9L! z)$G@PiBH~l)4wC)d6ms|->tc`i<8WI54ES%jANH)t|{BKUN@)hCTY|TxmG(>Lp*Ae zqKnntZxN30zZRU)7{9CSHJr9l+T?fR^4!j=2v{R|KnP?6MQ~2dHqoC1A925BTWy{p zHDAIn)*343^r1>{!M{CpI7ePRc=Nxu4;u8pLXl0y6_vf0fMJ$xzf!)w`)_AZs;@yO z?E0w4r)zEM&OxpF3v9^~|In5vc)=Nlf?6~A+*iz}E4RuqzjbjyQHEd*=$ueJ+$}x& z&h4uQYK&1#P&)RLR0wXFt9-1lfDZ`__y{fcC?|vp?{d4tY^3>WB9!xuQRx!K@#5_R z@a6$=q&X*b$na(oc2_5zl=Xx^B%tu4Oi1)PL zQTAn-2DS=yv!VB04u4=Aay4Cx`HnJwC!~He5^6r#Jzb!`DrLFARUQrHAJ<}e%AKZJ`s`%cx1Xb z{DveS__ZYr@`)MDLeC9|2dG}#;#v%)ss}pXyOr%^-FbVf=tl3P%#YdbTjk=iq4Gqy zo<)SP4+bI~NG!?Cw=_zbqKf{oTq(*o^^Vkd^}6zts~xkBuU^Q0Ekf&<9)2e%armjB&B}%k@``9Xo)?=NUX-4a;naOTv!c5XU9A3SVMA;YU?X%)u zzll(ZD>j;`wqE+trrI&jbu{M_HQwmv!TiPfKO)2OJnw4!`8IO&^56fhJ-vKzAP~Z% z?g$|1DT;u~;>$eWyxT`eVpm7y@t~Cqy*8ql_#U5*zfzaqgK+Gp+s$pNX zP3w=@F0qydV|33bYbOL9fQa)EJB_;PN|xTN9<5?xMw@8Ji31BlTPfmcyfdR6rWBN=p@?vobu)k)~UiKZA*v@v$;nT zkQ`Dj2!5)Y@xjxmJ7=rWdZ2AcZLy8tvauiOFIS1V_%b_`VkP^d&C6@J-6{Cj^wp=3 zNIcWjIaK;p`G|F-L1~Y3r17C^wpt^H`>3K(P^F_WonsCN9wbY1XHK7&zd$om&@F|* z;`~v%QQ}(uxtY!#iKQfWWo2|15SD$q0p{1Oaj{4nIRqG#bJcg)`T43kM)_rOCqXcb zTX<9aqdnf3oMF)s%V4V*Tx4_E(5caOq`%Se?W?us{$78wA)aZ(Vo$Q!m5c^R<^$< z*A;$i#lSuxqQnLX;j3O(hdosWkj(FiO82CSd2rW>tz zHw}zK+|eqJuaoKNzUHyH3_pvXZO>(HhN;R2jJwWuln!l17+nvTjGMiGgKz7kjr_6c zyxGp%u}$WqWc36J9rd$uRV}8I|FWP1BkuLd7WdD*ZOSF7C+DQd6Iq4)7KYw|2N63n)>@8=CQvpH?yl4`{vl*E8XDHi zp}}JCcBplLfK4}~tYl6fC|QEYqu0n}uaDz<6Qe|zH# z-1&*MunqJD7w}2XNF@KwU1W2@m~+y=C#L)=-r}>SKOxI7AH6Fn(a)P!Y{W{O_1?a1 zQR%2U9UHh8^}8=SRS!m;DsXk~tvEKRhu*NaGpk61t^t3aS zH~<(;_)4?(!y?_~5P_2W$zm}Sh#xZVX<+PYJb?GqEnGjXFeBfy$|rP~fXg-4l*E_+ ztvnHe6)-c=l$dfSU(`sJWQ)7r%%h7CWE*5}#MAZ0k4Oeo_Uq@KW2QJaE2Ch_V#m3R zfn9sY;shVUK*122({^1^Q7bICvg|xUL)g4}3I4SCGxBr}-kKDh`qch|DRJpxdQ>=h zd}>&e(Jtg$u&}IZ*E8l*l~{IjVMQln?^%Sx*@_nnt41Sx&y%apR()GoJ0kG=Ia7b9 zMmS6nZarwjd8F!inj@`Yn5%f;{85O#^8C8O41RWKSmIxAEi4)X(-~av(o1QZ9(_`# zZ@bOhXJov3ks?tdJ;on~NP24WQyzCdBg2Bj=G|JWcRfFZ4Z5wA7i&K?Ydi!iLVz%N z$E8`71LJ|Q=A&t;5uIg+#8yjVKCcPj~8ulK=d z%?ZjVDR_a!|NcH1_VkP__Z@|))#M3_+qDu$Dl!5E$if-F$Yk}TJ};FAhe7GT7zln_ zgH$W!X_w#v_Ppnp>JibX@`0L*w1f-SS)KUks=B0QYo!^to| zYyNqzx<0!>?7RFi0ORLg^UuIeS#RP;TG1MmQFkoYeXjOlc0s+cpoc!cW4AiZ6JLPi zCq@|~Af*Z_;N;Xe7$sI~SPg2ITh}Eg*-`1GQ)>1xGAH3P-7;gejVA zc`K@1d9QZRv2$>*!rF0xs_1TUvK^>V{m63vf%<2BNCEgTwCI1QwZbK{Ea@#|F5?rJ zFGKu5s%202n>%bS3byK=x9ZM+6^jwOY-`72*mH*M8X1n9;iGuE2A&=}GfYZl*cCwH7$d1ABeAHFbCry93|=gm zkqQ~Pv_E_~%`OcwN>v%98IIDeM;YGs%-#|4<%}al2qr9Fj#1haO;qXyBLW-b>I@-7 zEdvVOTcp9|bml97l$=ye%g?57kuje2-9cy<(KzM|BNGj84 zR9+{jw|4LW;w4RsMJrP3(~2K&P|;8;a8#{!yc-VEa0g-WG$kAe%RQjh_79pq>LSD& zqiV%;Kg;~hdhC;QrwY#>ZJlnuOI0)(RIvx!1Qn){bp!9U2L1sma-E*;KkHF(W{J=S z_ML{lQ+q^cilac~QPIuvhA;L5<4L)1DDZGhzl%HndQ_hN=FkUw_(%M}v)!29E_btY)|X_y)Tn^ED76fI$F2 z2#erLS5W4S;NHf`UX!7Bf65JcP_92+*Zxl349J)@e6hqXevkoiCOC)isjmY-7>Xs7 z<$!~b@Q|OVk^LqH1ZDSc=EdJ2xBcbe3kZ8(`xied4;TmD?tq^!_>!jtm{ZWwDZ$%Q zLJy{dU%!AHXZnQ59VIXtrp+)Y(O08jgGM^$8aglB&{rR3x^4*#Xh`!^5UqGA#%#fz zWH9q->Ly7Y6eX8Oj{b%vfz)ZP-MYUs7-kc=nWVg#g zk_eIKtj6aIav00jBE)#tqp6eYmHB1`2Vj$GpDk~CVC*&H#_UIpU}K)^yAFCBCCl@U zL*G3yEeD&o(ZfsWR`#hbYU*qywBMuE?f0w`&-Q|KU<6Vg% zuLT}4l8=kH#ryro6j`v~dsgk|vo7MM1U|e7iN!%cE5mkBJ4mygZvhZYd110kk98*e z@pgmwyvShsXFM5!9CvfYgJUa4d{_*VDck)dcLxfmKx&TXlolDy72C{}_{^0?%t5pv z88Q5X-6=#ToBq4PnW*Y`jh;=MIc z@@E9mbSS@1x9%%k;|Y%g`L3QkFOK=|5KpyHgwHNWKNS4t@dM4|GTlli>#hFodalq%!>@&du5&l@L&iHR!IPhBAw$1MpR|rzx3Cpa~i}Q$8O8 z!3Nw(!*!Y-;Jx1NaYIb7VF>te6nMFmXGrH8;z364ccqtP>c_#BZSO7OU$2Tlytf!G z-1lF927gL>IGif-+=OX7MKc$BeD1-U$pSv-b05UCpkd*|36c+|ESM2!=12FufU z=%6k8^4XBww~Yr1g~cO3t=;}D4F5s^L1NUTWm|{pMF%A0pm#CW+6}_Av*X(GqZwh< zK)G^;J>iA;!mzj@Rb$F7wb#u-Y=qJqBJ}k|*@Gqd;U(1UQgQPVEJE%YOxl+?mL+24 z+QH}exqU5Fe%;e!{Ose4Y7hK%Cd|%3@I@N@H=2hsH;yiWwRzZKIWsh#?u6$*+-;;7|D=o0Sr_7L zpIk;fK4ZhgpNyX9x*e{y<@D!~wS6a$hjn_F>I?!_R;>M2JKuZuz32U$&AUP7oFk`n zd>6eA=!O`&ZuN@JI!%YiH0*)`hGz}ej~p(49eO1A)N$Vk=5ggz=ObGS7GGs7x!|Kv z2EimJ`MBR$e9nJTKJy4=;yTEujrm;cv0v(d)_J{T&&>Nm3&A2GVcvNqS8N;sh(+#) zq1z{)HlNhiNUs)g2%i$PtAT~zE08O_3ajYEEK5Y62EY9%DjQHh|E)Vk!an%&G&Y9e z*zM-(&LHj%+o$>`C(-2a;M^74yefz-&a~(dBg~&E9?s_w!sm-*J7zL`8X-kt(Ph&7 zn00_J(#}4f0W18m>R7zGvelNMyK^QxBp`t-h9!jO(O{n|zsgvOW8&87`H?Pg((#?1g zm+lj51O#Vl$j}LE}RaFssex<4WT^+ zOc0NR>;42{ryP~>Ak`31!yrg!3iR_t0A4&z*G0PdbqT(o1qIoHj|YQI zqQH+avyaywM;pFb>qMV&_4yPdQd}N0F%^0KV$9skjLVVJ>RoVK4;3E_SS@wpbu8HO zL7Uf=%%>6Grow~5X7aEqU}gXe_vl_#qjN8(}GhLj&-G^+1surD9i3 zv>hd#H3pFzPAA+k&~5U*0_8E8)W-#{OjJSy6{^>n!3ACaz7Lb!Syqb-eatCa!V~~y zr(O<{jt4QehW`dJ72*K`)j;321W6V{op*|lq=&5or7zLc79q&)1nEhLBmoE=P1u`R z*T(||@Klo!J^>`%r#w;8pXp2iO88SWOwvsVK$IWh4`lA1?{}kB6$2;whe(|MIa5r`P}ESy8h>rW|RKY`gCLl&owAsk~|o`0Q;XTI%qaSzE!mWoKq zU41bLj#jg@te*7toi%L)NAM-@5+XdGf_wdaO~rn0)*bjRZyk9*|73P`G7$bXa5mzj z3*A2$e99#_+-Aj$Wo0uH^Ei4=HZ`}4~Y-gLY;%CcfjFod78Cd^7C*(aj`4%pB~l-s#H52Ne0)CE7yDS zC3~vt#u;KK?~!@ZITEU%uOF+JsdMexO=ML_$Tg2B+&QKAyJ#-(=F90tCIJH`;y+UI zxM79gF=f?$-C(1(^6Yg~_jl;mb>^T1uN@w8Rfpji!q7+3flurX#e<|%fz=1+3Wp)Z zzqU=U z=g)^Z$#hFVSBUVvI7x_KO=P|%`^`#Un{~|k`Qfn-4>i@W2WgbA=&r9U z>AqL#@j3ncxYR9QUM-cmz3+Rf=;yj3m33jy2AnyE$K&7l_VfLRaFO|>!~gwsS?GM@ z(Oui{`AUetBG#j|S9)PHHSgcw57R8ZxchiZ4($(!dELFw`hgK%3Z!loWFx+~We+?5 z0UA~gCR(mZA$C=}Lbds!!5{&6=K)jLugx_seQC#L>MAK%oX?iAE_T&ATh3^wf1UfL zRfkxBAuFkiR+VUOFC_eQ`Z$nlpyLS{dxoqw>Z1ul_Joo6n;7(@_9^dbeV+_P9fjKRpRx?+e{&8s0k}}on^6_{;>xX+lOjuzNVS4n(Z>e?x{IbUoIna)Duum z$Ce3&VD)#DA0e;T^0B_|A*e5hu&-zumFHPeQ{h?ku(m@)Jh`6;n`f$dwZ{E5`?dM@ z;n{Cr|C;Y|i}zfE9|)Z|ICL~~nN@gb?IPNAXXOR;RXR-maPkaJgJ$a@pEC9EH7a?A zoPqvtk)5GPgMczI*MpRn)UGFigm6_kiR0-Fsi|3-cY8yf(1E*bVV%|~rEKj^&c|9E zeK|%p(E#50(v2l@$Qgg+*ZOPx=t51p&hVyxj=qDj(L@n@b9Xt<^%oRTdSV5Mu;~@K zRjp4#tAynU2wE%K8YL%95&Nb7wzWfY_3|qETc%At5P(CYc?$Lu#y$Qd-+~d_9lF5 z9G6R6+c+K7u;i;1=WKubWoi3~j7zt= zizN86#8r+Ljx1_Q_1$%^54`uN=|=Uoqd&aow}r*j zCU!>ISz$BN*6PzqQ+m9W*D<-c98VE9n1@!JUP^A!RpnBQ@u*5=j`)bCPFTMqsxp;$ z<_UD!+yOO#7tHJ7=acjYsG;zDzS^7olL0o8m?^Np6u`KW;)1FI0Og!1{7sla%>GXZ zzw;ENDT*4cHU$x|0E!Fy+b9wE8G;ry;Dk0(^g_mt#bA-nQ8p~waT zNdY z84WL$Lk{9$yoffNo4IBVRt&kjKC43#nud~5F+bS`5wIg%G_?ll~u7yoOoTK3T z6yBlsW^}^&4xpsxwnUFanG8Gimi~ktXJ{O9wK|0Eh50BsEd5KSwHqW+RL#d}o)+!k zj%#T+`5|OKNkolmPMuPJd)H!IBPAZpOT^vlX)#Wn^JdD=;tzzB|K=(`_*v=4%jFzS z?RTJNo%Yy}$nn6CkPJLTwBdV(CG>}=5{3n|USy7706^Dx5D*#ykZl7=hQ+haO8W;7 zw$(n-F>knFly%*~`QekM5D2S^1pe54_;AxM{bGQ}717mt(W2%g()qM|5aU%;JiO=QWZ5Fr6rT75`~@cENw*Ao&|&Zx8PlX;o_ECW(ml2V*GY zoIqDdk7c`XaOGpt|7#8zT;U{T{VQ@!#r%Lgy5xjAQXE+gb}gUOG|*@M`FXm3y{JofI&X6Ktjg$u!JXMQ7)dI{od@dKJGT{X zVJwIwG%d05T(&T_dl&RMbI0!fk8nxiFv&n>&16InE5>%8FTe37i~%)xkvN>FzX`|+ zom&2g>hZx(wXNvhD^l%v%=Mylgx?u;JPDGQ%a(7;j&+r*x{K4z<$s)TAbae(5E8XcDKiJ~y z9cPr~*qQd_X#LWq8f&eA%<*`dRBKt3s^Q!B;|oV5&Yl=rXiyNm>vfT9_563wuF{pK zA%FDp@&`XDi|&m%_3e~A?Oi#PzxVuf-}lOc-ZlAFQj%-G#lHOuW;8@5VU2pvSyVFj zG^*?2H5jslW2I2be|YXH()mB^fNEv`g|1L3Sjlc(Lm%>w*>BM3y=6LYDag;_GfTjn zHK21=s<3V6`se>R5d7O=mrGuEb14U0x>uFMr4!Mgd2`Lb#{)o-jZK$R?^}W02>}Og zWQIf9dcTHBzT%eR^KC2rUK$!FnQv%4coF_ILCC$gAMNZGlRW4IMH5pc&wd`N#qxJu zT!i;{pJPg@8TL!O%m34RO!SG<(l%4s1f*=ze{XE@?cO_U9r2G?g-5vH4=`^5g_q&} z*Tvviap@XyIqXx^u;#J|CJkge)$cjhk4_@Wry=Jipui4~oVrr^!a}W7(GTI+M}^OM z%$@8e@_$#b2<+gG_}szVo3|)=%}G`Tx3lCoU&Gh0R8JA|cUnus%v0m>3gg+eMOHUHIC+R(_mL)dP_ zBP74!BavQfWkWONN1M+arFiwY=#F<@Mhe3!hW$sRY{@yd$OXzq^|#Dgl+C+tnfEDM z4BxVt{A3>5uUT2ejPO6k6IxkpEs=p{28TP8E4^B%!(qz=S+yGuazyGDOoZ?gL^oVZuEXk{$VK0X3#inW&2k(McH>yd?P5#* zO6LkPbO3bB0fs7`22^xcQXQXEbLPW&`cC|1kQN8!7N@mpYd7}C2VgR<-Yri)f!ufR z_e_1(EQ0nqx8NTS!?Y0}7UUDc9c_Pr@H}gaLO1SJ4H~{3lrj)FeH-7qa(w)D@K@Cn zzit~(t(=&>eFCmVmaZo&sD-N4hw9dcDu9C&z>=OI0}ju)rDo_4YGpp}+fvjmhp8u1 z(b}b)!5U;JLkB|F2D}@9Wy#gb|KM#}rxktw5vX#m4(yL{!fl3XlF+A1|`b!No?r3*}}$I)mcvjRFZ zE6S{ilr!0wGmFc8-RMzWzIQ82Lj`|dk#6i&7Vx^-(4(PuP z3H@lsHxV$Vo4BhX1^l;UgQRP912L@9!3gYenfx5 z7&uHJQ92r1|D7_+#AT+?_e1*4(&!yDQtKt$eNC-ST4Ss0=~m;@osV#)yb(kiI8#$A zvxwelaIZV@bhqml({imxRbP7Q!EGJ)9(QT=_TB3p)_O8|@5!uI-}`%gt6ERL-g^qV z_efL2WRvvpI8AYi=H;#OuCv~C2U1xQy4$WX0B7iP+0qM2-7cG?k~ul(iOmQysoP2+ zHQ;((7JBLq9K*(?X`XCZ!pDHZO>b<#P^XVWh&i$WIt-tK`sHh(5;*+;d>UIiq`|Rr z937;jrf^%Wt5V(awojs$x8;^IW)R;y?^3CB+BBrb=H&mnX{aV5pra|t>ZE=$O68mj zselJL0u#0}Z)M&w7zCSElDdvXy(=SiMQUYM3|N>D1)98!lLi*5?qx`5we#aXPB&-g z(P^|s^KP(dH{A>u_kMLNTdu{#yJa;_cP*u5?UL?#ddqsA?&q?W&&PD%KZ-J~JUt1q z>Ma~Y|J-z}bam&AVGEFzVwqt>7Q)OPd0IMoV?2DGz(`sUToFgm%~i9W9XO9cgX7KXP+x~6Ef zGNh`H!Sxzl@+ns6PM~U%n=h4SFgmd6+44TU(R_w(#=NSZG+^32&`BeirVW@dz-yXc zSFG0Y;dHaKfltHn`Y~Wr2A%maUi?$M31<7Val7PEeS}>*qF9&B5AqaL*`9=X^#J7% zGSVlv(WZR7IGD~>z#p^a+$a4q-JnKVLPcZ$Xhr4bGEfr1R$UNs_OEk{Ydcq~xLrq% z&qER&wdIJC_$I1Ww~F$m6@_BK=Lg4q?CLVLdU^e^6ItQ)gTEc~1qZ+V(zCa??VLHM z^~9#4?i81^Ia_HZ$7QSYooq-uS@Uw?E4%JDdQfMDEyqJ}dxuKXcJlY_U*WGzs|Xqx z^1Xt5FXl4z5p>N7wj4s$prB3gv@YDMg*n}9+DlTLq5xAV#*G6Dns+jaNM?fr5~sgh z*4@5541Sjd7JEe!RU`PXz8Jcp{j z;Q7v7>e@s{q=aMXSAF6^W&N;h!v+`htycxfu8Ztn-urERFULVwC0Q4D^B)twXZ1?? zf1c>nQ!iX6{|l{ck~1nLJa;p>@@f-`k4Ie}&C0VFo5l+kBL!cj8X3rsS4&eJrzXJGw8ol)R@;y>&?RpY<>swwqCPBXy2 zEkMa6plkuru$R8tMK^$0nIP6Tss@a%(%X%JS~GNWg4V-JVDtEaLo;BDc)CRz-Ed-n znhrMX23u&~F?A;iH7N8ACFj7%)K^rks43a^`;v zzT0Zyh64YAWDnfuY|MqMPYmJxUmmUZDHAy({i#SViKsEjQGUFwl>@r;A2hSKUt?L< z@n*Z+=Vir=Ts;<56S~t^2+LVdXxgV)jjp=5bzEpDT(($#fn2+`+^;j3skaVt&iEE{ z3D&J0?^0q^!bm|kCKolO7IE!;ugp13bY>?-X1RA{IvbpLYIWi!h_`5t6Z?f*q)Kzx zIDdPl{V3V1Ulo%=uanrsjG{9;Q8R40Mygyjn}@*4Cb4CbsFC-GWvy(vMZ4JrKm@mg8xSVD^|ksN@068Oqno&S!SciLT8 ztD^t+^nd(**R%=Ieo1Q5kv{_90~Z&ka~>NY&q$!SRPWC>AG+C;MxD3-PQ{X}v(h|d zdi!^7jAgfF){NRed3_ymyynHs|Eh|Bzp|Lc>n71^CYW^Ohn&bqH4dI()*8-f8c?Cl zUvb&iJG6$(>?ZqTPZ+8n{^L~}h2N7uL~QHtwE@;ku=fZCKh>(6~0SCasaJo24oj0M<<9P z-6Ww(E6p_4AqGe=ie%;|8+Zz14s=yBqz_Y7UGn)iDap(zlTh988y zvFP_B1D}<8&nkZZAYL9C;$te>GZN>@Z*pzFqeKM!R^@(v(-FUu#cvPJJjinv+{?dM zVu8+mYM;fKQ|qN^rrKww+N(E$b~ki&y6x@O{}Ai!-|z<4z2}FrWpo2NQ|D@v3#4@d zd(N*^FrB1sxXU<|{vP^LHbCo+Hyw<~Rv9boBG3#23hG)t(m=pkmCWf0m+%%!MS$1T zZI|n|d{S~hX0-f3xk52f*>ChtU@rd!8Ry*9zvq_=)8g%SqWl8xq`ww2j=|q$Q(RzO z#?5mN&V2B6k$-(vk2Y{=i71(=srUGjVEv%a;RuHyMX;ipJ@?zkA>|CJXIWlQ#Ixo1 ze@}TezdM}pb>UngacM|cNE=c9=NAlh_)-*O@tL&p3))*jSK2YyvojyIa-x=?)%!y2EV6OPxda3gJREX z`zM5seuSH>M%~IYU2GeGSxz6*PzfmSx51DuH;EsxhukN&uLdOoSEY2V$ZA>c zj#&QMULAwfBJ6d<|64@Q;tS`dB@xHS~?-MMVgvVLqw#kV5TDV#d^Bz z(l<}fM~KYjdRiB@AkIC}vqNQ^2z^U9cCHi!2%IKP@0*S{t2# zO6adqSJbP=RRe^?+$qdh4!Hq!mWvI8UUD?0mLtSI+g?B4LFm6}oQ8{poZ64BDKm)V zs^_D-Wy#l%gmMK6Wt*~xDy1^VCS{W!{b_k}m7Eu_dM#S_%*{wpPq??h!6}6GZ~IzR zWY8w3zxa{0=1(@5Xzg$t?zY2K4g9l);gX(DqRjhe}+8mkfp zmw;Cm__OQuumPwb`*!*z>rPv1#f2B23xa{Y*gmP1dFcSqO?fO$Zezae#4d)OYlQPt zhM7K?>W3M>jR)r)TH$&+5p*@4I3B&L{iN7~Ab9tum#wLd)Z9rw8!2j#sip>%(zBe$ z@cnTc=|~`6ABubEGP-uN=WmK%Xr_iL!n0mIQYI*IFW`b$fPuDtU|PZeJcR#j(%Scz z0u%GYLPBb3#?~=+=MvcH|8Z77UwtVP;=1>(lw4JG6bPTX#4Zqt(0!E`*^QOkZWJ+@ zY0nNxt>OQrN$5jxVK#EKpq~1J6HsZsILRX7HasgyUHTQjU!^dZ4fAqCa1m# z6iQ^}Bk?uqCQ-mKcQN7rnh3Jb?AhbTQsCdT+aq0)K1$YfSDo!ux76Bpx-=uBi!$Z6 zV=eOWUR3zaMFx<4IN`ZT1E~&&h?v;$?0~+MvIlkBQtUQ9`Hgs7-Qr|Q+u3(TWy@D? z?k`Ii3NkP|@d6eL)WXovWhKQs_LeF;@VF4#&5aNNLg^J)98}CcIH3lp(QK(^np5LE zR>^bb@)e#!E&7pr>e`nDS#sUS4Bebs zWCmIK&%(7A9uJ;Nhu^Z6+X)d4OSQhaCi&)~NTbMq$JNmD-NR;OWYyhN@Dx#eU z5FKTK`PV733v5w52Ow1+B4Dx#%(3VOp=MHT&06$j&(|r5KA0LduN8;7JCo4UqkKm? zuuwPqFw{6F-MoYhKa2Y$zZ?>ZsFCxzV^x}Uy=|Ps3B5Wn21@9ezvbbbP%<}WC3Rw| zU)B4inIm38?8YMLbDF0;af%_4(KJ@JU*M;^L~TutA2{)Dihn#=0v3+nlzG&~>my$h zy5Z#||CZ%&=*kOtGOzy_jlUl7+)Cp9+3pzhzfSwURiK!m#yd5OmseaD$W^zv5D!Zi2QLSN);}4HaZKcL4v-7ulfdS2-cS7V>sD-Os`Xp917p zwIy0E#9hURw^#kd@o9eDIOLfnYs<6!5cS$#w&st;flJr5!g8!&6z;S0OV>~QeLHlK zvTKFO0_ObQI{Z|;Xu?YNEj%G@7(G%A1VS;iFcTubPytcVpG*NK5%~8;1yJRSqA7Ks zP#+3LEH{YoF1~3fSkRn(V>5_s4&tj7wv!wsR;o!1=G;3S zFOuDqBsgK5K7{PR3~11{v)y?zhEwr;qRYD=pVnh>CZV%h`_&U?mOjd)AcyepuPga} zJEotqXM@(IevzwLmr5Z(&z^f1Tby+|y&#aAV>NO=;LlPUmKFWHeKy_(@U-;QowIsYv~qBw(Q>vcrzR~-X07Ah`yd|)2r`BO zZuw6|`C)5uz<~d}S{6_z;o)Nz4s;@Xp^e`M8K&H!md26%otI5N$$keMG5c5zjpeBv zUnq8_7H37Q<7?#?ar!1KY@XVg%Ad{u{T;q{-nM6EVfFF(EbU9%S!M-5#ISpzm3u$- zz~_T>z^Ez-z3}Esn8sGu#ECUB4VV!l`0nke2mgM)Tss{kLK2IC4*!N0T`)#2+bs8A zvb-FjYrObMpG^qA@IvwOUiM$BA#UZj=ieq9{xEetWYe{#DWX}#*~hqQRra3Z8Y%2nd}OmZ{SUup0WyrOajx3cs9s(gcf3rAnu>zbc3woSQDl z-ca&O!_I6}!-9ba^${19rY@=2T;nQ<&H}``zGWvZZ}UvZW%5q{fVrj~N_un2j4R(y zG_q|oz<8ki+a!-{OUCkB>Mm83rK`F|Af^HEg*Mxdaj#RcNL?~4OMSh6GIrReG6k|B zQg?Ieo?zg%%;omDz7RzEu#IOwH1BGRx!oPMbdIyU&P*P1)(&$jq*-_FrP&P_DP(IK{-xYdDsQqj# zfT*BVu5v9|YciVAe^@6U{?Mze`c{&T6&<#hF5;>rc*3qL!Eo$U1BeWdW@YKCM?2Zj zs7^T{gNG8d3Mlecd&(;+DbDdE(LUhX~*9>n;(o*zW{!L!wj?QO3)_MqEa8AZVJ!~`-~f2#nxRdY_paSk1(QX->k{rWgHkVqX2bc z3C;nCc`^-!wPRK2ij#-1qKUe%iWMuX!I~Qfa@-}|6)y!)B34{N;cFsc>;8$|8imy* zJ@IMhtwh(kCASr}?rSOA^IJyc2=@p7u%F4y}BrDf#tRo+N5`u=5+{r z*B~#1%U`=A_3c^EBbHRB(tJMDIJ}`t zHF?gps(nTBF}ygLh$x@*aWb;&72i59mF>=uu9ASyvNkG8UbjU)Rrn;6Q^T35mgH~S zAD*#Tn|9?ZR@i3?YK{XcYveb`dXkCQBj5Da$mn$<<_%SEyA+**mFL#TOG}Ifk>wY^ zANf>-o*|=uGhN@kR>Vnr>ii1Tmp&k>N}a?#kmU}TJcB5`83Maopc(5F7ljpx?TSuk!*@Sg*Gziy7(Qd7G^9zi z;g!REZ>I#TSQ0|!=tr4BXivDYZ~j`s@}1ORJo1^r(X{7CLj*i{Dd=gk*;uFS?$Xf} z1N1aIc&$ibV@WKE012;-!y03@BosE-iaTt*H#G{oHH1$<#oq`8PL2FJQ1KW>e7{D1 zGf}Yv%U4ZRd_>h-DjxYoMgJlza*Yw0)qDuH-d2bEp|0fP|4aTv4m+EEj-~GSiXd8Z zHcI%@!RX>9#qPh$L)L~q2b>lM!d-3_<&D%WKEHpT;lI@1)G{qEEg_bxPZ!G|32azj zYfr6}6qf}zW5aIH;C7Ne0#SY~QJ34E$vye$_hRz=h1b@9#*T6UewD7LE_dJ|kVhaQ zjEk|FN~Q$Alq>=2N_HshEXnRrP&>r9pZ8BZCQDT;BDqwBf6{Jzhvl7Oc!h zvO?XG%s4jbFIBFD%#Q#nc9In)YEY43vd2g~QdXYQgsfmImJnsRH41Mr;=9$LN}%F~ zL`v>%CfX;(+?R-K=ngpHGqVQ8n}T!6}6>YB~ukU7a^I8z>p<)9ZL~F z6q=?&I+oxiEJfEE=sKI<6TlZ4!fzWQybDy^C(GwGx_>K17o^^po6|2v`gc8->6(2wra=c|2I;XcibNn*_dY%sH#PY2Y2DCcTR+-Dsv48^U-5jGymm{reVQ zid1c$lzNMStvlov9>TjDKRIU9?olkW!m_ILI0&kh6kAr4oGT2G3$L`kZ2akS?{;2+U#3=@%QbIadCPdl+s2xHTX@k^0_nbo0N@U+%nz(~VuaD= zN8=;@1e0Nli|{wky2!;Pt~R811Zhxf?3j%er9$_AHJt96_%FaSJWA1?4*J1|;w&9~ z##ZE1L-(ojp#+3IfIl9sTxYC;oBvfWY&mKD9rRllxK+i+eOo_0D<)yzH~O) zwOXzc$j2ZnrW4Bls2)A|-LG$vqJF;`ccsyiPqA(m4(6?kr2ODmsCcgNHFNw;&y~Jh%;V~hVkAXK1rOo~|YnxX$m}bG1 zs2Z5=;C$>$?>d^a1yRiQf}|_ZWBAQXP8+6f5nkSDgCMbZdhiBD)Rk@hg=mE7a9!k&11L-`Ui(H7*roCaJ^?j=bQiGPD}))j2yME>cc~8* zS&d95$#vB5wO|E27x|9?q=jB5tQF5TE2MmomC0dC&0-W{U*%^QTX6}njnOKXSuG#< zLf+Y3|4>Pu#7|pxJl&a-u*8GH)9j};ieTr)0Ggt5Dp^FBD{wC3o6rX*Y1^6>+sBe` z|9-eo-_!OGDtEd%&E;C~lB&g9jincX{=XNWtvuTt-SqlF{QWtvPI&BEYQQ1L)oD+7 z+}5AB!Z^D<=MOdFW7JH(tM4_(!5cQqhwmQTvJ_I-T@p#e$Tb2LXR(T1ROvEcZ9h=4 zk1D?iRBWUoTgbnMfXIR+)CLjVg4H`qMq++}KT%Jxh~#%mvL!XLeQdWs-#3;%B*&r; z0jV*0hwdN!m~e>*>uZk%fMi;!5MeosOni+MqlAPk*fhsKdv3C8-Yc*mE{e@gZz6oYQ}u?p@m}yS%1+?8T+uD-Lsg|7|;7Z?TgL zeiCK~6{}8|m_UeX=Lw#TWjP$VMD5xg_#a%MH*KH$yx8x&LSOQi-M{IF^KU%8_|yB_ z^~3p!PtWgkzqyz3_d?&rxA(#h=UP7b{d05v@nzAYefxVqzFfcbe*nWkJioWES)fgz zy3`?hQAjn3L|}mi9*AIq1lmH>DQNJ4l!6jYNTGoP+2V^WX{aLLfE6N`6DWL8qRLhv zmGxnYCvoMJMtr;^2q>=%1Cojf@-oaQeDvg@jXqWg%q4CNy4EAVb zo+r`riz{T{fme}w=D8GJfsi2xjv@gAifE*<_gy!M5MaO<_^>0+D&64Ijt3%$5C=c> z>^9G%>YayOsqc_>o@u4VqiU=1n5yck@*rnluDb5ZYp=epho63%pwWpjztA$#pnBFs z%P^FDF^Vy~9EPW|KGr157oG%zY_f#nG8Qc&3ew3a7;<%@pa<4eZGdHUmEkL%1d@kQ zl$^q6Fd?byt&MkWl1ES04lI%{r?3IcNd&_Q%uG(n@`@{`baDwLg2)w!A977ah8uwh zsYE^JY_kIsRiX6NfHg6=@I)xGfk!d_akgwEO1RWvhb+TrHS>xqf>q<7alT0lFtX$^ z$0aH85)3HKjK*H7_~63{C;W87j&keFQ%^T>IMa=A@w6kKtiPU(cG_yMoolfB;mGb} zav$^yFn6FKi=BVXEtyEapmEezd@JM%D3s7OeWWIrqilo+AAATh3N66| z^VLs#ttpu;#@u1YN_!8Um`HA@k}&FxkF}RUO?kE#MYg;`3m;$Py@?k4gj3HoLTC}? zE8sSMy4)az#fBX+qv*Qa;1=_2CrHu0)Ish>|K^1#snSLptPcaqGf=~~&punT!`#;E zu*1(j@qBly*=*mBfByR4@Af7Cv~SNnpj?C&#lS_!fRQ1W1yCuK8HOAvfs_uRjw0Y9 z%PR~Ah$ji+Ojn|kmRyFEtU$~aZP~;n0>Otn+`$i&=){%6@(}_7=0vqio=I#`3^(wB zTQ*$aLMCDiI9%d+KCEEudIYqwkYy}E1cWg*afN(@V~Wuj9wj{SiW(JUB*{_;oG9oQ zgmh&McPJnYedxuX?WJg-_(C8M$gj^?h!?id${HDj$0Dh$FG>UqV7dYp3@ks!F5CSt)Xqq%5T=Pl?J@s&bXA zY^5t-3Cmcva#roAWi9jn^Raf(tU@>(MHe8nOJ&Kz7w-zai*$uSuQ&xLDi(;j z00LuzpadW0kTJ{gL4%aI;wffsxZl!;p)<$Vm{EDTFKm`phfV z;0sV(VISNG2RG_rj2X-U5Sx(2%-l2)J$5mB^>o+I2;v4n6tJOsVp;9-h*1XFF_{P#gBH;6jC!PF zsOKPuQOQw`a**R3Lrn)$)3J_hI71uiXh%7?K~#4T^&DL7YEh30*073otYj^#SvpgV{F3e^b&!J_+#qHFs{svP=z^)qkOl|C!3}I^gB;{A2RyWa3|DY<9qw>zJKSLo zcIb3}-SBET=vsw*m`flieThv(I?{?h#i6TIrE;=pEHs@-1RE6(w2I>!?x05>rT~C& z1AqemELcZ3%5jbob2X_jZnwMN4exlrRmPXNQE8RMuDiT~40a&Wl&Snhfi&w9T98Eo z8_Fgs=hPT$5JWJHS33bwREGV+tB-==iZ1NTTlWqozgPy0Ii$16b4=pns4HDNXSWzE zZ|UZ;Yf=O*x40wCQ5u4vg&cgrA825LHA#1ed$k48=S^>=EuAqySgyXE?sXg10QEJf z!NH(zwH(+0Y)}8!4RcV#6|?{cHi&)fP)7qA2rPCu)PYWS-~%3XeK||BcN26!)1w#N zY*)C2vXi|Mw6&5IU=#xnX?TS(O4?kLrWDV5)^p2Sn%$UEw{A?{;=amRAfEuE6UeCl zhqg%!4|0op0Ho){F+yAp5i1p`t3T>j_i(L{=s$OM7bZKwsUWMQkmY^q?@C2`J3x7 zV+g_z$Qb|TyrL$+N9?hTZZvx9ehEtpB7=FrL*=wtFL%&?ZC5#XfHQT_Uvdz3Yk&nf z=LR+q48{-xNuUHua0OfN1q;Ro3dnVHph5z8Uzrwye2_sTcxlHLCF}(X{NZSdc4$}P zcZ!1xYmf)m1Af}oc#F4qET?!dCsW@?Q_+PNFys||O0izdgPH+t7Ko90n4)l;zUxjW;#Z}?JdbCG} zb!dk$CS#kBMrafgA2AGoum-LWL40Tu>;gtyK?`Vb3M+9ZaU(%}Gkpe9B$~qpf&dIs z<`WimSo5Sr%VTm)QC%sgaw<_bxfd12u!D;CeM_+=jsx%FFFk|p6aS%~Ir zW@&#Fqil7Di@R8LZLkGc&;?|m25RthX}4+|_-X&OYJ0hLV)kha<^}_Xc5sjxT!%Al zR~6M%6_nNqEvRUVMg~(tC6x(nWXT}1&{%v?ggKFT^te*ng@Y>pRgaugT~hfA)UyV_ zKnX$s3d17^d4M^;CquS?1`sq7^t3FIh?8r?3&s!#XaEY*@)->oH1I?g5$Soa*AC4f z2i2g3N0koaz>yvqZi@h7=AfPQunTw~4d#FhBZCa)unnm|3E997;6Rh>$(}Qrhl2GX z-9vq};0v=G6tq&`hoRzjcfO5zSv*`HkSm3U|o=EY=8!9&}v*q zfb}I`l|vPB(U|0-1$QuM-H2YzW|l-(S>e@+1KKc<$9PTuS`5g5ilrH$68e6=Pz-i3 z3d2BCfP_FZwLG!&7YmY6ca%p0`8j23I|(`rYrq6~u#SEJ2%W%VG15f~_S7PP>4`~nsIB*p+ zun({>1LiOUD=-5nAPn7L4(?!K?a8XG8gK8Jp8$!by;(3I(S5~LH@IL7Z8QopLv341 zT`Ca_E*F7Os)LM2n)B!|bW}$lM3!%nXp0uDD|iZBparKucll>R-E=Y0q;&D6UoXLG zVwVPF@N@^3V5qhRW(RdxCkF_KfO8;?;rbFlr)z2dAO(0JuXj*6EQD+n1F(=uS$vlz zS^*MUF;fw!5_>k4=hs}nK#wkE40CV_TlsP^$2nffIAFmhc?5Wv*hNmETRFuqaWV{- za0f&peTO(Sb(%Ui;SXbb_rQVhz7|;0|5+z_81DZvqDjv3it|6(TR_^ zKy6~E%7Cb0^$xG#2HCI+hUl16D3 zGfhhOc6M-e%Q%?G*lJ=IKA^^ReFD#WgM6!{)&+mv*A)VRSrc)5J^K*>`Eevy zpLO6014)n+LbPADMc6Y8o`5is(L+NUMwvMb{Z}PavVWK(IOF?}81f2fkfl>bzCoc^ zmp}%aPz-$pKucSw{U2u#ux(03Fi=LKiaOZ!KOBYT5^0=>Si;oEkE$D0m8;+NWJDTSd5DUD4a0gK8 zc#d~xFGY&ewOq`lu?>luAK_d*f>U2MNM!J17$rw66Oa@lC~?y!K6VlgQ3p;jFxgXD z2FWG^;tQ?-QvXJqk{DifqXwWLaEW%kRR~XBMn}P*3SaOTYm&$b0t~M31$f|G?MtX9 z5|K{}Rsh2dR%K!1;11fb4Alt$PT&P0He%~QlJuYkG4Kl<&tDejSH4MnGs~sLpd!Tfd_06A%Rt>rMy&J zMGozt41BN+(P?2x)eXYn0SZt62v7sZP-0)p4fK!&GtdHMP!CIx0xi%2-B1L4;15+0 z2JBD{DcO3;Y}F^6hh?m{5sPP$2anaYIr>OXI0Oo4kfr71pC9*Iy!DT9WPEJhpGO&5 zyZ{Pt3_IAXFuF9*U#2iF<1;I=CT9T$B0bW7jSIyfBn@4Vys08v#Mg^a6T=`xDqGmw zQ=dg+2bUn%m7O7$j0T(k(0i3#PYgmnUjQMUvrhker~+(MQ*@C=RnsK44GXXUt`P-i zD3ay?4(SjM&48ZeFb`67kzn|e;E_-%#uIR`TW-vPuFAi>g!dfc#0V%$L624Da{fU2r`VXV9k?l2BU z1rO7ClIRvz?3Uao-m11|5pF^f-Ca%zqXuqpWBa1CL_0Tm9Z$UQ3R^G=cG5WjUWf(S z32a~ti6yivPKZMP3odv73K>%4K&}wBKn53a-%t+71ko&cPzO7sM^>&qZ&D2R-Od-F6hcFEM`s_ z&nKV5a0*}GaL97y$kW#>Yh(z$H@k}xyzto)@#JMrAisd#ehld)N50AO3u~YXF;wPX zE^)Zv28+1qK;F-Lu?C}XOsSp_4e<(H0NQ|M>)5>)LtsMi9U-3S>Yd`~GANp$c8#3D0BiRE{CEz-q5R69VsJ z$$6-9h*n9}=k&l0&HxVSDd&97=O(W0A+OwZbqU2zLB3EFg_kh>Yvn`9ylQX<#QEx8 zUOT>^h^^D>3ZWBeP~bEl43uyO_?hzzrK@m&2TnokL*HGeum#q`>qE~J%5(|gPSS%z z7T>E3p4U`c&-GiMhV-xwC%M~SIO0y#^=FUvX|MKc&-QKa_HPgOaWD6CPxohk4%}Yu zcR>q;;l~|q(arK{WPY3pPZWUQ2AZDm1!6FFQ16LP<*&d7m*@EPqz1NyA_?Cazu-$* z+AWFyPuh^r2V;TPHo~!I(G31j5BboN-@*E=pZec1NvuCfmohc5Z~Lx~`?;_CyU+W* z@B6VO3Ce)_s?Y!Z4-okT=EH|? zAVGr#6&5_$(BVUf5hYHfSkdA|j2Sg<sa3CL-MTZaU!cC&@CBb9X0 ziuP+pr0t9e1W)AN^OUC1q7<~KPd#-K5IK4*byZw^c_j^2S+!-DJ1)6PyI8sVNsu;f zg)Z0VZlo(v_kiW@Mp@W!qorSm12R5Jqm_1ABb5}1Dw=K#rVce^xs_0*YQp8GG!$(W zTt1iTB9#ppMfW6Jeo=*t4d11T7GMOiV;Fm<8rPUL!t=4;qwsxYi&13%a?4$C#|0A* zG)^gIs6oSh_EBmx)_7yctR2bU!iG@=4Xl1)xZm1>VIvQPD<-(AVR#LOmY0+I&l5Z9 zt@)^UUHL-Boq2K+(N}mOD(IfP`V*9_jz(IgkVhfI4_{R53dm;sF^FTXyY~7aORt@3 zykS6za^jQUt;v`=*y!aB-Lj<^KG-m3yw;Z* z29K}?ZoM#I;8-hddsmtjjZtO>zG0(%QIBbwkDs$J+KLI}ix}7cv^+@6H`ji9Ncjuo zlH0VadX6=mgwWXNj5danEkwi>{pdpVjVSoHqs16BI$5;-?QAi|jyV*AJp7A}FFKKi z4awqt1jJ2IfN=^kfFK@jFAGnm571<_y!woqq+6l9G} ziZO~V{KqgWWT9$|Mk_uDkcKs6&8*-63J&rxIKbFM&V(qOnQRLW#yev8ctMLEp&>j* zYvOHw0Sr5!fpjyxjR!;cMKDsvTHveTtU$4aOH7PRRkYz)g7FG6xI$HItRODtwMIJL zMizB=g<$gN8W+K;SbtoNP41)$KN2!EB;gksY&DbtD$+*(!|=-{ih-RSat0XK3u7le zsgba4rZwXUMjp06xn?OcG@+3NpcE#_)X<_BbJ$lTVX4Ve)PXj)1Wjn*P&ZzFhB<5y zU@&cClVB{bn6^}kuV~ zOQuqiB>_gFW`{>(zD^E!m{KP5h|D6s(wq()1sv)*(!vA-f)&zdJRPWtFN_2)yj<8y zf+4j)@T-uH%AP`f8b*eCW-Lu11Jfi5OR}v2E2M(|CodKx3)+l^nUdTlASjVf9x^q2 zuSipZ?D-!&81Ab>>%u9F;n6?d$QE#51DGUwP_6w`u0ZwP$KVy!JWNic;IxUi0I0*S zg02pLkV#w6N=KUA0f<%9s%vKDhEB9Au)IKnD)?s4S)JkwJen#}!6XPY07hKr;ptpW z3&Js)#IQHw1sOERx5G9OJ+T`GZ0+d_shuyjRs4k;EX&y44#g#ckZe=E;t4j$$hcsV zjkoYJ)0SHBrd?2!VB8eA(w{^n{Qg?swbdfPYfrimw)SOO|gCLZ9R9FII z4GIiwVQ}k)w|$jxZa9v9aiKsEsR9^O9H~wJ<^qQ`sN$?^glkW?`{0c!i4T-0iC|tw zi7%|>o5r-sPc$nFlhxN3s#rtfCM%0JKsT$S4PUEX5hD1)k|c9U!!DPb*)+t&s~mnJ z=mbFqLG%bX4Tf-$yS9yKM8ihB7)Bk)P>aI$;+Vl@VDb)@Fcyz=R(V)#eLqx(9oM%F zrwFk;$m93uPR=4YAR#x3Ai(2Rcf`WjBE^1-_wDJ5Cl8LVAsmGEu$H8lcC~4N6jx*ERq2zUN zxT^DN_BuZJp=HrtiVG=0&t&f|7@dFvTddu${}zKTr)U?q7v`i+#MImu+nTKHjif%; z8p?tw!zp0F3th;976PY*c!GWK&KT{RwBsL`+F)r#!*axGXr7m6bqDu$)|jqZL&fXM zi(t4R$X;%hN?`&F6>}JR*i86b+we%(VFJv*fu){Oh z!|=oxUQsXq-slc#7={HK=Y2klxj8v%T?RMQ;uJw2{3!-6^q~8^=(1pZ!H4V_ zTNHfYjHf)~XHjs{@&%Fyzr`)a)A>o-!3_m+P>AD>J14NovEHCF>`0- zxczis9BK_kJNJXi#237%bPa&0JI3^We9QE`)`6f!EK+d_MPwrSiBLo$44(?3(_$7! zkNiwHKXA!AKG>HZkHMeLY+Kwy``fR)EM~F&@c_dQXgG7Y5!WhXh@8`|KejB$Fl7GY z9ZJ9hs0ctGVFOTzCfS1?AaOaA3%5l&HVM>;cp{5qT9JVnmkogfGKdD_Lp~6U4CM<4 zQ~-ri7zJiv25YbeI_cMg;&^x9`r$5pgi##w!-MV z^5a2QpoOA~g;!|8CX|J|`2rguIbZ-0_0q3jaD_E^z^1x`c-Q|Lh&BsivXJY49!g5yC`Fa=dmg;N*> zRz!s++y%246SA8uCvgK?DMN4q22bDvxFb2E@vXEoGv2v_eTg{pXsqGrHYV!?GWadX zizo7!3GqlcDq0x-w`hwEsv2O}AnKqFUi26tq~VaPpd z@cjCj`Gs6c1T=1z0o%PISUpaD`OB zzFnZfSs0h@t47IdLRH{I?5oI&k~>KF8jN` z4*P{VAhXshy_Lwl%CfEr+=<&D4-2Zpf9k$NgPy5ks&~VMV(^3-`$lq9$8`jTcMJw& zCqyOArLPyb2Vl13QodH(-M`_<}D$ z1HV**HBbZp51hGrEKF>|Icq?Nez=Ez&?69yvq6=-g-m>fRWyY}5Cs*qhJqZ0SU{AKput+G1!Vjv&{2yx5j(8|j8G%S zR_TN#a>^F6#v{UxV(5f6s10EoHmP&EZfm`tydrZ%i?D3RVi3o5WXG!fM(SvbstM2f zb58NVFjpJ}P#6VI*n~@JPdTsyIOxy3Y&kU` zgTCy7F4%%KSOaC512~WaKH!5u2n0&F&_ ze~e83L<~rNw1-A~g+w5_qMN+;Ye-i>g;e+iL&OGezy^C*#84mxL1e;L0Kf3tK99@< zLcE7$@X-`a1{T}{U5JH}6pxkcgmggW9SN{CCV3WPl1 z13>VD37t)w$OKe41;xuu9^}DQv<6L(%xbOHRzL@cOa)5RKJkz|9{jmM)JJPw(SB&eQ4qS6 zgsPS7JvND_VL$^e(1;ldF=C56I+yp+opbQ}FCYa_m!N@B>dU24OWvZ~VsVsv76SB%^7_ zhFsZ}?F5;9PeJg5K)}?T%}b%JIyZm=I{?t6Em}B0urzQ`HfRGf7~j5J131`%EBH@8 zkWc6Z1i6%1L9kj-NYq?SS+0dDIm}qE^w_Q3%Iq9Rb0k~vbd%7)BkhPh=IDZ1K)Gl{ zx};pj+)O$uF)U{NK)o%|5$szR{aeOl(Z1JR>$=@@yrQ2}aoUA%l47$){Nf0gh$%9B-Nl}$_a z&n6Sk*hw)b3>iG#FL#B?C41US;XtqUBG!TvY(lR0ws0G|+-Or~?X> z%SPqU^;An&{5iwL-jDr{Wg%K6CIbb$wPg(ETXMw)E3g7ffJ_aBVMk1aiqu3aJ%t=T#J}aoM0{b+ zrG&ww;aAwcS;$co+=Ft(W)-jmZ`ftCmQv~a+*wfSV3FnjGEF)sUP?nEo_3Mjx;+U} zMpml~)c=)f#TMRG8ZBz{NRLzn_GI3Xc27aL3O-N+EYOh#4c|hRgElB+H@IH?w1cND zP`zA(G(b=^aL|gbgFDEB+K%2ppjBJ#1oiY#ZdKW!3%a7y$a7J(bUfRwoRF^kQ?eyn z92t#@t+3&Uy5vv^#c_k2g03;X zo=hu9fCR8=Yj#Ytj$!HpYbP8!4^>2gwC{Vc0xEFa6b%IsRqJ;}g+xdM74(M4#0EXE zY6<^Q7|vGNWI~>Xx>T0k=OhX+ZfV^8RhMpwVeLl$rT_)mY3x4@OH*@?hHOF)wd_T; z)tdB!Jc!i!oX|Vy@vsW39#2|MjqRKzg9Q!b@$CXNIPD0PT4O}yY>Qt9h2!|81m-R2 ztc^j#RmuW>XOV5}mj+(N4&KoKN8(i>0*0ERxWR3LgHa$bWqdp$%)H+-7FTh*D-@R< zf{=Btu*hbWV}qVyV6_|3r&)Gt_kQm_#O21M>I6^$`nGRw?uQs=@KG4e$~^^70EHC2 z2XBCM6`%qY7FLO2F#YzOHTFA zI=J4u#NGgfgVXj;ANK=6uu!aRS+y)Y85C~X`9@>K=Z$r4anuyE($4G*);movGHE)~ zl)CE9ymcO4!%_)aAwU2mt;ahZsFAH%0R%S~Fk%D4)D`b!#6~9xgf7^o*JY#iezjUw zbmU`neQ`m|lbQs7_R{;Y508)QpMI6$5oe3@V!GnBo z$dqtBNQP|Q|n*~(x(47x(Do9ZRXXeGkhCSGWXQ$QZ9rrm1g)C@cPp@kGCf8Qbgf0*R zo)y(CP*4T!OJxbr(>~-&HE6k{RSY#~D~D9*6=@C4T2(;ai>*qo{8+SgY;Rlx9aH#) zSGJ#y&MS_*b`>^&u!U>jK!LmnA|%L5ATEZy9^yJUP$DlhvV18_sBvRLh8#bF3>lIa zuvd0oNffDaCCio^d7VOIih@x6-xnc9lsd# zr=f=;nkYoJ?6(P_ib5Kxq~+0qhAIk5nyIFIGMF7DU)VxunnE?FXH7Nf;!7~Opz(6Hcio+6Htg*);o7P%w=>u7o&%PxYHt2{V$|tSq(32vGhBg zMW$p z1XB!jzsN%W@GvOTqAD)6B*A+CAH49xgXMHMS4yVZi_enQW!A85 z9cGxWqziWi=Oyl7_{gGD&C+UXM%HRH2GffPzPXum&B_5x->kg%aNbAGZD@i?+$a6|Kq42m+*oX%2^07C?OLJ#=;M^P!LF9WsEblzy?SdhAwzv3@xNG3C74nDsAA3 zTI}K%NXUT@jL`-rKrBob>YdR-RK#N`VYdFQnBzDo#N#qv52m~5_5sVrC zTmc!i$OQ)0q& zXTQ#9i!;7r7P3%-AYAdTZc;)JfbfGLC_xECbfT=;nw511s!*HIDUcr}3L?{BCy!26 zCA@e=8!($$kVpg=n?OVECimHw90eD>pv6>=!!ZBSLVwi$u&I6~w?n7mP6s zQN$nLw=hN>8X$*a zxMCNuqAfvc@d{!jq6Mii1`fnv3}XOd2C9IC4cc&nFhnD{u$VrXn_bfP=zjP zfeR>wHdw~&E|o&+75Xn`Q)T#6VZ0v0RqL=dh3 zRH5dO7|19>9fnW}Be+3@jIPa8y=?7k9}CR&^^scxi-@?!O?!?1%JigCtm%{N`^Zf|>|XU4{=38KId1RfBGVgli!V03(7O*g{E-DWSIp`-Bz#xeyVqu#*j6&L)^PP5=Zu--Q z#dz0xo0@y1=6ALGta?t^x#O#KD!#cod=ADY*zic}z&FmgFZa0_t!hXSWEgO$s6&qL zd_B>f4VQT2^Q-^pgQUR~&apoC4+4x)q~TPk?tZFoRlz_Myw<8^sX<=Vkl)xO7^nM1 zF^sV*Mj2!CxJlJ8fU!bj0L^(o1nC74>KWhxV%4&Q!`A8l+rFiXyHOEZX`Do0N7lWY z)h!w=6wN1H2b{$jUNM&LY1~H%1TA!dDojY>g@i^OkP3!GcC0}Qx*$jd!yNE|3e6ye zEX2jtL58G+=8TGJc~C9%LQTv>R9y%Lx!;7WlX>)xmLXsiN}=(j)z)>L*PYeBji3{D zpze9$)rHC_e1R(9Muu3&n8cUaRfoAXA4Eyi9oRv}B}@(?MC8C79d1O)1VTdLVNv{o zrNjvx7Dz+*0)K3t<}}EIj1WOY5UT7SZfu@%-~vX7M|N$Q6k_7i8PD)>O(#a+z1@#U zNQW2x%Ov{38mL0%U`R&*oEk2ggM3tayuucoTHMY5;4h3q8!%iS`p_sun`8B%r>p_Q z^x;wj10Wm>MnsiRa8S|R0<5Uksp!HZ`hqTC2rwuJhz*2?{7xo%qtY2qE>Oqr;2zEF zPIcS@tK`C~uwy&2Bdgp(Jj!D_zT;|%0Vo7R4Y7(lo=!Z%<2?G~tL!5`5@bOd*B4Z~GYomhn- zQWr!AFD3-<{UTi|M5x#SDEJ>I`brnM$^s z0Rv$PPHpPuZt^DT*pdIKSZ@mFaF%8;7)*B%XL2g1idm!`)WNFI0+anhZ2Dw%s-tOI zB3EkXc5-KTdgph7XLzawScb!N$>B2pmYTpuvL(6DnNDu%W|;5F<*Q zNU@^Dix@L%+{m$`$B!T}N()J{q{)*gQ>t9avZc$HFk{M`NwcQSn>cgo-06^-&!0a% z0v$@UsL`WHlLF|-@kwZ3m#0kuwZJ05f4^OI3~1$XQ>K|Tu__k%h)nwv&Olz z=g*!siylq7wCU5RQ>(^yxwYlhrCrOOO}jPh+qiS<)(qNnZEdE3?;cLPxbfV=k1Jo! zyg6%buQ^wXI`#2DS_Y3DGe)dCv0%V((f^_)OV;@F=+o1(#lAgzT)lqDpHIKO{rmXy z>(>tqSg`*9_O~B?{S|27fe0q(pD+wI=-`78Mkt{$-c@Mfg&1b2;f5S`=;4PThA85Q zB$ikqg%c9vpo$YV$RdL;wisiKDXvH%F~;Pm-Htr==;Mz-{%DML$t>dxG}3UEnKsbz zHX1j*803m8uT*Izl~!h{<(6D_>E)MThAHNlWNumBnP{e&rh4aF1w-1}f;FgcfS(p@=4`Xrj0@>gc18Mk?u~lvZk~rM8e4=cb%?>gg+T znn%kkw%}q*FBB5FjFHY*^GY)P5dXC4n__xu>#exvsw=K{vRSI6?_DY^e2W%qtf2!Y ztL(DOHtX!O(BgOOwA3y-Y@>Q+tL?Vzsb^lM zQPDsnt@P4J7o^M6P)99wLM|Ufv&-qBOsB=p#5xeCC5Jtey*l}epV$`t5`cU`-=sFd za7Sw_E(>K#P{XzafZla%{{Pa6GiV3iQr-{eNf4z0AZ)Bc`3XLed@2SI3_-#O?YKdW z7pqZ}$5y&9-4@xcH+Ho6efjAr(XG0|6FG|d>jJ6Gr`oU^M0ew$x5Vc_`aTL$djhRo z`|ubMzEPjVqfYzbQR1}xLuT9er%m`yTD*IOC$D|z0pt$7K&*G~eW~5U#P;?L{bG6Z z0_BR-9_dL2yS|a}==UE0-rjRxLRc3iy6rA;@HqxC+IK*fJWnOlbIIF! zp(0>BFm|%LpiXYrtc7^bBl~JppFHQk5>A9$<@+E*qExE-?FoLk7{wagKnz^WCw3vR z+}dKdyZFT9g7bUG4gX~qj8n{E6v6<{+Xk{T+QDxnPQ+nDkjK9I6a;rBIhY6qr9TsT zv2F?RQ$$RKi&qGO5|=mys8r#JOKbuTNWg&>ev!8WHjpE|IF&#q=R@!buq0LI>@8+RS-eRXLdWAT;ep?ylH8WCDp4` zFS_`}RxYd~35(At_y7u3n8z65Y1AuJQ7#o>Xd~VUz%gvG30ItgO2)KB{AyxFhN#bw z%lic`gt3Vv7-0){poA&}B8xnpf)Z`mrZEDrz=5>roal^@K!mZjGFAx}q70)vE26@W zD9%sebLAKRX#bH_+E5jgz(XDes?B5wQ<%pnl0j9X3OqP84}74+CN_~cn=tL71zKCb zh;fM`B%uqC9ECt!F^WJq^bUMbMKX?&kRE|VJG7`I9|CX(L7XC<5&2j7P$Hp*5g7Omdy$?Z#9D+}Y)+V464h;D zvRpkW9{6Afik?Ch;0^C7#!KGvn)kfs4X=9DI|@GtM4$r6!&~ie1wjylpJP1`Q~E=U zIT#@cQV4)-ZA;+LQX&9TO0a?#%-{w)_`#~U#2rM-2l@eA-I{L4Wjx?kl zJyZY5fj&-avJ=_3PSh9ks z<0&^h*upMXVU${>bVnyV-MvJFmk4cSLn~-DbO8-yfHoPXE$wMj8x7dbwzjv;?QWA{ z4Wx}PA8K1@HOL~hLJbBn(m>@a=s+M^U~_20Es#4%JKF;3w!Zg`hBWy5-vC#`8q&aq zaWgx)z;}~g zSe6pCO==#FdIuxyUQ~Qt)c-vIj4uLY877|jeje7 zdkIn8@E_7q5SgYaAovhR#_!+f8VR__sj-^w0nO2LJ~)5P(v^eWSHhmmmwcU|Ged zd%cDe!sZfaViFsp673;kHQ^_gbqdI5RBNCFIFNn;@OM4{fL)LWZU6@;CHrV||YI-LR&;71Y|$BVca5}X4c;m13`pbB=t z1jaZJM|gxu=LX{xiE-0e9@ah@b&X!6Hm)EA+-L_zu!$i!cs9@lsH@sO%l+?t>~?9ypX(X#>?t{`}W79Of1w=C1-suw`W;5%af; z$YhR{NRHNjkwvBr)mjaTXQh(e4@DI}m+ksuyIJsf9AAT0T964{4RlrZQo6wRI3ZE4 zWXOE<6=TcFbiidz&J~%;CGx?)WX{JMn`(#~p0oX$Taw2D`Dnbwth>z2;4 zGZv$wiZea+aW|m0Mj7DmVDrvszi7wA4BPSyC76t(yDxTksmXf4w(-z5Mz#6iOnUrL zo9ruQR~>BM&nUS-6rn0NBu$k#2MRt}*dI$u_QzHARf>lho&t?YVOGlA1{J<3*JN2i z%j9N)D`w=M@(-g`<_t(xlybhbicyM+bc$+bmGa+($`sj_f|^^h-M2EUT0Y=gig>c_ zqc~(I9hQxQ+2P8R^TG9`dk!I2Qk>|FOr6&-ai$mff&|7JX**h16<@@?4sN?0<+y4C59j*?dj=;~ViCWLW%9@c_0`1|!jNhJ z%DA?>o_p_x=Qkb_#3fpIbqTKUfdjCMpBoOg)IaE0W zx+psu3$2B>7vAnWU3oT$1qs;kdn(mVa%sS{#_Aw1_=vL+;n5TU7#h-X03xEJ2~oplh9x?Jdq1a>x@gn!i(<5{TYw-CVQkYsoiu)JPV#gXr*ci+fG8yVc|*K zr~ekko+VSo6D~$~o+C{@JBx*_nwnQ_-ertzGg^((DTHF4?w!o;g(b4!)l3wJiDN!g z7-eAYb|NWUSR%mX{*Jh9K?;=JQrWAZ`D6q-!qBhk9<8jpBfazzI4tceA%5dw& z5&Ldczg~qTChC~?gsq7h8w+Q4VxCP*;P^meCvu?+Ln1)jg@@87Gsg~+ED4Z!E}Y$o zVKY@-)cig)B-OKENnDif>`2M4argVkB<@*Gr+1b7xP7_mVCT?TF067AJ` zad9^E<*P5b%EBjx#a^W}n~5-?l*oDfQ8sIUpH33K1Kr7XY2%{0iS8eV-29eN)eKk= z115tBd(_<9#@h)kcW}wh~(^;^p*5*d01hun%#U+q%A)rgATc^odFu_b~ak?wssD4_*BdhiL=(FaSw zq35q?!wNN4MKDb`SjP@pOiZtPQvbajdQf<1P?-vgwY*D$`?k!i?zse4lK)FaT?D|@ zdB2A}XWOiSteV91|MQ$?ryBB<@gz^P9sjuy7JoX%-sDgsLRM zQ~38o7d~$5(gTEpfqdNR+Q^|h{ZO8L`wkR{gYDG8(im{?Hq2Lx?rlL!=!80CK=~*p9S z@15m0=yiqPPxTJiCM|WLJ6_?PP??MHxUdbKK6c0uED#HgC&8Jl!Ie~#O z8qc&6UeDZrV&rzO6qe3~GXaH(|Duy3?f*nLUH9ZaKBsMv;*Ij-%#84Q7W}Ny29@k` z+f;`Mn!7DNd$tprfJKzgpnnVM#O~5AR=~sg`0WmDx&JNK+v*ko@o^p5jXUnwt$3BX zBXa`7#KPlA$jvBp3RSboMDZ@^^4AN<@=RZEGWaF$0n2I!Tno4rYV=i8U*oN=tE zEVt*7u$A7hk86dM%oW#T``R91%lk96+>b!kp4qW5-$w`L7p7~;uwVec7gkpfeJvvg zFi%vkB*4wzA^TVgb`?!W%FgGRC`n!rz3F20ZE9)|i)IQV63H;lmYL0axGUba?%9}N zJp@q;o=tZ6Gvz6FOxV%ECwB5_J%jv_N6~+xp!BgTVDc2al8k=O)`T@WME^pO888h4 z^hc4a{{Xi;$Sdhw6e@azb1?AN*a%>0v{arjNCl#QqUSkbeUi)F62&#fCt@K;F<64H zf^Bfh7J%;!CM#HgzMlcR2i_%0hdvc|nqV3ShkGjc6nL$_th1skfMZUpbk*3D{It33 zG;4fCI#}|U>(;!s&52qR`m)~_{~VIjc0#}3mJc(Oq;N!Xw#7KYv ziwN&3Op1RenzoG(m15WT5{jPz99o6^?|EKsXq6dA~86U^Xh7D8k@+FSAps$euf zw1g^f*}l|r)#!zQ#aEVnk=oOeDCNDtc}nwELBdJauEuD#sgU^xyEE*p>@dr#2T-tNa{-fUKK~0XENw< z9nO^l5VD6}X0gmC04gWM)mt{9)P7M+%$C`3d{tXWKUZA&rwfoT%%TV^Vv9FZKbKxg z$cH}T!lU+1DbIiRs5Z514(Be5M+3?cnP9`88K2#Rm7TC$2Ie0o;@DT2id@OP!mxIr zxP#p#UB903fJuHnOU6)UM*sL;^BE@+VZadbc3h(MxP-jxD~Vz(-HHno3g+#UIFtDC zR7|bQo1dE%p5l-pZOg@E7Dz@)bUPuI7|G?PeRVv-; zT_!*D$SY%gb{EaLp(yN99*Ol!sn?k>R>%^Laf6c>mP`3)>w?J!?p zp4H5;Ek8EM?;S|pEwRZi-do94##~Z?fB&ElC#%^gSF1RDP)#pN25p?1FSfWWsd{qI z9^0cO(<|+u+qeW)!qTp-oT3}C864AwF}S6gvZ2)uP;ib^e2cY;9VS=GN0&*?k)2HP z*oE%tgRm1exnA#k$M6?H7?1uX(UUzAPKzy7NxfdeaPh(N(j_NO?B{aPh-vMw+(GMW z%bM1E0x1r%-i*@jd*@PL!kWMu?peYGSym&MLk66R)~ zeAHn2pUn_W;&#Os-YN^E1BS}WBW_Fb?w5;pNoXDLh;W-gXX!XSO!>bm6%emT!MMIb zZ|^PHftDPtCa%3K;cT(;`M30A5pG5#J7ltcfr&v*p(kega`>XMz%6H3@cco!{~115#>l~E&0f-mO_PXEMIG&)0U7uO0-o8CF2{ZmaQHiI7bYq=Z{ zk~bZQ#A$wI6o0M%H8aS9%2AD19jh0#V_kCPA;vW?H-@C^PPrOpr$b98Zu}45wjp-yrGCXQ5-Yq)BMUfp{()Zt3~lhy%p)|GTNz{NX8knwa1AO zg}M+*t|h_lg{N`HeK79SPF$hDMF73acdLQ-(KmzhMMc|1K(NlZ)kWn#UNVTO1y;V)M*l@Ng2k#>Q{dj~uGkKTRt^AKSoeQL*M- z1w~QWTW;SD)wQ~i1cXXvKuy=2PyNp>-3wyJK00XHu;JQ_2(hM-f8Rp?PPYvd6Ut9>u?vX`0cPIg#Vzhw@)q zuUW-{Z$*IAaf&H3!!Ilq%@JfE(BabCqU*_E{z&stgM8wm(cI)+(9p(7ZP2KsRGmJG7^2ZnV+SY3UJ92K|O!Vb5gG^=wQO z0%hHo6VP`*zNkn1cCj+L495}=|F`#g&V%PfR8$}=f(1T0Ukp6b=={#q!#dZhM9KDH@it*vpiO~tyCk7o)x&CrRMo5%=f5B{2l3I&t_(wo|NwT~MI=Y@gdB_adIn zJrlMxrj=3fiqUh^853mzrS3t7D+^{ZW6F;(M@MLc;G?fd?%Sp+vl&o4snLxIy-``n zoEST8j}Go^ncTFw#T=nMGFt0XUD>(1(~uLuYV~&!6KEA&&FHdq1#8RGGuef|g`1(s z+sgfo9tg-G1N>LtCE9$mk+#rJroPcTdFy$|7vWrGOMRhjQK&>Nph3Wv^~z0K{lRpJ zewR+Ra;{Gw#H8iHAA}kTTH!q{5tTu=rGf(p#vaopoubV?V?shmhzXZQn=i-7dZYG5 zL--1#=^|YW;INhEFb#UWT<)O)yP~76A<_J}+sk-L-!it!99W44d-EbmVB7pEw2zOu z0yF}rZ?Se;9163*ihC^k9H*)sm-QO2aDF;g65f}y@r9~;t!Q8c9NRKw&Xz8Z)_ zyvODSkijMZI&kH+#H@q}r|Clt>L?EEx?i}X1DqUZ$KBQ+PFaQ z%O!B_bOixF<%Yanb0BoUylM@g*EZ_UWHm{YPvpvippvrg7qBNV`1 zzj168x9M++s!?s~etmqQT&ujK-ekckx#>+~nMf%3q*2?^xLFTpklF^dA3GpY?9^+5 zIMzRcSSFXI6N+ih?_DS#-kcNgI#eJIiIDm-#KRpq+9I> zn)HEXzcc^{&?gqq0LJ^bb^d$O(65tJ006@KQ`8o~)D&pFwcl6CJdna`iNx&Q+^v~| zmC=6?@&gzGCM{q|@2=5p=t<%w!o8+&-Kaza}xBv1*V>4cHIK@WFK?+pdzX- z2Vg`s9HDhwod#Zp_Fm~;S?o!7Te@JKYpe1yUbpbei1|4&fhY#lGLYtZP@pqiRG)KC zxB^v+$)U(Y(F?dIu^qQM@5dluJl2TTOS8uINwI~o{9>Gm>Myz%ix&MI{JYu2Q#5K) zU9iG+&Q_!Jwu?ert9;5LRZV!qj220I=F2ALk=hvTeaE@-4 zcl=G&C4z31QNN8i&}4-1^1{he!;XVgpIjLe#_ApZq}xk@t}WdYK`XdoF?d+}(1jL$ z&9S{z-suBK9m{7Uhi1H_+dr3fzm-F|fD5BQ^uwz;UJ8#7huU3g{&y-`{QzW(d#iL` z!x{mSM}Tgfsrmb@bW4Hs)weYzqgO6{ueo_fw(?M>_7HTb;dJ)pPgyUePhmFF|J3~b z^2&^h!r{ghs@Fzd?uMO#9FHExhry_HpnQ(kwUdii4L9Vq2{qxqbzXRC#xDW2c5h1@ z?Yc}2L-AB(M;+Mp`kp2BEBA^aV2A{CIIAc9Mp@XRg%um)bRE?lu}k>ctOK&!^9KWb$<|&Zyj^F|0hga&xz zACsl~5vOvqO+T1m^b!aeR1t04)OgPgix(j8Ghch|NaI=1DSob!kd8%qI7~((U+}L431=u%|?mF?6$GY%`k7ee$9>j+;8FqW+I}Oh@wIPowp8# zUs*ZRo-e!#C+n!?vnz+{b%tmQ+fZB|Rp7mPmbYfQw`QT8kSn%UMWp3)kmg?0tzCP~ zecZgkq!wUlCv}XpcSH-2qy6X62KMz|5E~YCn&iizpGC!)YPs%jJUw{*^sCz~DhFf1 zrHQ%}d8Wi~^ck%X(LqdzWAq6>BS}{mLSH$;>iyKo2tGv}Wj8gAk-PB)k-L9;`1l2S z&&bJ>y+%BfKVmIC`IhtmOu9gmos{~T%fhK*0dIJJUT*jIKO9yW(uI6N-k*X?7g{j={kdM(Dsu}>L9_FG}0x_g8wpS(Ws0@=>?R} z*+P0>X&Bcz^;T2(dBer!?r&3q+Bz-JY2xI`5gJNaQXMs9#qxM#Op64O5SikIEzXOg;rc z$>{YftPn!Qk)kExfupDfsGef$xl9S|awzKnWJ7>TwfUmYt5s?B?w_R@hFs>EewkH) zm!8uu&3Uu3?ID&YA%>?)oOqb?FoFh)Dk$jnHxto4z94FKjGq6$5g(SgRgBk{WcfNFE z5x;8PUAn}HK?fKTpI}j`v0s)Q^PW(@A1)Wp+Y@hng=n1=6{@$+tXVxUM$O+1dlqs> zMuIiRx@L9Gv&WH-fkj!IzoNIWqcvU33Y*PL6N@C*^|=cEj@jSrvY`}<=x@$`@w*MA z@~JrV{F@e=zk%^`J{q-dn1WvIMo6iWjib*(e~#EqTx8~AA1YV(rXTN0#NSZF7yrOc zxA5IPlT$_Cmxuo+ab(zWVqWWLya80$JZ+QJ5_jno=Kh|b?9sM-kzl=_iSzkvYU|kR zTmkiyJ#tr9GsUHiLv9^3M}R+-w-X0JrdwBkTK(M8xEu5=NpJq{ri{I3g0(SD!7_G^ z@GEv=b80Z}ZR3CYALe!~6ArGS?iZ&=-I&sF2Mi+Yi{sUisuQ~DOt0gbJ@PcJ;UoPF zA|UZhACWTHSFWgZSNd$RQNp$)CYlAQP!3{M=F2;0^e8(UjbfeUN-Z}nu!+yOUBlWu zg_L&yB^VPhs@4Gw9O_*&!5~P%RGjLAG8Vyh7&Lf3?sENE}I7Ewhrn zr%{`*oH3!DFnG57=;}%*mqTiW$P!jM(rWzRvtE>$w7!XVUgu+Lp`IN}v6!u_xoEZ78gGhIW1nh`i+n@5)ZYYBL|nb}C6YI0C~ z$b!6Vy(?CYlY854e&jargs|mfh!%(f(}-<2UD>I;Hj;O22DzNe(rwWE-Dzr05X^1? zUza#>Zs7Zsq^xt3RLLFTr*4beqI$YPQx|{UtMQ5yaK+hU&G9`{nZyVP_{zBGWjOxe zQi3l^cKm6%=u||3fb=6fIV}p@8Y4imm7iDGGJSpd-sOiX6F(8kixR?hH8b2uiZ~`fP$e$d~0T z0MSlZ`%zmNau$qLulS#qtxIH|nGqftjV+L8ynT_Bo+4QBxY^AmGta#JQ%z-tqfx0c z10C0S>#di&=kr~Z?L4KX(gOO>JzAomXDzq`k2Wriz=R+ouP0|h6A5ZJlVZ~F!+~=- zPC&RhcS)Q-(<*dV(EtN^EjU)Eh}H}P=6bMt`}Gw;N_y%XR3=Bd;mVhey{k>-tIloL zEr$(%ohb@6`+Ov>t?EwT{>v7p*-kPDw&-rB{#ODUW-Xj^WI-4q*M;n+CyL&dt;JX- zMB2S++w~Sda$`!lt&{qUAbbAOixgQPl~x;s&d*IGLW20m-&2 zUD~q|;sqSBv$Zowo5ztdXzFiiLCfk!rjV0g5N;pa`OdF<408XYh3U>8_y)~WXuct`s ziQFI37;}W#A{vc&Pndj;`@3*)i?ntRff4?Vm20|(xy{YY_mqzmDZVyj`c8d79`YS^ ze1ILV?OEmspf3hOUFPJ=bO%sjFi;^HO-1_eqcH0 zNZEs88EpyWVeJ`Ko@jr+vQQaR$+^4Qnj{Ig1YD6TKeDd?2= zTBG!2C5%atq+i}+maK?b7pq9yD7$(Zg_Z$U-P(|8%7DTCFGt(Xf+`00Krds-wET1n;#!@Zuql$C zb8e!qIq?{!vnh#%+$>eE?>V%3)ke|8JS(Epu4714&31>TQ2hbac;a=P;OQOl%Gd#^ zpDTq!cEifuMyB3^9m`_?dx@Yhusp6y1f}uoeZQcPK3N(6Y=I)s_`-r3?VVJ|)zIjX zLCSqKLM_ZwC1+i_-BUw1#@(~Up zVj%^Go-03!a1+1Ovj2btQ%O)8=~JHqrWnO#VbWY?#g*k8~SqZbU$ zRRotvCmi4Jlxk8QXb0X3hg;8|=uzps2gP?4r761GmAlqQTE%LQa?Nu7N7Oq*nFW89fiStKVnu}>`a?o7y;h)u~$;x<2rW0TI#lSA$N-$ zodSM1F?*274}q;ronJWbztUrPc5RQ1TV#Eo#-lp&b$+K;%dSoqOuiZB8^Y47()8-C z0EW_=c8YJQ3Y4jeJ;EL;ZWe!M7J}K3iAIf)1MMk#*y~8VK>yxI?-jiSMWYaqoV;LM z_Ek_)u5k;t*~MA0 zi?UE#HgTQ>;l98MJfuT_90jACw$V^8Vs5zz4ckK@xO1mGxTvd;dB0(e2_B_y#34v; z_CdSb2PjSN@qz>dx2#|9vcpb@&X=<@7wUoAZebtc=rWCE4Q912#}6N2y} z4p+YAc=E9a58EOn<0D;#*beW5#)P@^x$FGhBeUAWWevLk)zKORWkH`K)!Da$1bWCM*S zIn{TCx*`+NIfZ#}_HdU6%xAcw|_~q$|ztds>ZcUi>R9mP7s=YF-LxHT;ZBRVds!XUr2*l zF5N=bXwvR;8b^M6S%ca_*;`)k0tO0qqG&=9s_lTh49%f#e(N z%B93!KK(z*QIkEYT!P&h=-72rw}cC`jg!OIJ1_lhHJWNVmU?qE9?CM|g0Q{;d1}b3 zoh~l(v!MzuZHNJN!l{_4Q(;Sm_2QRHTB!Ke5Z_s;==Rx~X4l+Q5biBdi%a#Tzkjsn zkX}4(^TJyJD;67sCZw{Z7!>gyZ-pHma=U7s8;_>^h>r>0#HVaEzyUs z&-AXG_OU(o+4WAP+~l}yi1yfTABU>fc#3zH`+Chq@1s>>glzU`DqFpz)phOl@%_)o zM)4XA6ww5{V!L)_n78JX&#^TzlQJhr*%5sYi!#QfwGr%zW_orl3PpO^h&yHnjCm+P|UF|t!-*wi-BoVJx3FCj0EKHwK|mvqk_WVI;xHZ-Qo;I zHiWACn4{ar(MC*a_fd6bwg7c{V8>T4Bh|`4AT4I(%eI6ml<=$Fgt3=;O8n!_w_2x| zs$+8kpv(Xs6PmLX+Sd|Fl_}rtVSp0t_KNKQF^O|dLUVKNWiY#!lEQm|iJ(l*{=ATS zF-P5*A~(M+UH0m5QRq+fCG6y1+dXpYGoxdZIH5iR6qUyJ=zLgy;r1yj>GKRlGz2~8;PH+j zJwAaMsq~n&5F95`MEM~BUZoS5ORHh-tcMiQY_>pI$v1CL7vjrpQNyPWdJo~YbC4JIPCyuM@>-H=I zOuDmVqx}4wzcd(`&WLGR9oI)HTj|hbuMOP%a&AG@>P>dP^V#2-uu|bc46n zBm$N#9_qGKvpsRrL@y;}^~i~0HRG0hL)(K#IY&lY^K}^bUj^^quQ?4zphdHRi1j9y z1GcqKbB%Ve_1EL~M!#jd%Q*jUnCIvKcnp&70s5Okf|Dd&sH_jA#O38ETTdcmLdVh)P&t8@tVXN|xgRhCJ2&bfvW+k+kOd9pa3wC{$ChKMoPdUcGu- zkdT3sgZq$ipWX8d#NW#fkM|S}hUKAGNBDh?Iuj@tTj1X@|4`WRf}S6G?519`uG}i# zz-Q8@ve{)>*6fp ztYb8-!7tyqz1u^fG5mq~IeDkV9xvl~dFS!7_P4|E%|~SCflupr#8-#hBu&e6Qtz}$ zFRNo=#0>>^vLk%+&FK}22p1rl(U8q}KqxZx+IwF(h!(2EcbSRT0K@g`ufM*4}J*YHa5IsZ-u^`X!CAf z#wmBTI6L`gld3Xzn_K1a+<7A3Am04C57xqZYT>1+V4LQ}ERjYXbdE^28odLabdA7r&MsI`~MAYyL8RR6MD#J*4 zLsg zX6v{AUHsPZ9HVC-#RST~PdSuS1$(KO5BqnUT6^C=0byI%#%~8t!f+-KvPI3H+q{AS z?%z}~N8jnSa0FQ2cUP7R{QF*z`d9-Fmj9WZle)*V!!p>i37kmnS{v^u&mx)st@P;w zI8x%*DK?PSTF8U58WR;K4If+o?e)v~Yj$$N^ON&bwHyCLyD1m(XOD@;9a`*0V&|~R z6ajIdXWG9zayCRd$;4uBB5#F^)#|2v9<9LyFG0a5p-caVT~sZIb8@iXgy!8Oc> zLjO#+7zcLZ;>DJ7GX5SjS)t9wrM+3H2+utLoBFdE(OvitNm(sS8l5qmA?^jCQt zeRPHGv4bth4SUNGI9nQ?&&ooEAd-}I> z7BA+!ZdP_rgn? z*My#qzsB?X?FE9yf=BOHh=z;|7Xx_m&eB2aSa2l>$r+Lio{ZCOQ$?e^t^BqKQDU_! z-ugPKy3;Ls%HLHqYCPsQwk4t@~1e!hOmYy1!E))kZ~F4NI3P)^~7Ul@hn>*Gh_dk_o_kj$xour9j) zsqixOg_BpRhJxZ7=#tV+=4{8H*qBVocL}36?k|wSKa(DP{oMzGE8)5vC4*~j41GBN z{mBCn0M$L)XFRRtLjC)(1OF^v7rKzK-2bgU!+geh8KpN9OFJ;Qzp;$oe0^N$ zKf}cn;TQMTPEe70bKmTEKiBfE|HpfK>)C%7lmX!kssf0s{FS>Tn9ZUJkeKwP3;0Zl z9-?gDEtp0EJM+U2F8o+cu7MT>BMphTZdz?8(Lta`_i@$C}TKWKdG!Jbgxlvs}rgb zm@Ein*aM8t^|MCtf}~C`_!~ocdUi?hY^Qx*4+(0r$QDeip>6+}e{O{-XV6VovD=d@ zGv}qibS@A4Sz|fZa*=W=y;DuyIMctfL5M)P})$KBW# zPBXC}{x$EqRL$sk&`t1*7+bMxLQ_79BMf+u{ED;!Qq$sOjzy;Vy429)9N7b6QAfUy zRZ!5neRES~FCx`A9yn}#QN%TpjARO(bO-DmA>43pW={GRzAcS#vBi@3Bx|!Iwx&H- z@1{lh8HO>S3x;Ip-Ox{Kb()WaKS{V#3r5%6o22H(AG;k9+f}U_t=z1g6E;BVdTCmI{e^cgtbJidt|3ih8w8)a&S?84w**4b;`M-`s3U6yUN&=t ze=3<+jdukexXbtI_Vu(tT;!o;&~PX_-Fa=PKAK|7bx6d7AK5 zToW4icLoK}y67lGlyjh60UVl9c5pwhq`$F>-cq`;~mc5)8xRV1ix?c7n7UwW7CvRL+h zQCTL#HTfm=Z1F}YrOCL~InRkLYxa9&Xv!s|kb;qUB2NfAiU zb68wl=;LQ+OI0ViO%34!R^Bw|1IN$uVVz)Iqs?7s@G}oPjkGtd1L$&5V^2Kn1lh$& zMtRRw=f8T=rB<8F1G|fR_GMK28}F-ZH?%hyxo%vf%f99RI!_o}zV^GsEgk_`qTU{gF0Gv|r$6uA7H2GdmdMzdp5^=zcRe1xF*xra+jDlC68(s0sBfkn=ubn_m$y8h z-h8kST;5Cb=FGD<9I@pu>S8LC;TBwbzn0&n$D{Z%(yk3ui~Fw2*q=UN{2# z)J6*Sq#(?$*t3tFu+JXJ){-nfA5J+{5KtW!-3Y6%ZT?F`bM*6!;UQz_etbJeq$m=p^7G2R(i0H5`*P{tPG~OLv zIJs#jTTq*)f7@Y9_hF>^^-0a&?~>=7iTr1 zG3a~AU(w&rodI)<8^x7SrVlxskmNuClsZ#eJiwx)ck;ly2S(deiw zju?S5;~f_L!yWZwl`hY7f5Bn7MZvjA=QMAdM;Vi zIqr9c-EX}}+t`<`q$RX0?XOdw_^+!^r&-d!gbv6;wmD0JR_tRTW5zEX(1kd398zdb z{ZvM-v=d$+WJ&FDr_;QVdr0I)7F%$UxUm7*f5^ZbF;t&c16Tnc`>(i4*y~#ht;S&Y+1i*k>u*Tyvl14dZ1?KoW+s&%KSHstt@N&AZh&Z zOwo!3OeFy?9Tp+@lqfFm;gqtj965zv64A3**Db~iPvRs>l^5kbRqpHlW`Z^=U#VP+ zF@r>)cUJq%l>rF}xB16M0#-n{&2TtUQCTH!nq05ZsB+>J^!6ouh@Hk9YiF)gc+^NW zi~Z6`RMov(Re~h$->q_?#GSk((aA*I$5Lc>m3O$GrR|(QxC*T6|B3Dr`1h+jrg7xp zg*e<>GwhO7NzOtLSioHQg{vsO*#3Qxo%#&u*Bk&cyCe73L*3oZbKUEGZoC*5V1W2! za*bv|q)NSUGU42*PoRi)v~w^6n3a-R}~F0OLBoE8BthHoovK;!k`fW9FG+ z9KDV9Z$AbF<~Ivmo_fQlsHZ!2H#9s{eNQ!*0|jsy1MQ>1nO5A#YpK?91}!?Sn(x^080|q6jjlPi@XRB* zZ#Nla5;!O^jI4svnyi0IMlLBZ3&7+0ow1C~84m!0r_^lSJx{E+#C4%ev~w(@D?!7> zLp$sQdvzZgKt*P5Xy?nB%2YBY4-1Lt3QTFAUky61@W5oo(k~tV*v&#ZNDIG-`8bg) ztkY%|H_Y+6qSUzx@#>I^)*_RR5oK#Dpjt0YD58T~z8~e@K-sdz>TMor=d^As2IU!C zX4YSNTq?E2x-f-#mWL45X3x(Sa2XNtiUo+%nZNE5I*&}e?tIIxW!uEhQhIzsX?{c- zPgYW5(hr&tk@8@o3^9UYNnP;_4%NLPtp>NcdR6tLTXPvH02EPIR-625x0U*H%Vd=) zpeC(fb;9*$w-hk*@}9AmhYWyIT9txRXVC?k&hKWr`+ijIv{=IZQ&3?Apv1v^AayYG%*dej(!jY>D3e>GpSqA37p`G{oqIMLs#^ z`aFumvdjBygsuY7KCwdOf$C0v0>ae>0h@E@6yo&jEU(|)IIj@B9{Il>+9EzU=F`u& zip{S!k)-HAv>z4vrX}NMT;*z|jFhMUe_NWp@{e3c72?^=`?G@7ew}4*un$2|cSo^- zAgPg?Y)c+KxEc##E~O%GMT^|s*|_c9Ax5iCe+D7bFW)phmefyi!Y-9at>KGz&1Grn z^B*MdT?{Nh3-NPa&GpzM-M!i|+dyRby8b*a^oJ(DY;$1f_Vev4FDEfCT08Da zpI(1(pJ8^{3v**rrf5L^5f*iWks5?OpY}Jg(OGLeo|hWs1Pmu}c83=Z4(mpdsPz0LtF zd4VR4HNy2HwF2c=+ykbG<-%y24dfAKmoIT`;jzJ7q0s9mZzfxjn1FzQOX#xhvt_&yU?jT<#uOUdTAu1Hd$jSh^RzZBo+-HMKL-TE}0xxv}y zE6u+3vY;VX<9Ai^EORDSWO?LvIzi6L4xV12VxfoIn`HujqYH*PwKf%Ueixrts+GJI=YAByorOleoho*Fd%Na$aoF!--&kf)lBCy` zLg??(>WI=ohhl3LKr2b^aYUXAchSB>xej;HhuPaV38cUG2QebNIW%>8dC?KVmtyMDHZp%hZIp(2j7 zm_7~FUVCwWH95m0DdU_}((=2%?YAR~Z@PkqepcY0EQY`B$SKBFEv5rl-RMNk4uFv! z5RB3FKA|>`s@F*-)wabjPA>

    ;?WTsRhQg{8&w2*$cDQ55Xrf=Fu`0w{KdBRz(>E zc{sMe2QXQD3{4+OP3;fVeHTKH$(Hi%<+$(d@#sEyKW9u0o=(jis20`OF2IX7{!Y#b z5Y3ioc(+PLWW_Lw5m2CE<}9Wj@28)-+HnH4l}zro0hK z?dF%`u#3n0?7ALTS64hMrd^*2JMHeAV^WWw#mpl@p7v~|RZ0wpTx+%%VK(S@h-q{d zbGCa%Lxha3o_p*Zu2mq_HHR;Xv^au0WY##C#w~b+uM(r#A2nL|Y`k`jwUQFsGFuomnfmemJZ`K&cbv-f9jkp3QyLd}Zg)riaxrb01(aNBJO8^ux4| z8-6VQwU^8+6U#jIbWVJO6*tJ%4q(zGphnK-v3C~VonghW1@wf$d8a~py0A42YWweC zknfU%%d>r_0r!i`QyR=3Q}eQPsCFs>;LaW>{>+kJJJM>&_TQ2_Kk8(Nnc_6?-f7@B zk@4J&110AE?4!mrr}8B@|LRWZD%@q2|KjTPlK2zq@vRQcM|mN&01GWRpS{rHrr zV7N!j_H*ECPb(`<&~Py1h3F?RQ8o_urRIWYkWzdlY^j2cz1jeOODfk+T0Vo(x$@h3 z^>r>wN zko1^-BY_;`HtW^mlK&X+_0_Mmp5;~VPctDHkJ}#p$FTolKi{-(_QCwLUf+JLYhEmY z@%UCHJ9)n_mNiu?OoDg#6P0z%B=4}eJe`i~zZ;)kKGR~Tk{OEs{Br7cJ$JdwZw0+r z#&a7iH*Pxbb6;sW_o2oxlRB1r_rX!6+TruxWnnBOuiN##ZgA^ye?2UI@VGCZ|9VBi zehJ?u6LpCBxJ@$a(p=|%C&mAvoj1^Nr&8cI*SnDTg|@^RW)sQ`nG3zgutYx0#x6@S zKG>GIv=T?xbAb3Ub`dLLknr;mDe?gKcM{}v>33^u%X_9V2bNcsucj zu*C5?0bZB^_i??~P&2>Gpq3WDyxjUvr+c^ET|8qBm8~{0RQ}PY_fp(LKUZA{Jw#k4>nhrvn>s_`Afb9potF=>Xj9*GLjZ*%+`+*J#y&Tm* zTkVP^1;0HRIQ!idBrpTqTbcNM_IHt?7$U|vSdc3hW-SfnPs-bX#4ZdeGZbo)&K)Z^!;;c$Y zCOUT8(faQ11f<-M1?vz`HE7G(t+h|&k%V6b7Ae=W(z*O#hVGYT+2G`c9>C_##}5&I z;U7_Qp}n_FGTS?JbAx!r(J{ec034V}I~j$s$$_#G1CBqQYCpyPW4LI{^xO zA*XRW+^fAzS^u5vNcf1p&WOxATt;cL9MxhDEcikY5YM*Du3t|zI3yzw%+w_nl8QEyp2+t@@{sHBCLr(j`TFVct=Ny zE15NQ(cQi>-#Wg#{}gHOwXG>0or7DwMWTN%s((vg{-ZviViU`cv7@5KMB-~dQY2kK zTK2TFr^k4?i3(Hpmad-onl2fZQGLwkXEV3f{uZC6@^NjJ|LQv)-Y}eWuktnFWgCuV zF$s^4oK9G;dXt8aZD(P45CfgVncmLSo)Dfm>yMzGr|h4n^7;is6+f0uNLb@1XzMa= zuPJWted{Jf&f6Ch)?}AL3i|u(vENxXe&~2(f+vsNG|wksBGvj8p{>_?=Xvl*BHt(0 zADrV?P`n}BUO*-g!A$QBKxpzZF^Vnt{q?@F)Un9D~_coM#8u6r4#=&M>lRFC#{c3yVelc zcNHxa!Q#p8U$ib>Lj;Kn5#T}g^ZYg}qods#uvyp7kW_`fsF2A znHOFFl!u1+Cma`Z;dcX}N+4hP8yj5h@x45a=P}w$J-H^1ClHYz8C4NMq;cP$IhPkR-D1Vki})s0Z;sU8!2~u z4AzuB)PR~$`On%D`1Sy(5%iRwStZ0RTawm#O2-rsLw4rbV2^LG-@hxEB{Qk#-I7); z=edX5pU>6K4a3Rk{{(7DOzcq>!o`R zcrf|217$NT+X1II`-HJ^u@xU^q)hF3_~K!?P5M~b8)0KpeKQ=Uz7d<8?OHGoX=>jqpvym^)VbzICXsMJdj*P;Joh;4eok;a| zf>ohWy4vDYPAE3mJy0p2jsLvhnfnba1uCTn#Vi%qt(r(z!mC9WbUNsJVTZ z@X8BoFx{V6FgXHK*V1M!B0~37Wtbzv!K!XoYl=~Vgs}>+`eK7QOUs0&Q;nZ#q&|aD z4V^D$b4_HJTqn@s&Y08i(!%Je)VI?K)n_9>9vP4HtU;lRy)7&G>aV91SL0X%NMy`2 zwEXtE0q0!|a1J9cx49PlbmZL1+BtH=N~LTBt?h1nn9ijT)!DA-VU^5zMk+05^lL3{ zS-3WEk~$DT&sgDO=YG2@kGpF4j=djGa?EXbbE1*@FWR}|K~_UE$dk>>!WC~b91o}n zf%2@=F{QV|r@gMoMY6t4{^il98P8z%VEEHfGEXoU+V!6!&%K-J?Y?z}&gQ00;IvGmo3GKtBohgT26Q${&p ztDyNrEs9vwmyHvxM9Bv^!OAh=$+=NlLXYL?i>$oaCdBx>=OYb|^a7}4shc{;LPpVB zyE`34Bo>(bWNe`TyyV<9;fI1~*p8%Pu#Uo#(1#}m9kO4M05|P8NaT^Nv9QMHWbT3k zq7PSJZ~0U_N3-pvn&II9%KhRgN(%Bl1;W4F&J;*%$&(@vq&pN{$2InN8a#cA^z4zV zz(UPcw-mR#$0hX$DaOw9?EaA{%{SurC0MptL(uOP(%wz^^$cS>v*MVNqZ2eV=Wd5j z>de=)JmfHp5}e8kmCqrlj`ES^1}( z>)v5ui~1AsU$qKtL#O-#S$|SJ2il7EZz$v>D&#Cut}%N1{nksSL%`;9#k#WAoK|XF zg9uhMplFn5_Z)Aazu5d#c6-`%LNQ6PqH(&C$3 zo9J*_oU<#748YJK|7FhUEz_#CXMcVRh%x+j|3b{}t7S$vgAtz9_C$>sR~YZxSmt01 z*oeVV=T14F0ck5q<~Y!;G+O0aYR`oFv4~_~lGEZPD__kU(PG52&;K-Y*dKI@Xv+D2 zi^T@GpW~k65hN-kMhl7N05lylkSQ>776)OR9iM0J83=W=&=0iI^pW$_?^K8YT~PXl zj5!9!l6VCdLux~X6gG^!d)%r#&1=~_Z&s5vR#=rEgRNt4eqy)lP+=RwBSN3B=(2;9 zV<2(zyf-l16&4^>6hNJrFp+pwjY!L7C%Eh-xJ@QJ0VVe30UN&q148(9L!3FU^92wc z__<`;e_`9)u{2Ulp#!X10n%#+M^xN$NMMNoKvnTT=Sf*7G{B~p#i>4-*D{fu1of^| zfk0TVZNS~A@QE1w4;FEay%erad>p`=Qy0_4DQ*>F*VV}`{R>Is9z#$;)*k2B+HCeZ zm`Msj%tt}rFALg9LX@EZMKSQ)oX{Q^-&O~@%>wF)MLxK#J7LdPvx7SdVyFN@nNK;B zv#qvAU5b`CMB<=+SzNcU0^uhq#pKK?kmJK-kyZ-$6Aq_hclY^iL@#G@V0-*c4pEx) zH3LAz6(%>>C9FSjzeEN4>;NxUWI_Af8B?wz8nV{Ivfxwh2yRe)($%Cwpiu=vC)~jr z$Xd!F*ZF9Dg^Je0E8puS!p0zL&}>K_OTr6QuBqIM5s4_PEV_y; z8tb+D+Rx9Dwe>hv#~sMaBEnJ%BN_^$rV5z~-Rg!QRzr|F>J1vJ*A`Qh z(omE(MN6I*4Pub~?ch=^WGksC*|)g3p*VA@I9VLonN<{@0|}@QNfk%BofJ1Tl%!0Q zTzeZ*`N$4i9Wp{H5fipimlM;Uyals?(ri^v1)ZBa@VH+<+j=0+ZgPr!Vvla({UYO6 zh6&e-%2Esh8uPC5?3P`%PgITp_k2{RcV`Gi1<)q*@EqljDG&Dd1LCmkfjN*i3giVm zH+slaYS@}^ocuyB(MKtZ?@{^H`bb!V5nY8*lHGZDd{U%pJ4EKu14hRiuSFP;Do{eD z@^&|Vak*jwK;oUQCJN4}|#(%(clW`P{rA$pDBZWfOU>mG$gKAL(F9W`C| z@&(9|qB-*-`i540f?s{oG~~u{L`9D6KX0fu5okb(vcnUNCs`Zo64-`8?yKNp=p$>R z$PCd&8gXdN6XAr3u!;ef8`aTrqT1ARcUsG?wgu>p5A;cDQ(t4#)5fNXE^sKmGGwSJ zG>c`_uend6c_gwaTI-QU1<2qS{5=BAwLyFSAl+R8?U+qNh-UdU(@}w3hD~~S77ZJa zItE0*fV7W+9?8Z|Xpnup(l?{FA4YB5*=-BG5Xew0DxHE>>85`3nj)V!#bPD@- zBA&7Y_p$67JXZ35yeGzvb<_|vayMNb;D~m!@?IFsW`e+R617d$&T7N@Rf9X(vDFD$Hm12(pz2a#R2!!SV`obd+ zA0UWg-r(nd`-hQ;NAKVjfTAzSeWe&!9sm|yAsy2WFVuoB8V@e{4=x?HN7L|GDpc$c znumhf9fM2pow4nMlJ7cY{&pVDJp24~@GfP5zX;@!*Tl-(0ZDs)8r8IF1vSBdZ)UOF zRc&9zolE>SZvR(6gK43mL#(-YcoIvfN=^pZL#j(35^bUIXu=aqkUQySX>*9fZwyyd zO0wlcep{vSUt{+{j!2)yU8G~sOcF6DED#APEzG738c-{GClTMAcrTVS5q>=)&IA4W)rv+of)3P8WAhn6f45<$3tai+(k;GkpcjR|#5F)$TzA!NusHPKkl%tnMljG+RTaldIsl2#q|9MdO*WZSM39*KNq%Hx2nq(Z ztCmMhWixQ9dNN2!Ocj<@jSXF#%BgH*Goe2v}U^&C7^K8 zY!P3cH%$C!4VKqtnr1zJHFF)rL2*B{@3AeYY#{qlfa+t0CQQ1LK98$AQlttIm<0*9 zP-FZjGU&-caFMs0&zk@s{HPG-USTsh+P`l>FP8lU3g$*a6yq|6gwDwe46i{hoM8a> zx7JpUjF)39UjBOoTK?MDSz?@62P6Qb=hrU(R8f1%1q;k#xZbeTqnaN?aeK}h#)5kz z4$UEKu}+ZSS1{4Olvh8w0rYX>i^;AZ>CsyR1`d`NSHgMyRpMvkbRAelUT9%Usghs_ z_LktdXfcQMFN8k^DoGCIOLC5>)>s#2<5c8c0$WRY^2P$uN!auZl;O!1C#QVWsy^H& z*RG0Xes7CIC4j^Acf<$sJeY9Nyc{jEpea0`=a*7odM8ih3avCx`h82mw*ZsvJ6NdD zSi}%WtsRKqjvm$zr;7nMP_R!EJ~&qjJGf)Qss5tiTVr15>W1zN9@m!c<_8J9?p5fGcKAf+n*aXm<@bDJ z02o&^5Bp>N9ypnpWUWb<^@)LY>TNIQ#-3SS)ZJmVtXf>ZO?lTl?WD~;fE$apkZ7oT zLhlQ-!y~Uf7FG#gY7yp>d(3k)MjLh{!++fb3y0-lQZ77kMLciz@B@zzF%hcUayr3<x--<#plL~e#mZj|ckTw|Kw@He zogRrNbc=J!bH`@!#0kd-jXFrfGu#bnm=Gu@5xvc2UuLqfjQn zIu8im_hi$w-m-G@kI!LIsn!?+)4_RBJKh=69=*#q?=U!2bXfYWtjPbI z@9@km(-4hMJ1o3P2skLidCy!0EY?}CPh7le-)8K!5P(pA!@0C{U+#I_;x!w?`%|_a zd@vLAL#4K4!!J@6*C(ZYU8-x2&VS-+2s9V&>ny`^OikGBoe% zn)2!`E&5`F2wKws(JXl+FTcm-+>h5z)i|+AW-g-lCy7i&X78X0lv6O8^^1R2<+3Yq z8)@6)|7k4UYBU4wF6K^VKJ>#G=%Ishn`%~$C^ALQNtLs@i8mi-h#NiAs%GP1lVH}1 z52&ogYpfg#7NwF(bBx4&#m$)135L__dLq)6hFMZ7Ycpi^rj`VW_?(paNw0;29Hn@#^a7~6 ztpR62JWD)-q840B(m8X{_f33^9E4qQMRiutH;g|GZQG9mX^~h?<}l^SXY_e0{yFLM z-}E|iD+Z3Kf*F9&Awsh0Zj}mFC|BVmPgW>HMUXbsj4ka=;7FdGCXX9116m8W-{F@X~6wVjda4z%|GE9hK3o1#cASXCO(q*6hT51uoXq;T& z2@teYN%UgcPE$H|LC%HCZcZ23t&o6u3s(^+=SI-TPLXlkdnPr-MNM9`(}U(4S51|y zA}ZBlzuIBXV;AxE$(nw-A#QkoL}HHe(Ynu<7d;18(6(z8!gcFa+VzzCDi0NkEc1qN z)mn-=kvlAhhr(#JPp28)340e&R*v%I@@isoM|GNM{FF(>VpJJl;mW7*@gm~f@+9-T zS@G<2zM_ESSBC`be@Ly@RSD{owcjLSK71kpAJ^SvruG6_)3b6s&2R=U6kRl~P&E%k zlkY3jpT;u7HZF^)3GM5mLjmkIk)!!-)FjW}4k=-qBan~oHCiyfEc#ztyh_e=C=toG zT1Q$b;{lm|<#I36?usxd4oKc)Jh`Ba16C0Yn=$VN-EWp?r`yfaF}A5reBZp%mhi7C zX;$9#yn-f+B^(ntUeTwW41u|_Vmy$cq;ahP@+FB7WEy9O=@ZgQf;wO{bl1An%&RjY zY_Kg>vbpjM<^fgxQ)6pD9nBV+#3W%YGK%);#n^YdeKIIP37y3sdwm#`)8lS>&s!qL ztMqhC6ImVii~&Rl`=F{29^zHmY*q`&>D{##Td?u+6PX;Q(kr^aK%U;cPwo^i+KR%oP+EYu)*CZ?g%aGlagyI1>BWC?5G|@mA7^~rzlzo7YW{2wayN zk9Tg|x)Y^CbY^Ivt9Ycz8hB+}#IA4VnoOWMJ*!bgB~uS3N2(;sW%tsz-f8f|mQMh# zLjh<@dv$_N+%V+fF-PQ+D1<$aB%39tvZ>*}55Lnlpz?fMChX~-=)P1d!xPy|!}HQa zUlSR=nxQJPI0Aq{RrS4l@fk1K_b!wBI4G5|oX^!b*e_0ZIt11~u@pD?tV~EW&I660 zcI$2K%{aZb7Yd8D2MRM)i;D#y#sS|qcLJZ zhUmV>35tdFoUGaPs*ap`g@b3;@MN_aPm!P$daYJVzAYO|@1WB613U6B&iiJc1p#@} z=?blVAK}YCH;wK}6!Km0H!I#^BEz=av#7(&7teN*1Npes&WnOHU%5WrO)i%;uQ|PYx7&jm`1e^WfaW0d((`I{ zq}-}=dVlEst6#h$C2YcJ{dge$c@ZkvGQfkaoErB0-@jWiVIFK1=qtmFcS-SreC&pw zN5u8$5Xo$O>~&(d#(lBK^qEbL<#OBY0bPgm3)i>0!pA3!T>~?o;~t(zKW4rEbRo@p zK%1kHlptv)lcp3f!YTT(PfBJTb?BOl8R!e2j<_3KQ~2g%D{)j36Q9=YXxKtqlR0uL zTFm;+-hr`yxz+@-=w|6kPk&uD5qh|1$}8Bf2A)m6`;SHK#l;x`fp4*yyF8xTSVrcz zaC|SQXo=u({2!=qfGGv#)&G%V&L znXH@zR2?Fyt_<_%UAk~axFD4KDNRtL7g!;t{aHaX(pOf*UD2qE zQBN*i<#WSSUW($I!{^x1puq~Y6d>3ki!2+SU}=$H-K!TcHc|Xe@8&1HTV;Lzn!VS9 zd*gs$+g^}#Jn|xx=TbOrh6MeGy<0-#a)YMrK!edAx$)_iwumAKh27JC?2w=mXM)kGehtqkaDx=k?*}@+y*-aH8 zTBP!N3a%*Ha2p5Fs;{2xPtM+a=FvA@H9H07)k}ndt$ZL>um>;11e2ya@2f%zQh6qP zH0%_0r^%hNPVyfrvp2;ul&L_ar!!Mz1=ZZgPlM%06gAxq5{0M9j%A%PI`XPgvqB1x zsWOu(n@&%XKmjc???c4$)61z)!Zs@e13!oFNkG);R;pM(}SYsk~! zsb?G$EbHq3FDC~ObYV`Bki$^-$R6o|A7@(Rs<#Ach%q)0UxGJNV_}JAy})}1hbIKN7f-Kdz z{t(T;XjwnmaH~JZ^jm|wV)jGUy8EoyXYedS152HA50slX%|{N!VF?_8TOK6XX#uq) zknX*p8}63zVi4CNELzRz88&U%0;okOwD3ol9PmA{D7n#B5U-ZmP|3=1!^(q1(;b1U zLkpF0{2vufyC=y`#qw|kjgQUkGmcZz7~a)26GW=@zvB$bo~Y`ziqQo@!OxjL>B|el z``b=wnkCSOyY}BXsBk|5akZ2~EAXM67VdWA%P~6Ra+@YVIQSM%^+QLosx@n~_k6@& zlTUpL0vZ`d^L)_0285}mIZaao2yhIJ*&8nQq6Cj-gb(*iFE1@-RJOYMkpD*KW^5RZ zI#yc^RsaCJiWUhin%NnAHkp_-z+N@&+(&7iUSZ^_ur#e6T}bh3>GzZ-;e^YaN-#+{ z#8!*e`^`!V7${~l6u=VIV}LTToUV?@$JZVjIZh#|vm z<%Y;rd^-~NN5R&HjT(~->-AP4OLZ?$5W5w6^LmR!n8WQQskNFyH!UE;Crf_09OEJ~ z(bfTd-e55`L=NjK^IqlrWB-=$UYL29!M14PK_gaM-eSl=Q)>nLZ&PVyJ}V6aDI;UH zhm&JWOQ4?_yRjw2Qv;*D1`Z{wSwxI!uY}|u)v4bNoZ1r!zG&LFj`qTTVkFzyRxecX zDh>fbP3-(r;wscjB3JknO_M#3f$3kdt@d2wj{Jk=MK|R*yH2u*$Dqzei>cwOV(Jic z4B0fR_`nAt_}O+7M^;-YPQ4=h)1!U6^1fzr=48H{h5=d9P$KWOmX1iMt!dQ|2TJ)+w>)J*IxkUSS} z$zNiy#Q-mhF)R)BP&(_%sa39`@Gc;yZzp5P3i?wScOk^QlAHs_hW6b0^(gO zj~|*Qs}-g9T-;a^>kIa6YxE#D5{ZI8u!LT&sOf&rmw7EOVJ=_Gsibn^Ia(Y!_qrVB z_IJPBLAPuI_vBE*Y8Yy-ofP>05$fmDxWYt)^^YcMLA@5xE;qUwF3_VGrn3e zlB?ns@nz77bltc@&jHKzm=trfYbO>7X*gz&UZ8SOn$fy#1`C8~5M&5{8t`6Xv%J)< zYgL^{_7L3O?}oXnCY)_ym$KRzk2rgMfI*d|WU3a#$-4vvd!5hS;t6ZB0Gq=++<%s} zdvft3T#VqCkJK)>QyoAW?gyJ>_S{{C?ka~4vKefec$0WL;c_3v?SbVrA_*w9jtlr~ z>5~ms$|75D>=8^^+|db&B=V?g$%A69*>EDb2eGV&`Mu*)+5`d@r@Z%&!UGoPG%nPOFX}R27lOH zzGX@&`55>I#~!pUN?7aa@UA?mMDVk+)l2wVmy{6!AZ1uQkPf-J z`$t>V4p0gnM^Zgwig#)&&sIRhO9yf788V~bOBf(_qrhNiTVkGmt$S<6g-m^)q0TT` z_2^9`xLDLtWWpfBlP+Pq5_|u5f+8kmV%aG~B+>Mg-W=dJ=E`{5(L}6Bkb9J22l_+~ zPmnDlOT_j2nUzRn!&S7%_kV1Dp=j8cq@10CKb@PTy}VPK-(4wVouFwCR1MFx<9oh7 zmQjudUme(c3r@6E)MyK~JRVN4+|#yDt%CZ_Z-_`N4e{D7 zyj$T3cOh$0S`5m4%v~gYi10kzS4CI8d&wCu!%dQK=bD>qf+m*uixW+pTHy*tDLG`Mqw?*9*E_5pP-1s$(9QcpdXJ2z=*ygT@}n!2(&~ z<(bN2DBoLeay<|GlFT^~YP+7jy>ZJ(Y%sDZWGL-<+68q_AE1=hpP`(JhaF&x$#v7B z{QZgK;YpG(xx1h{nfG6MDCx8dK$J0m8!y>aMu~ks*3<;;&oWEJOHT04mvxn9|G?mdKLq zx$U>LMaO~AbDhOsn(5OHWKM46zgd{41-N6_<=&mh&7ZSN+(j~O;qdca z8PqMxt#>7|>2{bqF(}=sMRB_>(m$gj6uRAwjun!Oj=_$*_4*8|@1*2B)Qmp0u=;_p z$0rVwDowa63dag$+>FLJKIQOxh&hbRHUx>jD(sD!(*Abn^{R^XHstV!(b6NWI8dCG zu<=#dM3yMEfyf2U*8H9v@%d2wsRlEMOT$TU%BynY#=BtN$WE^J1*$IV@871`KPc(# zTlP_>}3(wkPl%rkYynotn;)?<(!8nnCo$1yr^HD`96V76_ zF?#e|T4boP)3Ec6bMA3ffYB<8^}1#X9^GPHt$w>E*q7~_Wt~l5pP7IkW1ht7yD5v{K=}(<#(JN>T&T6-=*FB0m?n`uU^5M3!6Lh0Cc!4(ak~me5qcF z?b6*rN?PEyqMEES(8ODiGPUn!~HIKLl-I67EG9u z8)|_$81(>jkQdwnJWQ?!?g#73j)m9@`aMSjjksb_i^i#fJlrdWLm&!7EPVr1n=wEK zb@m)!+(C%Vx&*?7;{a#_uFz=EWP+Kc_LNAqK?26`Z%9gor-h%d4cQF@aC>NJ6!C$- zLe+4!;@P>au!&*sXz)#S;(6a#tuoBnu&7OWX@{UUump!E7fKIe-MiSpt0r!YhLEk$_7s< zD#*f4jQNvwQV*SH5>Mmne%9HVjr`-(E|AWwh|_lVQEc^o7mmlq5}Pm+9)BAp znOA1#huwG{lgz_!0jgh(?H)utx{j3gF;Qt7ymv9en)LgiN$i##)Y}nX-5y&tWUsHs zfKht?q&`~Yf}+Zu5=$Faxtp+sKzS1>pt;)nipP3@Xy?FGDdvrkygBvZm)~3*;(jA} zqz-*c-Yl)#7D-RQPR7NK=Y_e}o{%&CepWv$jasXv3wy_ZV-I2{IgWW@6w=t(e22wu^ z&nb#I5#w9{cLsK)ZC8vl7D>*(3{{qL@UI`0%Ty;#ksr z#sn9xi;B_dC0zAXEfQi7O;p2iECG21;|xS-nP2I$ZQ=E<7Dq>x-@px`K!La#TLiW ziZ+XCP7)bHWq0-!)!|lWv8W($KF2%JF2u*o1VHF$d$L44AuZsMd`%BMRyutnRilQE zr%hL1*Jfj(@Y#3viD9&5eYb(dCMoso-#b%ccM zE$?sDRv8j<)GP>lG2_FoqG|m_YfMCOMw6B8{VVUpX#$&jm0$)H>9kl0bOq%qI@Yc^;D7%EcmvIr5XE|E#F3?ej2p7oR z2efw?-LRL9df)DM=L-g<^&B!%x}j*Nt$&KMer0 zVSOq|4ooJ;K%N{F44Xv|xS}Y`g}|OZ$e%?qui%saAI+b6Sj=|ZNU8N zu+h@GXrhiD(eF#tmc|E}@j27KpKqmKxx(bHdZitC^Zd{ZGr(3Ksx->$Dq<>bg(*p8 z8<(WT?*d{40jsJn)C6E!ryGJ{6ADv?0@>ubi0$YhGGDUEwp!NkbacHAS7=41T^AK; zPto?@MQy9S#@cGN0q4_>z6l6k+`srUf^yiND750v6bMk~`$U2^z1f&?EIe6CJNnT^ zzQbf^PG+Z)pbvqAGgfx$@3J$0K6yjOM4FUa{S1I!FDn!sE%6rk%T!7nx{c%P^FTYD z>K4UV==OWwXHFSz4+;q?e3I9+eSMoX=`BOGW4yq|cez$J+ z$xZ*ljU1R@U*g3H@m;(NW#U2K+l#HY+;Ucu&jSh`KfWOSRUetu1`^~p%+ldWZ7(;* z7m)5{Uu|_YTWij0^j$hMqf&QD1qsdi;e7U^y6JLBbBnciD4w$fy=I*S}XJ1VFv$u&)WfY4Y z;S9F9#8NG=TXi8cEy`pDJBR&}H6f>D%A*Iu(?Akfs^S4I?KIQnEJ3b!SR|O)lJZib zA4CbK7vF(N0}@1uC6gp3X`Zy?U;~Q^9M3|odT2`bdm2P(!1o|m-FqGq$|_f;4WOiQ z<+Erf+6cT&{7y}0*RB!0`0^YWas^*T&m-hYe<{b(hSF4TV7Bs7WR37E`hK@f4u7n> zaU?8iCAPOFnIOT!*1@0$%95mEjOn_*D}tx06KFWuB4R|VKZ}rPR^dFt6%%K~nP#fJ za3zyD3bpFd%V_JjV+au7CJMKkWX(1Uxm#G-SfRl0K~ZNYL8j^6;+-l=vLO$Kf$kw+ z@{GM6%?`n#>45dyldeWPwr8OAvn#PguuG-j2ZkM6dnb!BdK-ZUHp>ZY2yI3BT?xP1 zQ&o7#5FMW71>s~0ks>TguvEGPlF5n{t?}?G5%M3gfLY?41`(GKWSU@U)c?q)BvCGy zZUz9^%=fyxCw%@;C{?m~*kbG&G1UM70&eMUct^XR4W%!^M#btcjDqS+BNr{&3A~^5 zsm|Wtq&)X@MWgCRxV8zoFb4F3Dc5e5i=v16pILM22&c{N9rl{QU1sU#SjmBmyQ$UZ zy@Vlysz6pIaR*(Rg6;wv6>p}Cv)6qh_R*~TJQi^k@uuJM z>RrQ4&)34O!7jQL+XNn=Es?k2QV;iNWlzCGPhS~JSMbQ+;I!-$Q;Ta0g{LOmqG>Q`QTN%k#JOeapq0d7LWU0HE%m` zhZ2F1?2x_xF?82|O*C*Ez{i?x!06GV8wS$3jgXR78YvN^Q%W2gF=>z%b%eAqIu%9; zDC$H|MAQ)?D*Awlit_Le+%I?cy1VavzVFW+fP%fd2yTvGZY*=Me-g^tfD)u5;SLTyc-e9t|{WpfnRDOUd z0z*XfX_dZ=$t!lwGsG~lv22fE|6 zmAOK)d16f>7ODy~jxA?D>t%rtibHJav8vDLV5e5};(Z&&v+$u5ry=--M75R(CQxLB zKqSetA;Je&CN=Vjg5ZzStBQ3z2-#1|mfGy;ol2x^>aM#St7f<8euj!>=hH^826~sg zb-pNNM|S!GwyoXtH&RINcvIl^;34r!nrcP9!eV09n|L+_m8Vgw9U6|4!Yhw+&xF4R z5`_((eGZ)NrEQsj{+1T~)DHB3!M->@roc=l|(EzBCv45z6Yj z(EI{zCLf+*hXoHgzke0awtO#KgJVW9oJ|_qWe%tOCEj}Jt8_F%*l$uT@5#hDPM*G= zBM{cCzfKU&2OlK~cbTTlgtV|JCi8Ix7J)s?6Vh>M0PC6Gc{m!Qx&{Y!%QMph+oY6< zwtiM0B8zJAh_yFZfX&1lfs>7qMfGz3x^QNrU<*3evk)STRw1#m3{D$ zpRuXjK`^tC4zAB+#uMbnl%?|aqQFx+zE_r8)NBrcBDLhQ&#{MxGa84E!7|%F?-mN< z*Hd11ikDk$f;ClnyQ}&aF5m6BZSN}hgvk6WgZ#=tEc22(WqW4r(}R4bKoYr7s`-Nr z4y)37r1>Q#Y72g61~LZi>d|C>7x|T?s3{EQBuJbHpRf=H6t?|1aj;c{0+QW6_gZtI za2>INTr)?OQKw*l?*k~O-ERt-bAoeZ!FSs)U(c%N1BDtL4W%P+wP$n@-9bG$qJCGe z+iU+g;KUWPNlvB`hskj6{6Z*p?BzD_`&R(E} zlZ6jEd5|4PDy?U8`ppj=oGK&s)a-;?f(5(#gAxl*J}kDM+I4!6!^vxgZzF&I{pzfl zhzQf>)R`EayJX=IzYvhbc4NR9TRBw#+I=>h!3xJfqE5rhp~j^bW{WsouoGJIgB#jM z5q5bZ9c-xpJ&CVscl0`x=sYJmLXBl>t)Cq1SaXO6S(WSJO1l=T&!G4E<91&Np6r*bpOhb?DT{o((d&h&T6*J9f{0$42vp;?0DaN0~<=xcAk{ zdZ}W5;Ke?bF<^5$9QrgA8GX>6`7+wk?bYixwHCG3826 zKNluDMazhW&?*}ea61PfjTak01rnm~T%~Sb9iqEl2>bFzVS>c z8{@osNqhI+NRb4h;iH`Ik7IzCZy-Anb9FDo@8j)3ZXboPs!HUwux4{KOn8g%9p{oS z9p<)zjeE^_D3iqx8O;j^x(s&Zi)^XKZxw#N-u*7;MaTz#m|mwqcsDGSR<>Cq^1Ie6 zptuIyYp7$pMHM?RkhcHRw@6f7BIA~TLhdXznQs36z7p){Q34w=sp}{-)dDxiF!`-I z^YWX3pM1KJVvigg5()Go4^4c?!?ghGY?VipQJp|yoboR;=pm+vc-9Qz*dC@j1ec-` zJd};bQjIWEP@EN4a8lP$SD0s4MpAED*#cO?N_*z~Ch9etvy^cO@094+7`R5KK5z)( zb7#fi3bT<=Xb=>8q0V+`QZ4Ag04-C!kHwSDi?O|@7*w1B{TqIbqp4l*kxSZtP3IRt zA@31_gY?mqtJz2B?=8+om(v&~XHuLIDt{RzqB4-vEL&SvvH22Eq=TV`o>JSLT>WSi z`%`mJWb5|lz(}@0E3N-P0ZYqJyV*N+*Iw98)9Tv5k(~mvyfKvDAyRB?Oz>WM z{}_CyUh!13y7yMb?>kUJr~Tt16UG$Tq2jK&6@UBdN!2yWNc5Cy%eAGm7Elf2U#6ML z6NCx)zgw$B5kUD}q>7gA%O{CmT?5Zba`%yee{UPqM|Q z$G0_wA79>{BPf~p?SMPTszlo2*_ZE#hjRYCe5LWfc!C!S`>3zhr5F6vy)~16d=m;^ z67+|A{nkoxJ#H9nAaS3f^0htjb&25K43x*HW;rw@zV+aD6?7XPFnRT!KVr^z0EiY@ z&T_ytvkMt~J!lK4&utSAp5Dog@?`V@mz>QMt8RPgA3=0Elh5!AdFXSA$EOW%PTHQ$ ze^K*WC~gOE`bBu@pX9cX+4C`V!#hI#7Z`?u&QhR-ijI|vb5mQNV%~N6n!Tj6V^Ked zj){gN2Frtkn_eM%;9>}>vg`hnCmX*lP@LE;C`ar~v3xGs-LlKqPTJ@?cxSe}94#7t zT5&sb8aOPutq=IUdm>lIE1x^FV0y*&wh46yq>6vwEPaImReq_~3n2ZPsqh28Czc;2 z2F%qJT3VZzIb#>MYJ!RH;rs>A%$;%%gHp&z&0V^^z>L5(4JCi_Z;Qctl6hNO23hfA zhjalD%BNeidf&RW>9;J$>59gl`!_fd+lAT#K}S9FMGG6H%AJ-E)4 zPlrqH-voSPQ@nNwI5g`(b$+jT4`7+hS?)F60;+NgsynBlGn)UtQXBuoT3%cJEjy-r zn;7D9Bi#wYF?=6!y2(&+U)@wmmj9HCIu}n9r|!Kio*`Yrvi7rzwZ?)4zbw@-C2uO> zJ?HKgu(cYnm%QVV2DDg~_FZxZRk;TwYc2Y;Layipp!vA_pyOFql9K-=!Cg>~`R7O7 z7Wcvlac^XmFt)R)IN}@e!;6ElY~p$Y0Fahtp%FFtL|r0#y1O4$R<6p(o6HX7RJ;

    %^W9en8;fJ@CYWDMd zZa0lRA1LXVtE}!6rL=p08W1QveocRs?L%wse#;z_Qfu%k9$Sd zof9ZSURJmkUi;}#(k(z^>?9>!|F5?kN1s{Yt<7|wmBXN$*MF==3}y*<1X4%D zl2&uBBYzBqvfbmf$$Wx%NT(#+|IpqbapPbG6iq25Z$J8WVnzO+cz^b&+jSJ77$osG zL)uQl@4sgOAso823?*)JlYKCsqovT1Y`Lo=L6*On`Nq~Hrp2X}$j?6gLfM;b;<(9^ zk854T{6`GeojM|a1AJl!)7*Rg5;{|o@AyW1%l{u5l%=R;slJ9q1$d*fHOl;PncVq& zuhBWjQxMLg7*yaPno8i?KvQlc%?kAE zhkIC=36zHHO1q21JW(>(a1sc?%s8U-b?@{2X9snWi5lX$<~K%6SKEJTV)d(dVm%Of zeupSHM}oR_`g5F9pkVIfk6;E{r#v60%o&IOf@shP9O39D+)GD0?M4Fc?Sq%EEukeR z8YR;si?_8}Jx+!B#??eKn?#3RoQg{4tz9pp=*+)|8ix2I`=#C)ym(rmWV?Vt^6uR$7a0J$K^G};AdOo4r#PdeF zo5^EGuGohI8!LCFt*kwruhuN_-q2h6_v0tJ;x1p4hR^$lJT3UzSA6G%=HDx?0N@@& zKy}hQ+&3gcutA)^)%p(nk*2Hh5dQY!iEwCwPbN=?6C= z=7J5ay*FYXF^-O9Tu|SoFPvP4AufvZQQWEKdrWIntDG-b z_!`cdHN47y_gZ{(mz{#?Bnu?|?3s?8v1Pd5d5)DJV9g;_#q8fN!q(xS8|1j{e1bzjkP_P;Y3*LFA4FPuKW!UDIz`z4iWQ#@Y~dSk%b z5y*>2L+neg{_GThfJ8ORbos1G{cjxzYj)+-rpPTazVbm!ma2S)LE2Z4@@5qJpP&XVVY z{S%r0{b>WTWqpoVXiRFc{Nb#AYI56FfsLcE?&NFxAFn}Hq;q3V2p@8m ztG~^U|9sDIUF^BX`AB}hCU_MNiYUuTCPitlHZt!8bXdI zE=wSD9a$f&7OgJg^=QpY2f9Y&U zgSq5PK1-xKi@V>a*oWG++(Id zFqyDXHl7q9`Ewev>3{yD(oB}KuR{_awyI6}u7SA4rTCpWWl&!#ynz|m0D)ivW);8@ zyw0bS!2@Q7oJ3GhReK?m(PzfC<4|4@#uS4b;AJu zK(>|+Y0Q`7#;pt~AQzuFvmZFY^#yOt=CAuJN{d>@xn!wK-8LGJ<&1p9^VnHHt;;9h zTxU3zgRhHl>x&+Mjl)|Gkj92dBMACw5{fq1E|v0#lQlprw#^eQMqrK_sg@t|mzQ{@ z0CmQ0-E;Zb%A+KIx+WntL!b}v6^!e6^i^;d!1tOf< zZwaJJV(hjh@qIGNX6G!mWbFC4)%-1VshyeYW(NUY=?G2TbxDOfJO63kD|H-dgbTUx z1}EPl^<-F0y-FBWfJ2-?>akM_i21On|B!?8pP2>_i#hZIZ%VkxD)0*(UW&zy5nFgqW&8o-;W_3DwDg7gNE zjjI0N%!x%mF?B5-Q;I--21iO)0R5{9rH;4sD9h^7jMdo;6p`cmmNxtIjd*$vCVfu| zu#Pn7W1&7tCiO{Y(mYk;o+djiR;P471LvPx}D)IU?;Vvgw48yj+xsOwEY!jC2e^cvlFyB%kud}Ey*WS?tN{drd=Fd+mzw5#2_ zr)k*dXQ%d+o|8nI%Vpm16s=D3%527*`1!VqPbStJ-8Z`~^<2NGj^lvFlP48q>WukJ zvqx~W>A0N|i&`y4J6_4)Da*ci$u(9Z;*6zgyli8bPNmD|W384Uh}TLtYy_Hg`k{Y^h2$y!H+fL6LcNe+;mJqm_=3qyEY+%!M`=(*MlQu1aKVo zp_`A5zD}*TWMAisOb{#SSq`3)%!mc7#OmmpD>C*?R$_0s+g-H8*t2nx*d*GAa=Y{Z z@fjQn+)`sJxsT&SUf`1_4fU#cX~s`eEJor(J?=QS z`#v1$|M;99`17~Ls1AJ<<9~#pr^?dbOi+*#_J==rSIaN6nJtVBe|^VnfVpq0;8!ZT zI7bkyHp6F3)>Ph+gu~sjcMrD-vyB$Ymy&<P%l&&2m{EByjq*j5Eqga)4sYfokrClo&LU+)XO@<6?f#f?`d%YD0szhzUo z8X2SWL8)QD@kq)F&;Z5@D_nDoy&^#5W3y>n2o-)CIax~v^MrVVsrZ|SrBK?K#-9&; ziJueicMRMmqBJJJao1EQ(7dFfB?10?B|B_g7O@RHk&WL#Nax4JlRt(JACRlJ6WR8- z0pg_i02B=D9V^q0Ejtt=byiNR{n_n%DvtluJ>HoF7)8oZc@kY;h%A$^jA(AT-?q%2YTf_J zFLi}xA#wfNPg4J51FJJdW9OW5#4fH#{yQG~-$c)fH+TKR`vs;KfAmzkoRxP6G}io8 zD&mXv=-W>-aU?33A#x30C%EVQyjqYOt5VK$>nzlE%VT1#|tt(inAsu{oLRsK{bk zN_d}YVMpev95R>1W^gFmu8r%-<=8KTIo^u~@sy!SQae~>XLti<*2+>7k;%?xb)9H4 zI|*r>wer5|?{5M@6j1e9W7%iJ>BE}oCn3rkew`Uvc4M)2R>0h9}#Uu)Rt1f9XwhZlS^ z1Iv<_2wNf9e-RMVdP-reZ}*k*Wq-0D_oOVC4Nh43dgEaFJobms5%uK2V(UFO@rA*)z)<)NNtVyp$J+TjF${AjrjG!P0(`0F%@6 z8cjCKZJyuTxLxLK=g&AR_U|OO1_{M&XlYegmRgXRKy!BMIlPplKd9u?H$ACYwX6sJ z&h)9nSUmb}eN3%*NqbmNQ^~8Pa?6}gAM|bc6oad^vxod1TBt}<)xeT~Fn%k}XBWU; z(Wkow-=9%`mH;sck*tBeAi5&s+SCd{Te>`*{LlPe0UR0INLNonWSLm-U1)Fbq?JlY zmVaJ?KcmmaVorc`Uv$&&ibL#)X8#W^UN3(rN(YWSlwI)yzY!0D*_A^yfEvPu(49M2L zKk~Kg+-T$1Yv--4-6#L@q}|BGtXRUTF)s@IFF#>#tQU|p1wb@B6Rx2)AM-m?g|H)j z4?H+=o_w8Ed*8PFWlve1)@0zq;i-~>yj!m8UyeD))Dp39B1Yv$l*ki)k{Uc9c#_Xb ziXwmRndiZ9nr3VjKZwy z>dJi{JGuTamK3+;e0$`<9QTP#Zv%OclkAVb)CCUN-}`u#eHt^1u6|@E*A?(U88Gp= zzsEsm`CJk5oSW9Yo=RiQbEelY_i*=mv$*p+zNBDRA}fW-=yi`pE%enVI%8+Tc9%JW zg4lKxhhARVO+NKq3N8m9V0_{!i3mEsh0q)4mily2BG6wGlqn1>ew%Ul@Xg-j+(5l& zcqaIG@!|51A>zQN>ob3HziuSTXlRKzpI$W=JyOyt_>x-phn4I-5S=9tq(i~0he)4^ zWI@fT?JBD3VY=4%q%X58#e@;gdy~qXrb`5g} zAARx4srUe1deNob%W}no1@*i)Fc5|4vwvP)-1s?h(OAK9{mP5+*WcmQ$pF{7T&ET( zE*lw&#IxhfM)()bE=<;s!N-?gAqx+h=N=s?-g|uL5_0pf4R`sr>w4~|q9eZdx<`LN zy19F!Qqfa_@Wa{v4igy?f)HJ$&fw783cm}%JVSoSE)tUAr_jejkm%4j8Z;6MpL%|2 z>K)=C43Wsf8Op=IJiqi8hA0ETd}t8P6KOO$S!IWP_*9)xTm9M>qYh(g9amu2IZ&D=y=7xr+`y~fdIsE))5Kf0wVv{>gtBt%bzuoOSTqS177e+`G(LMC7RfY* z`@@o$aml!gAvE()7VJMB|GSxBXIg??vrZTddOUH8V8*+=gL*lF-LSAozk~>Md`NK| zs?o`Z4zY}eaDIbuEkS~cor3lt&RDSXvEe$450B1wcn%Gjh#!O_2GHSy8A?HMu_pDg zkGLfSC0)NHNi-}XUr$D~Vc}_XXy_iL4Ud}jLk;dDH%cRB{g9u`oo;_cK&2y$EVS8% zQPa_?(Re5cfMC#3^Z3(?I_iLAR3|<00v6ujckIYTm2wv|f=j1a>?Axi4U2rJ6Cu)y zNTfqGj*?N*SC2=P#aByE4;&T4>Fm?kk_{=fdAh3WjH=F6SN4674gmJRG2${15rjj$ z4?g{&A_A(2ynwwb-w@#@i=OmDUBn|#Yoiqu)!tX2;`R{otq}_|<=(&K6KM#>k8q>v z)8hhwc|X`SJdUjuJ&}k?V8I??D?T)#8Nsl00P4}6t~EV6nuONFf^Xnp;ebk)(^WqP z%1dJq#~e`92_ZJc3I#=>dpJZK^H{h+;j2$`KdqkKL#A#+Nm!(?{%I-L>3tp)4FI>U zgjHgZYZZ!jxnShd6>{IX9UE!&;XvB3thwvjT#JB}o z#$;d3QSN+4ep#)&H18BRbZK>%yep(<^Nix-2iqIWSkq10yO_%6cRhiANpR)n_sUCY z(GX88tU3Df*PrS8?~c!*o|hl23y=Jxe|gm{y~__ta)fEl_=5H=^uI&8CejD$p#fhJ z>(8;mn9F-7g?*ygHQpfq&^ZXobK0!73K>F?jbdJvJibF$$d#zt3Zi?J!Cqa z9XF$7l_EI-K!gHNe`F=Hn?&PyJQ^2~p=h}B8KoZzpDL3OJ0V#_j}04YNm2 zz{Y8j#>>b_nkWN}Qtwx7aCACx9u;&VW{s!`3Pc*t!H%lRq>cnDIM`7cOyl*&nn`H* z3uqaSJ|YbZyGR!^nlFS}p;b#I1tuGRK0z933(F2bBmLqXoq*NM$FmhfFJKd9haf~W*ozK*?w%WYA;IolLO2sbB!LYF;}dDnMQR)@zQ9uV z1kv%FLJM?$2;$?|seiKbY%w&bxWF!&ylev{=n~Cxpw5F38#=^&uOO5Joos{t8;L$6 zpAbYkKC-SCz&FCeN-r8R+fvO2upM22@+f!P|BQbFhlSC=X92M3-+AS~^2S%7vB$h2 zO(*8LaZOdinsoc?t5647Sh@8Tw!H+PzsZTCR9F!0Sp2+l;-k~XrV~s9b`jsX4oZA| zHQ`+4m1|ZPW9bD+#R+Vrcr9CW*-HCabe8p=c{&R^_tfpp2WaFh*b5I$1oX~qbz9}c zUxM~cix%nURqD@FC?!J>~yCBR>bW!XsmUe#C6kgPC^UNTfm*6P`LkPkD0wwFb2 zYdrV%)<0>~#Ie9tjB0p-{IQQ@#tA6{QPEg9a@&+WB;=%0UA6`Cp5uv$J;XRk*fUpZ zfQ-Dp2N`0jHTo;d%c4yU5I*S1Pj#e)!O2%o#M<@{oiqq3x_#}Tg)kh0(3ol9)k}Sv)0)pA$=`3je9vwRN6hG^wb9wnPJlxI@Mipsvr($A z_vHpU`^^JLBI(8rKZolV9lF1!l#yVeez3|t#6(4N$+F@DA#A_@Fpw-nK&ZWdDpitt z*N#OD(c;%%oa>J6sfI2j#!bLvha=uhHvUjR-iRLkyT~rY6K*^c;rdkdPhjN<@VSqzIngFk;iuS18-M#Dn(5U)O}PIoug{XlkwC`@!Wk24-l9&2AToi)qQ zK8;7$jWi#~z{;XgXd7JkaT=E7IP32bU1)%qJvd?QQ9Pl8o>LaO6U`n+yP5v}TJOhV ziBJ^aNFbNYRFl`&R8oBUl8C&{YzsoeT>=%x2)@Z3vvFTULz|qLtt1+*&y5B?>3*We zEVIUnZo$efvVTZEhZupTN3)O2rqsbwGg#9iw(P@#ncrHk zZ^ICwc=PTIP5elAHeZ9b(9@+=~QTce|`SR`>mU`mQ|kj5YMy z9ul{U=yir!GJPj9LGA$91y=pS^U1bT!ly={0r!R6u97g$5+ZWQ@jXb_mEfhU@pIZD z?glhQw5ZgwNT*~-q@$kH>7^#3NLTSg>)S;5>7^lDNe~uE7VwPbMMc~PGXkG@9=QmW zxHgZYhnn$fuX!$TiA6DRujX-xa1yk#IO5e8#->1hw)t=6;e-K)?Uu1C!>1M z@C%M(_vXiw44ir0s_x(r3AAJD7rv?zQL$bK>6tzGif1pWQ9VJVKNS|iguHp`)B#G? z2{JB{Nq#yAu_FyOD!~3^QcrDao$7TUlVBIH5aHCT?4oeMjGoApUJwU7k_54)L%9Ae z+q;;ogJ7x!uvi*oxCZLOf>sVCRJUBYrqFj0cjGe=8d;oF3x`P>cAs(^aC((*^|N65 zpg`b3o{M0A#P7J{O0eZ2W05$>+a?bp{TOS2Qb(iNB|FagbvZ|qPaIY4Y^~;R+jQn} zn&&>+IkA$zh3Mj)?mAlx4l8!r9O|0<{a#j!xVh4K&4hTg+Qh4azBAYEH1r;<(GBzO z4(fzB<2u;r30AP)sOALkix9zxC)X^{);QQLh4xx_dk_m3&eD1VGKr(>w!=-{#F_b! zbV3|2Uh36dpVC|Ny-0lyrFiAXRKXG)Pb4&7WSMOS(ZHxYC{}4Zk!iDPviWsQ zzSTw8ut(I-^{DZ>r{n0_3wv|@nwpGLZ=5WO=N(Vpc-d}zB;?I@sdiKckZaR$wJJwj!aA~u!)YaDOvpFkeIJzebX1d9qF=22ajr|YUkPQph z6{5Z^C>;F$pHBTTJ%V+Uk~qj{LnI;6aD*^cjrx(1+EB6BCx#R=uHJBHC^nkC6M*_= zq!_v=ggW?3n@9}7E%eZveLW?5m~uZdZrRA4063j5>j<0xGV9N^KkotzMZcI#u&Zh} z^m)e8hvcsi3I~8`jmva5b&vFs;<}(bj9MmK(qNY#zpft0045NgDz4b%aESdl3`MSV zyIgoSrU^w=KF*$0dodjM&bAm}5bHXVF-29mWqK#&yR{0(wQ@8Fhr)dc^t_2EdNFUd za0W*S`*fo}FRuz~Gfjr@S_-cCO=htpze-!Js83yd{*NE3Qhn2K9tcPrtEi$EG1A3& z!6yTP{3h*StngL$N`RZmw!e$aNlsD2BOqO_;!h`iZ8n+_8mL^|{g6#3PAAex_k3U* zu;qohipT!ia*>a`n%#ziPOL(x>5nH`Q5)CT-lg-y3q=S+rK%4icHNT$r^AFl-pYL} ztcOV!>gSgCbjM0GKJA(au@w?4M>Gc)@o*3{pzvBnG8Hcu-kkv?FEbp$$ zr=XOqQox!!h0DRWwe!S;k>P)pXD#=qIJLHiz^%V@et)dQrfLKe9rye;IURl3qlOp3 zFI(rhL+ij?nxFNusw7TH+gWDEie$|gS+en97N|nu^8Wc65#~0}{HDr-vR^9P{r$P) z@lasMFr~n$>CZXoQL;X?46p~EI4V>tMb{tKpdIUZ)LbLSe*G2tuF)~j{HV|1w8xa) zL%rLDi$ywKP)C~Xh)L&2}}+upqK!cZyMTwMwG1tP{Y^VTgol# zrVG_ahU%%xbC_Rws%Ku;=T)4v+{{z1DhB2$=PLm7)GZUM&#Csg|3d1nt!%tgYs3Nb zw4V7HaA-ZlOLH{e3~o5$(4AvS0aO|tH}cxn`%*%>U(r1|4Oj3&@6}dFW}Lb#Qfhen zi|EZlqb)3mL#8tX#AUS2q8IAd_cTPe)Zd@t&>6r>ahMzof!d4?_NIzv)yIv{_zyIp z{@4O>eG~RNLXbyJ28yO995h{S z}H7F^>2SPwKx7e*Oh}T?9Cxi65Fw|K&2H$XA6wt@n=K;>o0JNC_U&Im7=b z)DH;4<+?St93i>Ws7l8*hi>t7imaBu8EHLNKRg3PBT-d?Vu-wF<}&~FSjY!#%X=J> zW#!Vcve1i+lDPmrs}DpGox0LFoOwV(w>#ghA*_hLLN5P@tWa^QD>}^E7E)UXHMOK% zXsHuFF_|T|vX|AuzsGMTQwMjjB39H+@Fn`@4owOwXdq6Lj%hNIxB_j^=JbuC(hJ38 zo=+ET932Bv2jYFz)ctK87ueWC;BR)x%@4dIf#^i9yf=G*VVM;yJP`nXt0FiuThN8P zc0?7!`pLr|tV=4r0lyPFBtccd8=SAdd5JF#+XI9-m7-ffLUe2n{SHUu&uMv+oO{{I zfb-!h254cEdZ=7HfrAabjB-cUGf4+|@qjBhrKxR6sd0oH1{&+kdb1a|0I^w>PHlxnRqvvhJ@dO<)p zU`zc(>(QC!(^@@AHez>K*JTT=Fn5yXY{kjQ5%4BIS?`+gA(P!pE8G{PYebR}!vPV^7=|588LTV22ss&O*)!Jk#o1ou`89 zvJK~?6mOM0_j8_7+=K@jWH?SKTqtcC*Lpt8z}-{)>{l7Ly)_er7% zk0?y*HH3hK)VjG-2=CR~#882bCvx>08Jx|`4Uq_^xE+@WPD z>pd&QdQz!EtJ7kxDeUt#+4ysixGLU0iMr+E{E*`(Gp*FsB89E4t|S}4U9^hB0g|r4 z9gr17@S5M4{P*xkzZi`!vzN&-nSZm&!3=a3 zSV!jKK6T78W4);OGiO>cF+ykmd4Il)9LX4pT}0zv@ghwhuWr^e`-*5VV1w3#$||; z^BT?K-baowftyvQ#^*F&r38sSUJ_Xgur%;M4wZe3R>G0k?SfFLbi*Y{bRYJfW<|zF zGFs8Z^S6__CAW$p7-%^k^832yj7X%#Hh*K588$p7|D4@B(`$^>e9Lc0M~nr!rhwl3 z69*}c|@QMeWzIaew($$K~zJ4+X@Z z>AqPzU%t3>nC2k`GO+u&59gqxno(7-&GSloh#;_hM4hlY zmCyUMP0d3Fs=x%;MJEUMo{v#YE)k?EP@PDi*Rff1R(VOvf_*sTZxE!X1mxhz4*QiQ zX-mDagGkko5%2)nBxTjj^jvE-H_s`Gjxs2{k|MPwz&Z~(0XwCnQqW)w z$Z)U8u!^Fy0+hxd>wr8_8=#h*mi(U1^GL8M9BjgBmRcce@70Ekh?>&XjNqAgTIO`s z_2<@<#?TU9H#i;{;ME;t2 zC{+=KnssRHH;OJi>u<>TIJ1PyK6j91+XB+V^r;efH<{EAxT|Yc+5dqu@h3*5TG_ME zXx{ia@C)L@Zqb(vIh_OAkqnb;P$dU2kQXqjo%3kQ_XKIeNs_gc{7K6E715ZQ+G5w{ zX}D0bO)FzP5AWEVpCW3iCkLnzU3pP-yQjtoof+6R(t;6X=+`!`amf~woAu?5T0oqN zwJnEohOA;n@_+#osNzlm%(b*B*LL*SwANCZY?MZ0T8_;mBNC-4*QSNu*8aQMFj`@J zp03-+CdLG^;EE;A6dk;xwqMEJAYna!Py<$^+SzUgxPP=Kl$8>2l? zlyh_Z7diPQkvi`C*J^7YRM&)OkeybAFu zhG-^1P<*Zg5)G#+F+m(Ou2D+3Ky1Y~m9 zm^;!=;}<0U5wJE)pe6?L#ah-=TXuIp^W*#FV^>RYNdJTWEtfBu!Nxc3hcfYwW;QFC zulzxZ$7-9N#G8FF?QdccWHARorcnq*#!Ar;ApXtH;T(^{O(UYNyR9RY`r!l;(f=Hp zJX-u4XgHL)9_A!kDrsX#wYrt(o0RooZ5)rG&N#x6>zJHNSKP}gDOsQ+tq_X6o@%7@ zfc0^c=mF%fo|q}sDMhTK_rjp_)hokrsOJPlI|Sqa=Y#F{n{wnz24YTEQPhVhU9p(U z8CT#BH3sk;fk|0Uoz&zt2Y3D$k1>%RD}|)-Jy?|1)Fq>pEiii9p3z}$X8WGXNRwzl^Of3mo){3 z2wW-=vIo-mh7|F!Gu4}ng@>Axomk3QQtMTc?{NW3QQRS$Qv zst@2FN8J>GV8be6jC0m_J-;`-IGcqjcF(;|%TfuHj{mMIq9{{sm3K3XeN8y)?+_0G zN1Y>4VZ(VjG(lIsOdWSngzQKO4dPEVj+@fD%*~@UT=D1o?U|Or(|!1hl&3qBB1Tn) zkFhV+kuQ5E4FZdE_tyvEcQD`|k}>U#_90GQXmGGsUhC~u?P6s9`hc3=$>`Am)Be0( z9v&^$UB(^cP`^}uC|G2f=Mh6j0V|Mm5&>v*{=)w`%zrVR7~+e znUIo%k-Q(pf{zcBd)S`#N1HILt|~bT9{gCOt z57+MM02upU1nK=cySD^Syx`3uZ$53+Y29bXUC%^7LUIbK)Q}slArWHz;6W(=$MRx zG!NQzMAjGfDC#6WZ5(vfncaJbZ0~+WJ9{t(2Q@+$1f>pogq!r!1U(MOE&}bR*H|LY z;DQ;ZRIk+qYM;viFo#W-Q=G5chhnQxdSr+r%TPDsM(Dw#Ai_jmy>bC3BkOZ&FeMUo zb+baZp`l~GXbNaQJYm&cx@xJF!m*t@td73<}QUv z^}W9ohGZA*<(^CGWUcc4ImZK66LcyWVUFetye%q#=O@>Jc?R;d4%kF?$O5<6y_n=v z(Tn>BbmfH3^Mc9f;Ha5poC8cQ)yaA_O{I(`7M8kL%c z?Hsf19@i?UDv&#z$o&~LvUxQ(*lNo46)PB5uwy_K98h(oTGrvAddq^!V-cg(8a=+@ zIai9-9-52o+GXLIBLgeYY8hFdrc}bCIP>daTj(|J$BdDTTdLIBfs9st_vQDV6ft^6 zo{e?LNAf!eO?*uu@!a!-5mB2JvKF0qq4ZmRsn~;GTiTfW0C*;=&B z5A`kgjUv{Lie(4fGtc!uvDFyVw&V@{A>ij@2yYmPAIh|6eg7zV6F)>Yz+nk}%K@-w zfaomz3RwqR2ho)NYaM2p*~sbaqMF1Fl9KJ`tpA^)`wUC^ecJ#I4v;AdD6RxoxWSdH z0vx%wxfMsHrG=w1e^!VKXE<|ZIC5p?%G9*Lty!s=X<4~TGymGO>ErVn-f+OdeIM8N zygsLOH`lJL`jAf1Tu-9f1MZ=ckA)L$jv<--;$7>|bsAKmaqv0YN8~IdCAUaWlP+4# zhVuk=(tbjZ-4Y%?oNPbh75hf0iSoAbG9ANLAg_S>RyF(YhB^Z*@mkD2!hI`uE*6 zRVnSV+NB1iwTCev-qoY1>%8{1X5sZp83RC)^Df*^{hmwPa~>2E$Q6D`5In^5TprOI zIx=l`UPKx#WMq|S#3blRH6AZpP1qrLFPiiUuuYoSe>c8;T+pWTpjxK0+w{Bi0SA6U zoAqo<5)vD=IYQn?mxlfCL`IK!HV5F3UVuwv-m;|wuiVKo+r*Ks_xaj<4LJyy-~vBS ziv=x1$BfFeA!pQbaMN7-T8CsC4N7zH8B3|sjj0CG?Vvl-x)KXTEy2;D!o-i?BfKi2 zUY8uc0G@5>ie4N#ymrw`+i*B{^@U73gSi(%%M$}B3tLZ^M1KlT|J}iOW6JQC`wcC) z>v{jw1C@R(_sQ)L==qde8*YK-L9hyzO&ciR*5?spabvag(DqwiybSz|tIM(TX0Wq4gg zp({(vUe(>?kp9u&(iTDtuzc)?7o!Ztty)xZtl#HB)!~UEr&8FeQuvjKt@~=kGt)au zoU-n9l^oC|NV;^0h6OzTicb3en?RItBBMDl!0Yy6_oOAB9Ac+kzOpkYTeUEVCpq-y zqa8cHSFT^@Zs(-PFw4Ye?0WxRB=tqlMM0HMw~KA7!%llE_)wB(RkhkDSdYo=WkJI! zQOs6+N43kV*9DLMMrCU5HO%e^%fyd-j;J=UQ47mHR6b`7IK5B-CHdYmonN!-ZKT>>Ny#bRcsrHdmqMOX={Zywp4nP^H7UbSk#v`nb3afAxa#86 z2b!<|c#J6DZoJ5B&2x$Xt>%*3s~5ozw6~@2&blD8Cx)~m=Bzz|&`XWfpwkagku}0? zkZ~?WIV3YtP`TPJ#4;pPJ*pXatY!#)@Z?i|?U=K+(`3}B?2+5K?lwUOtg9NH{kF{f zUOUnPl8!HXC&k^XZ+&FAC;bYzuYQ3rS?(VW_p;rxX-OT<;|YjMxi8(7@~fx?RxIVE z67{W#6n(%_ya(iM+lqiJSL3}?JR?zB3)lddtvpGEJWb+Mw}{GVA+C$035m}1tje10 zQ*(lv&C2zQ5JwgFR_T12d4~Re4ickNaE?WWaz|{4v1}gzi+%`IxX!*&VoS{q1e?gJ z#W|S<|Lc=vYxy;1geEPqwkDMKxREx!hM)sNIg(lzkjFeB^TmvN!X7&ZMT>JY)_4Yu zH^wUv-&p0AZ}X3?oybhRTlDVo)G1CtSoP)O58OSCTT%>&jyOWlf%a<2s^lV-(9T&Q znIMTHd*MIVeESshxRwKWcR=4hq1msl)F+!5<`8$;Cz~dI2zta2{$CA&?YlejD6zK> zx2>T38N&Dp0NA}c8BY#7=qSEX@JTEfjT992z961^`Ey&TQ!&&(GzToNoJhsoAzFT1 zE%3($WBfYJPkkPwN85qqG6a`@Ko&=<4Xm(7j&J!cj-V+!bnEqQ1VNgC8bF!s*O;p1W8-dTFU2bI(Yj z=dfe6qk@cEd@jhqNrBn#Dnqj|@57N#U}T=4iB@VdiOQMhGGIya00LXzrLyCCr;xHx zWSYIxQb+l0lDtD~vU)s0^!oOIvJiDY%U6lM|3)aL^nuUX+Y6Ygx=)ft+rnd>*Sl_P z3&m1_>F-$gdzSxh5go`-Dt!@J?KViHOs4Imd-TlQ(Iz(j7qC+Z7WLj`;b*G?K9*PV zKu5L{+$$D5zS2-048il5@$xU8wS6Kva5h1D6OalJDxDoD7i@mNy^}uC zvldNB#H`@IWL@l0Anh4VBqF1;?*d_r1;g=0UiB^A-gUcY-$4ZnDSLk&Y|N$X?oUI$ z7y~Tc1B?1ceky`ht7p?Gf#(mLlwtd|^?s^riii*|CJ|z<2?)ypeqV&nrwUQJ`X&wOT_~OP!5Zt0yM@B@YO2t zz^1gcQi5EgoJ6ZPu0#6O3He4kp>Yw|*gG~520ZXpTAt@EYrKeqym?0OliQVkAho|H zSTPkTD`N_m=}hP(%0AaD6ZCr~oBvvZ2=res{TLx5ZKt4oTtT`nLAui)-^!POUr+br zcSR%+FC-8PD^&{>R7*dv0sW2A4(nS@%2qfTa)*?jJp9^6+#Hi83O}S+E59ix zJ@gzJVcBlGT%6^r#@mv_mw{n+G4QIhLW$}keG;66Jd99g*Q|j7ogvb%z5tXON$4>b z$+Q^bwtKp}bIiBd_`0Nwv6&XO2oJNzlncSU$%&=)&emZ7>f~4dFW|oiH zCl}2J%PIA{`eNK;0)9Zubhd#u!cXs8Ra^Qe2M~jEcZNAe@?Inn83z21$e_C?+GB~f)$}GP>T)>CK4zdMko@GvWZGKy^f_j+ zKjp7E7$xOo2H0yJduN3xD4SGYq0S03rD+F{A9%{~oHo0sQu6dm;U5(g;zBIwu7>Fzr@f1icCXcg9e!&)S3?e?k=y zJw6~(-a?g2a@71ZbQX_#8snZ-C)6>&5)mUDFqe6L4W1baf3Q+4y-ls7K5ZeTPsTzm zXZutDgL}UAB(?-hSh&7AR4Gk@+(SFq43ui58U>m!SfTqu@YC$PkIGi0P)Fg4%v<{m ze*TCaO<3d39`!)=jC=J5E=9<^eWKoX^oJOG-}h0TU1Ky7UvS5=gt9c6v7}o`jOuiu z#VNbk0V+yRGjwDb=X}-II@JN8$qbIXWSzWQ@B?1kHbMJdjFS(gA~z}cP3JG%^-p#7 zIwRBryEfDDVtcYln!ZmnO`qujpOJB=bU4s}t(r6S&(1dUdANa75Qk6gS^ie|0~)D} zIO5e!OVWZsM!c1RaJrka%gv-~q;QBbY2@V6h7*5;5&DeXns9JnH77sqDaUCtf8=i# zZ7{dVV4tRcM~-8Z)XzE)Gy}V&lho{sQcUJ+yx!HyfMgl z_`&cE6%}zR358^AuNHl1kZ-j9s`SB$4{BHtR<2Gsm}&EBchYO!B6C&%|3SDhoQhna zRAoDbxrB#FCm!SgQ=?A36A`p9teucZB26nBKqB7Z%nptNSIn<%FkY~~+ckgy@;x=% za@L;HeCa>4Et%eWUJWf)qb!cOGy`;&HTfg9o*I)(Y~iox+cBFXKCNJAO!GwjC(84a zX;aIm5}e4^)-63W?MRM#JQ}t-;X^3kPW1h?o|J18kuMW?2}mY!PaAzbw*UPnh^!6N z8Y(_I&KC5CYnDOMT7W-=Q7bDW6`)#iDXeD$n~y$Rez|M(x!)mduDyvjehEHp!f;ZE5M?Bvf$~KzpR(eg@*WD?&TcaPFO( zgohsl(j}xkZGU0GN}(7#yOQ|@Bjm;wSJf9T*|Ps#{j|8zX3fAJFC?aS@76wr0#1GM zFhq!GWhw2{cO^c}R2s5VqB*t;dO*3Y9rnQ$Z+9v!&EU=W&2hG=#9o?tPhVjj|6*hM zpc^~x;b`W-Y=*Fi{>hs%zJ1pmjtvT>#>7W%-KdJ$%upNQOA7rj$Er&D`qo7Lbcd=V zM?C9LLzPjvNN2d!LZ(v=`;>^axH31;DYQa9W)GQW~0C$rA&E>WrGb!xzn6!zEkTG&U!mZANe=S9`?Vhy#N&l{_8Tf6iJl65YpQp7Qp1VCXd}9s1@%G;}k>ZdHIqK-O z?=<{wu3V--Fr>aJnXSDiwqtI7s*Hx}PWWq=W4a60O2Ta!?cooxc7`@>Njw8#?%3BzH(yqVBZ4u@`OO(^gDgIn*r6rzwf+b?j|6Fc{;P`yvswJVlOY*o8{h8>rVh<4H?ya+ zu{Tv0tHZydpKYy8)}hJ!nCXbn@$^w!bHop;f`D7~+u?)P%QXIe&*E$YI}1KTBKqpW z9qu%_+#4e2>RD+USbY8NPRo2h%C_D|3sp_WFaKcy-(==IjT}ySrj0pM!wEZ7E+PY~ zDxIG$7h!G8)Y%j2ZlMfD|AFShrSa^?a=h}1P-JfVUL*UDWwp@$e2^tS0+bS>nEU`g zkCY`$l|2ufm&J`>_m`-Zs5%CyKEE&x{Tox{8=d({J-I<*bgKP;i_E6a`|K%@U#0T# zrIRfQ;fbZvT&I|Ret-LgGrF?(UI6F!*&G3Z7Qe}~6BV(`)K`D$Z*P=f$7aGGi{16B zz`lADF?c`z*^hWZ$-+_LeLNPq0Jw{Pdy!mzu+Ae+YL++-cM!+1AiKmO@PB%piHBk@ zRi~C1rm8WEl6?&I6tXlI_$p;19$r{Il_&1jPDAZt5Tg<8ul_>CRW>NPBedU<^ZA1z z!ADip?b->mg~v9)^X5ke#i$`heKBEDK0>*cwB#mrIb(%OHC zrC4Pr=PkiJ$)+$vwfDnW)gtIDLsyzq!seXFuLgE(${HtnSx z9f-!P5#4^lz2nYJUcBt_E9#PfycJc_Ng#^v7sZ!r95z;VT9o!$RAIc4p6xc$!t;pN(pzRN}IECn*Z)jk$ppSsB*h5{eBPn)_tVIP3~X(?>?9( z9h!g%nSWna*>%%I&AU=sh$$h&>+snNl6K4Zm;;o~6n8Ro0uX(jLdpc~%laGn_gWHU zr)8g556QCKAD$|fZ|8T4zJ3fWZ9CR8;Mmh9D!l)Za0Enkqtg zHgfoVn1L#rJ$XB(=kcRIX?J?sz^}3TL6VFc)Mr4adHz_={o6agnrs6xThe#If%y?Y zam>rJs}gSqjq9%)FYzUP5)_m%p7DeO%YWZM3=R-Ub~?QNHKhALQ}bRW@ktxK@1r!G zkb5>O;P*=Tj!=v2xzN|ssUBlV4uE8LA&WeJ^t(grI+?785x2eAgYN>8Ed`XVV)Er1 zfzM*o-X2or|LOG+kRmJfKg-^u<jg(q zKsaJ3@EI5X{h|lLQgZ3=FYI^%Y=~aBJQFe69WnYN>cxx-fFLx z#$+AWgm#23_H_t|RGHU2o$h9Slr9X%5y?j3zJIf18beO&v&3Dq0TxW}A(*BcHA797)3RA0k2J{hM>miD1$;wCS7q-HiJswt zw{5q1LTThRoXrI8L~)3;=};exJU}W&81-!P0P}hMNUv<`AsSlDZQBeiCS-FYNUcqn zqrVk9NaKFpd(dS3Xh87x;h+#PbL1hRmenCZqnS$&cLhCZRD26#Il0BX4%D$^+G%^dwKuHU_2R`94#?ar8LfvcA40DC^T%qDAi3=~%l|zQC6P%0y8WIxw4TSm&&acK7<9 zw2I!5V9Ty$n4y*w_KsSfG1m3Tyy__%yM#*R77v5^M7W8Tb-0^%b04&^+P@bb|&4O)ghZ}OWzze8=hQf zu;0+yC7<|lc4jW*YFISl=!Ep@i>|GrDiN9dB25inv4=A_$|e`;7I+o8hB5hY!>wuD zdAN{h-~bs4nb_G}#Tf~a*S=ZX!xmtQtXpW@k$Id?lXJk$sg+HwpF!xL4JDuO&Fno< z$0GaC>eZ9|*Rw9hI^PjKnFpA*oC=e>ck_1RK$&f#_`nCDzfNcS6)Ydy&vf^r#Urk1 zdCey4ASAtQEPErb7bFX9U_&7Ck%Fx=LmyY@wHbtHw^*V~ zrsy}HGN84k&l|Awn`2WG0&|iBv=Tr^4eKwhCcgam+5B#6e#()H_(b)h;X5t_OZMED z%tTpIiZQNAqt@`LT{;S&G!bObJ?0x5x|7`6o^{n&?Me40Z$K+o({&%-%^b2a@Ms3Q zr}QP0I(QF0&Qh^_t}uf|7JDpL8=KN6QD{j-_;r;3(~!mfjI z^ApM6q|9(Uu~)_8!~AA^jT+^1zpDYYa&83SJ=KLg&Q;C~@KuQ5Hs?*l*9&NV5Y%_q-wl0inYW~w}=C(A4y^jpFr z_G_QdTb&mm8`)*D!NBwNfhf4i_9AY`T9K9&2)3E{TzOp}gS>%a#{&nsPyb{})Z~NR zSDFHc8CDiQL#>W(Ks3XFc@|%WXzsZxk?O(u>MPAD9_^wRwslYW?$s2h7-aUHhi2IN zWg25HClBM=Ma-o;3+0~XyM=?4%c63tpYP%Nu^uN9@%}sV)-ML#`2xv!f#wubChcgs z%Ytj-3koT#4-wLtxI954zG5^R7&q7y8tgc9|D&m&=dZin6Mlk?n?iRBoJ>F{O(AN-Xv^`(*cW*zd$y|BF`r z>I1WrCl~vySqqP^X1+IVp+j)_o@O!zftiPwoSZ}ch`k!&?z!B$blj9}`ywojrTP68 z60@c(4mc+~PVeH|1{Oa7FV6TOFGv#EJ4(v)&7dOylqE4b^wjTLm|=-c@gFye3PbpM zG1;&SZf=TQhtwRtv&shmI44N6o|q zoP=tm!GW$`W(Q4EgEr}p(|MO~iis&_XmL(>=7mL%#r{6<6MyjhK?$20V;A@6Ej>Uh zkA^v4jnxZO&d4XOY#;g2kuPQ8#C0+|*lqSoee8DIQ1hU|HFBx5{i}>1>$|Rgj_HY;U!=~_rPW$*Zp9 z(95rwDR$HvhmID+)69fagL!y;D;?pqMS5+rn*af#1c=h3AL35gpco79cS|xo$j&PK zFHfG|p9PdxrJub2s$~4k=)(Brzn1=IY!clnk4dXKsxElwB7^poJZJOtYSSTf->*Yh z_iDaq<>$@UL!Nh!qj51lz0$V@W55mDd5SnM|@lh#IQL*+_l9) z^*^1lo*CO#khyQa2GA!SI@t5zd z9oa%i$EUBjzT(@Ty*FTcs&yp6K2df3oJ+i{&x#LH@l&%0GcsKrR{?toG@od;x1e?) zi_Y(;1opDZjOQxt!;2C%DTzJ2yN7aFxX%Ctkw8|m@QphS`1mQ|?CO8xR!7-ksoOPf ztq1eiV2{}hoWmk=0wC&^aPxRw?M8T;cxv($2M50k-u|pMT@fNftP&9u5>98oSRe`1eF_w$s`jKd(Nc6Eqj3ohMF&VkF0Hujx zD9#wi3RQ+S7vuol-*^TrVvp=#j!$CUfRgTfiERopoQjQ_#QHB{eJgO$JJ`AiTtTE% zaSpCtbBMM0;0odN9)~P-J7=yuCrrs!XCT`@`wT|siA=$*Z@(1D17^!>l}F+N5j{^W zvJ(nJfrrP1jTSZxcf+Lofk@+ebDe7WzhtxN6WeS)jYvhHf}bWW?HE7X8d%1K66%IT zEurS$cN2dWY1?jW9o4c8+BmH-68U8)aoC0Qv;3R}QwTK+KsG|G#WnQe6?4Y2iI$L< z@D`ObEh?^&m}Ab^@Ep;ReT|TZ_9bA+JL0-K;)nTYV?G+yf-d{4dQ(T0$`^M`5P!&o z%r1yK05KS6F<1*qHAh@9M^t-J9lRqhF^Oo-72mfbfYe`qc%lG;(wYtmz}FHaX#ejs z!A9ZW9%u`hONVVRMNxgojRp851IeV3rCbq$bmR&ENz;J6;30y7b>eVowQ~dMvDOA%7W1%57`btZ1Qv#7mQc&0Mr+wt}n(|bj%v_YzO5q#}&B& zh}XzNLV6G%0J;fD(OqS{T0J=1nj_eQlQk=C0lSSRY=>G7^o-!CGJvSF#s?zQ0hZ4b!GT` zb|6wK!6vcY+NJ(PJ7RAC3ZZ3%o#(2DQzibr&!$gH*CP%_x?ltN5($yVukzsm3AAVz z^J9_dJeOmIQJ8iL%Cth`mNq~j5)IJ3wE#tZX6kQFQ4n9n_fT%AU7l#Qwn919``&pU z#5D5u{zGmZ-&JwZecWT^vm$d}4+-+K4MHAcX`f$G`b=l$Qeb+0M-d8uO&;Rs3&bSj z(6ukBDb;!f3(z(CM;+ZmT_{8i3L#slUy4GcHwQ`;!l&?vD>{%S3Z$9`y}uAlH3&I+ z0s4XxG{*~cmN@aGUv2~#vk~+><%HemWsJ}o(wDDodM_+C_zhrrI6FwqKM>gs5M>Zt zwnX=o6wgkrBxs#dUKq0*uj$XWPbLkP)|lyp=ZkhMWDY5vt&>n~N0dmboHeKq{Ivp` zvXS8zsyEjkxIK>i!-Yiwz#A0Y7W*{$meB;yZtuc~^3H`jJsm;f@JK_!lM@T-A@+9B zACAE?BTI#>hbD2xgpRL*-zsg1RwvObcqv0|GDrtN;dj)m$ZLi?%?{K`Q25`!e#ifr z9r0e-_H?|WvJ~yNV*CfA7%6G#kkDtPBPc*;Y z!42GLu}?I(2rhzazq!XX+!MR6RW5Hv1ps~AZ2A{H2Dmk8( z1tX2wStGG_iMRplE`y%}w*3-&BlP^zIg^sdhzTpZ5_M1Giu4h%?F;}lq2O%QP)r^? zJi$dnAvs@9cBPCW6{+^>Jl}hv7QTp#rf& zk9P6f6|U`5s}iNn%d?uE-7L;~x_jA5 zlAZLu*Y?CcQ>pz+iw85Y=|L#_)4+RXNc*IKR@sA$sAJf6{F}4Ceby8@wn!r3Tv*(C zS7IP0#_V1q0TGWENvDVunu=7@>vlzA4kXUDslnMU0AoZDfJm>te!*a`680iA;r^kD>rGFpj{bg> zMY!ZUxPeT+;dru6?5V)$DUGs`#Ge#od_0WxRV`_;Y&Eq(kPbee4~W47!kGy1r=+Rh z!^Zu%y^?#CN){f|Kd;RnG-gv#oAg7UO+QfV5uKecPjN*qXdhN`_S_g19OZecjXIo0 zw8d|7bc8W)ZQZG?L=An@Ywh8>#-NgCp|=J?D6q{wk-w^N zr)cSgCBfwD%MHxgp&qMbigDj_ruLCP*}qgYxM7)4Tbx!PY!mM~6mj~9_h8`@{}}*V z=g;%I0=Uow_{pu_RF-PrYb1RcdRCd(VS*SC!6EO@3gW@>3t+fIer`uIK5_Kla(80c zIqa`l+Wua^Sv_Nd$$j63vCvC3w0*TJyU9#QHS1i*Z&;{aqC<^M`>C}rAfi7Iv4wxW z7hkj%sf62JfLYp4UTZ2i7QFTF6jB8AK%`vDxar*5;|t|kh(CbBAk+VyACMqY=|X|_ zGBp){-Y3PB>pc}p(fKP*4{5Eso&GuwQ?8)_-Av_S!+6 zSH3}+q>8>|IQoE_NF$f*5j9_DJhQ*2pCW5=U>dg|Num$2{DKtUyNxFCQ2$=-?M^8V zXNl-`|4CNIkv-xkI)TcKN=@0a59;QWGG{G)I^*UVq>`R8~F{cjUJEUl3x|5x!(;PJ%0H2iyG~F zH@?TMjygzc_)Iy)y|}$<#ghvdil19^C)KlWn^aqjKT!_iZ!VB%de6K*iliAm2ua2D z1&?O`Wqlf3B?lUWdEd8zJ6(6imF7Nz|6U?Y=__nqGnKH{8tT6vnkLw~%c}eR?O*nJYhW z6sm@RVkSQM@HdR6joPI-*O|cc*nC;>Xz)29seySGq89^~&RWFclI~JEPzPe?f#qVt zi!``q$ZSxing_E((9CF)S&KB>EH=A&aj7d&^oS6_yyD0Qu3-7)C9foLYa(Hw+`z8; zpe)~T-KFr!V$isBt!G_*VW@@0IPuJf52;8irN}`!*~Q5rX^|GfN9m5YB^>EC5ao;v zFlNybz;7ZXhot>OF=bmhp#hoXgjNtfGEfce{6zd4htx4o-5VmxrmN*8N}a5pRz5ph zkshZX7&c*hRak}V4Mat!%UxV>4%Fcm;h2h78JNsOM7B^NPf;$D)CV-UmqWTU%` zq8C>_kn+on96IqtMESUZa5S74(oBGnTPJ8QX`K^;I)1hf;kskQHapw>wCCcGWh*6Y zzv&@ZgZ_YOB3WR`<3tXV?RJVHpG&%)fE7cFFC7y%6d^p;X3Rud>(r70%>d^Ws?BI7 z`1A{}*#97Pufl$Jy)Or@Fp1n)0RcO|(Z8vA%eCLx$HkuqIk_*S1G&Up`Bjy&( zW?AYXf=I3~_Y~3~G)J~*#v&$6`T{^#&Q^9m{}Qv|crK(tuA@#;&5Mk^vqO<ho>p_ENe=Yfr1LR(^QJ5b@IM z)?N*}6D!fbXJW)C662++$0r3tF*mO_N9BCm!5&ifz@xT~a1oAVG8^h*MJ}rRt8cXNG zo0B=a8ib9Ho}80hjXus@3rjXt& zAJL;xBbyExH=5=n|7^aO`**44YBoodDPoQnN^nX737~xWeadjC2-P>J5_6}{Lc1l+ zo*9I>j&dyC;-!j1se7oZ*kp-aQo2&oP`F6_{QT04OOZ`>R9?e+wE+Ej*$k$JiW1Un zm(*3({G=rpB}gt8P)haPR0hMO*TpZ80!V1OA47`k6?-6ET~ZKrtcQ{!-9Lq@Jh5Vl>z{FwA>e0QC8-9fWCb%7mW z$DC)_`PT;`0(DDge9zr)2z>IT1nm1_o(c=aC99W!p-!=V=+TI#=$oaJng02elW&BS z4S;NQ4j+Aek86Ih_dmZ3m6)FW!p=+2{`03&FsRKeB3>(D+#coDdu1W<^8Yg4{rOA~ zEBQOu%79M7nJG%ENX^Q31Usn5>5Y~kc{p3U`(gn;t8P= zJt1}?JJ@a=2R%+j*_nx38GiF19bbay;8zvd73Q++``zom$`Y?#^-aaYyhbjFF#q4m zG+y8%2EGBs1$gc$D}hK$BCVi+d7?vr>{w{)RvxweLgpV2bgE6&%-|yU>My>iuzp?X zJ6ZP7wj?T_s7V+vT$=XvJreO66!FKODu06R6SJO!WvI){os=Bo?A8Q zYEV#Mrg$UhJPYML@;}V~o>#g(ZbN;uVocvEr0ZDjBs+{}%*p0AxIxZ*3P0oX8siJP zk0-hZIX##Y&tJNV7MOy3q{JHr2_R2q~I%0>y%3)hHC00 zZKullqDVL2G8&?`xxHWWvdo*Uj<^P(1{2ylO6@|HnVVJsSz>?@IC26Ovw^-s^$tzcX9eVONy!-i$ zy(24i@?N9o@q*}f(z8=j&k^1?RSwThJZ{dAD{Xh_m+a29gP#dRe6TY!8l6bia*N%H zIY*M7V%+vDu0tjB29#9px739X;Ce?A9UUeI%zmwM%ERM-JmH|8(ycMK&xwV)l6(n5AiR_Vy2QI$HW*h|orH9`BRRR3P zPURvoz$Jjk7Evu>7G}~XWXTZ^N8r$T>V4Cpww=kfdF; z4Zpp1k(Gx<6OKl0Lx&bjnm~#UR&v@da$YS8$?x~F^l6%ige?1IG0)2MJ|5U_TUD!4 z)x5ainPIw~m`E5`cMKQzB1o=)%2HSX`!NNNa)_zo=hzCu*Y6!Vy5Budh496-+jXy@tS8BOD1w0aulMQL2S=rcpz4hjJZyic33p3q$NGBx*mc$ z#}zwQ*e|3UO(1{HaSntl#=!Yqd*#qb6rTjGisr%ySi=h8g-H3Y5OgmC9>oC<15~J& zuIHzf7#k|YHiMd&Ud7_M(Zp2aI+g+z{>}_yodD}nHB^12h-ibLs-OxA5&_l9lf?z0 z6$hf3ASOjoND>=!DK#KTzJUh{U_iHaZi0VdYA1xRpd=9+R*Y7N4^zP^oyDhwBb=@2 zp4W1o-{f)houOKr%OLhCE~3Hf5gr!8M0=(az`z4%xt8n%PDqYIC`x2#y8!Vj^8pZw z7A(7UDF5UKZe9#3BM^Ls9tqizofYRUiC_l+@Z}$9mqE8>_N`}zm_AB)7+$2QOXvJt zk^JImX9D;PWe-9%y7_UgQtA{TF^+o;3Jq9*dPi65TA4O9*TP#sCJduv7=R4`YB5_Y zmktYXB3~%MN$)ha^C~W!)(e=hoJucw8VK9>h&L4Od~ZS5lz2Sp#*@XWh5(w;3~Z)# zUDF(_EmTan!RCX_O|upp%?4X9-JmlG30Y{$VBh{22BQPP>|2`iCG`yx!c8biOmVdg zp%Kv%a+Gn9iUHUyKs= zoG@0G^h){ltJa2U{YNBd2wqNv&@yiWFIa)H#;UrY*kLX-Y6A2}Osvtm9{n5D>_Hf@ zLT5a{KN~T5+Z7qYXsDGk1(l)>6GRkgY|mfDDd}~(FlBGWymm^;?Oz8@DV$)Sgv>$& zZ5AMQ$u_hMsk5lMbJ7j=RQSJIy$2b$%-JB;W3g7Ja(6LwAEVPKGVg>*%D!_ljE9Zx z^b$o(ts^1w?@PY#pk5kR>2=lv7g!sMb$PlCN?oAS3<$~ldaU~W6A7qw+};&?+g5>} z7)>#Cbr-!P8>`J_sp|~f?FS7V02(yM@)8|vv3=HXJA@2He;n1zu#`{qIdFsS_Q|kG zFb5<;Zd3`!4pSguPKt@P=vF|^(pWRNMe$dQT!xiivRCnO48Y>Qc5iZ`VMBjCM z6-$Jt_FVT-G`xxjI?eI?Y;>FFEuoJFgfhSqxmf3T$qizayo+u|DwD zYhT6R5(~;K>Kr2Z3Nc^{x}YV1ZO>QC)=+p;l&B&r-cI*24|}Y;3v1x*W7qmnpv#-l z=3#(Ttx=~EP=qbqZ~=-|Y=P9>?!2nbc~W10IkNpr!o7SahsSZZkqHGC+1MDM1o_ep zm`v=2F%=m;$P0dVuUkh(%!(-Wgvf>^kYbuX55+qP(I}8YYByLz&7SO)&}?!o)Jh=} zJAfLkflqwt1GxZb?^94L3Lh*@8sLHUevCP~r~#Yh^vKU^UDNix?nOnfTBR<-2$Mt7 z8n-0@mR@ocpAxvCa|JMuqZg z*k!8zDV-P}da85xgfuJhj1%FBXC6+|@LEaa`I6^|NGy*8^_RKgl&+_f6#GE= z*e?1R-3U6zA?D#lTsM$ZudIv7pXIu@L&BNho3xxO781iC#g@liB0JD`A(0L(NskYe zrKF{Zv_QO@A=0OhsFpsP{Rql`G165c-9nbBtAPIJS}`A|X9UHa%VItAnH)hhnoZ*1 zfdOe)m0`PV(e5_I3eXJ->c7L-PvYKix^UONGDTc6B(?)Bm#q|*G=iT}oYrV7tx%|QcofvB3o@YjN3BBAtq zf&v{rFmP%7BNJI{{{HaYI{Z5x87b^3$XqxkX|NkRY`MFLBBGlhaLXDEBR`>(zn z@|BtW$c>yaTGtCrIf+a^^;Sc8a_=c!7VwlJVO$tv^CRY8KKR#(fXx#DumYz9hF{r` z(D`P_JALO;K+XZ) z5mVkr&+Dw`Ns2T)cdv`3_F;(2TPs~!UOI0H#bbY}sDJX{A_Z{U0}PKN3K9=dg@NH+ zb)#Zkcj*(a zQu?}{z!fX$$mTS6u>Ev7YF78C;S%Cmd&cfOoZU8liYz~Btz@#(8YJpU4OP47e7?hp zandQ@eZb)2$Blx(3rwd&!+X)z66cTBeEVgtzP$1c3Hl!SL)dRyID{@V7Bd*e1)X{J zJ>uPW?e9UoE9d>eV95^0x7ESXBo3!5x)S(&{-5&!0hDjTgD1fj{u{~8R@eTIt+#$_`v2p9Hx`T@J$m#QwIMAc z8zIe*?lBN45fKSRg>7_5OLw<`2na|w3W$`bbc=w6_2%&To^xI2hjadgUDuws*Y$YZ zAGf>tfZ*roAWyz6hw(IMQ4{a`NA!$ca@$E>;b!`hem&L3f7GkQ1NTBUTSUYZwg#K% ze5Tp1nfmd4(;9oD6?>PqZ}rjn-K%-59Ai(ePI)}$Q+)hZ4_6uP7Pf^1yI|f_w$okG z(9+Kx>CM(Pvh8qx?j1w@U%Td2D_(F<*Xbd%yeS`-TNRl61}^YVBW?tJa^y z>ApDaigSH+|6hsi45`t%&3ER$_(Z9Uy|C_mut&6UqeYEnN5J>-t=d@b2WvS7mjHTk z-86@rJb(`)uDgeGUIW98xzbLnXX29{Q%_A;YxfgsW>97o-R|b) zLvz)#75q-G_e0|LO<&8qEalKINxjR-zH^78?5Ur_<*-&yI_k)+mA2crzHBE-zPY^` zMrDyKh<=lw|LXQv)>hp(p|(e0IvT|fzwaG9Rlc?JvHLRWcx@y_b3(CbB)gXAk{y_st&~4u7o)j2rzWlBEGC(VS{m-}{GmV6qp)l75V5 z^h(*{bk+Dp)A0@^hUv|c8JAK>xSj_?a5=O_A}-{k&$ziL&#-_vC?gS75!CwS(gcC8 zrbaL^uI^fX6r-U5ATbqIUE^#A6LF;q>v1W^Ji9YNtoe3ogcZ;)u=!x1Y;hvT1N|PJ2L~GN=yK}Ye5FcyDyF;8W+7H_Y z7VIgUL5pgRH$Y5Mty#6!s{6^>@03@PgY3PlWe=Bq7PKggifxg@ukZt$D!TSTc)8?D zOdP=gZZyA0BY9_x^e#aRKUmF5s0y|Qx&FY4Gyt`4 z67As5D#4;b?lA7p$9y|;OO{&MlO|RLw3}1j%UTkz)1b=JNr5xsH|7%hcPsf`)}@XwQRd zGynQ3WWEhaxKI^J6&AbvBe4N^hU8GWp3|S0&xGdpNQA81ryCUt7cpfKCY?}cy7=Hi z`s-U^z;JHy>1nzUlX7>BCD-n6(5`}HmTSWykaLLJ%`3S|NB4p*<}#Z4mAP;b_gyV* zK+H*+WCb(#@TxXIW1viiKGr{Xw_m1+Z2(j8Oj5oR#M`7N&)Y#}yz8CEn_brVkI9(p z9s$xd2fLiTWg4uD=DevQm!`{ToW!#m!9R)x0cjheQD6_W!zY;69~z2JCp7%J>Tyt zT*2RUj(c#V!duj+1I-4fQ_E*eVS1)<^$ZRE)A_J-yVvB1i)*oc0=N6jK#`{fJOZZIVVph8Mzg`3 zJB`rv+Ks)O2QT_7T9iNg!ib;gZul$Yu)rLWf#e$~*+|p|tW?i-sSV|t*@1LvJ!de? zblii<{3zvR4*4J)xvwQn#-HBe4&5PlKU|0Vca=pAyp(B7rt(~WoU8XAEsHov@;di| z`BWc_=_@op<|7Mdm#kcu?DZew zg73Yla(r9cn;R$V3#L_Q$A^GLp**~0wxE3`QH@*Lm?xcSYSaBs?hNsnc$akKZ$~g) zl`4`o+ThXjWHek$Ulf=H(4U8<%oFIoQhApN4dR^&qGoDC-21CKle}>5{*WQAu;q6J zW!n;ki3eh|+zB?xIA;G-1N~|mMyuXFi2*TpjNY^HlaB_>ol}m21NPA}PJ~A0oEj1| zq+5MFDZS`IClIH<{B3`e^VS*7hZSkt>(@&dH1AbNo5wIHIIbsBy;r6E#+}o2pIqx5 z-QuPZ)>RVV)Uy*|GJcFDG7LON*Yx_YI-2)|LQ0wa{MYpi?nf)NujeLDK8@wb?tuGL zSCiXG0WC2pmA&ySPRA5Xuil*h>~m(X5Z%3TrO8;;I&M!-_Q0!YQ>N1*O|l)CJl8IS5aOqZ(N?+t;4P1%Bblh_sZCP zp(n5;&c51A3T?e%tiNBZuA1Iy*BXoQoN+lqPmVV8#bIWfuE<*uvQ-B!t^Vb{Fk=Ck z!inO9bE)*~Q3OY?zIt0XKrKULJh3UHRr(Kv7Yuw=C>WR@mP~3ik~W|K z2c8P8FH{*+y%p^4XIA+ZJD~iV!^v3$(EH&VZ7zO6nc%<`cW*&n3rimndO3kd>gmPl zZ>mPus07wH703DWZSkfs_JwlW>JJ?TP5mH8&9Mf_DB0QEX%f?|=@$XP>9h)jlJw2` zRH3#eIxg3Wjq~O|kvgxA>CfuKU6Gk1nSvXfk{lk;T=Nn>!-e& z!mGDBb-3SuIL6cCA2K%DUAH`eSUIjdpJ9gz&KJd{uWKZV{~5xPuFyXEH{+yAGc3Ni z3T3{*?)tdZAeJH=uQV6YK;ZJtPK@|p!26S8Xe3etn0|6(x*gQ!oawdeMVNDC3h{?D zo>$l+hO)ohzjr91pJx$n3h`lk?fnwr_EA3O*J>NTs+7tJq?MT$?Ihyn>(dqTxWbYN z|GD811c;N1ah#-ZUBWIRX?19iv~uC#=#Y{I$xOXU1Gx{VvtFnwp`Wu{@x%5PcLq0^ zX@uGNxhTeTP486RH1T)M?}9pk2H>^=6T7RJ*NvdFU3j`dys)oQ}zI> z9U|f8gXW*_Rj#;}s}n$64!r^Wpv%*R9TS(V)g!e4kR6_e=YNocK58K;5VIzV@+igP zxZ)2w(Puryxr$;woz?z3a;yongi|tX5s#TE&wQ)?XDv2h4Wu|-NRqD16isvqrzoki z^Y?X6@X*^@l#5(X<#*%;vPBsoL8{2|9Z~tpWXK_@QuN!U3Z~BDLgux9;&59(F_pi-p|VX`gCzNYX@8Df`Qs-QTX2q%_jF=#pk*KkRq3v8r7j! z37~S@uDPOD78jnznDkJiv^}g~8td?<;@Z^WNDDYsqlm$96&aoKa<7=j{cD0D{~$m$ zN(p|krz*+EFc^k32q{)3EvX!(Q0RSiXiL-bm#K>F)L9^E$ThD28AYjAcDN*)`&Xoz zEl7mY{LM#bC>y2`-WyzppWb+?wM&D#gQp2VH1R-8I;amGKx%7XoW)2^wZilVkrsq> zEn6gR5ggZ*60!d(HXdQvOX2;Bb{hrFdNqohL+&vEw1};>B3P9?{nAwj5VIdIuj_L(U+`CsL zMk%8fp0P=UjxGAvyDI!%!oLq9Z3sg90IKN;2TtEWs|b9MWweH2#Emz8KgLi3pItMC~g;Ah&Ns<7PdI|mKt268{>%_3r9I1FEp1D zjcivg1Z)=iJvcF_%`pR)Pkjt4cQ82j&B^2>30H!IzEp?Ao*3E$$e1mX?JpS~@U&<0 z6(ughZ3uLRMd?5EV>1D zMbNtfs9FO}Tg@PXKOFM?Rdx8&S9pp@4!dU)?VVNVJ$)2#3pKJ&RrJjA5Fg3)S5V1% zC9rW-<}F<-D_>AfKl56wSvg}HD;*s!SCZc97CnGZLC5~zlP958uBs4OxU$BKjO+8O zj>Ke1i))wv7$P2Mj-Yiq+~i5Ul>6i!3-!u}=IT|eQoIgt1en78R_Vl>(qD4C?G=vF zI-Ae)oHIo;Rkqf-5!C+Uuc$1l#h<@Ndy1wjEV0ScK|9&f3Iyy+KBN}O!p06F|FIVy z19L6`?G?Q2OJoaAI-Y`gY;_*6DVM(zGh{Qr%l*8#sSQY%gdwP4%0hK>Tgw-Qdl!<; zb6K-tl;6GjHCO+t+tTjazkD9)2B7w`n_t1%>00mv-lJDig*fU%#oE)1{LO6?rqA|g zr=_2pBSGF40%fzpcBq9Pu&3U|Tn^b8>eCr^9iVkpr?q3y>fiK(-gNyvuq+C5?Ih`F zm-+?9Vm9jZ;XC*^gyqw{C+P&bHGz-m1eT2}k<#tpD{iq*lOdpLM6+(LNXIB`$ue&- z8x|W?ZeCo%${VH1OKM{Kat?9%ax13z3VS`4-4!NZU!77tBzSPkUWl(KbYO}jn}9ei zS8Ep;!PNiDcFxQC^oQo%xGFtJk8Kpn)oqlqt!}i_%9Vv&3?F?@3#w zfYcUADo8g)Q#Ymm9KF3VJo~s_?J}UPLCU>kX-|qw183KwTQ`EUaTT;-{6P!Ofd4VI z>Z`|H;e_aUVSWyHvNiZD=^ORaKc{VXI-?%D^8S^xn92#z=?$6n&QPP1e3hR>&K7+7D%ItLAfB))0`rH#Fd@7 zC%;IRJ71*9d%c%8PfkC|gkhwk@oJ$SyVMhFe(;8>{G0zJE^QZ7h z4gI9F9?(X+whP3T1+s0!G&zx?!HXH^@Kx?s@DM-xE~bguMdE+(7aNO=In-geib-S4pH$l%cvZfkdh#OrtG zH$LE)H#f?tvIzBpKXj%EU%Xs5eBCBIkLW>*t>vbS!QPqHpx4zXlq`lNGf#03lqe$PIw%9{fC`l6i0a z*rd(F=KwWf+?Q_BOZgAR|MH$KbxB0iU+&)>yK9`unYqsaSuYwi1g8a08JM9s0tL*; zD&i9Gt^(q9%R=G{5%q!*oG+sg!QM=PGR|B!>`W+k7C>qk?t`z zg+3P!L(1P`e&L0a`*cxCMau8K26w4Nb?ZxYSxHrNu2_&h`?E%w#x&OCARI-}l^A)Y zv)Ydg^n<#rNY)kS7bPwiRUNxFLFPdTCKYkL)s+}DiJ-#oT|n9)CZF$_I$UQ5kM%2Z zN_2~#`8&$lgjV{@%c3kJYXsg8gYNhM;H2AgAYV}rD>C|7RQc*hfQr6}{A?_3X9)!@|I0l$ZU&$j(V&eo3Kn!>x<1@vCTi z+*^_Ru7F5k>OICw@~XDF8hrF>F@3F1damCE1#@6(PXA1&!AMOYHffWXID%4a3z{9- zy-+W9XZ#LYz;sS}PZZrV1X4*2+gykx?*3WYQLN<0?@Qj7KCh9&4P3fm4~kQ~I58(U z@O0dY9C6$yD=HaGy)sa;YqkXZ!v)e)KHX~+zeHRGg@<4CFUdOsnMI7N{DlXin1#?B z!<9)``)(v@vT8o?;nJfR(!`BXc%{6x;&?NnDa%ihSi>9U7?=KHcp8 zfG!t=M%35(eOagBiZR1D1W!1BMyy)$+O?AZdH;FpiBrgpp>x(yY^o==FOSmA+dOlR z*89LE<2m7ncNo+wW~H`&bua4&rvN=BzSz!VS?JH*2BHz~KepZec_d;aweyMh@+=r~ zv*k|7;O6F@!^=5=fQKm^KZlzTCX zzdo7)E96IFyd`QV!7e*E+8o8#t2M+CPoLruf8is=vOQ3do6E%bIMUb!YYAE|i3cBB z3#S4dZ!qw1rTh>}s`$|7o?-oZP!L;?EF6zf6HpVe>Z>Y=5&(T4*)mn5+j#5uN^HBr z3b-gTiE`>9SLT1~){o_T|F3!)dvEd1q-W&0$Xq&KDJBPQ(pY9?RYu@#q2p~k-r0;= zwVF5LyQt_XuY3v}%fyC;73b^vEG;o$D+AXI6CDCNKFTk}-rG+LN>~@H0qTP-BNEv3 z6NG}QLiThA0V1vzH<}T=*swZt=W9KB-cP-Hn^Nk1t(RiT5?kiuDx-q*42%T>n&_O1 z=f}vdjA8!OO9@F{P;I~jc&(ARz^8r%LKk1;hULCsfN;9tOJ zt|G0dm9DnDcS9(UxOMYm=-y(~GvV_Gfd+vW-zUjvzl)6DfL9)g$ARP!^G@FTP?>ER zs;mo_yW13z<#ZY}!6n-d9*E)#eZAe5!J&M^j{E5<_@Gemo=EYmlh6iKJX5MiHDWVS z;(3JStL@>}gdY=@Ch1j(>|A`GxIVAh6E5DGwyr8e?hv@>`}h9b96z|i2jjgB-4iaB zKmysr(6S=4gq?<(zcFYF&pZ*uh~B`2!0McZ7xkF@Wb;k^v0(QEq@YkK_Q$ZRRkE*B zlh}HfZ#LH`|Kz>*teA#&VTK1=aR#@XrndSzwbkz#R*xmpx||1~288)X?C*j9g;r}c|{4gkrQ%w#a(U`ht^*&lvM_$ZugTvQHqFsIXhPm>RS zrA0TYQ%^7rb>llDq`WkdkuN1^&wkr2Y+qw#?t7Ul-Xh6JD2p(uVsn15GELV)muP!Y zIV7*ZU2R>msd%-ztmD2#w0su{8Fa9DyWI_=HZ60vtBlz?p)bl5L1#rCV=r8E>ooe; z&v_R^s;gsTG^;A+KHolgY84kmtDJQ+Yaci2dU0+1)Jiw+njK4}V=+|axIT7evYc<8 zm{5_|q#4>t<^Q@TRMEYDdoICJfGnx__#cVsiMb>;_mn@!bvpLj8V7bCFi3NyMN{|v zAeY=7vn~_kYv0A9_@b3$;lGaW(Rb+x*pCsuY>qMI!u8N;90?XxK&*Ts@-^5zWn5}j zCwLIb7!coYMdr<7Di5CvQJ@Fuy3ziyg@DvtKLpu?_luwMep}9syBW4+oC?s*BtUbZU(XP8hUQ29cF}C!i!YpcNFq8p0(R2 zcf72ReRk%k@Kg+@IU3d7-8xi}qvA+v6&8CJS>Y9>&;GT3L5_J1gLrwVdYS&*5enxn==Y%f2Wl-xXu|f2>WU*x%{;UBaIz*dtRdpFu{wAs^ zs0m*_ztUeL$W>;E%w3GvRAlH}R1WPRSD-|Go%H)Z|W;+2|QxgQ)2$rcSR4Ow|`xcCoYp}#BRyJDu|3}N}7 z`nha+aTKk{3Y+6&H8zLn`;o%s-}XJDxBia4suM=?BzI)8_v~`G98<7CDF`RA^4ZJP z35S~lbC%xh+znbFlY8A+#N(=9u}7uIw$43$E}OU-&%$=`!1k9b(aKaG3)qm>TulUCzn}6v!K9qES1Z5LzHcRgINZWb z1CxK_t!mAjvx!W6QlY~D%)8!6RXV6g7koHDEWPFk&T?28P{dXS#f;ce~ z>Tk^4(}>Hl{fbt-@6{hh8qqI$Tf}R)Y%DT@~a{d?-7BXYg!^LzJ`#hA&qx+-n zFU+9r{cIZcCQWEN`Wn~#H||PL(87u{k1~ekYn%=YxR$YfgVrqu$oJQjK$cKEUlm5+ zCD;udpW*d8){!;-x@el!xGib1gGUh`e7UYalu~g&VBs%wX)=v>h!OnzRuc5ZdiU$l z=pd&9VWRk5oefBx*QKusWc%iv`_aFCrpiT^sTW};3Sj7$D|tp|Q?BWb230iLD7*-& zA610M=Y7B-qQEx<@bD)tllbpSI@N(L+hAtd(SDgpvW%?&zN_E02qy>|kXVz?>pFr$gjXaIegqZUhG}gXt&wseb9>e(uwLdU2g<%hhw=5Eod~Dr}f6 z-A;qfBXY0w$$cA>ozwlhWhlQg$Ll`HmXzu`CGdexoBsp6>3b9|nF%fIXwd}|ti!n& zlh|`$_58DqH*`e6S}1<1!r6ezDg{q)<(yxW4qpQc8u2%~;?wbbscG>0pI|*?nZbVP zE*f+Z4eD%NCajP55HCB3FLcd6%%J|u9$vc@1<>SopvLAFkB>D)Fef?hguxa2sbE%$ zKnSl&k525+Xwf%_i5C?G)>1yy2Aol@wz}ax@qlAIXVCOg1Q9~Yhe5;9XB)V=H6pkd z6qg{oTIve!{rO>oTkj)i7>^yK;idM;1s0Dc7s2|A&wqNkZjHtzZ1Vpm`k;6$ksHY8o$X$#UaWh z?>+*B3hMA3_6bt^1y^x`GF(D%&j`8s2oV$+N=Ab5NC2LyS0w}^BMJTDM9(O{eu+RD zRLE}hqg_PMTCO7DJ(Bi!iPt@z{N8=? zpQpSSMF7^1&B}iA`$j5yFIAyB;q`8srj)1Qp67L`NuC5gBy&pjc4ou2camFY_eY7| zgmuRuktv;wQ;FLmX5+Ft=VL@syd{JenRJ6mGD#y@M(ifHZ@-ibNKdESa#&RROj{bP zB`el1)lQB-5|#hBCMAX}7SSmZ)DelnOQxgH2`H2=jYt?x)O9?HN^=*#a~Z$$$a&!L zDUM=~LLNs5$?TGraCH~AfBnF)<^6gQyN3P!Fq*ggXZwvmY8nmmnwSq7U*j$+MmR=+ z5BK+*qbBMN*GCimSV`2+>wxZ5S4Uq1-D_>Xo*2y6lcvkp3P4k$IXoizQC z0UWQ*@m<3Q;=Z2U0iKc}G%@?qv8O(9zYpSRe0zI56{4c9(MSYB`h{az)jMfj4Yw25 zcU?uc2Tf%L<+jhUhr2{UspKfy$14f$B^y&K3CH=vywu1W5_*-2!qApWBxO~wCh>+u7WwA~vfMF^Y*xQ?86KU`ujEO#wBN$bea5BZ zrP^sm6NiVltA@}LL-caP9(4mEQXYm<`G>TS(_5G_J$YE&23=kJvg?+n%Yw7)t0d3p zed(C(gXryANndC%Y`-I+R=@J*xO%U`w2|;9hUTQE#jWZ9faY(d`CAP&c8irh~QrY zmP~rrZAaAhpoIwJ$nk^U%hJ)0sun!tVt-SS{-1FgpK#ykV3|>_p6&|dRWFHBFY8bD z0TP}`+wyrbR=aSIxJ(3a0GstTo*?n$2(`*3hy7NS>TwLdi@6~R?UJ8~(5E6N zUYUEz7fHZ3cHv@->*$6F2|rGXgjF5wCmAm{2WPX|Iiatwb;Rm|k%Ph}5n2eEnNizicam!kdmST7F`lF%s>`-ETljMLx3 zsji-SmBUiYQB@mKhV|lM11z*?v=}+Q&7EC3a7N(-f7{3jtj!yaC#zx4bL8_ZFVA74ULZCm)BH$8e(V^P$B(75Ab`be!mMEkfRZ7 zt^0LcUj?Ym4f|-1QMsm%$aZLL6R-5wpwk~T>@7L>>OU%kbprXsbm-HDM#Ad9b`KUh zh1&`ZJll*Nwp0JxJ$ISiHL1Pxgsp;4 zXh3`tN6Ngjs^CFlmLstRyLLWv`MsMEb#27Y#ardM#ch?X@qY0p=;_oYJnE)8v^Ta{ zg!kjx33BkQx{k8r04jW4gCew_k?C6kmireIR2}sAPcS>XPJJtz`^e#AzK|JBY9ear zZ)~+E`NwhZ+EgTXbV|pUPWEQuRIWW_r@rEg0l$;2%g+<}^2ErW+2c@>i(F^^g`z?!DC`Od5+E7{bhu_A>sw466GBg#>rAQUT zfJGSfWWt4~>%t*4c3 z!XeGo-uW_E0U^B$c~7O@NcTP+=jimi8(Y?PAK(Z&5BXU-`pv+`5QnOAD>J=SW>_Nv zyZ`Dh{$`x+zzc3UOG91hPTU;TzN(|8-4y3|?N)c!R7^4k1OFqXH`AW_({J;K0NM2!DtM^jCHpSvqb3!ZeG5zqdTHM%_a4_bu(&3R=4}Dv!Ey4 z88WE3t3j zte>2&7_5$%YbGy>f++_)n+GQLVz%9XB8^%nx!pY$7Ne%whcq6Mqt#vH8m46}r=>U5 zL^Q5AE&De}{>a5;F?FzQzVFA{GNoGdL~Qk)mudGnZ_Td@(L(S>d@wurEDb&XQafm` zhJ?-~aKB_2SrSa6Q2v2}Q z%oWa9-StyM4KfwI*lfayo_dg$$Xc86v`b#|t!iJN%BnPzK7RYfzB@)NU4|WSA}c0~ zjIw7rBs`h14kp#s|3Wxw`-pyrum?*MHsMXyW4xC3K~hzKTsY)-_vCt|MGa$TDyMH^ z9)$`-p?e^-SNP|D2|tRd0g$W-!guj0^1hKit%eR3ZRj_fo%i9V(f?ZN^DjGW+5*kRnO$&f(K^z`bCxY=66C zHsyq0-q*rz_UmSu^HcVmBaE8wq$yb%+pYy$iM(Z3`0*8+6=;=yiPXIK-Dq5nI6?m$ zfD~mjvik6F@2R}r(s|ZK(k->9C+bPh8r^cj%_A9ql3s^mmHn>B?o3yZI1*h*vmEOs zlDXE&a_-gK+o~2K3gOjFem_um_a>ITQV*GilT5ohzub&?kP?|_v(MyUT*la-BGrEL zGZ#1M&>v(re+Zq*^pZEAaCP=cs}Yl%2UW6cx}r2 zg=C0T__gFQe^DT{iwp;jX}vJy#$RLI;3Ni~=staKHtxh7d=EH`Py?`5{9It_@3z8{ z$NrW2em=^_;SxHAxOWQQTtQf+FI_a7ybZ;veY?56gK_p?C2v&eXpa|lH?HXCJ0s{a6GC)8VK!Ii-0DzqXKrnv&rlLLyj2-Pb+EhFc4JtRt(|=Yn6hDjfUKxE> zI`Ram9mj9bTsD@5vZ!$!Yc8L7ig6pyGia%p%2mC)zcSWR`KC~dLeG?Zr^-BiItlGG z-db%DHK!+W%d@`bUG0TYk%>@WyWnltf-ci*t6OSuheSC|wAIho`)`aVUbZ66BrP^2 z{vCgjgL{Rq74bE?{$*t#hF$uRr)`n)bHOyP^zSvzTN7Eb(t|@CEjw?DwBrR$I`1~V ztu(r;7sK%UV4=xkq`>5*^1e$q*TKiBKV{DVBVzIt30d@*4Z{s7mxiujoE^PaY`S1? z=J$hn$n5g#?w3Eme7vQ0E@am8S9=p&oa^$Yr~A)Ov7v!NvsXR;{+xY1`1I!0tMhXJ z6h$=6c2!=DfJtN_@6#*qu2TNP!q%u9)}y%*Tpo+7^1RL=cF{;d*rbnermcva#D2O1 zMyhSGSoW3Ux`@dmn7ff*d$ICH68(>oaq$9_?uQ5;m{h6$?ju&RqGr~Lid)sW_5J%kjxNcnUpzx9-_Jm&Dd;mE#<=}|Dkm1d*JWCb+qNoBr+L?+6ssfD?|qvk z++D#wj?fhN{tiTrE_!Dh{NYoubF}P_Mfaz-ek^%b*8d2ZL+jjn|4RYs>WzZp@8FU|NTKan%nIkrpmyG=hozUKz|)=Y01&79K9IT2FZ zzqrqTzW9-%Eycc?$QBlcSg?cj0VRLpqK5g`igYlq3&9C|&4_{R&vU`<4$YtDQ9y{T6_4_yLZQ= zQRcMnkyEtXVW~dWB3E0PFjW0qZ9$Egey&Ud2Cv-=hMS&gGWk&&-|U4MyhgQibTC-R zVKMyN<&=-(A4aa3uY}D(q)S}=B$kj+!cnO|gtkA4vz;vAdNDdAx4c7jW)yv(df^$% zIl=U*uJbIw3fY=Z67L#_@b9#9s?DAxg-n(T{u~|A?8iQM#8_sM6=2%2=s7qNeDQ{55ZvDx&;$>6-mtkNm?q0_KtHAmfliffU{fE(AW; z5A)VX1R%Ay|JoTx1d@v$atw+aM@?%SH5J1Xt8^p{XX5O?l^~|7^i;-YlJ0*iMKV?E z^X*Kfs6SJB1#nZH8XIx;k6}9r+z`0oJ)5)qtwMFG+BA6lZGonod&6lp+b<%mRIzc@ zC5|Y=l>4}Y)qXBThhp$KO9*^fER0M;ooI^ZslfHE9TV`lseKX5mT%@06And-yx!pO@ZQCEhHU zNS~`Zy|qv$r}4OW{Ir6#i~s)n;EoE>BZV!_%Ej_97vXq|s`Z|;?nY^P%c3oW8CTmP zv*pVcp@(H{wzj?foHYIr2tyfz(;}WK`ZtnT3}o^e^^ba26s1%b!GvVS^34OH)hE{m zB{Wa?f4H$o8@Bmu{__ik%*F$J>X8{d`sGlCH~|0nQ;=G^!2?FMgP_f>1x0y{FKTMz1wVDh?C1So6U1#t%K_tUh1_40o|zNzZzs2vU)pgt4zcMo zhxt#d4D7H!Yr6ZGJ~TNT@P9~2_diks0IC24=pOL@my~c(!~dId<<6{dAl<8KT--9wpPuQ>ZhSURH5_uu%J+SnU2=~k+Q}6!}#;s1*&UXw}}4t z+NBoHw>1}}yfu3VxZRO&^rGRz%aE@%y3q~ps)6@G41&h(O>6%nrSoL_vyG8tQKJIm zj{lMJlF!G<|Cf}ldvB{OYMrM#|3^xS7)_IQ zdEM3Vb!WQNsL-^#^ZUVKi_fS3L(0{G`2Ufz>(|%ax3&K_DUUZM{=cML4F_||HEa?vMMZe1E=ZM5maIi13o=Hu)~TNBu{K^fx;UA(kn}6Stj+ZV z#n+n_fZeK6(?pFQyBklma>UI5+EA~}6n%;6%~WIMz0EX&p43*lrM1^qhOI~SR;FXn z-qurMl+<>Xd#2ZRwr554c8+h`-gd74u+&ao;JnvPe#mz9PC?j@y`92vD0;W(G#m8# zGF75xw5!wt{e#9{sPtjeAeYbKvr!4OSM#Lu!C}j^p7iI|IcuNK&lf#v zKew#}9ejSV8YO+yzM1KB)UjJpd(?T@c5w9acv$*N*SC3}FWs3@rKU-L*BzvZz%0?H zT02>wr>~y-v6rg%?{Z8v!`|>Rr+^|^pI%vOW!F+M(($dmvVRt+16a-zowgNhS!TKd z3cZxfIue+oQ1`LR;t3LzPeI{kFxZyb6WBM#tF&IC$iWtQ+{g9JugL{EGMc`kx=eex85+ z`6--M?rfFH?RU0z^?K?5L(1f9a=$iHX|*~wGF@JWZ0ATn;#7)xRgpL&?@Hm@1?sc^ z_8D$H`hCzeBKPO8b;0i?c95F?;0U<+=+Bp4+E2d;^WgAA<&^}#zxz#V>wmvaUz7j$ zZO-O)_gDI*l7Bx|g1`Lxxf(71-x+>JBw6jhXJ8}I~< zqHIs&iD7Um&E6o63}kf7N){L9hmG^P#d8&`OSoQMBL+6}6IK~7zdq1qJWm_e-dG}wz`9cZK?Fcd45*@v(dUKy%5e4;~$9OaV*^!$q6jP5f6|B4nD=g8Fc*G+MDjP~G&>RwLF? zBCS?es<=CHfV=17-exX><))&MeCD3MtwLG4VR|CAhe*9herMVsN{su5uQmo^9s!Sw zF7eD7Fa8zDu>uaO(oz_RF)d0RjywK_QVhZ4m&_XB!L%=5eV(cv z-IXjX%L!HI!7D|=`X55*a@m06FQe+7AYZ=E*Rn^aWb+PHF%|RTnM4@F4a+KZZq%4X zqTfXZw)%Vd!}wQJla=Nyg#)y-wfB+9M(9E2P^}87nfu8a$J6yp9rifnTx$#%4=2M0 zwT|N!w05nK(#;Va(<;6@92$X(nGVPF@JG4vd~y|2y%-6>u@UGbh+dPPrR zK+Wo>o1i8;1)mfya+7wD&}^i|H2ysP+TF-VmgZ{_RixLzMVA8F#dlS5gIog{L;t`Z zSRJz9O!65qq7M?_u8vHI0Fy85EU5{iSKXOBvlO%yP;Qh~jy|AmRGfU@4w-)gF%f<- zAT9SIYsJ*rdc^XLK1gnyR|7b~rM350AU|h$7CNm5Y~CfmGo{sH@b(8id-?mFLPJC? zH?FaD=DiZR9mj0U5YF!|vr*q!{GJA@{BD`BMefBh-wS^ZeODA2@bLO6#Lh`sL=aODGUtqFjDo2p@p#Q^zf47siU{Wx6n)r^`DFWOhT+@VlgER{ zIfanf*EZ87*^ohy)*aSW>LMwT$tfliN3#Q{3KA|t3~4nU!L5ut_H)E#cp$~P66`u} zf9u&`Od0777cYyS$i-aVpq;M1w8`BI*v;XjnHGGHW6nodjR!ztB!zR+SlEel0iXp9pu*%%0ig#*GMSlX*#VH2v}y$twj2K?b1+{(jv zfD_<-4DmU8LxF2;x{p1F`k5)k69~|Kii!cuJrxhhXoDzXO z>UE(5nu=fZ@KJ=Lbr`RHH|;HQ1)kYG!rWs*!S7r76?40z#TjeDX}$doxvlR?TSn7k zAA?x6X3i}wdVAgIiZ64|(|N7ZrgJk6HtE47;Ks=hV64jbl4&Q1k7+&QM1GnH1~LM^ zN7EFWDh9(RbxenezRJKL#uR-}*^LIGUCj%4&5$lW2A=)=B6N&riH4)+yv_AlgNgot zapCKZtl1H19oP2W@mSH=XpL) zij2*`NBB?cYfal9U$ycSM}258BRGbA zjZJFABd=`1qH1p@>?d5;0LnoAbxu(n>1Tqa5_l$6 zh6>5xn6Refy?G*K)56&~-}`@&RN0S!xspsc>tJVRVS(dt4=T)P&cf0#@RSVTw-xJO zdnW!N%yQfUOpW2NL0C>*3SC);Mh_Bg0( zN6vX(WV0_f-*?WYL||PS=LC}pSW*kva*FPAaV_C!07&Br{<$Vjt%9Jp{Gje9>}5ng znXn7s@nlMbe)TxJW4LM4Afe|#=B&Gqry;LZlo?@^ZUGSc_ z{-GHgEl+JCaN|KBI^>=R?b646Y26E)8&7R_=Qu5lQ1!v=!r`W|u+UcnmaRZ~o(yLe z)yN+}7E(D65b2Ok9U2kggGb~ONqcL|k4!7ztT=6*EinkR`zQ;*6twz}SA86P$@3!J; zMv2EV*szz{46%Wl!0?ZiB6ANQMaVVBFe@&Sw*7=lWJ_@E{$j(pT6T`~`5Z11zfx%sRog z-63ytu7lKe42x2Kgp+g!jD)xgYeTqcRuv$$Hu+BGoPd;1q$uLN&sq!Hyrq_<)PoId zhzRyi9Bjr&@RdW*;xV4^CpC}!_g{ql!s=M`$|a>|W0F zvQ(@?(W1Cy!vJ@BdSMy1oi#L3)cVr3nphW!_SEOUcsjsyBnm(1bbk;xkrhEi6xR+5 zVGa5LQlNEbKe?B4*-X_JD+$AU>+z20*3@RQV<2(zifJNS5j>I-kr!InePDK;C!ha!@r8Ko<31*;&GIQ9;d*oD zAiI)9q6ufHT8?9=+KwBK4`?hXJ>vH@0Xq-u<>&o_%Lb8+=U_CZ-PK85`W;ewpPP{Y zeuUIlDIllX#2ca(Ms%mYYVD@MoPztIp6Q4QnD`vbhj}JJB2EY`5nzpAF(-_5ZymuJ z9Q(m>^;=%V#K>iVxp=}Dx4Q|4A)*m)eb=VC`y<0#)>C&A}vJHyL!2rS8SPZ*m$nk#za%e19l#R%83 z`nc%pNxj$89B zn~AsuTv|_9RRO<78J5_R_UKWiSx4-Or!lQ|#?5vHO=#he#J09#n@RJTgihWfgRK#) z#b=;k>#enikl<(Xk5Oz_Fh}GPTtVg*NQH3XZ!b?e`L7;U&T64APTlPzdYRXsXfAV&`|TpO`}-uK2=2>VK2QXFsloohl^|jc z{EUE4oDpgxScrg(Bz;AaYx!=v+dOa$Kx1=zzj)lYT9rb!zXmi);Db+A1(kMAY@d@k zfg5yqpZ1Eg|A55)D}J4!JJP|N<&Kz2InUXm$;W4+W@){gN;5K}!d<__0bIzfJkwKw z=DyHx)@Sqd^(D_$V;!EJ8RfabTW4dHZ7O$Mpp@tPQ5t6t-kZpkf^xCiK1{5E2@W;< znhvgX6t-<>Y9f~N#u9wz+9QNBpe1suw(--6uJBvKShyxNAxX7v6FYlj;PMMzKc9zw zm?sl*~jniCKY!eB=fE0x#vr6QBu0%mL-H;tf5rwZ z!Eaj|3{+z~m)JY!*+H=Gf*Mmlo4hFNbNahB`A54Iz5>Iy1V@kJzOE)k)WYfGX#!YM z5AhHDAhf7XlOt^Fy&%}Sx!eZ4I>JxrVI!cl?_sk@@aQG`7dLrjjrWDHUq{H_fueEI zp1&Y0X^BLKp>cnBLC!TX&={ov0h<-0BwmFxJ-IgTOwvU4&Ped#=PE(LZBYDA8&(yF z;9~I!ru1%@7Hk3&XPjKKD%87<@!4G8u)c4cdgS#(Ici=G7{@0mh1#&9mu_y8 zO|dsIk+TC>hQqecQ1;_lS$XR+Q}>RP!Dl?wQy>?kGLD%P|HtQMPo&muPcK}sTzGPD z?n*ZM^gDC!_R!rFyZN2&v@aorbAxIor_YAvV+uwMx_1r9sPc69` zw^LKBGt25JKMU0|Q@&-ufv+oMBwFM)8=>SSD4=C_w3933fieHtaHjFh#bm$YU&v>e z?tL$ji^L;0p*v-b5es6}V^=S7s?l=ueABd$U7s|Q|KKZ{Y3l4tn5tTauW{iA22sqV zPa@3np7XQgr+x-C$Ove>jm{*tX51MO(D}N$C9M_nXMm)C0G+N-CAn;sogCOi9t@w9 zlb2}#$&Cb=-K!QyvR5uGRivs;HkVha>%%Uand{*=9>)`}D}%I_h~MxdOH?&SOUT*) zm&G5X1QQghw~0Fo(K*MWa4lv!df$3dQBk;skFiZ%LYd6dkS8DTYfeWVZYbusRLGXh zYF6Tb-DytUu#lqCmK5J~V_pY$!A6$NV!;odYYy*?hf+F*IGLpV{b4Tsq(2(BX#2!S zmM-6!=3+(bPn+fgtIpYE)gA+N@6?3n-p^8}uYcel3I8@F?&hdtY*;+NEUk{w?HiR< zyXiL}P8pMPWHm=W`mpXz3dzA^6QuHbS~dd)x~r&lhHvi;WE&3OicL&9Q1lyB3G=RM znytjBm5=Eb?X?FXNpsjyumq)y)W+J_YUrLee4mwlm5FL7*=&d&BW zb7^#0)eh;c@~YtXiWW{HWB_{cL22>_K$c>QZc?u9dSpvLoV@m*Vj(5DR%Lle!b6#n zD_5_F%wH(e6Mu2lv-Pw3ED|k{du_7r)7Gz2Q!(EmId0cc^yxwi~od-p<9bEvT^*}=vGMTrK|#B zWJ$s1sZ^ajvV}oVbGnmRsu)TTCA1`yt}5@tgxMqoH#@4_s4^5yi1o4QVDMlHj0n>C z60WMlIG8E2*>P<79Tw{+IXbTj%ZfTEDspI611wSWoVTlHMChSj zYY&q*G3mr3Ch3E>cS; z8TaeyV!c+pi$gMtO9bJ43IZIwZVbC`bJSN70p5%ymN=-?q}cnb-cKhploC{@>-3WD z#2iaWe^JRk{lLt8CcSYbUXe%uJ(RN$Qe2N$xme1*YLvtSwJqXh7ds=YV1`k=2&w*q z2PVuf%+~K@`M&;i-c_YfsYlzf4wGhheL_fb7SD6>OSyQ*7K{<3?UY!~=HWJPAY^4D zQ|vCLLtjj)ZUCq!_dm)wmv0K;`r<|4q~f$Esa7jle2YFBAm-u8() z(WFZU2DmHdUfhBXc8hLN5GQv!{cbM2Gg5!Ttxj=l{Qd{l(IS@ej%aag3%efrhd3u1 z$p!>b*f5O)tzY{F1a5#leE5EFwB3N7{8qZA)GUtR5sE9o8+VKR`pK<6u*}~s$sriL zVw=r)iHK;XmuhoRQY9sTyK>BxJiEuyu0}Z`M@s4oB^Dmx?a*&NTWr`i^z2N)XG^V5wKZNu~Vjn#d5OwPwj*y;uJ=6)D5bU_QsRAsvA_}aVu zHjY4xd1R>OKj|MU_Dy=m>z9w<3Ez>b>mAJ=EoVc6ibHK2i?i$i!%3?0*Oe4}I#>`U z&}^n^Yxc@7d%EZ)ir&)<8`D3CcW1jT@=V1vYlh#=`MI>EfST=CyjMH`sRGnFC{s_f zqaQyQ00%=e5c)gCbN6R{Pg`gkW^5G&+`r&xK48}^Z`9r*hJJQ+Ma8TwtZ=Dou!lq# z)~S!<&_Yb#RO;(XS3Z%Df1%X4e8s0{a_@p5#LnRDf;6))tomk&K`Gx`$MDs#3U0*{ zw)P^#79QW~#cT2r9qKkiiqB0WUVq`Ki!+x?m74zL zxnah9$cv;&;TN80%yT(AEzGL)K@VHgPhQ+=l&;1J9!j~|RPl+`MGgD^?7i*wdFg&Q zccN*2svcAKHc7;>nx7GHkT30Aqi1?!_e<`4BeCPA-NY4xT}b{4CPEJSF*` zQ0(oJPGp-3^6mQ*h1~_Ib~(}AntIr3Z({t*cZs}&hx87;ANj|mwjWn-0Z3J}!o##i zKjfYL=k&-#tVBT!{;<)d|4yYKJGdSMij{d<&1g>3VOCdxpmNyb9*Ip=;~4?zPeCkw z&XkfxKMhbyOZ+CAzKm`aKIJ<%*NsYsW~KqCIF+&;yWysg1jM?hE0xUAb$qi0SCbR~ zJuS^NCGoC&A+CdNLKB_YKFEaSxpd!Rc5y5+3KNrJs3&LwsHZrTCUCshI%aEGPP?K@ z8^wxk&NFH-ba(FfYQdm%@DLuyp-PVS$-r%i9E`~NWCrFdvw)&`)YQHQT#;nQl6L@P z?N*U{41If*cqyI3Lr(nKj-xHbc_Be(x8lxh8CNkAgMKF;N1<*WLk?&ezp{%tnfvh7 zik?>oc7}bT{#=4C!N3KC`2=t4L7By|0(tzm%D>DG2l0!(SR< zj52z9e`>iQV}+BFE1dho7ln#BQ9SSa#g*e3I!G;-P6-`BjC=9fEoP&0OYyELml%97 zA9dg%7!)uJ=)54USf=PQ=r9F}ojaJNm%iN&FrPsl!>(Ntu7*%l-wt3*cic6+h#%aqYKd!xiKosNZ7HBy;JdkFaIiuSj;JCHXe$6nc|^&n;Ek@254lV%o_ljiCr0L1lL2mu*;Dj2p) z=x`E%iN248`B}7pMs+WaA=UU&ipG=87+sb{R^`CmS6rTE5Qojv)tfMfExr4AcFb$e z6IpDRNr-E{kjkByQ(Lhl0II(Q;px2XOVcWlvFN3+lQ-EopG@?=FZxOyKS-hu)5>kC z>yF0Eu}Q5-@4DN4*yO98GyEz5JEFkQV#SJ$!vj0wgUn(CogwPTSStaTli6)PS*yzC zsWc?tg^>vrJ+T}Ryl6A74u!8H#+&yd)y=f$H&ZSQi@)zdN)Z!6frKCuLW9Jny9IU8 z6kHs9@o6G)vS(W2WQyQS-Xa!5k>v0iu*eum=2x{!1mNz@5ODzEWQ@363l|w@vzUWI zzNN0Ljta@?7SiMJoA3Y!gcOr* zHE!$v9vY%{yV|!a^iDEplb+~+dFJE%OUdrmQpOGwwznin(*y2C!qiq1*;j=;W!MNE zY=ouwvjCgL5<~$VdomJc`Rhcrrl2PkVr87xxa4r=nhTdfj4HLR5TEZ{l$!xcktjtq zTx`2V;df;^-D|$JP=WM~$}C{T9oLLkK*rv*rmG3SESjMX&BL`cvC#z~ z?b8)E*$BA^i(J~_gwb*5mWVS$W#wajjj?S@(%djcTu_EsMb?`u4Qc8lHEKLCB z35?A$nt8!-HjMe-y!dK!A@{>d! zpuF&gr(H3gTVBCk>>^cME6@`iM8|pSnQZ4uT`NKk6_PN@dEyMjVwUrP%*w)WW~R%# zKcg#mVppYC?wLfiG^N+)YcF?nu&c_9O{I+3-K6ifOO8mwwaw_t{#?^n^1jrxU74A`tUJvz7vtBMkiY2<;r`cL zA(}xz#EMI@XTy z0{roO^-uFtiJAEGy~K|d!2#37YeUUYI$!UQN$a2b<3E-uZ#ypT5}$&c11Ht_S{@|v zhODpdd(VAm&y;6>*b#V8U2Lw2UmSQ4HC3KF1e(lY&x~HkX}mt;AnkTMxPv!5p1q`{am;*180`ap{Owsox1fPWoFI<-M@t|f?g@+Q5WiX{gu| zCuG6a~{{JV~}v<2$jf{R5$Wl%c}~vH{{0 zPlp%ohtbV08@E8LHjwI+9mCUO*Z0G9&W4+`CtRX@QP`x<>Tyi_CMzSU*5k3^`|$w+ ztvZz9j^Ji>;+vbOTcASktjW}Wngu>qvb`nWx1mWse2kZ~;VwUr(UkBQ=e^ShdjZYy zr%AAw+_*@75G9F|NpR#3R3?c5=4R7%|61;%d3F z7B=E9Ts(NN?&$0|<*aX&LQOlG4!_y<4dfh7KfIBh?niCoT!Aof3(_Sw&TW4;w;7hX zQDf&D4=Vo_`c>Pb6O#QW@%Ylh=IDFce%53!L#sSSt2Rd10Bwi8>Pp~l!&yDywYsJS zTV9nslL7m=dcs{MRcYHtNNZKCk<07}7hUFYeY>DI2Rrs&iZ(UAtnnwE6qQ1PIhZA0 zc`*V4B5A<43A;SGd&$%Hm77$M1&nK{43_OK^aMKNqc=o#PQKqXW_N~d_ci_4;dtLB zn<_qLR66GPK3hLmGXJ$YH8XqlV8~N!b*Nq|yfC zzz)Ru@8Z>6%Q$P$H_$jFdhQwo3O_-GJh@%QFk4N-6WV_yk5RmLL|(+sr7088Rbt4o z2}&*VmmMgs=WFZ~+r^lU?D*!-YtAtj2mEV;<9P4v#qYmIRIsB^iOdgefqQHjs|^d-j=9N z>0kp@YN-f}Q8*K~SD)@kTPNhxaS9jrWF|{2R0_rRKV)~>?AMcd4s)pTZuLH`q1gjV zZP$l5TwN}Hmv?2fw>4XQoLwrV5jWcOl9fvjyXBa%)I>+e*A0bi+=>DFTayPhWwtP? zwsm%y4R}kdg`YJy4ytQx6qS6s)JD&0CnyHy6%9<8dgH_yl@b9nr5ayezp_>TviR)E zZeKwn#VsZV5_>~tp0~!ij+OSyqHKSaRt3M&ec`D_L_-+k^XMDwtt+gD-I>QP{nPzb zIuBKpP>}05ob^^mAiq=yZtwm2!Tp7Yv=R76Qnir!>!$;r&R#g{cpm6=V9M7)69x>% zWg`jk?BsK9@lf_DLPXpC2{4rJcB#_1BAy#$N8+qUCNS6B~tNzji8$zKY zAU2?x5jdSE0tV%+Svud99Kt}^m6(dn;TDQnkr&It<6MkbsD9rgbnBJR z*{A+qo8|BMl>DV94xA{3Yx`7*ldmQE7=oMt)y$`_&$aA$9^4iX0X2&%{i>2?MfWL> zS-^KG1wj%j$%;SEhokUHS$D=2bm7)eauO(PxbEw^uG*!0wE96QfnI)Uv_0Zm>GYYG z--@I?=z?Y-uX3KdV$XX(Nx%-ye#B&0z!O0Zg4SM|^Ew?sTyWr$n3u)s?z6gVd6Z*){>Z&9wrRN6p&{&(nTC1M6({LSU8`t%cj8J+I6S>AK!nu2SBcal6@SSeY+5$$#K^ zGiSHw<_Z0u9T2H=ltvkk8#W59^-90DhrfPn>wD()iKMar;%)x%&c&xEK#)wutOeec7lionh`zM#154%_!bHv`7^j|Fbf48ncAU==?;L8*mlU0pLk|S4O*S5 z+z1$Z-h34-19R3GcmMruUswYxBdXIJyNXn`x&c*(riZVOBwjgxsGWeGY51*|kNbU0KUI!_qC2~`3oCx3ua&L)vC zIfG_clYi*sNk1-gA50OMSBjw%Xd4UyiBWTo;2nz<5TDKkS1!y%KIb_M@v{c~7e%3xlm$QA-Ow*|HI%LV^ zUN2bbgQ<|Q2VYKd#tsul*8?DdT-dp7FadKN-D2-2B-8@~8 z7i7R7V7s@Q!{>A_wl3K>Z#!U7rcZ+3_l5ROv^!IW?e&N86KoS2^?F<7A|SnAS&vk1 z{Ft|7>KkLAVTR%du3XpukmSb4bu<*-aIs}K1M0=7hErogMMP^Et1F)ia0rF>D1&|| z%kwEJRj308ZsCp*0>=VW{F#>pqC}{IAc-IP^FRm`UAH%d=|}s8!3-pHGhg&XXqGG0twa}v#ghC!)dqmMTU3$uq0713QOI9cBV3WFf=^C1E$!F z3xCS{axLQiU7IJQpFDa@{ninFk}#XGVX8i2N8DPV-RZ>LJq7+)y%Uxyfxw8YMtBt2 z!tK(HOZt!P{*eL=-leFFJD2`2T)ubdAbc<7D0Le>`1s#n5Q+r?$5qgK7&_dZ2p#A1 z%*)U~DiDBf#o2a%KFON%*`J}}>LsolZ^e|e&lEx@Q+=JcEY|1n-`*58HWo;O7z=ph zg?*uGTV(voQk(;vj^N@jiZ`2!4?hSeFhgPFsPE;7I%GXuNLxwmW3CCgr;ZbjG4i|6 z;latCkrE}}jXxFMy*AB^m(Ei%)JKxOGH9_;&dAeK$i79Wayv+54A1`T9Vt(Ms!_0g ztDw_ZNF59Eq<$92de)V|w#BgyqX?2n`J_b>leBdTuY*G-L}~&@*>*Cs2611uOrFv4 zwhTxJaNQ~$L2o%6sX|iaN#?`DS*KE4h-~D!94#6MoDJ?UH0QO1wjpYu0fnE887?%qm=Vw*H^dEjIIFmzNfq+U&8k znmK~of2^y*bFmSl{^pwJZzX;B_FvZ3$+<3}@3sB3aotaebA8%5RgW^?S?D@RApQ30 zG+*C0Y#T>QW=)DMn9)h9s+uG5GwD#lvyn$8QF9^UM?WpZkZRAn-aDvYCis@0KI)If z>WdWfI3TIM{>k>)>|Vlsx{M#QRHVtBcie}VqX^EH<2(=aRFA^P{n{TaMt}yWn-iqN zSbO=2?@9FcTtrEbntig-bc;>vBa>XIv-?LP>b|2t8v5~rt~lFBf1#R2iFUnBM`?6vn)|#GZDM}+wG#>q=nV`K-cp3HQ;eiNu=8-^;Ki*#%^g*^x zJ7cT8jNk?hZ|{8M%LpH?00sfn4)hI&z^3f zrp3ETS$t`37BRRi5i`*>In;}%hpQnnp#|59<1`Z0(W*P^RxLlYX-it-xDS%#9BiS) z2nFBY){S&`GMX2YfUw&bBB?~M&L#xG<@p^oM`jZi$&Wt6Yo_N#Vyci>h&J1-m>7s*K5P1QMxn4!p(a>#te7XNADB$WGWYAQz zqKC=H9*d|oBZCzAlR=-T1SQfE?#g}*O|#?N!NHf~&tu-P^DC`lu9#^VK;JOs=4k8O zgQl1xJMgcf4E!AlyOL()ukmicU1-Pe;9*r5BP1*_P9#DxoR-4% z9QNLn4)cn6<8pniYq^_u&+!tSCvg)j(?_zd6H9*#MMc+%SkqKR`{Nz-eV>J zsG41(4Pjs`#~fuw9pMU;3-y=m>Ul4(8kWw>}JKaZrVwmdQ>CM~tTUS1{vT z&Pmzbzc4BkZ0)A-E1m1Q?$6+Fe1->{ju)6bwX~pR8T$ARZH<=Vj91_y$-*;qX$?zh zl*b3rxl|3jW{k-KB^;>)vGtLf3BC5j6Z4&g(W{r3gW?Ih(wiVzp7XfW`xq?<*Jlvs zUa8t=D#{}3T(%eRhJyK7i~bXanBIyKnnHhK!*Hoa%BZ+$OnE98h994l+oh^~qj2rU zs5!@w4yI+8%5qyBTpz5JK2R|Yy~oy+F{bg<2CURdFcm%_zDC8Iq!X4&7@Nqr-*l|L z1m+bHnNH+jJyfpo6E4fl@ zpI9#uS&BK9Ba?)~lpoZSKW<4c9g1tyNB=6}t?Pqq1%&0ez1(Lp*A2KhXMw$~3&KS< z7RAm2FxeeS%%!yxrDpo>>Pb1p6wXHH25t(Z4g;1-`du2z)<{9xOKf$B?peEfG$vLr zCtk8SYgFg_Kn55qPnmX3Rdb-t=B6$*r!LN=zKK+v{E-?Ud7UPe)`?ABH?ybRmWs|u zbMNKaCPsW=*uSBYuVx%hc|qD+4iF`%lq%Q9Ljj8D{&ylXb}y5_ z>pIbdS+ItcZCMO7Mb>Pg7OlB%Qys$%!)&*F9OrGgHBF%exc1g1$2xTBDteiibHzw} znt8LpPHp@Ow7)5bT}|5kHfkam?=;RiMqD z*`KM%cr?R=#~u ztUT0k;!lU7bC^sIH)xy1Ku$-znz!6!#&MVfHz&pS%}x0lfG^b4*M9dn>zHVooEh%k zsVN!c#p_~*T*BN~)Uy*JkDVb}fINf?+;_HW^DNGriRiR$m7%~FG(qM`yy8W;i@1M} zi^PTQv-#WyJjl!orls&Ktm)BbB${0S-hk;t{_TYR&mn7DWUuO#J9F7Wd( zr|>Wu92{Zri!9#F#R5RhQ_)Bzt}WsP(Wx8YC2yNw=8g=k!%$??B-j05*g=QpEQw2* z?|~|hasx~~(E1SeyaW!;0Je>NOJRS$`)3D|9>OjeJobB8|w_7E%2c~mSnJzi1$q2ikux?a1o z!L_pSYGrd?<+Ep%Een-xzbacU@_%D$wef>!et=={qv0v-$4icU6PO1{igj1yr!I<2 z*3yZ~@H_Ym4|qV?O&Au1b4P>YFa8R4I|y9MIXc1lX{cI!qIyfHX6HlooLGP*xKy21 zqh9m~(pe)*JGTuYEcSBEO>udd=oZT9gNdqJE?9ThheDp5IGs8kw>rLSbprWyLeJ|O z#_Nv!uG1z|Ym+&___|iS>8~Lid6)VHB+FonIMBpyZ!!Tl`Ns!FfW&W{h)^X{B!Tmx0A z@zQDZ;j9TGa0yh{8oUzCP~&OeY77=`3e{;m^NPpgSatI_4>!kIk7U8%V?3?+Ci?Ft zS8`3%wI@6i)!Eo4n%hm1Qu8OdCeM&&hA_5$srh#L6EoW3)&k$R1Wvc%C)vrsCyS>a zu+1UAc?ZLqDLT)11Bp;&m#{WbB7E+Uv+C+=ER9rwtla` z_0+a$CgU!-wel&|^?k(BE^-qQVd2=cJfr7o>4+;^Qj^Ep*~s<&$vEDVxGQ)|^l}?g z42awcmP>zT+}Q!PexOD}@L6^sLOP_EpF~x*;;|W8MV-(P#FUz!sLf5tUG9ew?QG!g z<2LQWBb^XJU3Wfiu(Lv#YHWMo*st|MD+IHU;D8~|LM#d(kLM&BJS)dey~aJOR-VN8Uwe2KpZe}dcS z5hvj1M#u4xr?JVr$`R%e!iZ_nP^}2IA)31rUyt@2P{%f(O^-$_kEtoW*nTty9v?(_ za!%Y8*b*7P7c$Paeb@sRFlNE-JsPh_ALsddYA#}eTXGCW8+%P?5h`eP@f?AKJT2TF zC+Gn~(R@*y;{xRIh>*686l}|Z4pw;-(0#-ki?UVx%Pad4z}zi|c21ZHg7mQ1b$RUN zCb1I*yym9>2{g}l3zUH#(0K^VqIth8OfC7eBnTrZ95@f+C>J);^Ez)7Y*|OUOVvz~$H@o&oRMKuzQJx%gn4LZPxN#si`t2x!CZ-R z=!Ij3v0K7;W(VPn$9y%3QRqi!vd+P3WVbKIa3z ztP6vzw_N1c*yU_Q`rA8?&HSmYFqo%!3hYXx}rQU-`)Ybtf#=lmmJk&w>c-5 zVx?EE1Gky)@L-Poadt-Q95kd|OYs$&um%G=YCa^~^#CTzIG|(N&_bX(_%XHP1+s1h zJZ|Ks4pdvuXO99}!Y4I;uW5*Y{H$l7((0LES5iT-B_52)e@Hg?RhF?gn(szD0^_9`5rgulpRQ60e%UFX-i>NcS^Z=n+> zBZ1Gb^zqIusaPK5%RgT@t)5mL16DXt9;^$OE^;pTzo?mhk0Nj?6gbDg6)V>3E0P=JY`~ExWbBi?+}Nl;!7~(;h$#;B7f^@`9<^ zrO6$in9us_Uw)pdcmD)*)xOQrnX^0UocRD2RO=V3x(5LxBUoitirl6xaFLaEOh^`{ z^9!PL+xbJY8HRzjF}ZPeoh==%v1d`w+DJVDI&$stxV z?m$pG7NZBX!*``5EdMAM>4doh`d|C7o`@+)t)Spfh)#HUDa`yJ$IVA{5xU%u0YCVd z8*M)8zi|K*X2PRI`+fBONfSPzX_>=?fTk8=_+RkzBY$C@P|&ty$A4JzH_P0VQ`F9>szNKlAYzwrIsP-OV zhGKxIFrQOWG?A76Y%eiuQ$?l(vc;nD@-^fN@sOMzH70H}D}iwSy2JSU4pHq0V*Gnq zkaZmoVtpc@)^3w_TRZK8gzxqW&4Uo+z$+hc+`aLD__nXW?MKj?*6RmHWIuX3IdyPw z^XQM~jM8qT|AU#F%o$w;=9%oEA=ZFXB82$jM#8DvpTs*6`)e1aJJ0q93hTbuEt#)s z|1P9|gfy#^X+RuO{?IhIqmuX}`-_gb0Nb!ZVy^eV?-aZ!W#y~HzXfMxZ3e^qJW=b2 zP=LfN8@LjWhUCiC*s)P!&^ji9n@0WA;yM%IOFc^ci$2>y-LxA&Wk@`nR~1co5|k_P z1VIi~CQS}S=|mSPAIqgMuplm~SFXNPv z(ZuUU=PuPUAKJxyqVF#!h_E@sCEMLyV-6mdp}Okv4iy%DV)QhZTFWOCdnE9a3br*p zeFCOtZxiKKk5{ej4q_?TqbW1?1hGpF^u}?zBcB_Zsw;^X^FBr&-^Aq@iG#xf3PjU69a{mW-_#}_yOGoW26X{`<=EF5OCYaFJiL82ctYO6brOYFPT3Qcd10fm z-t2uV?5?_#CJimrHEU_wgKdm#oFt z?B-Nuovj_+UzWrz`f5|7Oe@3>5-EXyx>U(#?hh*miAUJc@@$MIjR3a=jX%dvA#sL#+h9Ft2e>}E1&l=6(wDx5A?2o zd-*mu@Ya!)^bmSmWHx>h!EvXRb~lz-eMX3j`i{?-sfMp6s+*652Bg>0A}^fZ5xxhC zYlv6h@8sj*q?kuc>ScaXJfJ>FAGC%FbhMO!V&${FN})-@qBw@1*F-!qT!W5Q?254!Z_94C_Q$vIdPz4CNG zicyAQfKt+rtmSi`Bm$RW_D7KEwXwbO7u-aDg&O42$|V&f-p?ZaO$GRKR+Y1a%>Rzr z;32D$)Ca{*Mn|?Xt(BcS$Hn2Et8E~ea~bW7RbFE)3)^Q#aZ-Z9 z!e6Ke9eWJMCmkY^`=n|}&(!e>a!Ryut&tvFg^$`bJQ8~+p?Qe_&^9fUA>+q2Kwak5 z^Fqq#mAuOy%Z{fGgc9!)ajJc*L@Ah?hy{z0?v)y5BJndRHKWrU^JYD;D9cO7+($@w z+mx5;-2F;KqPLxrC~y#sbg|;+_PWcRb$`-ZmiO6s0;sFVBh-hyvcl8j5G4JPe3#rn zL6iZHPe$gZD3&=S_>^{{uOMR$Pe5$Xm`H$nrn7`193I^`*C5X8Vu)*~mn;-233dDR z5bh#2kU*@I)D+-Za%6kHzAx!uWNc_(Dl`)}`Gw$DyKMG_GOfUy=o)7I!BBr1Rw=Za zwc+JxU}esvVSJ>k!LdgpUh@-j)W!#@Va*M}~69n}qt3gX}~*RxC00+sn4bk{$)x_6TV#5&Ozr6HW57H~pvO zHFCK}AhBmuKLm?ZiZGm{xF`%8FieMn}>Ys}cf_af%h z=>yx@I|GfG%@i+Fw&;wrt7~EuH+I2>hm_w{P=kQrVq3;GCru(p@}l4rRfi2#U0+g= z5zXEK?=tJ2#&!l-*T!%OX*|d?GP_9imUgg}^A7%L>R4x-OOZg~0|lHQpdI;FQaD5?pXF<@`7<~y!6a&=a= z)2igw-+V=&Nn-gsk1aC@=anW`Iv&U#beRXqGV6RUFtKjl;+LTqY!rRuD?{$QqoQ%u z-*(Zu-hpS<*!4$_D}bM&Py{`5)kt74kRwH2^@-f<-T%hfeML3-g^!+3CxJA2htP|Z zAT2aW=$!!45kiw9C?X;tKPA+JX6PuOp(v<`QKX1~^e)m=q$nU=R8T;$F`W6&S?jF1 zo4L=`yOO=$?EUQT2eG8|UQI2|CTi#cl7Ee}uW~a%wDRGy&a?_*nj;sV_<2C-`s?x6 zHs6yH<%gP2+%J{u5d&CFeb{g0Pxe~lf~OZ9Nn;E}XKVN>CIJvovVg5i-91@BPqsie#HgDg5LJ5U#&s#A z5o2sKhsA{aRLJ~8qC4OevIp2bVxZ0}?dy6O%WyvF#Rg_c>waFR5RmKc^fP9&zML^) z6b{=>g7Z(24jHBC&7JvJE&+w2Ki%+iR(P2y)Yv)t(;c1}IN)I(9iWieMJ~IG=bVLO zq1|--5SD=xU2C2FpBv#WJk=inJ0dTDx3=%42&*T`3maEHwaRN1oa(kO$I%kH04!8T z4g9H_p0h05OE4niQwMD}goV=1T80xxkURH{0#Am6freR3Kj?ECu%> zz)A-UOKVh$SRtDfO|MW`gmC7de0yy{lhu>f**D; zfo^ZbCBF4EuOlTg3bA`hgTJI72)@%vG^gzLAE#jKlWBGXU@c+`JN;xn0Qtj{kVH;N zmgmzx{szUer_^JPGJ=W4glwJXm~K6KNO=kcZsd59gQ`Tos!sRbHrifHy7jw1x0q(3 zkEmj@?;6)8S|s_#50>o~zZa(a-M_OIY7jPqOe_{!9;z9arw=-n4zdH@oPgKF(_ACi zzsEq2hlM1g5bp5Qz4err-ByVagW~Fz1p?N($@qM)`IGDzGgbTCCwCHVn_NsUcyTxH@pg?y! zK2CK5AB|r^JlZPO7ho^&!fiW@B6aB^tiG;9n?3;KjWoUC7UFXif~7OObnes$-Y}2Q zdtVr?987N|^=1ROroX?M4X~F|qJ>hQXKfTssin`v)2@Zl2YFcY$q37vjHo=NM0S8C zi@x`)K5?6QQ+~J*57YA)+ww(fZ<`LBfZMO{`SvD~{hnSD2Hvu6| zSINX@w|SlEy5YqQ>(bW$!M|7_ZF_0-;7JG4R4y}JHwJ$zX4IOS{w)9@@7YUwFy(5> zZU4NK(vh!GOdE4dGg*1lG>sbFahR@>UJU4se3qsD-0A1Jmyo*%FI>0xE7Y@vjMyqV zQNDGc(=NEc@h#S|U^{zPpN>V?+EqFp&>LOKv>zpK+VAlQQ>MBqprzeN{{!RbGI~H& zt4?`x$s8&u1)=)JW#7bMgzzS9TeO5-2L;S@%OloN)nIROS=$_$!cIpHz9YhF+2v$X zzJ=U_0S;$e-a)=;5(Ghm3NTJO=dF>xn`YHwC z>*g->gxX=zi`DTF8ILctt zVhan&c#?9c>1LXf4vRFqs)^Wp#OVunp}{@p6Xq|^Wn=bFT#ct)eP6gH1K<2prjejm zB$F#^O!q$FG83V}STGkgJ$*5PvXAur;FfvH0HHOV+%>jPaVE1lAoH?dzlZ{#3>Fru zO!voeN}eLXkEihy_`YARR&S~Jx$Q?0_N_8~Jz+U`)E4|v{I+B2VM<aFf2=%wDf+e<>~9QKlvj2cbiS$`Yj z+}emFl?dMpe{l|ZB>}v=VNZ&sKcMVo+AX;dFKec=fnGNkC^Ve?@EiP{?V&lm#RGic z9Gt7rA2}P-QaJED`(Vzx-ImXrez5)i3@rQn8%`~^PX;0jLW5wBf1KQA0YZZr#_dLx z%l;0FswAzmluZ60u{Li4w|-2DOJPInAJcEN)ojN5f^D*or=#Kv6d+6sp@;AMTrd3d{87PQB<+qa1epTZK^;kmQ8*>;pzq z89v=?vq-+u?Ssz^ALKHwm7j_RWr8v=)+6t_p9Zw#t$-+|Mh*$(4uql zg=Fv0y$NcWK!j{`UZO=&EDt@2YhqjRHfx>dlHF#)e`POIpFNX+O9+%?+tH2hmuduC z<>4}dZx@Dm(`~1dT^n;8nm5yMIZg>P`BeJD-LThhISxCaW&6gNee3xsM!{Wn@Y(S4 zF(2+HwKtjXKM=$c4AdK@b#py^u!6{=cP^B?g^hN;ula5{=0Hf;&ER4SJ}UvJJ##BD z=6tdI*#X~8Md=&s$jN2d63>vFujg}e1cV6@No^8{_QR4NX5W5F2fXZ@+mF65;&wq- z!>pj@d>%RE<~l?GDB>)Crnn+DeVMn3mrMyLz_r%(dn=c_l?Er#NNl%l&qiFl?!JyRhmRPm{C3WbiLS(AI5Z# z?z3|i^8N|#KP%q;_ha(*dX$C>mrW$16wV0h}~*K z{6uUhwTz4MF++L*8`ceulCiS98o-v_oZ{Gcv5>@VAZ`_r__I4Z->DCu&gwWnl3?me z3&Keu$ON&-;KL}6!JywLUxAB#*z5(HDMil{`37WlvppF=i}8BQ2gLvy5tKKc8Eix=3v%h(!2Q8uj5n%EUuM1 zb>rWJuujUqI*XEsn=ZnDk`hEgV zraouU?*-OOix)Jx{+%N?27pOCCYVPG?$XkSBxkVp zp9k+Sq$AhYE}ZAL4%C(hVD=8^2&;AH8yqO`e+5NMe20q&ppQF3JCmoVsAGEIo7O;$VS@X}^Bdh?)jx zk_P~NZEeUnP>t8-JWQvW%ce`f7$FCw1&QU^>RP(t9n37rc*W2uQxcM^s(`Gk8;vMF z0!#1-ra>M1B~0US0sygCVlo@wCBb|%lIMEwIMJtyvrH(INy@z{ltma5xx`$<#vT2Y za}Osm0@%cXpe44u1&%@q;<2?l3_12|S8fJ)+~P?%-3ItnY1QAnG@tjV<=5uJq(!b} zRljnN+)$XijtAgW^hM9h1S_7r61I@ziGtxlErt+5EN{fS%hBBh-?c0xSR+Wy%`K8R z6FDYBg@bZLqj`QaO0?z|Wv}Kc-}*p|XjTjMzX&6)5u+-0f-J6^t#P(zL2#_tWENL~ zlyz4NzFXRC%2{gfD(s2cfs%H@$j zSPIvCZx#RAq}@8Q@|Ltg2yZ%tw#>(s_RE2#>kjq_@aW^|9^<$~RqJcgKPX;qmSN+1 zdW!)c5Yfs>yUv?DAX>#M(A^Buvx)sk9Qr8`x1pjf7dl4dIV%MMAjLvkTfHPmP$!eGupd5cxIi;TxhIeF4k0$x$&jMOk%HT*|k-yh4=t0em7 z12-%Imn+>NiTMG-BUbk$0Bji)0LY!;UV3oCn=Lb`4z@y6$>hX!Ty(Q^wSPKb@bUbln)!y8sZ zr4dyqrHpY=x>i6@(9A^A*J=VGt4O6YxlBrocyCCj3OS@I?cKH8L#WLu@H{bDyN?Fu zp0=LI=!{R*|0{h1ezPL=ac-WBaJPdvtbB6Q=BO*XnB@;J+MuPoXwXucKN|^+zqQ;h zc$^aRF!vw3>%;6I{Oy_tPHbTEkB%RfVtba(XL%=gM)DO@d^t!1`^A1Y*YB%&PFoJv zqb@)w&+f`>aisL-_QTF{4^0hI`ue5)rg=`r1Q%HvahN79*XftV+w2VaXS~yu&HG57 zXu8#ij6*_1S4nJ9l^NNWYyBmrQ2hkSu53V9(~CJ&g5F#w`f?_JLyl#gg>X`*cUGwW zx!r$0Oom0Y}(s(+g&8^Ej-0lIA`Ng=c0 zC08;)f*am3vOd16vbAwJk7B=j8uAtfTO3`LFvIJEKC*MK%BLmX(sNV#bf?D8uRoN-#&0<)~?9joIWw(i+$bmN5DhVQpw3%{dSpr9UwvAB=aDUB>P*y z9dNctya8IFoyoDi(rjYjbm_K~9|z^Yh`)6#MP=!?sJXhd08XYLmU6PgBG02wMH4P& zwU(#K5>f<4Xp)NY49yx}RAb%f6A(U4f^B8Q<7&zqKaYn1EXw3cU%hGqmBae;5?{-4 zx*$^XMfKo7bC%j^fUM+Qk^NAsyZ?@&iO%6zC8uRG4V|V;W^Z_8qr3dGn5NTwpbg@f z9^i%L7E#~~*0s6I_;E2*Rpn8J`!nIEwvl<_Tb>Lr?tuR6@$p;NtZ&lU_~-cgwaIl| z>Lc{NcjEWvEKIk|lH4+C{UK5+$vH@$g^CFv=0NH8f4TnMJ*0&5Z_2lrd_@OqYLN+G zHS4up8K2hmX@5?JK9bN8osGroC^g-Rv=Z3itM`nqzg)goZD^u+ zi5n$0b>?=}Se2PJ3Z`OG$rs*Kv}N}4MJB?Ap~Br89<42{lIg46H558NIF`uC!Xdp{ z6QhgkqFPfN3)DZB=v&pxm>gxd{Y)7c_!M*0n%4yqNch+F!$u;t=-=%pRF=u!UdHc= z{6b+0wv5$CXvM2glU>7>cp4L0OQb4enLGpB8EaR`@u~4+>V_vpm0we6hh>8t!+WI< z*=_ksj3g)h1U+MV4YzR+D=$BuXS1P~YuZ^vlRb%sxFgofw|@?k8ufcvryOKY#*ph@ z;O+%+{o`dQDJAi>f()mVME?+RVTmXHh&v1z-LQl)q-j$IusKxE_V^uG9hRh22>uH7 z3!qqa2%S=Rr4UbL^7h<+auZ(1P{uM(tb?_ilY}8uoL85E$%hHe9=1{PH-e>ObHB;7 z5y$xj7(1pLp2(?lL@&%Ye%ot?c(mso0#Xn3hj7> zDE5!)ZLO^|Q|Yk?8y2Zziavc$+`SnwWgnp_NX;@5Rza%Xw6cM8%M*K#ZCk@&ARied z1~57tH-i036t_c<7n?)RSK&XHscs|jemC$CD-)sQ4}qBX|Cu_%FapoXe{_)exe)~( z;Qx9AWv0NU7M0la-rrIQdXCihJ*B5chmOOdean54tQGwM)g&&Z*`gYd+(?Xx66QqKB4aR3OH(8XZd_->2eHz{Nw&5D#| zDR4RR0y?6x+I!5%Rr9V%x^OK|Ir`URA<~3NsixGvZ!SJtz$^A9EAd!R#w84m=y-He zBBMllExrK#5iFp(4@KRx&aJ7aO{pFl$VEs3q7v8%bOl7 z%ai+@rGq;Q)|NSaRcpHLnaHKY$)~XAo~EU`Y_B^x^h3}o_UA#C6-Sr{tHZl^v2OmE1HtK+enSsNav}R^f*|`)4iI!0{?CcS(5NJ$HOq)VDO1SG@i$@q#?4o06( zO*uV~SltdP=L;5FAg$Og%e)66PP!NFkrG$B>l%k-kiHi^j^0me*!-deA*y;NusIphqFBe4rzY@Sh@>(eK=eyEeme=9hcdjwhCCOxx5svD)=J7xQ}@%>2X znb*@sj}?XORa6$vel^O6ik#-1(k*-)f*!zo4pLuwUXnL0F0TIYg@WWwVIIR0|=3T@Gas(@u) zBtWauW_+63c@A7*veIstrH$$I!REBL4PCjn?zs93>9=UDG-mLsHB%Kuz-nVOHb}x~2RqlcwQw`=gdzRxmnXf4z(StyF%-y~-2Q)>BljM--cRlk zCBXlPB@4gG6;(=78^dSe5ntvc3N%K(of@3)io7pzE4Lwha_)Of6^ZM*n6YkFXbcD+ zkEygwp?r;4GkNQPRQA^#IcZU^XP!LKdh}f{Em=+I3n?rkwDeA5YJl@xpGs4@B)19b zb^Sj-%Sn@(x^VXudOP{6s%FtD_-hS!q>7MIYIy;ka{cTQ$wClgBcxwwa1H5?`7q91~?9R@c(_Zob^)+r8an82XLdrP?WzO05yg zo;ww0LTcoQZk`(!;D*zBs8BDM-KRKZf?~~EWaq*d+eDtOxzeMN z6LMlLSgpH;Rzu~x=oRX#E&e$0s8Ql_Z~dr`>z@hAx#Y=S%^)Yq6^*Y;Hs~RtMc2|q zJN|h}@jg2$^(sU4?4A9l@bt;zAG@R!|KHWJF1-zN_*jd^^TP9n!i%C|jrfWEyvrI3 zr!GaBd$`)$g{1}HAM}Yb8pgj!to(_(Y`>>ky5iGh<#Xf8jR`xshfRg1=eF9v)xb^S z`op7>K19CQCr&jz49LIAA06?L$CUl+q|MCrN_RjH>W|G5_1t@+>nNAwXv6kMa5cod z>HY;z5k8$9I_XN1=j}8n6Xmm*!eoL85_b7|j4^{W7l=8|B&M6g0?@;o3_-0c&o;PB zt~PC4J9jzLyr*rvkbV^7k35QU7&uHxF7T4Y1dmkzBf&J{WS1yG1=BJsWCgZ*8K3>FVl^z>gpcVV^ibd z-NI?z$4zoU@mf>MO*K+iRy2Mkx?-QbEUy*+o!9Yeh%o+46?yaTFYgZ+vkN0lCUJT2 zy8Eq1M#)ZN@)~c)4RW4`9loJpocGjPR5u~!y>WuSaoIUB##xsx zp>1i0%SgSIeCwA+uPE`>20yO`(15oNj2`M{H9ZznJ>P0Io!jrpt9~iuFVnQtJk>>B zzjw`tGzEgiu{wlJ@DAAUHgczNmf0n{pYXT2r1KiII_rJl!Vqqbs>-d#y}IxP1O4_J z{7t>*1HYkZumK6OqC98xSSRW}5S(Pu_V9p^GGqnV^7&kEhc3Uq$8WOF4><)P{>7MV zT(Pj<1`#1x`LTDzBsNZTEAIk73(yIJ<;f%cj563#0$ZDNDm#2c^_HxHIRY&6__WpZ zpXUZzXPoou%OA{jQ_WGoxQbjL2ie~-q{4W0^Mf63{zHDytI;49sd&cSBf;fXZv$fg z0H7ucM;$Vi$`>RdvRmievw2_bOAg8c)aozj<+KU7Fm03D;@)T$U%~mbU)}KdQ-Xc` zp~)u%D!|(@>Dzxp!o2S}=3_hcAH%~e{WPV;CId5ZYwtl|wF47WDztuohv;y1yMU)h zlZd0b{|zX!yew~XCsZ0^Bk0~h_Bsz9Fcof<`<^ZC{Hr&E-}UlmZ9}vf&HDF#&O5dT ziHb^3h@Q`ap=Z%gf5-j&w)ptx6;;m`axdGEmCY|)`!rZt5690bCbTjFZWN zHBYbp14rPTKnEvZqMX#Yhi{TI=mR=Qz~Ld=Mw;W!?%|r{r@b96;n4LC zq2jLuG-_VqgQ#OTj47wQEA{K*h;zmmdC!dqz;QafQKyg|A z@+hob@HE*`u(#VCsqc)l9UAGw8DNdFG<F&1E? zBsS_+6w*Dmo_IR`;31##6{woN<H2I`!@?RY5@$=8cTb;^W zgWCXUm7(np-7n*WE{Pj+ZFZ2B*@_GQMAr-4phl>5Knj|86F^gm#!V4ST828U`1E#S zo%!^lZ5_bMKl88Rfh;2Zu`0Z@ z2=t1d&>e5e51cjyuyYv+4zUDj>$%MVJGe+{aH>J(jbq=NpF0LsW+nu!~*H+9p;U{4DZ!agO_T&-Mni|W5ppL9pYg_)y>V|LGs~IM9w3mV{)E~2H-9ajVBVHoIfR5Bhj!b zi)EisIrWMcDq3p%Yv1{!$s=kzZrF}(sc?xF%KviO)SnQ{$j5>Ot|R-*AI`jXzXf@O zh!yqzkp0Mc#v67p(ZwOh;V3{Ja%HW$LiZf3Ly2S;m+>@TveM%)ze}Rfp%- zQAQQW$z_}_oAx8H(Q{E&6PdU2c6FL_H%Fhq-S27CU-e>|J=9-+l6z4qZ>H*fmrl{; z0;e*e=R}*r+7=UqJ@Bp-jw#>HQxX>6w}D zqW@Env1&NhNX_q-5%`ISxBt5!<6fu*8x@dblw@(5j{fh0ObG0fEZ(~<0Q?zITG;eI z8foLO3Q_+maO)9w&1CaClO9lT& zBUQbB^GxgF|E-ahF6^xSFOBrn4B`K)MmkKFLX+lclc)r^Yz@T`jE18L9A@&1$x z3>^@=08xi0dVMjCYn)8B2bU+I({T4{D$?z-1T;ymPX1FSm!vua2#nZUN?m3+q0=>B z3ewjwk^aYAfe_v295iZWf?gka&f96%dZl`ujQLxo!#yvYm%pomda??u4GFiC7fRCEd*@j;JyiR zc8G!{EG+@VDXs+VZ^bv)YsQtq)kNdoo)}28HfUzLU&0M9b{Wv}q zBrlNxg2jUE%76!49aI2&C|1W8mVnYKyxrn&-FWceky{H=dX@waSaPddWOCc%@2o3g zpK?pk#g4D!C<+It)$OKVFbaF|Q4K4KH76}X01w+`z7V%NeFp*KdSjAGxk87!N;{_^ zND~XvU8G3|P_}qyu18ctf`P#m)#k%_*<2nHYvlv5`m+5>KfJ18c+>2)smUz8?-0Nx z(q~%b*AWx`GraWfsY~c&)Jt#`@vHZ_-Ko(5V& zCT=-{%M<>w0Xc7+UJt=nxDzyU-XMbv_8DTtQ@QmVhns=J>h5~mZYtHp?*lsauhi#; z$B?<)8kncWBp3D1Jx-6#6&}XhV3Ut?J7dJZyXVK0P9VQk5h+~g)s@~WKD*cxCaqyQ zt_dn*C`d1!It(9=B+IKk10?5w6_#QF^;aLi9JIk!p%CC$GXRak2!-JIfQ-3I9b{}b zXBFJb(pb}ukx4{KU;jP4(9`3bDGA*-Ok;2h#nCX0i*+YL)UNZSQ5;9@W)%}xW(18PQHi0Kyl(ZNJF z71ucV`a+}OfI$`+t1-PG9)ci(DV>-L1KqaAd*d@pkuZ2L*cEu3NB3YQ$x##m-#aAu z*>n`$){Wzs*nyKEViq-75_Q|HX!9*E;M$@uZj@$bSk-xo`s`CW=ul9?T<2cOHkt8v zfh~0X;!7*ZjgR+wyHH%uLFO~((Za61xW=g<;~BliejcBQqU9i?j~YkL|$s{FHmlo=%!>VB7f zfPbS7SQnVqvE@0E)t-NJJ2t7Bs9=(PF}T};Xv8JiwOB`G{tz|0WpiqyN$YZg5%w^6 zov5A8O!y*ka(*lY15QW@ZuJ$33=IVQ>%1QkVTuFke^hVXQKlXMQR7QBcEIB(g#Z~B zb|9oQHO`?4H@Vpf2Z$z&IVBb2P7V^f%~6rB$~>G&t_Kh$SfW!dr!iZ}FCL=-0z=t? zinG8!;3>WQrg0|7+`BUbKpQvoL-q)ONKoNKp#Gxr{-nJmsPm13gBk zI02$ZkPdg%-qXS2@(S0Kt>N*2%+NGX@v~vJ*x_{q9#R2S&Xh3UYfdI^mfIzkN@b=6 zsvzmZXMPgRL~rR8K3VTXUtIqbwJ+bVH|l#Mn&D4G3A^ge0MVCXvc*$N0G4t^LpIJinGbuUU$O%UQ1S(h@_d< zilOojdgSe%q`QtR@x3_c#b-as46^woG<(oT7=4m`W#p6C?}L6K`Y9vLW?54BaKOUu zX|9grq>SF7dPCfHUUhu2%(iJKM9o|~+ImGL$u#z409^E*yu5PU;fRY42n};g3Cwai z!i9U&rp9d6?wce%^I*&gZ~baXJRsrjS{RkF*%rJ#DV+mszE=%@wO-L`9FUd$%q<%4 zXzBS&5eyOqslM8;< zZx0l-^ECg(0on-%bT!ZA*z~<--#GKSdF`ATc(E4sJb*Mnd^tUqbnSXJTxpQ_-c|d> z_#3n_fI-R9Ki;NzQ`K)h{t7Gor=aM^`d-t<$a6rg#62M6Gx7A|^OHQw_Tf~T{8Rk- zgEl zHKw?y*&|YyW#o2K+5*d_IU!=3gf}CY?;@zHdaG5Zvgyi+B)5~o>lQ^8>PhOGRWGxG zvSxLRA##Ks)L-fEqcmNUjpkG@Q7NC77VpYFJY+MVNqvfWOjw=EDf*fvxxPMb8Xcvr z*znmxNQMUfG_BoeOsW!%LeuJkKJ?QH$6-$#QUE_?1EOrk^KgYWY zuxm=UX-KS-<4H{CpVWA7oR@o=FbI#SlaRi%ZNRwsVW;XmErhs&OCq*o!Ni!PZ%IEf zX)RAuWQZnWUt|UdZ_i@!5h>sIq|Nm`RC41NC@(-Hpqc%7^zJPS( zkN=x<8Og~`r%2ZwvvOM4X_mrbgmz6QI)581E^&>G6UHJN7fE9OnPKC1u4F`8}T;wzcEpp7`pdmQu(px9K)1IP0?HkcY{w!;yW0|o-v zZWFM2EUY>aEgym0BZ59G7!M~%E3;6FD`{XgLEznV9wSeXgcocFHerUnHGa0v1UtJe z?H=LMgvVaRK`$>{at! zVzUiP-eGr;zQ!PM_EUm^SP1AS2V?jN2D?PJO>{qAV5PfIxMl9a1=KDD9Yg`r*6C)T zoL@DPSMjF41K4l-DIkfH9XQAcOQuf}OB=&%F);Czc;Sm|N6ZXx4k#aw+Dm|mEnn}~ zLQ6#;m!iWCw6OL}`iE`T7Ch(^1&ox&-p3NzmJ}+;Np#+8emLwr0R1K!n~{Hp)_ig? z0aQ~1e4CI_m*4^1c32>S?ndDHDa6+RxPk_D5Rg8?TW}&57Vg5fNQTAg9Q%ljNg1py zv=AYUwMl?yNyw?oV+;B?YidxH*rEhZusRcd4hLC>fm!4WhY2Oe3qFg1`AfzqK~cW) z?4WVj-y;?j7v%_~WF6o3X5+k$%g6LBkV1eF&_((S7CMZSJkP;(Wwsl?Bv;bgI|}VH?5fwr6!7oh7tM`H4`CUDzpb+uqDegawNAc*i_5-6SL(j&KHl|sT=W)o z82tEG%j443n}2Ra{rmM8q{sT!NepTb&i2LZFzO)Ip$QSNxel;YugdZAQ`nd!9+=1X zA~bqHNvr8ejVwl7O3s|^X_bqfY{^r_jI+HhPmNvT1|bQh<7iA^TJ%w{UEAhUJ(oD= z3I5y0n9T_L5+Q*0(7lTjnEeIx*!SoK@`-vW*^cUZ?P%=~c6^{NHcJpdt0~D!a?NKU zH<^_A2Inl7=)mqN;vlJQC7f7g`POah!>S zT6HMNN@L%zB)L0cg0TEF0tX2vA2^1w+?FHYQ68++xV*;~s@u=+NpA`QUgPAh0j>eb zs7eZISQEV&A=&>nawj6G|04S$1CikCwQkADrjM1$>~PUM@hiemCl8}vb^I}_Q}6`8 zZp=&wW^G%NBvna%4VJ&|3>U_I{FJK4tvKl^E{( zig8$f*B-2yj(alJttalFTcuD!PAgwfE6Uh9nIKbg{9jC1XSkO$S_i3zrAGB}oFk0R zTt*38F6Vi)s@N}m&-d(~zPNsC^kVJ&(StDF69ZDKM1f@Exyh%T7o)_%ayx4S%5T-P zfS4wK%qtUv1e9sGk=?5NU-w?=#^OZvsXt+K+f)w!4K$eS$IE(mGuFY{){b zP&)?O;KwW^apqKU{9WL1WBN>zQCsBU_PH}LP&o>=X-dNxl*6XW3g+HHRNx?kjMHZM z<_m-{APWo>e06;8v(0q8?B{y81Sx~MjC0%Xy_Rj31S0|i(IYw<|hyHT4E6}>$0QUmUVwBU*ywqpi*RhfHZ zYoS~Mevd;uCW37{lJh~tlKkx@F)^-t|IJ*YvY}M42J+mN6lNtSqm1!MoYZz=l=JJ4 zxm4cw~XIQ3mcoT2pn59K#LXSvqdwn!l^4NPoN*l_;p!l-=|_j z6P%j#IYT2>gR@tiu5muh67WTb@B`P}-{Z}a$k>0r`&gG{#M4#)j)zN_cyGGZI+R5oAf zU>(Ya5b#)kXR{Xrkk1Rdvd-!xY*b~7H6B}sxNO~obxpN-nlC-{`D*La4~vT%w;$bZ zzxH{V`eC$P?2N&d?hZ%H=$4k*mpkXbXq$ZjGQP~5_itPH@=-;66t(=G`sLGk@kZj@ zjKtTC+afBrIhDn}nL5nAvEwALwiJO|@F$DT67NNxczyW#Rgkm|Rb{FCJqvru*+oQJ z*YRLfIepOF?A`)qf!L7KI|%ALtaFF6e205+2N?0~`{rC5%d4U7HIVs)p2M~+c?Usd zdw3M|d6BSl4YxArkiq7A`hggL5W)5o%Yx@v(4}{gi#H!*mqdMc8D|#Q*_FO_ujhk0 z6DW%rB*gSj>~%Y=bmdjG+ajjzP*=bYFlQ634vdqBKGeoWjKMBiW5cmOkxyVA-dJY@ zR|pHn{|&({7N4nteF{(#wnJP`bwb%8J8|Drci6AmF*^|FJ9{u_Qprfm_Q`@ z4)(ZQRAk6^?!wQ-jZ;?g3xE8OW|$9mRJklyzNnv1sl5Chyoiu#hn^F+R8+-2ju!~g z<8)(w1Ce0o+n{}aIiGH`|4iiYG{hbkgc>PZMi+M^B_K~DkY%hmy9?M3+}G$M8RYxN zT!S6_J(NAQpL304OW?(ChqBmn0Jh?;tOx)bI()R_tzZbw^@8eOkObSWXiLDN)c-2T z%tC4^SFHd#Q1CNq%-EtyI`?}Gjiq}PB7}%#jamW6Ws6+NwP|X1vW;aS-^yG$!92S! zQG??e0>FkbEm8jOlu~mlYS6pw+Fz4fr#Bq$*_NG35pv!<{lM9Jzbnw%1wi4sn9jqO z;FjPGJa98D(F&Lbgwdaf!ZR_YfR})RU0%xRB3r-k`%sZ)<^!h(FxZ389w*c8IL{f* zEf)7(K%xhi6s$HZV6@EOI!x3ME}|G2=GK_g%zMrVH*liP7+Y z8C5Da%Ssv-th3K37q8v&P*BiZe+n%|8SAFh>3n~PHxmr1a(I~``pf{6asId3Vs_2ux$2?c3l1swHb zZrfi{|7$bYAUD1$Snl3Q$OCDC?&W%W!y}~-Vy@dmJLzNLDD;Rq0iW42zH_ZyS>US? zyP3dz6?=x&>$e@BYAEcY>$%j9s)1B$_UtQ-Mv7H>mMcT(q1<+(pY2$Vm{M@YiKG)7 zohh=&g?x(TFC%sr>rGV!vaD@)c{_w!$VHN$<-Y$B(5vMcu5-0uSnb42df_9pu9V`+ z+KOIoJ&Q;1BJXD{V+wu&zyOZYrIoi1p7(z}RM4a93^jix2C`$_<>H3NsTxD1G?944 zj4X~yj?a?}^6z~=|IBjRh6b0@QIdwiJA~zMdo!JtuWy6*8x!j;4}7AGigGHR>hMDP zHYQ8NC}eXA1?T7XT5)`AjI%q3j?OXiA0Gx0iZw=f_7O*#ItoUpWk5T*i;eo=YXCFd zI`JGz)qLw_&=ZkI#?vOEGfm8TSR7QdmZca{W2v6x9{BPIreDSNa#~WlG+#h|i2e*0 z%%RL~e&SOKM=tn9;Z4VGxP<6LzNFrEjs5-S;B9})PF>3+`aLZmmxA7#%>eHAsz4cl z7V*9G+I`uA&4OWsNqX)z^Ux6q`@$DPg)BBu;9PF7PGGfiYPw#;=f~CKv4wMDmRVQu-gAG%I^Fhsz3f8{%n{T+ZnsD zjeTeAyJnDmCtH$1mQa?8v>E%1ZN?Uoec!StsRo0wQxqj3m5@k_RBxBh_w&7exPH9O zA8>v;=iF}R`FcF>kB-Smd4qk>>Nf0GQGPZ4WSQT^iV-h6=2T6zk2L+nrJIu|43kMd z%Me+frKa$N9AiYK()g_Bxip#LBVmLy^YDb!t5!rraD=IBfOtkRVJ1ZFn9oVG$!};mZ>u5)?*YttM5+IZzWZo)CWjB&N$84bwa;(< zYIDb9cKDUb9-r?@7dx8MG?n%2qfBHol_C>C2#E~;zhRiO^kF&ups}ZW6-rv(NaNf} zsFQLHiARrLMLkd91J7{5!?0;NyeWzKXJ!Ia@1y0)LIFr~n~MPUpjmS90Vx-7y`aLV z+F;g5W*XnK!wY(6`kZI#b1~%i%emINR0%1fLtmn`N?ql6^&y6{LvF=^{z1KuJpk8J z{z3Mv9@hn*uNPAYw07*! zgH2UeW{Z*_3_-&!sHiNLPVu=k7A-9nyM+Oc7-@#^Uq>m`TYIwR@vrU8KXFU(>~hp9 z!ZC*c+!$1urz4mq@@;met~^hXBQrEg8G)*uH32Yx*)AU9#1d|9x?B`N#95tm6t{T09Wg zh4-5so1sklfayI!kCTs?)FqIMNce4(Y z3>zMmsYeoNqZtO}PJlmd3_PW}Tu!#VTRm}W{Q$32%kxbNsJVcbJFTg4GC3i#-N)9J zvzny)cv!oJw`E-XZ(U{Ap2{~W!I)%7a5-|x0Z|^Nz9JG~v{lcUclPOR*(O33_8S6& zj>DcCriu3u z9o2G=5jN=9qC9!g4IPj_LdEgLwrW_V{#K2pPHIg`56ZSm*=p!qX_ajNZ8;D^9 zy&Un%P`zl|GoeNZH^Ux+tFiLrVv2d*f1L1s*38iCFVpOhcf4O$>|Itj)M@Qw;h)S=>$GrNrYz*u27n7{_-Mvu!GhajNdDLDvg0=GKfvGn*y7XEoYm8&EvhOapPC0=C zf;3kRCcYa^jaGUP{Pbs_F@-l~<=C)p&}q! z+H_?9m&m)$7%;A2#|1;ZESVMi*y_L}|JjUFexxdFiW4SLlOgDJ$XadET7^@fpjn-W zDoz(^L;?OD5b1GYJ*XV#&UiG3HC6upthO)lX?<1az`o zVdPIja7}Q&yC2dz0@`&@Bb=^xNeJNuFk=xZXPZ&RCYkxzZVN=cFRf6IHbV6%wTox< z(8HvY6n0Q6p3R|3NMT;+1*sX2NNrA=f~Ozb(+11Zgbd?rCk^VoqdVK>s8?-~3TnJ33n+&M`L%#) zYNF(Rj(JY6NXJ3O55b%f|9tgCLBIJ&&lZ8=fV{#gIe2nSP@uY#!wZX7TsqfCb^$ZPBf;4p?>)EnRw4njJeW>GM`pxE3fD==pC6w0|DK_^c zQnP^vk@DIK>i-u(@Jw`4sDH+$ml~hgu~=2uoF>+mh#TtO1&vczp*-I??k42A!wlOA zNc#Y!w?XasRjVpRgrO3R65QApZ)4~EV0L+Y9+r`bO37)=TlUTD^n&W)@C1+*^^oZS zYy8r(0=(ED%$j`cFUb*PCgV7k7`RmF;57Zg4DASRTi7cj%0b$(whOi;BlqCC`?-1J zmbF|6V_l|x)4pCc+l>%1vLI%S~BtnLQEba9Iw1hWnyPz zmz;%ga3hT8IR`p5&S#9eg``cJ%?R8g|A?PFc~rT&zpNf@M=CV;qg z9CdVN(^T`2AOr~g7y%+UziN8&!4&y@Q!$m%thDgF&=*?x?Jf}u5h)xRu@=kaE}i zX-nw#g5UwP8CeGQqyU)9kt-P$M08W@eK7V;E!F2BeaPfV%lm0<9;TUWAPX-<73JAY zWc>Y21ioSd8;}_!O@7AHpkk9;c#s$Lt*Uwzy0FH(qpQgS(yypj11{4;|o90~0a zm#SIVT}+TPGt$H*Y6^HOO+A;LJhRuEI0yD^j6Yu%VPcS`L|#?KwRv@w>)nuE32~xvfafI1m?zdYl^?Ou3UD95#@d5#<>%kn0W8uBF zE^rU2-;!SWWdYrq*}^D0;^pk?a_w(<^xqHCCDJl=)2o4&@h=>4yxW#48|a_2*BjbQ z))kTUoi(C`C{%Z|zx$B!gzOqi^xPfz&BxURNF0J*M!xGkJReVksn6V zqxpQ)-RLT`|G8ab^RmEt%xeJTp99K2DxW<4a3`UfG66n$Ev<4*)(GkKSdb7N4hzMg~4_T#mmLdJd`;-*?q2%-A7hb?1QgQBDxm4DzxRt ze~_NgTn#_i^?y{U6HnW~ZjlR%TBi%;FV<|x*#@8X^mAnIo=S8n&pZ(6>h@_EyvXOn zKC8OORpTZ&AxD@4`20jk7xG7O^*Uso)J=Qy5!bPIW_ zfowuePD$oF01Zv<~wxTM}~d@86fi|Oihg7#56%k z$d5>NlDnXBko5Z_H{EyUiCB)UpeW$v#9F(#Kol7100O<@G?2k-9;ph!L@fi->n*MYiQ}0&*TkHdFGMGCVy8w zxBtMcH5$SC??2lIFw6Yhuox| z7uo1>b`RXP&uTP_+tZlpxmANk?s(Hr0`f;_m zv0C_8q~>|}yeo)`Jh1HI_?EUaD(Y#Qta&hPIHkmDA;>h}c5b7cHz@n6CudP-`SY9C zbSf*Zd@z#GZMzrnK&p51-m9Nk@<-j&o~-tIf1Yi13%)O5@2-|h+WMtuRn+g*f#m%$ z*%jEBj{E%wX6s>QP_coZIq^_!^kD=t<(Tbk>7nv zrr!k=rV$xZ>Z^w%cE;L=SL$LXy6ACXf`G3slR>a4O(5MK2R$~oGa6!g*^2b(*WLSm;1aRRj%&YaHR)e>A zEI33gV|F!vQWV@u%-CPgqIfMpZJwjox=vq{R4Y<}&h8*w_{vo;np=fw?#pppbK z59q}bErI2K+DIjpkG+!n^#X8YG9@t>Kp|$UkT=?tn)*=Se z5QV=s?Hiz`pqZbIaid!qmo(NBj3TB9eoy}T?$ku>6oVSkESoDHwUE6}|pGyY7ebAIv|54H`9tebm8Cy|(paq5+=HF1%` zb}K;;_t`5kr$J$^9*$_4nu-*3Xfts{0nGM|-2D{#Hd*lIrVRIwY(M#2`OX;C^ z26#4V40nx?U?rXle4lJv8CG+I9atNx4fBQuu&R+ozgOb##4Xoi?*`k>HVFRXcLNQW z6?07-D@XT#5-#8hw838Aqh=Het@%xO{f+C2#wILZjI{jsc0k25uX$g=iW@oPaba3J zDk5!yxs9Bfq(vFycITcq0W||g+Dj*7o(=ZR$9bVQ;oMTu&TuQgE0$zA=4;K#WU&kg>L zgW_icVc_>IW%Ds%mXCdak-KdFP>;eN{>zb-ga$iu7;Hog%d6MWd;MVVL>BkySSLHK zh%4gs9Q4~a>sH7w=DP1gYxGh-B*|BEMf@A%$Trm}6c{=Y^qxQ5 zRoM3RAx1Z+C1I_Iq84D1<0R!Tkg~`jl~N;{bSsE!?+vS@fSOr?fCN`j+j%^E?Np+` zdOF|su${9TFszBa26klQSN0STk^*Z~mI$lm%(7o$_zP;J;rSPRQ;!Xr+c7|8RhgH} zaM|X*L2o%sXi%05ZS_t6T9Fs%zc%Eopc!*OLjdS#Hg)DLNHWumaU|3J)TP)?pcVf7 zo%$7l-pB(pJBSa6cE-NruQFmi!a}bLl_3Ztx<6&5{kRRTZ(ohN@Bf)e4QrVLSgix1 z--Ko8<{&5=9S9Ui8-&k-Q@p-NrceSvGEP<*%<)w&u^z|F&smZqzh}R(4b)^;Cy|d1 z%zDaCL%)MQ}x#6z0jp4>{2Y|v+@QmzwNJhK!s-8h^P(c3F77fzCz0C)aW;| zf4P~V13O~9t@1v|wL`UV@ggVyo1DrVFOe(&lVQBZQZdKdzATby=f}O2Xl4?vw;Q&7 z*!tw z^w>(O)Ym4aX)D&)p)fYCq(mbKcKT>S;UzzbApIScwb^7&`N036=L|tfWbW!;XHwt# zkLtlQVO`(l9`K9G02UiUQIChZ78yhpA6PxtjuS^%us^f>B1EtUv!bcAkP{r7NpR;% zQ|%A(yEV%yg;{f(e(UyNLZ6PI{1%@PlnP}jN=gM}R+~kdPFn9^Y0PYeCQ2T(x%^4R z$w7+1&*xY=Xc+D1F>Sxg!}-gQEmh=DM|`mYe(dZxiuT$|R=!fvdA`lG$!v_Gg~MX& zbY~I?9sgtE2!U54v*br8KLh6S@G2R&CoU^RO#XOR_L(SHqMCLvp4T!qS;MP5S+&c9 zJ?e0e2POMxQTma?ssKaxxgjNHUJ|rROEWU_%gX7J1g&8#bq9$Y+4Yj3TgK|KWHwP_ zIiMV7^;O!m-`*Q03EZYM^DvoY_zRn!uE0Cb}6bn`FDrC3O z&cNnCLp)s`zkd0WAsjVKA^0c1Y_B*Du{(QI@}fACkA9c{|d{c zIla)YiYj0@&QW4~6=80FVJ?#A+{C&>Wcq}W%E3~19rwN7-&0JTC5p>BDQ5JYoDB_zWTj! z?MIz@)~SrKa72cwXWCA|U5S$h8Q2%3g|X*QNr2d&$LD^2i~$BW64NgFk=2ZL zO#S%Si=_8rQ(MPp)Xxodl}g?`37tnt6}dfG{{(Xyj>@?6`@?wyfiGI{=S=UvW#=nv zWLzIcm-6idUlqw?#+Qt845oj)V&sL(NyH+)0hb5X#IFW76GRi$M=P(xMDFwp9h@K$t?r@Af1)Opvb@xieB9q`_UxKCK zS)PKm50>fJzYw7=u!^Q{STG!GR_1rXa?>-1{~Cev)&{gl6nHvaS167-LdftYu_TPH zgbh4SPQ{j(@YPtcwQ~Qk;vX>dv+6fP@vTv*;xCybWS^G!$)zZ5418&}K(tzXS_a+7#0L;Q=G zqX zsme^Dpx3dqx}2ENJj%xhGiyxqOp|QfL!j#i9p(j;gAw+&??p-(*EdAVXz$HNq#z6D z$zAXH=fUc6sV4P!%!ZT+ty+QuCU`gy@((7LSG`2x-Xx`4-xjy^K64LiW>HLcy+qd; zmnvtk#D|?F*ZYy{ldgDFSVU9}FN4v0M1xX4-u%q=-J??h7O1nWM zWKgD4uH%U%D`P*bRN+wcYPBV!CID`RDY3wjlD>Tq@V@O#`-eEp2iCuj{G7^)+>j0$ zOv0`n*H~a)DprFd0%Vw(LFithgB$Cjh!?#0w1}&vx!Y=`_;kn^hd1*wsDOgp%`k}< zveGQ7?oXAC4+s*KwQw_!Y93SFn~c*0A`${EO2J?t4($vx0Qsj4viDByG@_^i5 zNc6%ddZDAd`ba1(OWLQBJ?jEKLfA+>sk{Q7Fc>6w29nHmefN-j$&$W;{HAa#wB?dv=<$fAD9xL!yN{1_s) zyy7qj^9QrYQKUwk94UQSSNFlvJCZL%(4M!A-JM{)TQcFbX;>-d ziQmQ9^Yxa(qi3!UayE`0e0Iu5J6?8N4eK*6x3t#nGfA!wDYHb-zQ`A+jH-TjPN}U% z9C1Y(zN$*0D{6Y%h0*205-`2eUkur=I03fEr0kTU#iEb!DdDgU*;vc7RFy_s1qEd; z7`pAEZ-zGl@+lhz8Vk=!qDdGJZ0&$*tD6Uk+00pBxDtfo&8KF?<$mN1A6f+6fgW6M zWw~+YO`*D?Rgx_gF|;yUl|2W2I2Z&)HOWUMHGj*D&I`r7PPpPhW~w;evQ*kO>}?{? z6KwRn_W`?_+pwy&P(c;n>jFWR%T0J%BCXH0_9%ZqV#c?(y2N?7s$zT4eqyD13}v)q z**`S=v8FC>YePU%C!1)L>DS{ zGgnuTuI5N~y=`{rsp#gHZ2`$E7z}e>FL5q#$=x|`K8gS1Sx4|C@|3*5m6yF5JTJn) zi>!i`#h32}OSt7p#xhKJ(PoLW3CKA5VQ*8HXLH-YrfTzCqn`4dF!@~;)5)tm>Siln zfXU(+5t+mQ4f}Q5oQLT|G-S8x=q6V+~3J#XYy#CFCC;DkYgHI@Gk{GDGA2-oDKZnTylJ=PA*S zG2w03)=io$!ypGv2P7Hj4;L=FLav5stcmseGG(Q!WbXubW394zF!QfAzY^=yO`*2x zbZKD7JpG<)cJkAFHIF*WvoVTaJWkxP=mdo%ZW}gJ-*1mgwXA&A+-JIPTiZT?_grF2 z5<2Nl5?aSCHq-Yw-tTm=O2Y8&Hcu9h!9ttegc%_Xb$hI%bzo}HHU&>eA9Y}K4^xOi zHj~jtCsQ4^AQ=m{_ZVdg@hx%}9O_@ZxfRB`dbRT2&ENs2S#ZTw&x@CxET#fh&^VdC4`KdmfCcRWYx-R&A2S@su5tFr$ zpf<}C@uo^4?cvSrDYZSJIEVCruQ3mw&&&PQ;n}SLpFYqKldY;D?#cJW^QQ>FXet{u zh`V+lbEb^9D{&yxL?y;=zIMFs)ug+0#W=Z#iJE)pko_1?Y4M@{PfI-_yU8=`qz&oTgN3?vnfnkc|@ z$%_!xfE=^egZwl-k6$Ji7TM{gRxvCOPr+zL0dysLtXrNQo}QpgPq2h8$aVg_eLU8} z_!*}uBP4J{`U~=fn_#J8g*B1SyU_Hqi^rkhHMY;KB ze+<3q540zJP_6`$7n&r;1{?ZnTKe$lP=0k9NXpQJ4ss@Sgug zVUC;!x6nr$T^}A_ga>EIC<~ZkDFzlEQm4BAii($+2Sbc^Oy{=yr;qo*4azTGz;E0( zpG~ekxWUs1$(|6dEIjJ(1q)v>wxEk1NZ#$Z=bac3@P#FQaNGDNH~oN{J>wR2|5Le1 zH8_Xm6b|n1FN*_tGofT$dnp9dR8Dd8JYA~a>2!Xz!1-RPzeTo~P#|mmMb`m$CMPD# zJj?ZmNlGqE6sDZO!9@6th50e3EUcHoi6Ddg9u$uoOp&>;I8lJZ(~%!t_46;DX>xB5 z>@J)-7Bjoabec(*clC^CQmcxDfg58nq)mv#C)<(9)a&7!G4jh+-=4SnS{$Cvlv zVy)SobKDB#f5i{!noo!0{!G-hjzgQh{|C~)WixZxH`&4>^ z3mv94!<^x0@}ci6ga5qkJ;xz-hd;?|2|Old03KawMsY9~9B!X6#3v5%6T;Z}y+Ijs zBSPKBeLKb-Jdor*9T+|!qm9dJUqkaI-DylZ_2PRDnTm{#Mqfz1qy+arcn8M88ydha zKfuNlr)U(uD>*dSwP{|oV0gx&YKG!mp%^%dsWys@=tAe&%aW=B75Xe;dAZr zk5{YZyUGvlB01eI5_@IrmetHgn+5OHu@3YgH0QaQ!U7Tf^VS^o4H04hM<5l?M4?9L z%H*T}^(;i~`no>9sQ)=%Fa-j> zy1(U7AawLiwn-0Q(L}0UaRNFqCX>C~M zi<4SEqA8%Lb#hu`1op7{aCf}{`mu0z%>>YsK++*aVV7dqNRR~$E1Sn%A$6f+i`?;r z5IZVG$N9D8tN~Q;WH+6#QRM(?fMKmci>~610%J4?t6}VNLrBORoNlAOm-Ze|PeSt8 z>v|)3Y(aV^L-{yE+_7N1Ce%oQBC*-k`?G5 zW2Gqu&?To?KI@l*+jjb}c4g1|$bc#3F=5wuv&}-u8r%jYINM--Pae<*Z*~TQ)|wB# zJT1Q3X!D3^A!655u2Lf_ud?7pO~dy%c}Km^j-p^3gA8NZxatrf^MbIOf|r0wcoVUM0jW?I>fvCz!ucJ!41j_`L9_sw9D@x z9rt!~duKrV`Qz^kt=Au^y!0OZxvy&#qx^F*;BL6%2ry8k{Tk8`e$QaO_=~uQ0e3(b z{%5uIuSszHagBh-?QAnnqi+mu+}o6ix8m4HsJCM$WSE&C`aSXqdgF!@(xx^btH?%L+mgmaXK}d)=z_$oadJWuw~)>)1Q5jTmHg3;BzC%8h%f;cM;Imqo) zk~=iyGxSL$3*J)zmQ|j;KZM)j$zHkuL;VBbYFj^YrC_wUgH8^kt^H=u#(NQMOF9Hf zNit-FA)r>}IH2MI&8qemFX|jC^K*9KFFo!-TKUzD3fU`Ie;deL$^=ZJDM8oNp*8rv z&heJH(0RtJ$pI*Rj`=PwZpTqf^YK}OLxL_!rd?aYP$GqmpEGXJ|LOq-)tx2)dI_Gn z+CG=kp5|wCpl6!?W==Trh(IgX1+tc@?}=f=(Oo(_eiWX9Jt`E5%(M2H{VX8PA0m(} zpF^dlVNc)Bp*dx4+~HQ<^OfFLtQMUQ@wB3F3teyC?@`KCjWgl}*s zdXRQO1@G3G>&Jh$K51O8(_dDTy1HlOvn8-w z8sx*ShzRvI-#zdGZ`+*f=HMk;5MsUn~t&Xe1!xaEWZ!(+;pN z!YF}M&zaGijYg$xn|=^g5}^ED^)r>OXk0r?p3Wxy`MB9brHkwxO4_cD7~9+l2!~r; zseTLPh>)8kh_yH9&PF<4$M#AXg+?eUt8+w^$BCmfQq7-KZ);Q_2I1oG>k(J{)0c}+ zJQ>Uv2qr7G`65P^Jyl=#8rI44voBJmp%o!rdv0g4Acg1B=tc6Fhw7xTtTYRnCoV;B zqeA4B@XxCXasY2pz{xV_ruksS1>QejF*kkQ5ApPLI$N~*<9DCy?dGT6uCEf>t*^3M zK)?Y!6CYTjn z3nP7S)DNT-_W|%i^k)z-)mMdnf@5)C#jxX>uMU8L9b8sq%FKA!hP1j?CKDG_rpuQ# z0YZnv*E5Y^7$(A=Fg^#Dpa?SrITpr?91;_W{Ss_ux{N&t0KHa@0ci)*Z~+ST#%y=N z6N`he2;@wJ4`yagHp+<@7ctK_4Mzb!#HD8)g3Sazf8UYg|XR^Zr*+DG+z!Y%9Ga_s$ zA5j$yrZJWc<5gw@8ckFysOPx7m;8rae&+*ZKh1>85;D(%+kvWi>5$oKPzL=A3WzgVF|=sZVUTGzB5DoYh${x z$2q_Yx(aZZud+FOxB}aUF;{@Wvk)@CIf}c^w8r}n#0x{kv9z0P$HO*d&n%mBraqnH zU`TLU<>@D-@O&!|VcNGZbxUWa>Z+xvNfiKlSkC#J^b0(o`RD1ozPgVO-E|ApTGPlw zPP)^&d=ECc&*}gvE+Lg88ISify2aBM>xJ_9F21TqZvts=(}Z56q1WU9+FsOzd)C8> z+a}sV%X{A4>sft7j;gNf&5>Eq3M6bT`)8WaYZIWTJi9*93LGLt+XQszK6R)}wn!vG z9{n-kGVOxSZvYwAhVMhMz15;NsBvys0@`u_5yX7a>}Ibxn;0UemY{1{3&;gip#cBTCzajKynnl!{2@KWh7<@DcGLdh%p`Ff!@+@P*mR#OC;_#!>n zh4YS9@IbIIt4Dqr%J0dXvEV_#TN?W!OTp8MGtB#$h3)AM4F$C*ZDdR=IJHa1ER z{XMF{Dw@nn(2d~L);@i^gb;OONs!rJ>-sfdI|Zd?mPFE1lYgntg3m^xqITz%UV}^q zYh>f}ii!tWy(Os00w`y!54}y!6T}qc7LX!e%q5w}*N%WjB20ay@zVEHbD{jG+{}(k z3m_9J;~sY+g)>R@!)h2i%1lH6Q~|OFx53gvN-(Bo+dwfC?{PmNp-Bh!7Jx&Ki6t)| zDZbDFp3#!n*4XQTsC}$wQ3S_S)J=#->6-)&lnyFxkkgclbA6S=SIyvZP}#k83hx?+ z6+;CY=>%((C-B@7Bx>J%QJzE(ff6csiYw546~bt4(?y*$dbY@s24s1M{QRn%s7vIDKK%9U^>UWhh|p#0@NbzE=oK4al7!Fc999b z9-u=)r~{1akesl9;8_ibtZE?=Qg1q7M3)UK6w%)=@;KK4f!CEO&~^6bsMHAl1LKTS zmpVSp`30j_#7uqa(RMznLxPoS3*GH})~ctx13A~qw;wR2PT<|PC%CpILLE?Q6*8~} zB0}H81_*g{^ra+Ncqk~MUvV;_?Idtm#<1@Cn--1IU=3c`P%Hj83S3GEfD zU?o59O@C~i`lmPT9(RC}u>M znsQMeU3w(c0X%NEL6;kJD}X!Q6FYLwW`fHzQQCdjH>}^tmEQi3VW*Rg54rp(t>!k8iKIUmpCBkJ=M>yxw0!WvK(P9g+FwC!PrJ_do_LKBqtC z0JHVT105LPwKdv`QnS@0P|eD97yImo5GWz(_MbOeId{=7xxEeDX{l>Z#EC4xO|H!& zezkGh=3HUyti-R-0q+-uq2i^&&7wq#t9TfOaE&{LA}{*aPTCtoo6XTCGRubn*MUIr z@*q^AR8fhWBZ(Oz1rYcG?_$^-I{B=8b9I*mVZtB-VeYH1Y{Bs?IWaUa=1EX{oYkb@ z-aUEO9WK3iXqhw+6TvcNhUj&qhlw*yNk&R)? zf-^6NH3q0X<)fjIOi!0apA%&Ejt%%%s~d5VPcMF^wGv0JQ-f0fa_0$;LE0JDE1);( zM3XWYPIF#mO5@xbEHMG&nD+>?y78X_V>mGK&wEDu{#eD%IIiOHmmA#W@hs;Z$9pHm zNa#sHF4s@LfzV0dDwbt5tPvPscJv0O(4hF6s8S^$ewI$ZDRz(!@Y({Uvxxhv2f{@5?h!{bzd4m`Z4W0()W;WyIyX#q}W5;>*PstCP7V z@wdxwi5RmBTCnFd@q#ek)*Cx*^=YuHuf$`Od7l|k-ABYHu0#{ipdLFO3wEmITao7? zp!?x(myW|lVK;Az+~=9PC4SS8y4SC8S_Cc|&J*4ucIxlQ&_5vQmiwuGuFKv)-rge4 ziSGJ)<#0djZF9t*g+RThRpB?jNv;mr#Sn%*MUPU z8AiZ|P&TG404wpFM2rjm+sck-4RB;JWfzK%XI1mzzd5D#TLi@CgObh?92n+p%Mc%l z?`ZdW5A3gAi$dVL-muQCQ1SVeD}bxuM)TZzF4PB${Z>mpw*MH+=yRxuwvpTCqzo=S z%YwXu?JsuiQ7^w0NaSIwHv&{eKpw`x%q{WL-k&(YWA-aDQ#VVQ?Q*d#f}?fQQKF#7 z$3;QWtw6W_TABDFYZ#Da&&S__ax<2ZX?jdwMc(&So>-V-LOso2%Widig&P)&D5``(nI?i!krCIvX|&*mgadb%-%?7Rux>C%`EH@w6_TVEoib6MzF3C?+ii2r zC%AuR#o7sG!_kF!^AC9Tgq9OD%i=UpzKT#gTB(XaaxJx>Dv)na|JEu(1$lo&6Q<41 zV>m9wK%Dl4_F1{b_#b@v#R^wYf^x0k`YV1H#4yP&B|8)(CQJO$8zf40ZKK*R$F(~~bVGiXi**9JNnQ<}w6 z%G-Qtw|Owjd0{0-G6mQJ!T8YFPq&p}N8 zv|`lG3s9K({eZJ)YU@bnPjO^!b9>Atgh84S)o1p62b0;w+=@^RAgy$VYo~<;8_tbM zUTrpHPMsO(S2S>!X}BnBRh0T(<=Udg4BprN4s*?LCKJNHNHUG1y6ZFFS zFk(G*8&(jjer-Ry!|m7Kg>=<}?AsP`WAwpNr8*e7 zKAN9LNa(Ijc^S^Z3j_Hw0S%f-a(P?npgdcp_)lHP9Ro0N;;VwjDJ~hq-$*VQY&zfL zjmiIqw=)fgGH@UDJNt}fjC~1>HTy1WjD5&5wyc${q9|*jZOprc-fLy#t{<5pS*~rR+d)vT%HI>p|u2(r~?JV1`w2%F)$e3;daPjgO@D zPIE_lpIz&fX`w*J#_t&`VDLBs&A0D`2Ld*F5A`H@RUtXpYgoxw{|O?`VStl0oV?Kp z!=bN6zPZOrZ@O7#D|b93JB?tB9u1PO;+2)Kkxsm4#9@6nFilTwc`W(8>hc3%^Z_vl zZzko%$s{PQXX$f75jZ(0jCCEFfwCF-W~)La)kiz1CuucIs&BzY#WR+=ZoeK-dvr<#C_GXM_brStu?otpuZs&x z|G9Lao<)Je(@G4q6%{N$;Dt#3pe-_wkea)aeF}NR`s}{UNzs$0@M=st_mBz5Eo1Ex zRqp6$BN5}YiDjizj7J`747krxGYoy7c49qX`Zwi_htw*5+U=;?PCwv(=2jfJce*vM zJoSrlxu0ccxB#W}5LQ@@>i_1h?g`9Uh2bJSm5TPHl!&wuRq57n3r2$Jwbq(~^gOZ? z-(4BA(*YQl05fZ1S3RF841+XMlR60%+~u9vfy@8k1ai6DRSu`xX*Bh@XVwS^IY4l1 zLxg|7jaEml^mee8xNLHEc@{G39ZhwH53Pv~Nb!N#C(0BKSosCq9~2Do% zI!j#jujSIm zd^s}hyYjIgk8Nu&=JhbK;=N`Ky$nIOzebO}8 zX}KkLWPl1s@Hck0K`ggMJv~iC`NAW{id6iUj1~=?cpqCPqh`4;rfc>dqF9S$SlV(P z0<(jF4ohE44vl8p*Z!NJE*Cx6(oAMZ-K`$)Z4O)D>ySMBr!NE*u~>UpbF?3=BSrQz z2d>rh$J*6j-%aH;KW^xH>!IugR-2-NqcGp|4+Ao4uqs}JrST&S(&Ah&RSY3B6c|>X zrxx?hjHcxN)Im_{$b*n$PrP~kVk?T?i`r`OD~x3i!*9!G1_F|Y`4a1Ow5rJGeCPK# zZb+Bk(!S~_N%qKWaF^xwnD;n8_0+xNnVUZvQeh>3EJ`uu(JMpn~nx|(dDb}p-4)%bjv-Qlw5$JevIDIPsKbLH8q z!rJgV(l2K?7%ST~i)j-r-yB$ogxwT+$ArdhFN^cND=AdjPRaS23uIoGTU$F0)dTmx z9X?pv1LqXcxdZRhnsdfR>rZyfMy|7JU>t!#d2t5%;~qS94Aa^l9XaijpreYP@>R2J zNqIi|XUQlIGpFa)9acw=+#RgeiS1te{XIkRGLHA>;E^8uYL6c~fci>22!$82%!0|D z9NyLMO_sAir*r9)8fU+qe&>0+4r3AT(1yOFbAh!zg;~|ardM4N+E$*m$-uz7q5F+d z#owFH9Qm35`udM37UW2V5y8F+xUQ=4!UtJvXWjb7l zCq*1%XpACO2r*Cek0si1XJ*;u2$bRuM#NNmZ6=vE-Wo?V#Q?s4m)4VmW%7pVQ;RPL z9%)LyJ)~XhgjW&wbG0Prq1$9w5?Qug5Y3zlIPvb_sQaiTm z+b4JxgWFeHo8zqHrM^(>|H=%1OdLF9ex~n`Gigg^`x`-) z_`2e{oX-ld-o6bLeo3V8#`{ai*Yp$f{|snaVm^hvAS2XqecyPX2|#Lz^w--UCLTvN zfdg9*JfujXEq2EU&jkqw9G4RiB1i!M>Pa%m5)t$xJ%p#q9#RAc!=IW|3CrR30e)_o zy!_UcL*kd~h`{p?^Aw6FSur>%dzlREQmJGLrNT60^2kh78*>>%4wQ)M+^JLITIEE_ z)}TlVP|hE!!Tr6m&q2CY8KoreeMgNGE*sG0^z4HG7-h01~)(|}tjfI`(^?`q3m zR~kSw-SaUM4;9r>!36F~u;(TlJDe%!XHX>11PL5eOTU>0CZA48)wM|W_UE5vN|khQ zn2K|$HFp3S3Fe+;KqOHg54n*?W^8l-%Vg-+1o=F`LAIU2f{3933u5d3z?MPK&$Z}w zb?bHu>UNLrK1S>I$nN$m@Aj(i_NH0o{?@Z!P6EQ8CD*j~(~quCg4Z2@kz{EuI##~T-TUqhnq}{PBQY_%g}R{^yox%r zYX#%gV^@f%hLkJHwHZ~$CS&Xw{?%NU6q3$YPz9J!-B=}s__m_h&fA_aP?>qV4c>1A zK=siGG*DCsim0G()ft2JpgTDMAS57`AtYn8d2d5*ApLp@&7@ZsWzWoRg;QHxI+M{zUjD?_d3P2rKcWBDgSGV;K7Sd{4}lTe z&3Aj;iOnIGX||0|Oh6h<<2fylVrdL69JMD~pee?k373h z;E3$tsLtS6bTi0BW^e(PpqO23Uqd&dGKVG(w-R zPnMCz*n@D2GN{N*Fwvm8hr{!fX{O;&;Xi%17oL8p?&~ddbbIqME?fJ!F&OV=pCV#q zUqPEF00&gS0ov=`?AO1_U+>kw{@wNZ&zskO-@pDT+e@86om^<1{ffB*K1iCu$dQt+ zhbI99ihu@1J^b#>fCcmk+F!pWo7r-+6K+uf?+JVzCeuidf(K6z0iHvAe;sLHQ%ICk z@QsGA;*IPpj|LX>-cb_)9D-Ah3&&aJK&GaAm8tJV%aW0Y+hEZO6d_Nl(X+CifLH6# zqnGCxhWd!#n4V0~KJT2d;Co%r(kOXD@7?dG=526oRhlh&jGYPCYrlP>xudsIKBRrz zoHmmrEUzw;y#l@`0+WfhcizC^ zowP~kBX2pDSH~7g5od;>dZZ+24QOUG)u>{4Z8U4rm!V6x&LN?OgNI|#fR8E| zADR>apu!c<04FL6krYmx07OtHJ>-YsDSQ}VoM8*u#^*!eX%@s)>DB3yYax+5BH2Ow~LqwT|z z?)#FPv3HsJbaj@=Nioy3+N8WYXwx?D)!r!zSn#Nnrb~hvf!;Sa#|-Q|%fq}g&^b?v zyp&Vih6tROF4H}j2yZf@?C(3vlEFD54<-CfpcyNG0Xcvs3n)-8;yv!)5jFGk?crve zd#~h0^vPMKmu;{dTN($t8v%g+bh($tG)h5#pfc&BIS7Id8$$ch3?k5u!D8+GZ<~ZWY!^fxO8gx&_$~2L`Ynq9iD5yB`Pm9axs^{+jm@e+# zx>atVUm_)Vc;o8R%AJ$JJ7W;}8K~rp{iq^EM5}KYalDb3IppsfszZHvoSUz%%)fZ-!}bQ`=Gs@Qj7#UiMBO zzjdfr?_yehT8jdDbvONz{Abbn)>*==v3cO<1jZ{X%(LFwxDLkUaaUs#jC1L{=SR4G z`W@=V!X>3sZ0geE;D{1HKRG!&we-ed93$Deqb}`QrIKqjvdJCOWZEL92uLsqk+4`(1i*LwS;tVCgk&pY&7XX&m>` z6?_Rt?l!Ez7cd2q40^g6&Yya%b){yh;b;xatk-psb8h4;Z|%nd;^}jMqPe5)(o>|` zvxe19=F)TdtgGXzt!e=;)N&8ho@tZ++JVKUDvIP{R-QiR%{lz_<;SYGjnKjzSnu1W zsKl=W7u9`4&NPmV|9l)ec>3%}-W)tSbi_K0!PoNU^xF8vwTZ;F$=tPf|AHn&LZ*7w z-v8?y_t#~A__6j0xjrMbUJR!A*DuXluXmhQDIq=Kkw>;Vt}jb6jbg_Gvs9C?xK-t} zMuEUD<7jCio}%#6?=$}pSq)P@BjNvs zKtF{w3ARY9e}v2@rR8Ir$-9&~WRU1;*zQ?siR34PvzsazvJZzNRDW)s?#3K$`>K9u z>r6v3yHPF5E0OVfJW{_Ae$Z(v&uUBm-qzaVNC&SC!-=R%-dxO&BFu#EM})VD6c_^? z-HF~X^Vs&Y+nmwgwn~Z?--eG|-X=bcK5_2d(TVL1IoL?WwgYNM(C9nq(2mQ`bN=W+ zSC1IZQzH5&cRYk^q`oz&`bT@#m}o%>qIbZhDyM}!$*SI zT?&yYp40$YhVHJx1F_whn>(MPM{AOoZ%tmF%WrWA>e2ep2 z!1Kh7wyYZmxePYq_1lWxOI58}Ewh1h%(k5gliv({ezvf*&g8GPmB=_T`qK^C^GBc& z57U5^?8(hAa9TfWioQ;WP1&Wn0a?+v=_?MHks4N{jdiiaw&lU}C-?>r@Rx)zg0pHm z9fMIOpidD|Qw7ri`Hz&X+QUP!OA6cpTQY{PXm)D<0STSe!~m|CUX`%acj8L#=Ki0u%3Ij~v`u^1e<3(AOdGJ${iHe1}^t zv^PE`T%ZHw{b_57u9g1pJ`3=!%zybT65T8|W&5+0JRXOB*_5+S$J+c`iP7>LC^WpZ z`Sr`zAyScm#grjhfsChFz-D~JwiVx0pd)O#?Q+h(t@ge>C2Pxh%Hz1_(=63Ja~H>1=$bdn?n?GSu0Gq;WBPfo@EB2K!*7A+d^ zyS7$}R!0x|L_IXiJEHjf4OBWsbw!qy!gz3r8TkGIZ`rj|aMA%{Uquiq-OSo11vG!W zi@19HgL6sd(@H+x81yf`Q&v9p*>tQ4d6P58Azn03<(B0&1Nr<@KiJY&SAhgLAKG*(v9HuR?id{I9piTPl8W zdd1s4`(k(Uo%yS>!em1wS~$E$zOvH#$MNC{6GT;2ZU5el%DSm45!I*5Rj-aUf80~9 zQTQT#vZniVeD3`orROSjgNDCV>i^@jc>7OmAa>mR|IF_}_HpIv{|8)|sA&dpiT_`5 zWdm1%{~cG}&+jE`xsg>Z|AQ-6{wKf3eM^OW&zta-yHNAV{fYmX-?OxY>|yF}N(1n^ z|Ai}~@})v?_=6w+2d=DPi{|4}{_nUlNpHUs%7iWaf5w#;FKiXOc)?!#6}t6_3^$qJ zHY4CqHuiddUbMb^sK zCm~hZSOaKxogF_sGpfp9mBvqQg4I%$8ou7Gs5FEWx;g>*IJX=^`NOD(`Y^MR^KJ%z zI1BIgwo!0;t7LxcU3ig{N9oI5MIunbQSGB;+R9Imp?`k9uv~7~>}PgATO) zD-$Itt}}FJANzDP$a|@Dzv&M)+sH6J>fGM9!KQ(u091{Zy!`NBw9>{v)MqU->HS8G zmKF~!fEyx?ZxI#KZoaZLbLnN{O}HFop#FQbYliW+fleZTB$_T7Ebg8S+uc2rr_RG=c1c}4@fB9K<>v>el-5ialwWe zq(bnlD9nID7*fd4zJ-kA2szrEU89l`8yLHXwwBGmgs)eq;Gxa=B@O2q$$$?_hbPQ zgZh>5s;3>hpJ~7%JEspIHysizsRjEV(721dz%^WX=|KsiHe}_VqZ0aNEI(RWr&2h< zO$uQ2nwx;~Xi=}B@)}GKU@3Z(3Q9?Bl4Us-L?7XBaCn|L(G(U=1%UJ`T2gYhoHQ*5 z|Dm*p`V+JEmP{A$&5atV9wMh!a>`7{ITXWMOWg47vA$kO_KXcbYHp;Jm}y!BzkhB! z!TQ>^Oy<^Z0MD-}rsd)CgX!WD_6<|xsFn(e+;b?yMJdDh#!LyP(j=p8`q-pz)Qya7 zXGv~pd-!2m-NkZ7zt}2ExM}>!#_%e^FvP2neetl~tpg9tccnZ_YWfvz{T^I6@!Pww zG^(L+;M|E?%M^g-+W1du&TyDFJ-h-Yp(X}CMw-hc)WA;Y@}Xs)XrCxVQ!N}am7>oC zb|!d|@JsrrIu5OqXWR8oe0sMYoL6&VIu%9>(M5#txt3v=L!1FuOj~jwd)SH2%0_6#qZXbDz-U!TM#V9`b zFPA0^n8SU$d(Zk+Kj9*QI|1zQN4z^@K^lOYa(x#3p+%%zy>f4HF&*zA0&14Cu!@#n z?{GjY%~=LaUHx?f*Snjn$HusSoAc}@w3&yIMlw^czFqk2P@Vrw2=f_7S-=sEURMNV z*bWoKc@k&CyU`{dDB$(Flq0vPL5b^fHaEuwg>fSjDZi-YuR`xf)XRVBw0U)xiI-ax zAK7&^8p)@MH`SpGNIeF?U8{QoW~djA`YWb`XUR}V!$rj0{Z*t<*laTP(dDc6n#{W- zwu2h#b;rDXk1jNf4gGjg{b0>J79RA^MzP$38 zz{7Fsb42$%^6#>im!4&I`u5!v+NF@gXbB#z#thZzFP@LUZ_i{uX}6|Nw$964gW(5& zGk?E|x4Wfav>M~c0@UD)-_|rHEfV9(y+-^(gOAQ?j+cpPWzpZGoH9Lx%MV&(EX?Bz z>A<#q%zH8Y*+Y+*ai>?c(aPxYEhs`<*>wE@Rv_(c_x^U#hc-Njcoxq8DCRCsC;!BWr z5dda;62wJ(;t@P}eIIEejz|rY&5QXYPubM4D(cd?zUXWs>*eT%v;RpEyJT%RZ%cB~ zw;z++PnD`RT-1Wvz8}WM+~JuX#_oQm^4NI76RafNJz)MiA7_LunWq9aj1#taUXhN$ zGNasf!@V~+_j78*2y7S$=Z!;49l99$RuMuv)<(ki=v@hEjF=?}ay~|tzu`XVhk{CB zui)Kp)+n&p0!aldAW9(j} zgFq|}B@%haRo_gI=Vcq`tZpXoQ~H)R&!$F}4S&>klFWXLjL$aftF;fi5odbO;vd`d zhSs~V;h)3<267HT1{38Lw&jt05wcD76oM$P4UNyX%kqc;pJ~&LZK=>NS>CntMnAVs zayH=hz3s|D*bP8^u}0OoNo{TM#ObHJAx*e2+t43L>JeWqpJOl)nm66NB-&29Yv-zH zMd8Pp%mw^KWbDnCOSbigcv&P|C>r}A9J@MtO*0S&KIXz-CFGJtV7`N6D|PGyX>Q@3z#93z4L`+h~%;E&HhewX2o zxk8e|DMdjcEc8x|x6tRy-)15Ty|_Cjzp;(*m+qJ=p8 zS?IMHZZRq-IH!+M!cEn1uHw17$!eDY?r0Hn2nl=JPba()6=tTB`h+#(@4e`O^VmoY z{lT?2$6+1L)zQY?9G-&wUdo|)!NL8QAT_Qa4kw_M0%Jos&){HAWb`ow9H%rcdWlPv zfU{;oJ!gccrFqUB!qsMT2_g_$qtL%dC^Q0@V2z3Cj9}zW@+MfTxVQC1}9*4;v0^;HEI@u`-Bj_=NDY67OB~Pf!nkug7(~Nr#@s*|8KC zez_gU_2)@=z>&#Q$Op)>RQ|jb{u7QAyn%C<@_adroz)<$ZN$MNps}Y#RhdHj!)*l` zmbjz%hjbh*3ugmdQsL_R8N=k4Ji$2lf+)bM#9RyGODWAxy6QlwLYJ8UYft;Qpwe0X!^%8@}!~JhS3j9xm}o;86ln zMG1E}9Ql{&)~$7}4YzNRgoSSKSZ$>KE45c3asH`6722X2>Y;w)*l+GUe#(Y&HJ1_2 z@Uye96kFW+wu?wj*f+olGkF{02MHsgTt6MQqhnPIQG~+CD6uTd(NIvQ`!=2=F^;sN884I!>k)+OZ5CxO8 zTsYoqK>G0csM!_@`@Y1zB&S=lxYxVL8J3b~F0MTucP$+5f=8b|>eOU`GPN; zEV1XVd$5G|3~|cgxb`Zm{cId$2DvvJi^#-8xbysoMJ%4tG7<##)8w%h&@dd@2ang> zcyx7Em;r~h1@ZVO;hM#O(hWa|p9U;J*Mq$Ow5=-$-pbPKYtxrJR580Mu^OJXO^TXl zVO>!tkX^T-v%(wFYHY6p=m<7(TXSARxge(uAJt8*JO0B%T9jeDjhA_#7zj1>?x_v-#|n+Mm9DI9{mHXEXPNlmgFyBUs&VRlH*2`fn3PtOp&{nfSt zc>38;TSINXI;i@+0G<_=<}6En2QW`~h3%%?JW?n=$Lzi%V1$8S>-exP)!19+tmde@ zudG#T18~pGv3#E9yITEyOL=&j+5ig)rKn-7%>=S4lF#AN8A?wT@!eY|7RUxE(%1@0 zP{0<3pQ_ehiv6aGo2=4=MHiffqja9%4p-DXuoNdxUQQ-G6w8X8G6BNqS zH8!))j9SW>XMY{W%2I~bW?%Qyg*BT5*xAE!+@qgMdQ|8CzF~fZ$UcWVK^hLX8V6;AV zb$me=N90X@CG2E8g9)9)_IM)C+_ex@lyF>|81pxf`BL*Ck4Rw#!ldA-fd)Ttl)jR2 zWJDk{OyUf@lq>-VsH7e)f!pJr!ZK6dK)8gBrpESjVm-A=Ouxp>claPp&_}G&4 zX5n~bjNALqACC2RU@33MJ^-Pg-;!LERzZ-b}U%LDapN$_Yl| z?^(}{pMC1#MHU?LDOcv*1@#tvcvdZLww7?%56-;PWCc zdxwU#*%9>!&&B5nA3}@82afPyK`QU8@ShSaLV)KNlV_P7j)f?RzanvWboE^}(YU3R z_13+cyB+&BwEO$!t;F#IyAofXB-m^ita!Ms9HZeHB%~W8#*n-eGh-jq&F+cZF_xOf zpH$ymx|ZBpf)qINPbkNBZuJS)SU+b~vVvEx$ag^DtFh;YP7?*)Wp8=iO0*`OCn5n} z;%YBr*twSe`lAXF##6#?D8?UXD1*NLk4Hqvt@c=x=H!B&C`Htn~Y^_EL+J=fobnroS;U(8X}A0F-Q zb*FHF3?E#m5f0mg>o2$0lcV~Tzcn)Bjz0PG;x`e>RhcZ*mdD*zNX=rN56_u4ha5wk z-#Hzq=6skCz;mqBr7gr8zg#jC4vWA}wVjN5?zGc}HH?!GVgG6m_*rVY7juyBZTOzN z88_?2UiFK;a`xV(g94GCJgsN+Aj5Mgsl&$v@-E`-1K}J?O4X1J#lan1#iR@4BrcNV zXHF($1Mt;BTd?wGrnwqD|AiBOVcGNXslmh9Imgz#8^WglT@m~#Nb-Wb z|JeQNN41wP(qbJkP;=qGaOGFVr^7{cGr!}8d{D2C1F`4{)l}ivC!W{fK6ks`BdI(G z(z&y+gjU6MUTK0nu~^;doi?fLBE%H7weAIpg>L@qTKnI=gd zHzYMdkgsT{Zx_v{r@4fglT ze{kiO(jjfYiTMfz_;alqGt@zvhB@X?d5wAJa)gt7WmjE|1&=9Q(~{RlwpJzX@%_-2 zw1qydcD|E^B-O{{Ek-NEgQD4$>)T)ZG97*EvqGWob}bPY)6%k)yFQg^lNoOSzL2|D z{@70W`s43*sxPOU?@BmLY1wPOtk!C3{g;Kdd(jI`9N^&mT6t9Ob9tR3&u@y0LvrDp zv7z^S+u9^El$^k!z4-4LY#Hq^+xp?#zRu{I#=IP-%{3&tbzB|#yobt8s$pnZz*5z@ z8xEJN-r#kyE_X&wB4OKZUT5ya40{Cd$>+J9TSWJ}W@|_T#__Ib7b<8b^sXg)@rl=& z+aI_yjJa0eQ^oe~3K>Q?!@JX6)d)S`2-W&|JHIJ`@JXOSw?`zPhpu-bZhrcrVa#XM zTIVZ27lk|gzomVfmPX_Udm9F>>G{*8%!eEaP;%LjF@R<9r>OVn2c{m)j`GhiH9;F( z9n^~LI-1rcb1FyCns_Q>C1zNbdFG?=kipU13fo+H`_eLW366#X0JNgn9@V|BQ z;<3|hEZMwMzp||>*s|q{T!+chvUcW}q;fP6TFV1{-kSy8rJub!ar!{%Ns4nfzA~=U zOGez(ts{+bab`K`AatXo?1gglDE`T`wej~zSjB;7M^Bi0yfTE&1g@ut*GNSS>Zx-L zei=sSlKW<1l^e3cPQgCO?+Crz6DO07T%1@F&ySk6F!nLLdBUpT`%ezjW*Z5CEOVz~ z?B?OP#hZ^@2WKuMU3*U`wIL=KM2~4l@_57-$A3fA|8i4sI5~Z1{e_L`)s9H;!lj*0 zNw-x*=aYu6Y*sE5T>E>qdX@EW%%fX_$S!?`EJMs zm0YSH^3s;6Op7v`AUVK|mXS73B5Nc(mYzlHHkupVX%9XyGA%5|S4(d+!$yUpvAkMM z;0P%iX(n+{A;H3Ax63bX!@}G$21mgld<@=MKGA`4B*vOc71c;T(GREw2drf7q1zO@ z(7YP)neHgaym_-ehfqVUWyUn|Km(2}EJ;g7`3JtoZq_8#XaZVpy%M|u-Hn61hkix% z$_X?v<&-j|tH;oy{gL#rG_@rC0@#YAG{WS4J2n_3zP=(tes{zY%j;ud`B>k zg_Fnj7`|#auvf>$h8iC3rUgmVIc3hN3+cSJ&JWjA0C6~_Y$>Z)D=ogc@{>3V4@}%m zJ$}9$m)5FidVOG9Ixm;mKtk~{?F)5^keTmj$q8Ww$-;ns_saHrkl0h^T$M_!=FPk4 z$`EtBVixdh8?PRtbYTXMqIy2YmMQxH6?ShEo9oYrj~wXgx@Aaihn$Ydv+z9lxUo`9 zwlaz=YLh&p8`JaVAzkyHdDdH;PPDm0k1w%hyAD^7=XRkjd_p~D&XJ0SIkosP*cLvK zCTVSq5?Urggu5#9Dz;lNpPZt9;}6a{AhKbWi#*B^r<5dkohs?Fw*5D4VH8R%nq!d(1nM zL23_U5#$F{{*xUxLW6X)Dn)a0-+$xq?`p5ZGeLkT7I>#E`hX@g{{t_Q+LU(n8!TnH zu-GdrlCP=5T;vGR0Ni+SwynWim22}RfzE_ zT7d6)4SdI>7CS6_GlvnBvt6aUBh%u$%K@}qsaDRWlgYo`yFQ+;ztm7J zE;IcXv#%y>eX_|KU)4Ei>5+0R-J$$QFxY(mHShk;I;n$S;%xmCBsg4)CyO`0(=$Ww z#2C1FZbcN*-;Xr-_|`I#D=EMb_;?Ln|1vTxZTYg4t{n0Sx7Gu;k;eEt30~xjow&Rp z;D%S=uLqi%kzrR3Xg`0s(UmR8$(y;dGJ^TFb~QnS#9&^LY5~`e@kV2BgA*=1c z@(0Td5=yK1B+AJ0Suy{O0}G6MXoW|jk&IRaeV2tYZL7)BgR+064dMuwz;V?mEP(DNIzStEwrQbpbFlZ-zq=)H-*+KE=lNB`K8^T}&<+%Lf? zKiO?8%X@B8RHM#l!`J>UGmPX5^8wYy)JI;yJcb2zMODI5a!!ymSOG7!>n&i^7q+Nh#+2!?ciQb5*$nVL(3Zo;C!aAa$RopP8Hw&wPCfV) zUbf7y(aV@jklwS> zl}=s2ceM?-2Z?q@6oA><=)afIZ3UQ1kP@%}%v0EBbS(5|WX|31nO3RY^RO*v=Bi=Vrm*R@XP=Bn0h$~9cv8EO4Th7 zcfR)|(gC??Be3{aE1gwU5dV}dUIilr*BMqko=4er0G|wL0U*&FebI*k+Fe4>9eFkG3OW%yF_?QXWNwvE= z8|P2%|M|WSvaPQh+7#@*O|YTkd-Dc(5vvt55f$xZSm8N4e})L?3tC1XOln#(M-J;; zK^OTNlHzZ+5(}>Dpqb^O@>ewPzR9{UOYIY-U+A;0apR*1w9{kv)oIlG#s)glb43>o7)U1)-(O*p&pKvIS|$d|d9=|x4p`DQ9yNX$ct)-64Z$YH z-aPEwMJHkdMGzToO;HAoz^($4o7_{bkgQ*l>kHcP4k;Sg6^7rPTa}I7!u*bU_@VLO z{+82(!Qc*Z;`mZBJyw#~Oue~jb3hv`&}mH^HlZyyHwS_xcIa7GP;F+UI8W<|-F{cG zU?*C6F%ZPNxG*-vAOl0!%$%vXmS6ms+q4X#PT_QQwLlt=b?s2!bng6(>_h|fIu-01 z$Y%?PRWH^cEJM)3_Gp75P^S@Ym@|}A0sC!GMLhG_XhTQC-yhQ3J?sn2V) zaz3IA$j?BwXclpO~N5}=sGj701~My3gg$otCj|utxXnw?VN}P55&Bq97%~ZGfT=- zIH~F!16O2%?~2ir`OA~-e$eLs4Z~9@g zb<)#ou4F!$BVxJncfb=QgxxZ9Z_zs;z+xc~rVqZIr8m-+t4G(W(EB;uW=yo=aYB>i z$cF-yJ0g(|z7`Xy==7@-`E(g0ZTBR=L2mf=@8; zFfHQi{9UN5AC&#f5~9XwwoJJt_S!@T zp}BCGiju!>cfU&ZwfO4Y5XdLOq<>%t^0`&{0vR>bpI0(oM&5dlD^I6aTWT&8niU*X zm`ZCyd_-6}BHxKx6|E-lf7a}ZQ>_^2o==<1bw~$IyaHxIaF*B5w305zXr$#sjcrF1gmJ|Q+CPk6 zeBSY5OV7D$M(i;hJscRk%umVRq~d?ot>6)iBXWNW9Tmq*Qyq<)S;FBCJRr*v2(s7WJDmIFS& zhK>z7C^~gIF+3@XNd_x{z}LT?~7VmR-)jad#q0EtN+bT{Z1JWDdf`J|_j= zAU_Z7tZYh=t^S;>cHK4eeJzixRwr9L(ATpgI|R>&e~DrWJInNW6Wy859ET8 zqQnn=P{R&}@W)EwvqYU;(fC1blikq5n({~RDa-q?7rx>tJ+);8_pYeily>>X@@rOs z(yM~d8s_1U3m>j`RJPr}khoiCS4(#cZt5NHDVgEDc>cv7AxwZf^{9Si=cJ&drr4cK zZ&C5onLilitjG)zI(uRhZl)BK$dXr7I$(lp5#MK3jarPu74w>4LMKfg`MUf|2S;kD z1mW$Nh%hNrbbvlR#EWVS76jtE-XS$A9nY}BH$nY3&qz1yK7)-#XdTvOOI}!6(ERSd zXjxQA5b5sjdGwy+Sg3vKp*Kq1_`53XBE>g?IjwhoXhc8O7Z2oJqIqt8*xB%4#Y|lr z?vUpyiaxnTYqvA|p}oUW-iR_)+0odEEZpGXqLM7X6n~zoyfd0{5_M7U{0);Y*%~`O zFK!(>b_0x@jKMGL{Oeow=Uz-FXNA{kleNsjMYt;I+9;=5bM-LW7xsy)syvZ}6|D_=WDoP# z&dbs5Lgx43>Pz|hyI*?Gark3CcncFc?p(jRNJmGSA5K9Es{e3Ha#;TOTYQGbLU3}% zfNi<1v1;0Hi;DVG`%S>Y&uDQ1G`Tp+{j&(G4d#K5YpXffOHr}pQPw*4TYleoTZ~!h zd3WbC_s!j%3i)b^ddjR;V%<%KpBc2u5uH3S_TUlU!wb_A`3eScyO-`U*WAIw%cl!W z*VCRaL+BQ57tDG29B6h@-Floq#=)g2iJ=VFY}|yo0g{b7u_|zNH1Q9cwL6tC+xsAF zu^eQF--tT3j@ApO=gq|PCC6Vj6;qGcEwIuqs{GZO@wcN_^@f&0r{0fu*E0>j)){aC zE;l`!4o>S>7KeJHYbVaj99;r8{?V8Bm8O5!Y|y&$wXWwbv$*j6{xLlAdG+qq}lIU98QJw_adeq>F zHFJ~oXX$A{=Tep4Hy&(y%uP_qdk?fLEv>EoRG;~;{9bEgWyv9S$~}UlNyRqbLIxQS zUEn9m6;sVC8_e?RWQ4@&X8jR?hEjz<ZF45NhlAzb$k+v*iq@_HK z|MgVd>gdzn9sC220f{Q_YFxUKlY|b3D@!Dn6n=v5J2Kb%zH%_ zlAK$+>D}jelJ%t-a_PMvE~(Pry!vmP-T6P%kN^MsSrJ6B=Aqi0k+4t;~wFZN+h9sn3NF}MzUV1s+@6Y+3%lBN)`Qcp7pD=T|%v|R3 zocrT;b>GmH&rOwFJY1pftJ{I~W32KoWG?>-sql|asJTrV5J{-a7Q%k>^=;QZbl3c> z+l846E28pJIl}jAoCs_pw^YKugQ$x_Kw?3NY++cvjR>K?)B2dE;g|wo-nWn>9DOD; zcjk_iXnTd#xpEvQM6&D$x;#y>zQ#L^w-W33`0L`dmNK^(wJ3CZ2VHQB%SqWE=!(vY zm;ReHUXW4Wy;<*fYqY+kFLraflG=q*wPLQFP;H_Pd1hY)tA(C!9uo6f$UuHPuhy>m zw=Kk6%k&V&Y4R1P;l66sd_$91_Va6WL|+K{L2=b3NypBKr8aAEge8Vx z`8-XT3@ zv1_(ut;O9x7VnlZzmSBkb7@Bw>X&{L+Z%5-3g~|m{_NrIkT7cKRl-f1l=a40Y#BM!G%VR2J=q{%^HHD} zb{aIA`z-hBXwBk6;Qq(k9a{Kyrq#EWBWkYtI+t>w`%!cBU6NE_(2ED{xmvXOC!%9 zSb=;v4P-rlZ}31WN{J5HTyZw#TAUz#?W|XZ^BJAN*#Nx!t7jwz7!P#KoBq%d~B3a2rhEo*WZKN>q@XcrIC;=}a&Y#h^vcrABAQ$kR3`_X#)&R{pNs*M#Xvm4cklBBN@LxNnii z78@RNGzq8LlAWrLSs1jAYP^(tYn$;tOHKtRfbxOMtvNAmbPmfPlNH;i*s5YPYq7cg z8|2(T{v!q(6~f(s^s)M*d5j$TX&om2(elX@>s3wNE*?EY+1!O#w!YS3rr1&f!VC%F z6GapGk#e~PdcjrrE|_$*f+L;Ch>a3uOXHRRYbAN!6K)*&EKhDL>V28ZB9?p<7K%*R zKbG(3#+2tbMA9jc%1OvE)i1I}N1N7<<4HM+0=q)?DQR-FVn^f0HhIB6bv0b>GgXhS zN{=3U(8g7e-hv4R99OhuE+8rVS6B#?f}(;u5rxlR$})1=s6p>cJDz2xMs|Of=U~T> zPX(t^8k5RXgOOm<0Vc@%tE}k?M)LCn;b^gCXT{wW5GE^-%hR#C-)^vrX8wuv%D4`Rypq~?9NrlZ?EJm zGbo~=D7$l+@p?Q8LnB>(?)$wCsExWNZHFB_9=wKB@>IJhxGDgTGHLLpLm93M)r#pEXvxzb( zRX&P<&7v1~I4kSXP}%h>uUUL|7COqM4{w83Rz)=QXDWEh;jKu;85G#d_w6Ruo)DNV zj}I=D*~+5mP(C0?zbxbvmP5`5XGi+Iees(2N7s1Yr`X3mFTZ5|==;$3IdP;%ORnGs zh=ZGMv3@%4leRqKc&ECJzf{BhY7vFB713&#wS1VkW$qS5Y z=DnJIzHd|{?G>jIQMXG6N@chRNL6YWa6>N- zonG-IbS8q*d(TFMnoGV>O2QrVZnmr%Jt_4f=I@8bW^EAE4DR`2ShG4m4i3U$Szvh> z1V$A#U{G2i%>_OnoU^$oLrYggZkd>32;ym!l(T?<>z3sKK!)uvy+>QDL~Ncc;=6)ezZnHw_c_@6|6 zpg`IQ5`!!Kv$7&C3L_wsI<}v!I*_qg*2e@Ic}{9alp)IoA5uFe?BTd_e79Wr1ia5PH`!=O3YI?_`y6>ig0my5?EujhgK2NmemUE) zw>VHSimRwoR$#^3xfjD)Yvo#D=CG_~TloY034 zrX^71+#rfAWDBVQlKlW4bjRXKg{&AwZlh#7ThLR+IjLZsObH@b49F2*%VoSSFon2h z2YK5M$i1O!<9xq`W~=`y2gf}bXn_NI7M0&1_qQr8h&~JN?-ve-@OOgE2>rrNWGN6t zsh2!g#c=#>3of>aETi}sCdmNM+b!D9QUM z&Q~$pd$!U#KZr~)2QkSpj6hqDf=mgD%C8U`k=2rxJH!JBN~B+KopvnHSE>>xhU+(3 zAp_p~5NS}7N|b|(zqOk)pH}HzKZzoe+OUQqWfaaLgww-kt1Z}yHq+Jm3)QW0l(UCV zdWV~vRmxfRd&Rhx`#ViM+qwmzS!i}9;auN_oJ=_jOX9Bu3*o^EKf(BeV~Z;kQPJv> z3D~(~$sPF&qYkLC1jRrJW{@#x$T~&Npd0oM8Zqcb9fuCSWQ}3eE5A<}l$x8@nwxZ* zgG%W}_*x@1CHmo7<5DQYvX)U!H*~5^KCYDFTbpw7KUIy?^GeJswagTyw9MMHTcOGI zP~%?nD=C93zrX>RmK34klNqv6-^X5uWKVa}a2fNlVibJ%fZ%e!GK_qh$N$gh{^*%k zwIooL_1+=#@WHN(K?5aEHSn*y%EdD1ICVR-?kcL*D2j3krDViVX0*L8 zJf>VUTvs%uTs&V_{7SjxZC%MH<-5aS3|WSa*83r~um`~kldZ@Deo|OO&`^P)CO@dv zn}m<5k^YG&)1ctvoiBTDG9<1&L#oW=4vtY(>PnFWorYAH-p4!&Ds#9Z+%Pqpc0;W&1CNcy6cE=C&VlFAf&w@uWoLQ+#s>(y}Pm(j#`#p$-SuvJ|}XD`SFbT z#-@eAnT_>hhl<&mqdC5`WaHg4V=$`5SNO6#7X@Tnq$KHIOOjl#9q3?~6u~YZ4`c7H zg*Xj73g&WgPElNPdt96D#t`>btF|G)*?H`?i;P_El;Q<)CXt7-z}q2euH;lYxPggHw{1X(3ZW3xW2a+T-)AC7WI? zk%56{T4p2CY8}sqT5a)^G@_7aWX2uxTuP8) z^#?tNIV|H)`nyeo_d#zpdg9B|T0nA`eJGfYRT4ZybR;9A8Fb z$#jd~mE<|Sk+-@PidXBdL=gyt z`Cf}rqg4Ht2-8x!LB~7%Y&5tkMXQAanGEMu-OW?r!??d>{n}~8F$h#h!tveSERn*f zI3;( zddMpES}3R2Up+)#gP?j`RFe@id$>9Zp&qrP>GuT~w3YWOBw=D&vnGvwGlJW!u2*V` z)Qx8L9@cA)VQRHQghroH_YZT$Urt9e9@8OdOqM z&Cnl7CV+Mtn9bnU7PDqF+oL@ue@HC&GesJ9fvsx2{N?&A#J7@m^b?WE#^tVSbg1Y6AOa+pdbaOCB7Gvh;>Xb?BHE zL7X$HKenN)^{w0<&sc_X^loyRxu`ZX=FUIHHZwV18#-i>;y&+hR<*jUN*ghQ`vY!V z_^1!PCM}{|+B31{9lOYnl+KediQFl(54me|jjqC;|1 zoU*9+4T*g{%|geyljwhsIwlNu%4;%JItQ3$BUk&p%ko|KEK_f4+FN$)1fDU-Kjjbv zBwW`jKLFWsD{RDi^>}|9$7idPyD zf>94~bfRAUGP%sixaLrej!Xjv8*dslX@}Ln(61XCwgFHr&>qtCgV^O%wPmAcn-5|; zjRZC=2(GA)E%8l`#`iTDH;*M91Deel7vf_m^?WJRcbSEWm+lLv4Bj$sNJL1y>-?@^ z)cs@shf)4u0TZ8F@zQ13LhOpY1W4})Cp<%r)pD-vEPa&ftrd+dhE_>Ui%u3c#y z#AA2iiHE(DH}<>|!3}0ebrI;9e@vzkrY$FotVHM%vEY#xg5KI;K5Bi_W~Op&m!jW+ z%NkI3%uVM<#MMrjT&zqPLU0Y9>RV_onoHH4xy`j1}1Lsa+Xb35Lf2c!9P%sR-f1{N?#d|-_uupbn1s`(_Ncc<0EgNhvJws z%kBFy=6^1|xyc#3@W@|n{5f=ZL%UpyEwFKuiLbo8*&Mxk=3p*Reuo|9|L{nA;+18C zzO?wS;2yB*i+`7H#9&4q`L7(=PNlq;zUnV;790Gpm5yW+`(oXvlrO4gdS{c+qL0C= zH^1LxypSe{iy*#unf+3=|MA*L`uf#h&HKF!la;3ee?}hfjqng^zwfzRTKmWB+xDY> zU5tqfC_S4-ZlVwNjLAm{GKG;=UI2&zN)>KGjzpPrQ?ie`>E?q z;FMbtUJrq*hd<){=a(K{*m?Ug-|DR2mw)>(M+}4vL5}z4M+c4EkkRZA$LHVc z%+@+J-&@e`6$pL=H0CXAHc!=v=U5)_dmnOxm3nST`n$M4ZIAu|xpqgNa)f>5ai7kT;Aw6eH$`eZwx8Te0-e&u2R)s0k(BUsI|*z zbE>ub8>*6D6RC=Pl(HFDw=frJa#~#{GvwYJh`b-o@0?W5W(xVlt}2w1_|}qdd4)n0 z{ce^{rtx{*B)c!S2j|6ErB}~Af5nJWupOsfH$4mzRtVlHcRyJtT0ya2yrJm*$;Z0S zQB$vdpl3M5+J`<1%0FbHxE6#z0?Iyk0<6_Dg5Nt9{j}6Mcp|0rQjVlSSz*91TCZNR zL4Bjt6EYO>5F4m33;A68qAL6kJCsLnp7@8T(EsY)2~1uO zXX#h+dMg{LqrLBv7@h?(oNxCM&uNGBa!x0Q^Rfho4jo(H237OkDxI_%IkUWwkjVXG z37Tvm>l&PBAtdZmg3Ja{Zx8Jhch6=0c&EGHT`}%d*8E5=u{Sc*ZQbvCbgATzoxi0Y zp;4ak3m5LDo&T_S7Wwu2>TPCRQt;%-ZAP0kGVgC9`^nfJo`cDnQuz^R7knrMLU=cH zgNFE(tUjB?zo|QIf9{VMXzF**#DS?NZkbPQp>{sFcRG zFhDJd8pbofxXvY;;^hit(3yOO}<9%awV{kr9R=$1twUkpO3cFY_&cPE@g`V{pw~W>+zTw0g?vxJ}rafB~(;I z%n!X~IdJTbP+g#@RaL2j$9DXd%0%(eT!&0-aIpDl#Ut1gLIG-;Wg+|}$xP(KB_{|r zH|h`tGOA(g6nMhA;EfyalGEdf0pae2*H>cwvnBZ{SQfL|TBZV3P*R?aFR&A@6T+Ba z(ADufLRyj0j!d-*e3dv-X+NC`kCb0`1BVX&xp?t*JpVfR1Ud-+HwkTH`7AwH1pa~z zI zW$0$T*jlRyzdoT>His*jZ$En>V9-a<2t}nOAIwTE1cx9JPlH`*AD6;Qm*_>H#>Upn z5c^XChuta~HE((8+KDTA-J0g2Vxlly} zs?-^g@cf)+Ao>LEq0;h4Tg|EYX*=RKwT<%8{Q7IpK^x>+Rl^na&}i?VItWj{ldF0A zIll+fdVM#SdC!jrE4=VRk#B}9X4>Cc^nk55G_(Kr4VbO~v;RW!&bp6|D`qWeyE-~aHuCF~Y@uSu#Q=@vW% zy%Hhbe?BP){U7Ku`gO}f2wXq%;U>r<^S{t#T;G!YT@B>P*47UzgV*+@{cf#SilJv{ zF-Hh_w?HhwMb`20qrZQ2ct(|?qMWH0b6RU=B!3G22f9>wYrz90FcwM6-e3Kb{tI0i zDpb5Q{N2(fZC)~7eY6c~ojX2$(%>)hYdP`by7qJjTr^=C)zkL6 z;r>STix4b$If_@`4W~0m+%s5@0DY@(`25IlisZzvht#1koVWlU9D>xIL|o&qv;?U) z3h?Gb)v>IBr$t$q#}XG3{iN`yxgp|~*qj>a5@uZ$3l1M-5WO(5j1isZCNGhRz#QZe zY{;L7^aRtv#Si_f?KB7pBf+$|;Ob7X;Ea_QdXp!^zC81I_}0pit1lZ6<+)EKkm2U1 z7(|2Md*7FeL)`31aj0Bwvz4T^TiU<(B%C#23j6#Zow>Ol%nOF_r^TjpG1Ch2l5(y( z`Gv+*=Dig6NJC%wrI^DFP)~KhxI`89hJopl3kO~IYx=!;pTU{Z+Z(VlODg**xSCC{q#Dq=ulXea~*bFZfDv`GtbmN$MB!Xp7#mUJJGy2liMM7 zn*YX@$7MU}_rju@wIL3dc1d92^&(TyxyA7duit6De6jWIX^P0yFSz*pcJWg|7#x-6 z1kx*e%w?1%=S~|YCi(*n+)0RwXwU+eEK|F83;$VbR(a|>i@y+%Wq@z0^X`)N`eZ=? z00&{{kwwf37ls8u|2@hXloG3yiokOO_e+JSojmISTwth_)H#IS&+Rm)N@o;g+aP%h zKyoKIg3d<)N?EHC2mfBmYl7A`EDd$^vrh3?;`gXN(udx&q(#>+Z4#^$x%o32wuX=8Vygaq zE2CzkvVI9(R;1+qi`dXlmud;FQafcceq!kWy37qR*~IcarK zTiJw5suBYo9T3a6ncRqIEL^B8mWJgdJ0mND<$HqkMiP2>a=sKb$jKT#_v~D3{ZhQ0 zQDgGX=E=pSFC{-GYL5IE-G6fB_m{gMo?0Tpb~;JyYbny9mMlCronrL047grPIb=JN ze&TDn$Yiah{@6_B_no*FwqU2hyO|t~l;b_J3d$c>r!JZD9vrb&*_^5uvUql*as>1747x9a?T z&_X{I`#}cuKsc7&SMAvoH<+1gwOGHmb>8$=%br5F6rsFZ(TilFd?lc2FIW_W*q zsQb?mvt!Oc#J)VZy)!QTv`g9&gLMtBg=0!0kEMfpUqARYcJJKT@{~{{`%F9!=&3Jk zGO3qP52@o49R{d+RIokGz)}gaeM3~^N3TJbq76I{Gc+Sti=df!>lz+xe16dt?DbR5bP|>4kKnVssA+G@ zLpAx{X_bWgIiU23^8t1&aIQZmM)ivI>sP|mZ`D7C!<-c|FQ^F=@UFY^weC<14h2hz z7ubW7kOsGUi>(ebToANf;;_u9d7=53<#6cfxtKSL>&h~dPvwVT9T=}xD~TNgZeuaw z%$SL=eSEIRNC0XGs0eqF-r5<;cm4iaN``H?vf_J7HQkoZl(PvEK-xsDt{c!Qq%Hvv ztgcm167sZ!#}TAiWa%B@`$Pa7YV{yVz=a@~FpV?SBCGY>2?QeWbXBJ80O5D$CItjB7QBBXwGF)pN00!0`jx*216%11H4v-a~wxBkVNz*O5L-12WgoCDQeS87TzzU?9Hy~u}? zOo?s}z)n_P8ni@LaRQW*>_H5K@w_!@IvidZ++OUBR1zR^>P*=`FCPsY=W-<3B2X9)JSd z4j;xDAdUe%XW2X`wsp$TglNW!BD)t;fzh9ujwtSykvZ>%RN~6{0)lM??1fq>y$ylT zTEb7+Xjx)(q{ljCj!JFtPPz@Z2KyxpO6Z)H7|O~JH8K2*51o9ruOSzxd$z1z!gFny z!QGaWe5vBfo(Do@FyPy*qDHA3P?Ilzei}F2wQ(e3K_rqAbk&$yDFrJ#Bm+^5q9|Hh zikRlee|sm8S1xGnd??nPGS)7h7AqJj1oET>U);6Prilu4UQLv@F;xhzCmZ$z2JNs^ z8p*bX7JLJ5gZP~Nn}Sq7tpvG}ZFN^w446rSFve@=07^c?wv%CR?V_a!EUqOv7$ozR zp^n$^{l@cwWYG{A)Iqw^RU`#Mv$T@q8+l47)!{)YrUZJN1G9J{Sg^G33E>{8JY`B7 zPVmww4C$0P*a)Njl^IsTUi9)QBqcJ zCQiUN0wX6s$v{v=k*nl z%r%3|b&t%q@tF&iD9Db>hIPc&O<-vubJyU;50c#XPJ{0twci^VUztHo@dC{;8Go71 zTGgk=nb>`UEP{}vDk{NI0^zUDmDbC}_XQsgZT0nZ4z-)(-Ca@LA<7L? zeSWuGD%Q^a%s@suTflY_(qH>urxVV*W2g3S0YAuIV1RFLg*)Yx|CgvNHJhVxfX?Iq zg7SrLc$&+AjXsfOWcC(VrTV&WBh9n$)AL9)n;h{US zOQmoxR;)n3{(hEvKM?m;{vx&-@R;WFT-C(x8mtf;&iLo06*!b5U`zhtHEzJOmNUOt zytOt6ZNyQiGb(L3p~)uw7akQe1S@GVKgj9$=>kgxZ77zaU30pwz+svJJJSJ>S!d2w z@sI>HSMV?t19;g&+4uKs*;fWE58AN00IdaP?1}*6Vc*($5*RSOA4PNQ66k6^cRWzA zqW(Dd2o!s{DFOBBEBd+(f5`T2uKrM18GH(N{-B@1cGB#zzT2f!mW4aLo~Pb(_zo7V z(aN#p8$JWiR{x%*-aA)dG+MU58i2F44_3}AsdW+mMMseo;PbrAmAtzwmFwm?TOfR& zYbXrNS53-QH#*wN00=0obtv&cj*Ea6A9q6KzjLat7lVW@R-Nds@?NU){axj+V*8j_ z8gQceq)K)0#p?c=ow9p}WY0ronxsjQ$^lIPsVSqZNwdFc zMNBZp3Gwf4WZ@XL!mSyBjT4kX=K6d7E(Caf15cH)D$4x0cfh4FY)w=Pf)xE~9sAGk zCgoLbTu*w;5WhXE#3t|fz7clnK_v7Ha0Oq2bw=FY1iEa2@1mflbcA&W|L%RP-!|O8 zBE54z45+tmf18V)P-&GSVTfJ=t>=N4KTDffzDnZQacZ-aa|<69IquZK9gR5j0eG0& z;o*h-`ML=iU2^n8yF*!~YJYN|Do{g2hj;-^Q5~>sk7i;GYNlP9ga)&kv0A8L5T>t% z3{Vs*H zHo(E%FGB$LGgwvQI9T?95886sk$5Ve;Okt>>7mjKllfDskQG>oe? z#?qCsRoA*)`ZI|N{I`ji{%LgIHag?Q!;FSr2^zYMbx(`*aDFHmLxW51e*kV6VVk#G z1f5%f8E$atBk;A}qgq{3JCfJ`U;`VPqPu&ePGjsFfLF#%%B@~F5@y6H^7acL5b>CY z#`<&z8?MUVG0kcMJw)uZ@%IxSupZj=CohX*{bL?0wYKxEhW``Lr?T4r)w+!!b6at; z2KoqnBK`Nd4#uEZSIb_0Yn=vroyTGULtk_O#SGxbc(T15Ca6fDhJa2N#Cj(JJmJ{- z71Z~Hj<>4(fjTEPdazeSKr%fJkBLK~Lu^QNqkB&)5_?e2{LSW;L5u96N}PH%v6Scu zezW9$po|6Sw=gP&8aiRsB!qmofV4Zq=zt+o$QW)1{m_cTtCbJm!$zwhqMYtS0}i@O zIPL0pr{=a9#WSfqJ+-_0AdmAjbIVl0UEFp;L;Fj6{1K=(_HFyd1To@r!bn0JV>q|46SS={h6e3_6 zDC@(5F{q2Z0?#_n;Km?jbJ1IQlWOR5J%Hw)ad6fH2yITN|F|X$Wn$`1;nCyo!xBB8 zB3ilbls*#5ZfURtpyE%#EQDtw_Cm{Zq1CygeFJ@hAo&hJRT8`V?Kv1fi#dhpYyc#R zyVH5F#m0yp@kODKyP;`-e*{)Bg9FX3K4tf;}1SriC>9+~Er z&p_|+bZU}jHAq}Fc+8(-;E@TioQ{6H@{FsMVyZU5wb~1Do}cpqV5c#=iNG^sU?;kS z>CP-EUbmy6sI@YkUG~)p|QD9B*8CT@=YR3z# z;b3iC5AawWzsnyH(4tY7Eq?il zQcqm`0-K;$E0Sh834Ctzol>lV*zX!c9)?D2o?hLi^pQN+wWv2Jj6>kNjSXZV(DPI3}4AWi|=T7Gd8>rSt!F z8CwQec+4;>SyBr0L>x422Yl^Y=cS<`kFma8Pe_57zgL7a?rcL1<37IvROLtg_8od% z`t&S#0+YSN{<9PJ`*4?Hb~5p6C~Aj}$ryh^TL!AuKNQ_KG1MKZfEbN zJ3lZobKKFuCYIpdI0D;o2w3;OVof_z&b{0Jh`hWZ?6@x)L8X`t>40WbS;Qnb&;Pv~ za{yhc`?5ux{fjdsO|JxtG~(}F>x1zYeQ5~F1WAw{F%qyI_Jz6;uh=%*IFf)UPU`Rz^PTJ6?)eV=#`1|(7Pno2iyzx))l8eJCT#zE(~%+7OC`GUu!-h|f|d44%Lg-XNz z5p8t$%Q|9o*Rr^9MMwvFvo=N2>w7qTcpsuvRqS=ae-?f>=?HS`edOBEb@AuX-oMVJ zM_~Tl{PW@YC}^%qd!)oCK{F^E{$ZiPXD?pw_2k{uG`sEKezm`)sg8-8_GWM3LnC+1 z0yMup`1YT241E@8A%2AMTjrU}ZP--N=3Jf-nYA}t$Y@QrQ|-+q5aU)zWnsN+P!4#y z3zRZWun=?))+(d z@jEtcy*UTvm_f)C`B3wEo1Nx$mm4AzkL26!wfFx-JrpGw3drHA*fafl@8;Bo7oyPq zxoYn_LLHCn!(7!2nP|lUqQV$--?)=Eq+_P^Voa_~o_BwHC&i^f=a_^3y{K`}`ubP= zK3U=Z97vghoU?v|n{{;``J*=Pf!=MO2!eFp=&pHXvZMU|%HMAauJpsM?Ep8-*3``} zM5tWU?A&-+AI>;e$O~VUTuHkKK5i7*m8|qsDjBOG>Lr1;T|W7oCuj1G5=~#mSa{bw zYkO*oJJay{n+yMd-u~40XRhNrSCZ<=k8A6BO}_6lxw@0-b6_Zpx!jGi$)E6xqRq*C z_7;WbI$J7w2B%wFCakAJu;YBUB~vzzWN0XCWTu^cWLp(@Y1y+eKn|rCT9$nLwq8)C zrP2EegjifzT{%yQ0kew-s% zWAZx?H>VLccyBc3aLI*t*TugMNcsl$Y1h)p>j|LM6R(K2M`mUAwqx*qms$x8^roUu zx@Kk5@K<1-{0vgPI zqj5L3@PNVa4`jT6_rdFzk(!%#k7X0klSl-w8qzKwplafIWxZGf0bH_!G<*QvLV1}? zUA>pdU{avJ%w>3^>LPA}s4x?1(`3!#x8$i;~^a+oA;I!-oEsxBn58!vc2Ak1cpl_trI&T%XWy9TAfNNX+W zw4b}Th4)*7@}fMgjikn~y=vA11~S=4U{rwDlL$)57O?RC68LEkO*>v!N5WBV3n)|M z4^Fw5{(%@BJW`jN3`uewkjW5%lH|dTS+x{}d%>X|sJs-XN9nh(#;55*32C&JHGB#Z zWDP|@>G}TnlqeX$J%GyOhgD$jr4jg%E;syl;(4FOkMbkEzBQ+Y>g&{qA(fkE-jKhYZD)f zKcOB1$~b{6mSUGihrks*qK{fS#gtj{go2K*GOg{)feSn!r-!!LfdO2NqVMzfzxW?7 zaBov;04u$-d?V(b>?+HDCS;SCk)D<-#tHKSIFlNDl?H6epuvZsB~Um z;yS$D#FS%H>UdC%h( zSO^V*$sCpn*U#^N8%1Dz?D6N;HUJ4$w-_lV2Jm=^3`)G(PPJHG#iZu5@!z-8til6@ zYC4C|nW^!)?zsWCp37)snQ0jP%;;@lnH3R~5rmo!j{lo`%crQi~ zYy)E6c*EC0iLxMdytOi>ElIG~@Q9Cs-PxEgD9f9Ra!_^}vBl(m42(4rD}v1Cf~3$Y z*Dx>|xe#+%>L$K&DoSmv1^2Qb{QgA(_9jyz%u+?VfrR|K!bJ)v9@7(Cm7W@1s~!3B zuvs?xnXbTtE4wrB4bEPDkLvoJT^w@1IMjIEL%HuRW;S{UFSrN ziT2#g@zuzQxFaIjy}cIl%fHg+Dk3VVitk9N6Vu73LMl&%+8sIj`)U*zri$hV&rX|v8F)B0zR~G__x z6B&dv7#b79*C))YQeJy%4PUxKJN^-74(RDiug0cIOakC!7+Pv_KZT4@rEy^xC z!OFX6U#oWA!sr7ETp6bdnx*$P_U_JSr3`6*;JxJe*NxJ4b9}@yzV^Ym@S2p;C7i{_ z>qbXvlKKQXIpme>Heug6xg0U+)5S?=`#_b~KgkJbKSd-Usow>N=RMoL*|veaSaI0C zLIAnk4z%Co*SSU%Z->vKfz$#Pk84+z3~HLw+q_N0x{^TI^eX`p{UBkmO}}79cflp* z?S9g$J4nObv}$5svIkVL_DF74=fgVvXDymMmHlTfDvlYFo_P@HPKe7+M1rbW*+!=7 z98SfPoaCQEW0K9UJ=TcDRT8)`49uvU`89)qece6eN`7)TfPCs{rmvH(mCK^#XY0v7 zeBM4-hG%iYSY~_a0Fvq>f)t-_9hxPRW7*^2>;D=T4_sn*i=+ml``xizW~^dc96H7T zq41UMEI*`e^XM4GqNp|5#eV4c)}41TLwliY54Cipjo}Hl#UQtUNfz6i!57@B?FY-) zT`>VH{AQ4AZ1lpjeW zmYg%`IaMh^Bc=zkfiQ~I%TBszY_Xj`^q*@ZiF-NGb0f6ZRv)t;U5PaiU&h0@sYW>K z)8-w1w!@5APO80v2ZM9hAUUdtvwuxq)`YvDs1L`(QMh z=ZcjI9=$!0WoT`ZUpcxj!oC87llX^kG}_!T5xCxatsoIYQyMMVd+C_V0(Uo(QZ}A(v=P(xW$d|fZkTwo zOO&2-X9_*)0X@|A_Y$3nC?XzihEp;-=|H#f9zhJc%cWDh%lUH0GI88x_5=Jk8gK zGFm{eJCKLB>CT*zJhl^1mF8GmdzmoB+<1~&>m+o4CS!qqZ3F$z6)Dv>BOQWlESdsY zr-G311GvlV64PPjC>;cEgUu>UB1r&)Ax8h~d@L0ynzYjNM+EAebwoOER*NSGM39W9 z2^;B@Y@#|J0AVe7>0+2k&L;mfNLnFNILAyaTpL&! zyY_RIlE}_!+iMGsW585Do+~rg!CE;<`UKNr75>5rl9XSPwan7YvNgARGDfuCnTGq9 zGW1t6Q-GA!ZHA4Tog*6#*Udv(@MO0PPXYWNCaxdrNlrs@Rbo;CEi4RAI9C|B5$jx8 zc&?|o8^^SfKGX0Ras06=(&18gBphdG>tJ{8&zCs3d&)lgl;ofDpEsVG ze?HG!^zFyy>+v7=4(2)0;OX~fW(R!I;>+5YyI0n;q%%FQ;HyvnzF zN-znKshZU``BPRgG#UQ4N-5Z}1I(y)xgz$vb3h z_|V{4N$<&7$=uO${uY)d$tzlHAPA#H$)wnT2$2f*c`2f6&O%(CFu&Yi{gKVaj(K+ak-xZLuDdn! zn;)9ZCYj}i-{+n-5CcFBTWv;f7M7WP4+Mx3TWX_Q_ZJFrVW3G*rergC?q<+~^;@br z=|5XvA4=*=e_hhGJ=`#3@Ksj%bKlRm2P2sJ?)F*B?XT?5to&KIQ=nZF`Hv)o_MCw6 zM-d5-DOw<0tKjSOU{;41T0UY3xA-HPeNHiPXOyV1_udjOj2kri1!Em;QhL4>Fbr9Q zI^5#oAte!&N-o->q3^#qsX@T>EImDaQvtIDrlm3|3aF%j61iAkwT*dg00h|eX3_}a z9+rrC6;CfGI`HC>s<{4s__{1P`XzKODt&b^dSP#003>ytHIm=gRCsYR)Bi0F_> zus;I1ln;C9uP_k{(utWrdgOCu3xYg~!hIvoWJNo@RX2uNkR?Zu)}UsWNWrPyjX?+O z6QJW7(K@)=Q3*QaJN={}2$s}<@M(pS&H|$_Qaq>R*&Jl;6yH-zM5*n`FJC$1Pxwrs z`j+2qZk{=O;*lx;`NrM9yW z@nV(*R_b(7Fm;(IWdX!{oC%Z$JFc&P$I9DlfGo4f!mv>7n+_OiPWH&ZLV*J}CxTAP zb}jjZk_I?9r=tcE){auo$bNkTLeywWo_)D?-tA6vNk~s=^Tmf%tjYjprdBHT_{q!| zTsq#}o@qdU4ONuhzzm?%bxUU~Dsk!JVC4V7+MB;a`3L^LvzZtYfDnBgvM=lBEzLLS;*o3Z=9<&gXou@43!(emd86{($-6zUI1S z?)!c{ACCtjWh$Ism<4tLp}%2dUVkeXX_VC|ENWX9o~*1~FK}g!s_~&ZyM<%eqs*2` zp~<04md7|dA@1qFPGP_UxycP)B^a(YFbBo^2#=A+G>SJwEo@O31BZj5Soj`T4N_Av$oYR!4Y zSk=R7tGl8na;DqLZtj;7Egfz~1%f#)s+jVACg#Xz46=&0Na#;|r|Faq5nqAdJN=;@ zKX2Im4+9Hgn^b%S=iU z-L~=Nyzc}=hJ97}HDhfZb6e>aC(dV=X0jwW8;#R(vgZ0l+HYXH_hRQIb#5Ee!%tp5o}Rem#dWhZ>-5vWzkw#t zw)B-^rHbe!;*-*qx!FmmulVIfAr}>krJ1-qLan9==P-~G3o=AoPq+_`xGXIl$4Vgj zu_WxUmwmMRCgh5vb2h_#z#yhv_iPb{hcqDJrGxujJ zR|(%WQ#mU&0I#SYeYv@#n8vfxS>cx&w=?hg;;%3CKmF04JMQH2Nh$l;`j5vTmNpW? zauvdN#6ViLC2~!y!gY=YfUGu(q~#jg^=OcLs?8f{USo+AFA!u2cc^n2wnY1ht8mcM zZ`RPc;EX4T{QR4amcBK9El=LwrDt6=7)WfZmHbdakHtwm=lOCp#=gH?yF26SA~-R| zBuyjsWBlhfxyJ>A*XK&*aw-`czF(bEJG$t1LBn|hjuUTmzj9Ae&k}Y4k~17sgNZa06w%CijuLYml`x$HzNN2cHq1S} zV3Qilb=CoPVxR{d68{O)FLBlh9fO*+NsLUlTcL#6zY|@31MjW`G-0_oqI5x}U7%h4 z|NiXG2>6AM3Ky&qf;17VFdWEMZh-(}J*UHRIZS!~#fd)Y`kbJ`8&RL>2|;sT_V-5g z{uij>;t2DA@oQ5#u{Lc&2XiJ9rh=gBSZ&A8ir4f^KR?vl^3B<|QGFg1GC(Go2wL2} zIQT)IHC}8&z>$Th`5tkH2_FTEv924$uDsUY^GX(&97^vbBG5T!%176LQ$##DpUfw;upQA{6$| ztc;XZoP|w_@7GzA9mLukYqrTT!Lp6H$_Lg)v^1K>K=nPCl(dn!&>QvwgcM__KK!pD z6hTJ*BIzyKU|m+By+*(@01O+5?{$p(>1ddH7LcWA337o0?Q!SGsSCQP|~;~ zYmq8&-{>-vFjE=>^V17!xO%zi0q~cgXfFjc0t)*Yz@*`&=O;6bJytsa#LNX!0iDd) znH6jytpKdp?;?el$_t;a`PS2HGmW~Rt(fX?7e^Jdlnxv zwh%`z#j1Oxr-v z3{jn`e(PeQMKm7No3C{X$ggaU+Gj{sd12$f=|H`u&99U;G%$m%nuFWSA#`o1J{G+l z>9fGQCsFp=+Y~VXPb6AyZ574c;vJAKpWZ*m&jz{)b%V@^eAY04(ec|`<-+QI5ssHe z6`8A#9j~Bwq?S>9yJHoD`%yur2QexNR|5>b?nxz?RhbrD_$96q z^Q!7!nm+<|O*21=spr}@gGH7untQF1-c8d}u_cUF&hR+S*t3e$^5UDr)!9N|JR( z5tXLqz8~7em|bwTYL(I6)sSjt@!LSg!@3%MH}1N+VSm;GS~3D`n9atTRLCQcU(Hml zbnv19{@X#p5L_^GMDUqdK9$|M6HXo1oDZjGwfG}St?2$w>w3( z4p5J26~(`rKO3^jY68#fRl%SNh$zf845t4Ji0Cj#zo>qg!`djGblAr9%;`?2j1I;Z zQN{zR9ZLIq0tNw~o-igU7z_JtT|$I`GI4Sd<1-jjr4a1P-TJ&)Wm9r{UTF`~XV#@1RyY1LyYwMUI1kZ*BMhMFYJO zK(|NO@hkl>EM%O@WRZIZ9H-xiWI={PU)8ovo^zO zS=-7utRA9-0q;TA2_Y|201G-|LJ?-w46L?k7Jy(9$orALs*^*KmN|%7AM~vsZOYpL z@`k0b8BAFiFd}6MpFyE)H4n7?de>zsRpq@Rkc-Fd9tHA;Wm@H!kS@=HMXQnOYh z^&8D^+&mfPtz0N0f6leL{i^{&)oEz-7IU?d^hgfg!3P|sANHenz8xS8wYFbZ&NFu_ z@GpsZijyy(xzE!PypBD3gE}r!Pv)Pb%(v2Kls=_*F!ry+)}%ME$q$A5IV_Igh*MFuhB#AW&h z!sfuMUCg*ti55U{&}y6;1jONL!{#x#R8^#u($iY@wI?1S1LB#(Ea6$&Tp;uKNG4&V z(Q8!b-@#Iw1oZcGUuxpKTgD18gTrEoz&&kmiy3w$aaM9fu>)?ylI^wxAfpS+ zPPjEx0DHHWFy07{*K@esS+Q!>=uCiSgP>!F+D==Fdy|+2K%)FOI&3x)Ek&C~=^QbI z5aw9-=TNu>4*D|scx`zo7?;TQ3{(A@BNxs!xpHrM>D1aQFzE3wU5g*(K-?bFX8}7f zaqb`H@c`&GLKrI$PiI!L@MXqb^LjJd8$>T}zeIckwOwVy!9+R$<^v{5W_ZAfF(_({ zpYHCI)6TT^3z3#45i@9aVStJv^VMD)7hyxf5U*E7kHGylroAgb@0 z-@j{e9Q=-Xf8)oeC+V%g+Gzl!fE@s>s(P$&>*^D0HP|Ub0mUqZ=+lPD`BDU)Y zr7b@z!1v8{LHdV@ySNS;2F?;N*JESsp^u|JqV+L9WqbC;*#X9U-wr1fX*o!~7bvC%|CXe3uH} z=6w4j;lBe&?stgo&Vx)K-(!2Y1McH_G#rKwAz6%08`)G^)hO&=>=X~(T@Ae9oq?a( z|NRrTHh(z*cy{hp$=pnAHsD7a9RN+o-uMb5o3(lVz&YfA z)$EnESpEYx{mYXH=OPJA@p$C>=fF*Qi~AifNM4sw^(08HJ6iuQ2uEBcCKh1rME)nA z1l3^L-fXsSOo1$C+}>^$sZ57vUV%yPISg80tebk2;y=Z1kYM9B{O3)nHp zQv7>FepR$q(S2?A%|O0mDCv>T8p#c9caEe09^*fo(N$ZJMNaJu-;iLGgIw9nFCJYZ zxIYsXz2w11voh8wfMQuHTn>X@-gSSRa&CHRy9{z%0dG6cK4+z`{}Xw&4{#b>gCye| zZtZn4yar;m?@=X4N{Q2#W?%E{I)NtV9Is2Nhh=pvLe&&xpDXH)tqn`vB`;5Rx4nba zTW7~C2i+sve8NwjqumNbc}cX!{`8l*Gwb`m@=4_O*t>1V@DJjQ98NdtnVfzClDizv zJ0r<_>mW?t#T*};3Npf?8u6YRqB)3BG>uE(T6wOpau}8_n)R8{(%|_41Hym7^RkRn zp86=2M-Z?|jG-kFESROO@wFDwFeB8)hY+;6ChP6) zr$4_?#l1{sZT0$)r{+YKo{+YxILFrX?$7RyW*8TQOHBfbeBOOXTsi?4p*e=tTesO$ zO0IT4(eR89m^6Hm+(whHCXt^)dnxPCT=^vSryCl?b&JFStyqq+m5PJyn>1}HmZxws z%s+5pp(Sr!@1QIL3nt%j-S8JiTL1=vUG@2;EM?BEVf>_-C5IoiMLr)@7LhaYKIWa zf3`B#(4r|LdC+*L_QzK57iGi3mdre&-Bsa=1W{XpOOEb!f-`4Uxcr9|5}W#6(bxC8 zV{U3sc|1?k`dqL|TVBz~+KkoezwPV#TH?`-b#1A!zYUL~mK{am_^$q=dtH|~J|q`; zy_`?;C8sSUmE*-vD4Sy z1yGojrqbDuyeDO(gUn-Je^=88h(os(nAL$}W;|SKG3QD0=nY+It1zDpD0ckAIo4PK zn>R0WX#3}q0-ky!k~N2w>E6s1;Bz+IPCR6+te6Xc#G7dX7N0hgvHD3*<<^ao>+Y#> z);@bp?czNJPc|TGZJdunvN?8yyZBOk`R9L}EuqSTl3mw`K3sW}+@^4>v>PaK4L^~Q z%-P9p`&CAnRSqFU+a-ca&JE%HI^}L44&zsKw1)cLtS?3mu6O)SHWa)Ey znO`nV@t2eJ1<|4rnsati9R-R9)q^8JV#2@fFo)`Pv%~fq&6w9% zZ^&^=RB1{FWgM&83;uTv8yfYZ?Cs`7g9}X6e$i}XH6ENg#{uST^03E`uj9O8DpT$+ zUsT@dhLOv^jwVlw7~gidXhL&e^giQ0n~Cun=Z1-Mhso=PpKsA=NM(8 z&RGcG9$STHlX(o)4rx?SF4V)TM^jdMG|D^! zUJN~sYZVt2&o8|kQ9#y^uw$BjYJAdTNIQE%QJ9OK^$JZf+|5^_r#&{RzFQz!?ps#C zS^=~DbWE`*hJ56@4-TWx41Q&N2b)QmT!^IUf8f^*Lk_@hxm0}8veP#SE;V6;`@OIi zdZ!=L_#*t0V0Gle*=wazGFmBhC$|be-mtUA9YGdHc7s&rkBrkV0$-?ksLQQFes;L`_mD1)0D$bnnbUt zZdnWGede;VC+%I3na@@iui^EMz(8s2wWLkuuKQvzJR6EwI{N6pM8z_-THc8%OXppYw^1< z2@8yATOCKZ!lX22_&;Q42C}TvbX^rNkqF>JxH5pjb7{Y{?R$@+)$Q9-!Frzd~WG6Ax zVo$$XlW7-ng4Kx~mq4E1g(^pPf-nQ}=0N7i&S8Yr?-sbtl+oA3bHiV*99eRdCI; zm)4fW6=$SBl)(y1w+2(JzMABY_%rnX@k5%HCM~0BL~cpJ5QbEdfD6WxACKOobtL`8g0`!v_qcZB8wXKP95Ad zuA-`viL_7KUEjxVV$d9uKTWIgl4+Y|Gc=Yvlxo~cmOOTXC8BU)^;uD{RK}|`GrMF} zG|Gw>Y2&1E@{t)l_0wwhoDr%~YCNS4KdH-Jdf9+iIKN{0t1kP)+J*hB-syQX8a;Jc{lk|}emPhB4 zx0BoisFC7S7JtX9SDDQ;&)0!c4E~r6h9%>f&`ZRZ54bamR?l7hmG{qAa&xClf%dW< zNA)ReZzd*#6qy`Kl4pY{$A(VS0K$T~jiY1^n3J1w_NpBLph~vQQfOoeB&eXmQCT+M zm~ysmn@K$^iS!!fQ;@SpbGG?2qbxmD;{{EoNG4t?E{{9!Ax=Hd4JCUqMTjFgqrv1b z2&WTMatVm+L~0hGqHHJi?V=pA94VAgV`T{_WLMA19C3}aF>I9Hd)FhDNN_yAy0}iB_ zTh&GRbj|u60V3<6J+tqav#ru{+tcMfaij_0aPyqARUnM4NJ%Dw$cy$?B`ahnCIrRNV#PX5fJRm$Sa`KHN(Rl)eH zMW>ljP)$%u3FN}jG?s&^XG%5Tp3y7uU}8ZbDq$D4Z9Z}!k9Jp8!&x+s5*?B=e?D3b zEI(*wx^7OE=SNX%f?YDG#Y^h#V{whXf~3#2Rv zP?!tfot&o0#rtz*oi{1j1hvgyt@p3bgmL|w$KHi0G`zFW^SyT7;c#8tAO=C)O1OIkM6UYy_B#g0ddaaM~5i=MTm9N)}`GH@AH*f|CnF$rynmzPoA9m zuXl~sfZeYH)JPD5%#HYFfsBk!y^2Ik|4oy}_lE<>NX67-o789<#Gzr(y0JujQ8rsm zz|%p^@=)m{j}zOAAlr-j-$-~>e@E>JljOCNj7+TorG_C9Vbox9^oKiwfi}*o){zM1Ptu?Zb8mIrlD7Eu7Hv<%L(Bf*S-8w;Mi$dj++yAUZ>KivM~4Yx6}^ zXQ?u)(gYPIeBKZv(Q4DrbDG}PAX$qVK7gnp4V=g;(;r)=g3mKn7Q$X3e+KvQi#|vJ zo`-y>4MSYvMnn-2w=W{rToG%&7SH-aCPH)6K$-0<=_6Jg2z%%;+Z(Q*r)4rkcw5!0 zqL8F{L28gGwLbrHT<5||B2stHco775C9KEkH<%l}T_A+iAPZfI=_`S4E46CpD+~V_ z=Fhgi1UV7Kqf^P6ox{weh_>AbDMWF@r^TE$Wi5jg-~#j#Ah$`a#O>IUuo6*%FRhy zRgt0e-BLK(9-!ihFmhX}oMs}8NIvhJnmu*!AU?1m5J}LHsPh^L3t*!;i8 z$?rIo16oRvFQN8v46RaJEA)JgO4evZUFKc66A4Gbf!_Pb5d|Z)X=b$FeyYh zeU!XWKKm?bgfc~?c#yTe#BZ0 ztSkfXmUDzH)BE}+S~FsFi8ngL^=L_(3F#R#$jg2(dsJ%OM$u%UB4R2Ku}f(`8CbaM zUVQ`lC(Yy=tt7PFBDOv?*4g%_I-mR*!rt1{&wcH;)l$*4#a+$B)TU7(0gZf5&F>~H z*^STZ*&o+dzpZcMy8izBx4_SG2lYbM_Jy8fzpPY3J3syIvd)jT{T`}SYtL$IYyIiG7FXu` z&1*YEl^myk=~osvhkc{<7>J9Xu5>Io0-_nP6$MT0=Ro;ysj6^mYZtldu#nX5IFbceHuo$ zCngYxUrlAw)m9B-@}VVEcKsQEAkTo|aEMsgNj_-+^2dC8Pk5M$yAI9|+!qIa3@3`;2HLBPGYPmbfhB2_|nkCZmYjMIVyO0I<(k7sFA=kj{BEjH5B@)a)s zQvEP@TeNkeFIK8`vDN}=Ftqpi-9pc`ub(HcM+L1akT1tr%7MxsScV_^^y@tQvOU{q zfA1eX=H6|?Y#r5$6Cyt-gCqHpHzMMk);PnHt(ye@yLU8wS9I9_QoYAm=hllaUyg6w zh@8MNNc!|@xIu)b7$OO+M@cn|^J79Lb6kLXnLQ3{5;i#UpDR=xxKhunI0|N~j3Nnh zlLEMVjzlt)2E~w>iA29zf|Kx-X=~4rWCtrO%O=708aEG7ko)NYXRNops*medfv9NV zd6%Cxm*isd^4%Q`;HlZi#`BsInMik$1$WJuZi%wX{avU6`6n^&@^Iq@n97*Yt4|#g z-MD82{tIVkXod2A$hTWMyed_j`Mq;3??3-(EB@E+v$ma0shH96fiK6y8 zZf*tlT%4#gbbj9&dsxill&HsEpV_4P~DNm-hw!vSKw9#OcZ z`ia4%Qoa{1y*mN(^X$27(9B5ruC?^}!prNWA8WL4GUKOow#4{I+V5So()&u8M7Ci+#TY|8L7lj6TTWx?5#8KuYAj_UHA7HovvF z>q=#fc_Ek2msDaEo*c{COHb4&c$T$IthXjj>1>zOPEBnOyWYR?4I(r^39Lvu8U-bzU4+1`2OvUTi2Pi zg3Ql<3+OkNb!&b5Up)O?kSFq>Vry+FTIpk>nvvg=0@&VnUyypoDw<0d?=2!nIfaGX5e?<}9?~;u%e$SxuKFY9I zaqi)^A>MQo{Zm(i{2?J&1x`D}k#vi(P&ucW`dSV$)J6j%?TC>+aLYmudw~CMX%^f=vn_Zo~YR_+-iYeby=Bg zo~6+|rNSeTGqj7QO}yWwTeOBXt3uoDAD?2$jsN>fx1T-e?(4w zx>f5tEp@AJB|Ha(^Yhg`PNII?k;+=aa0)SEKMis{Abcg_!KlJEDxU<*CewTT0D* zN)^qxdV*c416!$@cV3y7s!Eyu&u4~5o9D7kjk)Lf12Sszgs!kKaopZ^6j^l6`?9E? z-AngXy&Gc{GYBh#292l*LaY)bjFS6y2rG-G)9O!N2)`woYOCT%4t0YZbki}pR)377 z-no3t-zKL&^piJH8-ie@6c`a(AMZh_j|NM}JD^@z-ckkqjvkYQD54?%HaQznxiMZf zb_1Fz>34n_L+4G^S~epaZjYy&L-@>=o~^^U9zp(j4Gt;9*4**XO|$zdQ3Fi+7ohz! zLg2HEC*b23&5k`mpgl5hd+;jZRo7W7d!+(fZoHTp-XekmGq3bx6;aGEOJb8vbt@W< z!r6LD0zG4(RSWI2nOPRl`{y5y3=4s~5N6O-=lpfiM(}Eoh4Mby<*0*`KE6w|B=fpT z&59Z(r*Ua?((~uQBII8mePMXg8@mAC&gT59W4C$NBRVB34@2B=dC0jz*n_brfJvqS zwy_jFH+B>@~q@HS)|JDL6vRI4^38KM$ zR%F?a($z(t&LQ1w7r0#fI!>hp1{w)!=k(MJ23Bennmn0xV3dn6&$U?HV3MmXGjNnT zZU&Yr;5F!Q57=$i<}lEn?7ieJgXW5_3XwM=d&x+{ku(0d5aSHlZa5J)H@|b#h8%t4 z=X5cOpDxcdcv4Oc}FUeDymccgz6 zJ|QPKvx3_UWX*dtet&CF_!iXuh2;+aAxL|YbKj(JVI?o#=EQbW|AjaqdwwRpV9Zlx zIprP`r^>^b>C>-Li}~CgEj+b^W8s(RVRz!*%bByMAy;hhkYL0r!iIKeFMCI{Ho`}o8?5-Xr^xaaO&MXjt7yQmzNwBD6hrox zxT^UP*~C^-q2h+4}*FN^R zSYx?=?U>X)k&Co#SgA(R(M3i{Tj^S6*aC0y8*;imZ@+E~fz z;P>ZCMhbvX(mdRbhng)ibwex6VpXbh_FmWf=Acu*$-|*cZqC9+uT@j!7YCIb;Bwyt zJ+>1SKqf0Y1pvqlq&p=0?F}Dxm`%|FZp4>sxcr_-Q0rSn1gUe|C852JO{4 zZ9v*@Bo#HRAXjM=_ne3vP&PHfU@0On;#mPhkeEKmPoD*Aq+xtqQC7$&5`ukHZcxs| z$XgY%aKbSiKAX6k(s5`a*|B;l#PUvzk?{T?5r%Has8syM@j2J1_{zdZv&o_u2%g1= z{ogQm=WyrWN&k4Svx`jJE@q#3I8Yq3M3~5)_pNjeCMEfmtA2$-yja-Qs(hSl$Wfx` z;9SixUoi8$?24ISbX$~81z+UCJlTuE|41M|szRv;VX)$85XLh3 zZ5`h1!+Ll@C?!3l+&6^etIlb!0Jk#E(bwTM7oQS6t-$H4o_-&1>FBPDz&6irE|^Uf1^^aQy7cR zmj6MeIC#DP7b>N5jphIH1^@q#O7(T^Z;a*3dQSCqpP*8;|Kkfj{J41k(%TbM>c^M= z@daB~#%3LCzqsRhs8W#H7$m0r;M978L^H(neho%KGA^BR9p z4HTlm=AL0v)}w1#T99OWA%o!#m1zZ6eZw^`?Tqab^<5Zk)nypzyM9wqyTcT;<<%u( zcs^s+I79dQ7zYIHmuPt!93nMk@Mn{qC<7*~Z{*t;JfLbEFn6pO=wh#U7Pv(@<8#-V zUI6&sx)Kx6)#wvn@R`CP;54FL`hB_1Ez!4`SGJlPt@fL`-dB-&{H$pd&e;5v6p7nS zCLi(mshXU#GCOqz7lLxCbXb;nP7lw%XuNxe)0@(IPWVn8u|Rjsnf?SGWmoXNMo z2L^aRB2a-`9{T>UVF+mVn_-U7NAd6%;wx56lImdmhF`!Ay1=LZ5H9C%`sXHlcJB+` z<$$gLhRpQ+HF424zg>Kp0{xSh+6Vvb&=qEtfbri1Hp@7r{mO$n%a+pzjM~p_bFKWu zGhwZKML5SX+Y&j+GwQ6*z!~!qAoWX}_Xq!eZ|Si7+_cf5EnSJ`O@ZF}dditKLEjQI zLP!~zO)A{jB5uP75^)E)zEgvx^V^-vM?d$~7Sjq1?+`^|ho_{#*kg3oA_Q#p@NBUg zj-&z(@m^SM-7%adfoVyS8+dQ_QKRkv#p-r@Terx`!vl+I=5Uv4BA%_!cX%40@W zSBV^>U(=g#fe;5<4UWrO{#U?z8K~?25(xe}Bt@HmDD2yfmu=meXe{h`C1WKRZ#(Pp zUlAunSZ?~&QmQ9k`N{1>)!}+$Hn)}u+K*+^n9YGj`oF@8D&}(`dX5TVVY$@x9_FoXr;Mc=AQb#ngXEL(TUq4!k=g+ypP95x)yz7nD~%=7l!Yv zFX2uN`Z#vMMUu&0Ygwc|4E-CO9<7V{nk?&O9LJwt=s75C%cz(0Y(6tEc~B%qFVzyP&uZ{Cwp<;m zS2RAje|09w|NG*iV)3ioD9wBq7QY5nwb@2qZ58(qY{HjUt0#keOaxihT-bA|thMNejgGYmRpRZi_sTN+QA!QJOFs^Ni+*GBCnwFBimHd6&7HSEtfm zE35qDW~$y|Zr$r9O2>L`>FI+mCCstMr01>=LZ?sofy5wZk-2TUvac!e?N*V%r9XEg zYP*%7GLGFnnV&CL-C6mOQ5!!u8Cob~p!QdOv-Xvm_&;6|o20ow!cWa?r=gqAn)(w3 zLbbo>KfO>dK<6rMLNfR$VTk6MFa3P)p0M#I1G{Lk`ay26m^Z@9sV9&RzBZ~W$k!UT zN&x+QFlx!SV*c==6#t%1nfdoZ388Ovg6q1X%sz2wNojL14#PNkJV*jD*0D07;@X5) z+L2DmfyFSBs#UHj5RC}@B!y*JXn7=hQTaEBCUGFKoX|hT3=5A2W=xGjREX9yFP8fy zqn2CBkzHjMt?rkKYOzA^IUkouCw#p|A!$PR9;$j4-M^MGVdWdo{XpVSzYc#lQz$7m^|Y0Ih~$MG+w7s~ z6od#%c+*ht-mvA@Q=84@LDOebb#lM%*`%*Wf3`HADF1Y!&gd)Of08|c z!qcrkkON9aiC5Hwp+@!`3Vfiw55KSI$&U%nGQ=pPfhS<@p;+ji6}f9*2=U`}ny{{K zBbyQ0o%^o-zrY;6O`VN}V?(HVis=*7D}TOLi7{GAPQ!Iku{!XoF{pib9c07t4veWK zcIv3aZWIx^3``f`c~lpqAD&$Zr$G9QuaCYb(D?a8IW)wx137RLDNT*xS=C^q=@86qhWh| z7IQx25}`~{z>*lB`tR4f_iDNE0|C}WI*VlSearsOtn1fH{`edWp8!O$xW6Ai@HCeZxoj-oNj?$A9;-AOCr8o%ifTmFxG%H|i<+ zSeuVkt`(xd*$(@z3%JM}32oo-hisq-#s5=X32>7EB%#wj*m<{8xQSwK?*I6ey~ z7y~a}po9X+Hg@6QwmAM-fKL->cp);9gB_ek?F}LZO#oM4ZHs_J#r9M3+#qfQjtWOt zcmZ)L=rS+Qb9MmtqS!gAgzh52OcMC6M&j6KGS|dOhynsm%CH%-?U-O04J}myd?`SH zHF53_uE=NtB`QhYNO6Wu3Y>l(yy}Se)}C7cE=vJ}#ME%4sJ#?h=!5gr?^mGV)Vtxa zm z%5Lbw|JdeQ;07&iXQ|F)hi>D4N3(4?g>M}Jjm6mlEdaEUg#oH4n^ z)mdkx*yA?rMx$}MD(MmfhzQ1MmNZ=YJA@4Cl$sRo>Rz5APrmgUNhLh4t0s%%cqUSQ zKQD+Fp#{&pQsXqbnx;%gDTw58R_BQB=Sl{#SN z!vCh51j6KM!aA4z6&A=lit;W_^rAH&+14G}IWS-$VlM zG2OeyN&S8@<0@#TCykH_%@?l4Fc1L|aWFE>JSU|wh%>nDW-#OCOgPDg8`K#Srxa7} zE*-VyboQfWfr3E+8eC=xu2|7Wam7@m9md-FN7ME&b)#7jTnX}6DFNT8I{PYmgczIK zc&mN^ShORdy<@7Z5n}&HOAE{Bi=wZyDCJo3VBeeJ@)6i!n;NF@ zqP4)1bFa9+rd6xh(%1*05oUlkFQ~||_9P8h+|B9lTxXEZ6-~=0Rg)p%2+uGdr3(~s zr^MU0>JsRv>T#eJ#nmYdL~($JnRBz;#pS48{5G%^*jrywbBaHG7)z!x2nj7IwSa0nP#_el( zY~xQ%Uyn>;4=Oa4=XDx2Z8-WH8>n?v#LM|qM!@Y42yBd3a_%qoXGfe1!E6B^c%D7Q zx3-lfaGLf8;a_WWw|?Lqkip-37|+f2=8D9+#Zo>f68`diQQF-ZCRUZToOCFcegw| zHu)7MIGFwVkw3muG8jPeEaNzSs9g`j#~we8z7mB0*WId2zH_9B)8k{;@2#>PU|9_l zJvfvc+@o{NXz_hyA6`W}AK_p1@UBX;N%-E$onbLqRynm)X^BIAPsZ$&vZEgISXux< z1mwtG2m6|cAET}){6Dwfo)ZzxM1AZ@aq=`h^=m9o^lF=mZTKZdX`$`I_Th)N`)KK2 zE@{5Rl`(3L4o}_vQ|_`Mtuolqo5h1+67S8l(=i-D*MVzVYyuWd3b`j9*KWPo*e?#9 zHo_05z}S8wFiMpDvMSV5*4x+H+rQk)_}x3m*Eg)wH{#kicD?UuS>Hr&-_&y7^zXh| zzDM0tREFXpM1P=Vb*P0f0;QwDBrGwEapPrk>jvzi7eJH)REa>09AIq&9ovH;a0ti% z_z+&%cAdxZ_$Dur1cBp1SZJdVFzglpDhEbGErAvrWasy)n-jc^%WR12oHE$qTl}DN z0H{$87;8hb696>;q(KffM&oj86}CiHU6job3#c#gAt> zvm_ze3FrY`XSi=9;sKofyv*p{@098)#Q0B3gCssy3;<%&6%XirGSbiM3noxGCbkev zvLy-gJg~n!>{@W1GXR-74&M>>YC4F?y4xp-J)MD@WI;?m_%q>80W;A@AKFfSuBS+J z^1P9O$H~Bxk$o9d4g#E=jD@Gb5k4b5%({IqlSFIb2_sC|$7hGR#XVJkd z6Cec__AAxHS@<3@c7_!(4V@VC9qDeb7D)@a2d+Hbg?{i%Q)=NC53qWeKnFdj8|Ro9 zW2x`q5POflTs7hrmjC|jZE~ZY7WYRybh-M3qWXZp=}p`hS2=0Oj)$7F3R}08W?u zdmPL2!Z9CzxWPLE@4n~boXwVMpa6pzl=dPfjw-V`ulkbGQDuw(;JT9_<}QNw66nb+ z&rLm@eHWEYa?{kr!kPN}PsyVLV$iN+E_!-c192{^o=tL?s}s9uF2?zB^h_k}aa_y= zCQGiB)(XfRq=7u2S;*nH_y$$@nRkCeE}EBR_)HLTnO9f63w~vPp8I?aH!mlb&*EoE z|J?L50A#x0Me%YA`HzZSu=`$T?!R3`P28}XZ`Eu+Ys-e|erMnPh-3nV#lqRF0YLdx5k%Mp^iYl7*EIhcIYbe& z6>k?Ze9PzoXa_F+iY8LH!y?AQgayb(U)xnw37>rX9I@iKyLRIuFKnk6W7>~e+E&s9 z-<)Ss!29m~L#(6E3o)|X@1T1=`E%HA?jq#(WD%#{h%@W1NS!Q9(&Q;j@Gz_k*Bx!H z6^!ztL;%KUe^|H7r>^S3uE-+bu8_*z-E(Wxh>~X-{44YuQt$oL-<;0p4~u;F{c7ue z`S8c(w6H%W;a5S$pEk#wg-REe-ZMTVupiYYCjMk+0!I{_c}9f8Bj69uAN`50(i}e` zi~dRuI!wRuEBoQE+-JY?YVU-OM3Gi-LMcU_lya*eqI=G zLxS?UMmUqfO;URFu2uAeDCa)r?S0PmeX*t@G^}&yx0^rjEq*}A45{_=t{`YLpCOs? zy+SE^ul$OCrH(h8F@RUqEp2Zssd;+g;|=fKyWH2Fe{(K&K}3;s-u8}Q zEso((pPr))52i5yZvB>k{|_%X*Ji~q<-`kS6}+-)oPO3KeJkk7Sv|K4F0bPRude?O zFZl7*4a=vT$T>bj2vbHPoT%5{^l!_{0lVv6{AKJfC@bcP9VaeCGoO zApvp;x6J>!LXp^U6tF%jMhFsla8o;C^2H6QsQy#I+w2EH_vRm20GzB}wJ|@_rq%+y zr``}n({sI_OBeRns>9EV{yqB3F#4ulzRpr7J;W-5);;nbOw?t|2_S2iJBHVF?~~Nl z&L489kE%Pt<4k!EPF$hO+>bd{^-Heg>B;b>4&kbnTv=;0nX9_bR)41)pS@fjBc0aw zbO?e^s&*9v=WxdV8O_GJ{$ft8RGCT?5HH{$aP{VTY)k!YWBu`5rHQ$;Lok(N^gKt8 z3E0OW)R{V!_QElRq8v zSjG(=2+Q`Il~b-Zko?taI=LUYdacYNL%ey4{*sHgaS^}>d#E!iY zEgF@UE~nzaeY5n|;~hx+!!A$P(DvWY9Ud87L>Z<(zFh&aikk>=C9Vitz}c-@+H#b9 zEEAJ52j-sh?fuI*@_NEn>iecC0QXda`t1t##IuZS2mPn&cV4im@O56T zTTu6{zZ=Asb&Xlopx2ydFpgp~CZgfjZq`})IDMl}V~5|!#G}x+h8@e(36gR)czD>p zkq_7eBl+qeM9qLNhbG`>vHF8>zrjlzr&WjDIocY+iI>5-*zV53&C=toj)Odu)xfhn z^)KeNH!f8MaefNQ=_xV;Xn;dY7sSgy6G*z+VefOw1_C~~%YEV9H{9WNp}&SvxxcrT z8N&y88YGlH!77`}7UTjX9vq}`$&>BOOZ_QPxprUg#N0~r9Ji+z)9*8Eh$M7M8aYCK zjki)Dei5~&0p!?0`O+YN9laXLn7n29n?`i2TQh^%kPPcv?KZpKaX=rsUW^g@m1&Rq zt~ifai^{^0{(zf8X9uk>c;ny@E7eOjTdByF*>@{kMXEv%boCty#R~EM+P3T#ZtC-e zv-G8I0Hy4!=%tk~ zvBx(7XgdR?zU8aWg}}0NM?9L-OnBG&LR&7A{ulErB9aKULm_^=&fIM>-*JM+#X)1C zUn?nR!-UT>qaQhFdWil$T21h~q-emk8tbc&UI6c|JHRPOltHOlmXA$S@#4G{m`NE| z8&g8$ST;p`KGvL+Z0aD{=)8XLPX@a525Xt&qsSN}F2Vp^F$33_Tj$T( z&rtZ0nQjoSUoiP(-9Y5a;B6ql?sTEPRAiXWl|69)OY{wgKA!PjRT8W*oV3fyJRWb% zEifuMAevx8i=X;|th)fFr+BCBobljeRXmyRZs&FL70>3efO3oODP+#E;yPB>TCddG ze16b~Yz3R`oSVDSV~)ZRW()^(v`PYwD#j6g*k|47G%;)t5eeJ)K}_9Kdsb6l?+8o1W^sn*#k{ zkf7Zxwk6%vd5(SK!NIG~31ENmUn}?UAFIm$sFcJo8{%U4_nP{71?)Kpbu+=o(p!eJ z-R!R?%Q&kuD3ag0MaLWiBQ8U@>;!tH&I#U5E0TLqIQv!)@;_|E|8pQz9)M)I^S>4N zrHj1;teIAtlP<0e{Vz7+{9wk-R)DOFwx)Dusj5HoFz;DX&GVjO8ohWu|jI#R`NKn5&fL;Ve7LK*G-$A zxJLZh>QsDE+tA+O-FbUqq`h%toT7Kbpv)pq{qD?=f)cStSkAG#H(7$nDO77W(an~H zx~O=$$zr^K^WfaLusvxax>$BBPc@cQA(uzg7c&E|=v%Bk&%9@z9B8T4 z58u@nU_we+0lw3U#}w@F?y2&WkzxbcU!f}&`1L1>oT>*UTq1BQy893x9?fI`SS7p9 zME++Wl&sGuou@&EN+zp*&5WJ8?Nit@ih5e!U=hp{#XO|25cdP=#A(nos%}x}&L2{3 zV(iBI>kl_Zd$?`akSnM>g9x*dY=EE!q5i$XBwvMb%>?`;r|LJ-yD=Rav_ARLxBb{r z_;@JyY`Ee775Eu0%jiMnnL7iLZgVUt3qN#x8L+1D^)y3bDBC6Kai&9Mq8_LGY&nai zW7sE-Cwas6vj+TQGVUzTG~w<^h&o@rLB3`55>cf?Mr=&Qn7TZw5*Cz^dd9JQAX%%> zWA}ynJs@(RjNW%)r(?f6WbSN^H5c`4J}cHDLr0`{POaGY=GpB2$eWAmu0=25>a&2@ zVY$J5;4R%Q8&y_u(oyuNym@ucIA5`5Pp`^fXG$32B+;#Ko&{Yl7c+N5QKI2_fP_%}alm43-ostlhW-kl)XgPtvgjLZ?| zs#nl?%xeagns4DuL()%;C6W*uy@7Afeu6TYUW&n{jSISMn07TiE`;C;1t=64?zn{b`>|+=+DezlgpZqY90%iP2sZLnD(zBk&xrkY0JVv z^jJ}*O_0Wd+o}6;JtE%(`ZbTmQp09rPj3%^w8m^WByeA3r5=NH_T~En24Y2jwG~|r z9_ZIT-c40hOHg{k1oLL43QmPW^eqE8?|MrB7OjbDN3k$p-=0UZY8iT4A@I*ZD=0g0 zVogji=bw(ZCURf<)GBp}=1qDR+2Rsu`s}=x%qIh(BhN326>)~}^kzT13VOxL!V`qv zlDz(#bZ^Mx3?h9O=#z>XZt2Iu76cyP@3`Ifl&H|cQNxHG9r!%1+Q5CI}my}@$Lc;mhS+b zqy0YzLc{lqk+2G5Bh$(By!{fCMTM!|&}8<@{paZ93Ue>hcX@OBrK+P9mLWs$o*wU) zVPKWkMANAvp@VW`i^?lGLsO;d2Nl-ImDkElrz;%~D(y!rZCi(?Yr+qzu&^roe$$zT zyn||Qiz>(WLo+Qe4_@GstDHAX-@lwYs0kgda{W2<{`K)eEgn{l1)0ru3mw*xEUItv z56||gAJ&tTt39O5J`6b?Hsp?0-?}vXVJ!Txkpg?+ZDck#nRnP!Zt>!_-SFJZ%fsfn zg_1zvKUZHX`BD$P#D7Q4f-{o@8Xc%$0xCi?Xawv>RFGdv){{ol>9VWxgWx@u*LA ztUe`VWJTonQ9p*WflM@C6&Lk9e5Mm+ffFFi*9l%DZ0Msb8j(`EBpadjV%A*GE^e~xTu|Nb=|1Z+A9 z{Ja$}=#R7OHWjQnZyNp%6AR0(QtFsr2V7GFOrwmIRYt#9MjXGRj5U>YMSdaqewYM{ zHCMjyy=_hmpRP7EF6Cza=6FYKDnGmVd1s`L)9>T=)S82ulcL?t*mj|r(1RELou1Bi zD^t{Sr25*CTc&o$$jq8R=X$qfKb==Xlc*BK^yZ|1{NMANu7(OTqkh36{MWUvS}1I?9=nNoALrMF+uLP=FG3#w z{XDiEJ?fb(=GB^VrXT`r^PraJ$ z*FJR3{k!FDr7`!gE4YPaGa5qV!@%tbsoz8aK^aUKSy1!T8Y-KXU$O zXEDo-Fo1_Ew}U|M;q_C;TY=*dg@J#6Qd{5Z4_N+L7G@mT5j&Ro$N#KrFn-ZeU+4S1;(07oDE-dnkw9+CX$m1v3ExLFM-qq#yu$hadgn4$%*p-6FUqBDDJv-DQG++)yUe ziJ}rDxb%=E`aTmLB1(cZ(INiI5GFL_;y{c{xn3(eR>?kAxm@}+HspzCtWqw#6=z3p z)%#1t8#0GIdT-Z>4>AFB3Fg8rjBhwg$(=MPpX>$P^NPFcW#esk)5`k_428$$2A?HC zV5)GpP=Z_et-Eaaoc9F3BLYr<7~mb|XG{zTC58$>Wi~>*T7%lG!)~kEep=+5wp2Qt)W6kl0J`i~Nt+_2MCY^u(4rXyN5(*62jwQUKlv&Im=EQ-xDWgf|$- zEEy`Tif_Z;@5Dfdk+2W;sgr<2Dmsv6pXdN4Uv7@>r^4FEsj?0*`&lv=k-~&cK`_D) z#SIyn4hRYg3hoLp{>jmRfsWx}$s`yJ2gRrb&d&x&SEOq^kLjeP19DTlDX>rE)K+gq z=_WiH&fQ0cN8&)icu)=&vfBoop^;|lGBG|7Ew7jx(pl=)v*xV{Z@{qSMW~tyBK#=0 zgbQGT0Yv?yz790*z6!ID43idjL$EoLpZ#nyA$p!{=CS91Kp~~ z53vRnU>?=}3PRgGo+KwdHh~RepB9CW*s!-E36 zg9U{xf^rtw3+PH#v2sVu91fS_jz2t1|HYAseFjLBdy0YH^(L~a6PS?Dtgy#f#tCCs zC`Wt2h3i>!$Y@|RWZs%HS1^IJX)H2#@&-9-7da@49JScYy~D7SbKW*BK4aET*HrvA zvZ0R$NtvOf{Q=3ZI7}ag(1t4H&V%yKWwA{_?)@rABNEP$K$r2Xrf3#bGK*7P{!0gt zt>g2~iu|F3C(e0rmrD4_A)-s=^Nxz=w~jf4D}r{6Bej2W%#)!H*-NCSA(wAM^z+EG zNZ1=BG~_Ehyqwr)4Pv640EX}|JSdC|io}&87==KVXdqdrB3->AO&y-{63Dbz9tj5| zB!Zp{RfOSEuKj|SqBwiug#ov(wADcuK9n)Rp`GNi3?D?zZFnfI>gjO>w2Sp*Ahc5m zU=FD67OL)5ujcdz0sS9cQ%m+wgg+dBmF$r#9IsT(RSwQU<`$uij)-PQcwr@68(y<~ z9=_~Y!?ei4YE$#|m_-L(vo%z+$$>bf76vkg&Qnw0RbHt|gawDgXJ0}`D|uCEa26*x z+ei519J~ct!jxYt;R&H(VSjJKJE^c?d?mUI2=4;=l7T1liN1KC0Mk>1E~MHN67;3+ z>@#EBZHE^sH1aTP^5AZe2`mg;(QpBh?t)4~=W|c+H?sKGD!M_wdlzb( zU1`I>rr}M@Hue43ro3H97Y)Yl#MOd_4I`T^zS;b;PvUkexz*VGBs#}dn5&Hf>!;PZ z4cpYc^zqCmf5Je$UkTnnPE?$LIJLLTB^I5pTR}FA26uc$Q4k z(?M=+pN0f~g=Rkbi1^grPX1_}4r$ey5b44~7J)4iHspn0?c&qT+qn%3s(d-af=#rP za$zniCTWUZPz|}#MTPabH?qpV+;W4y!NbPTuaI3SG~BCBCmTu~`!F1ukLCcnp{Hqb z+y2QtKe%AtFdXB!LsS{mx5$1M3u3bY;V|rj0MOPhnnMeF=)5rg7M zWJk&u=%>Xu&-^(C(V$Euwe2^tR#l!{_D1OXtA1J|mrvHV8@US(-u`{^OvUjVRN-c} zetZ|u4dhqH-j4*uoEP%Lf%<8{0S<0MYtR&~NTk}PvW{&Q1KqWQ7h|9^IF2H*XFxsJ z@g%!VBUiL_<_&tca->Z^8bl>`08f@U7oqcj%p%>l!+01IE$LbZm$omg7O8F#Y12*N zI5k&Yv6n62ku7!<^Z56LPEidpdd_O0GvC7 zfd&oI*f;b0`42c|>1;Dj@TNtMLFz58dBLZ*HLF>;AGJdZ;Mrtnn{FCp4f}-ueE;_e zHc>%9Y&%zr6sNhv5WlAi$PL$c%aOm`c5SHpsKqV4&4^yjz+>N|Ge8<<)C6=?1dbCq2anupxu}eIU7(h z7G?#Trt?6R94A;2(78IO2X0F4%Qp?plD~Nvroq$LxYfCQ}lXPvaeBsaYX9 z`O3(LMSXTWj^k#UHwBkl=pWum0owoNswDSR;^!9iyC*e3z@^vr09Y`7tY~RmF%25C z2z&{%?8UwVJA>wFbA@8iVJb{<;{Bb@dAw56ARcDU(17>iK@@PSYc%AOMf<{?e*BA1 zmpmFSz9PRt!u*qYxfUG9ZKHYWhA+j>wr#Viax5k{SkL9gLy z>|=Emq%VT`iJ(C=hndT)T^-xgyl#sHBXhM>4o7$&ZQM>qsQB`S9|efa53np~ujfCb z2DDH9pMYYA%tHCcb4YpgL_tsodu-&!1BO22gnmWH=KYylbeL#MZCc=~uiHu9e5emu zBsB1cL!lSv^4*eyoVd0}zvONknSM(F*^vL_eR6h#unZ>4F+F+Y_qFV`o?L4aQ&dLv z#c!0Zuj2o>Tz)sdiu!g*Qr`3f1g{F`3e4R6E7(A5cx}nm>7CYxS?L>7OMe3Ob}X3~ zYvdIa`UL!Px^P&t;Co~V(1Qlaq_N$#hWp`x#dMC|zk;_h&|=E`h3Nm_sWfucCZ`VK zajMVvAhu{ot+nx|e}WVW>zhb+IRrS=TC?s9{Ss@~UE$YWE-$Cyu#aB_5nE8!g`!HAgAs^+GhoW8Rt3OEVz15OP`bXwlj9$X~UbpLDgzo{Vew6(l(MT zzo_fT&E`R`IK7I42{Av;kx%=o^=yAjubJsi+C5>RPhY-@>O!NE_iaVx?C-(bzqN?e z@IoSz6?RJnwGOxSKHMAMYQi6``tedfeCn#a_Ps(k2;?Hf zbsX_#@yq2iM^6=#Y2g_R`?Sn6`*}-ya2R(BEj?N8*WQ&JzXwC|&nR!`rT&(@{eZ*2 z5biEOdWhWdk1L=t>dy7s&zaDmq|@L4`app{C;$g7CJ)Gof%~ygL-XGSiX3wkj(qsv ziHGb4QS38y?7P1NqmT>5jJjpXB~SncT8aIms&tCr4?jS|M|(L5P4lv{@LVZ)=G~bB zHx;SccYMFIs-8(}VCB}g_iwTDaZ7VPS2w#{J8}LH^`<2`>|By`yb!N_9pFvW0T=K*pd(<7 zGq@S70O`A^`NU2I=}%*;AhV!QpHz%TDRZ?*76EZ>g+iJ5OTX3pJhY^ZR)_wv*j zkj?@LVu!9|`|w!F%TmT;tUxqG7Bc$7d-AzOfA7nm;ulXsJf^@%M~N->Ifi6EA@R-! zw-2!)+fc*mpSa~<-Fuwy*8c>4(}&_SuvXof`4|f?&XE}f-?qs))6!Af8ynWqX{Ru1 zczUg8S`JZEXUo6NZ|!scGls-{zXe&_H=J4<-VS|v@9Ve|`Ml~1pDXknD2IZ zVZ1@!>ECCoJXV>!o^a)OG?+*|i&Gdvz15XA5UcG?Zz}M0OEQX$dW@*3%xmO8IhIEo zW`m25-}3opPe>2v%tW5YhxZ9eDN6rbZM4#1%m>QQfTkvvdZ(HpjNG@rPA^otSbaHj zF8P?8Kkw9})@P<~!rX{-Gi1kz(3H3*PU}8bQtr9N zy~WwDUY6e_u=8!UbMUlhh)dYU^H$f0o&VT~KRfNtJh*aY+aVgHGKli(ja35B;Vu59 zTDFc7H&X*p#$YFu^kHdv-7-)mMvHkmS>u}6xmnN3yZukYY;QgGjM#K=@C@7kLKKa- z<`*WC72;R6@$`BrXfwxsMr|$Ae@1O1Y?D1)By80!+^gVTwh+T7V%6p(@M~Rvd8hUb zP{X(WZPZKOP-ei9d-MDCfpX@%?IbgT374dxw&qamb3x3|QkHm~aj1jQhiwv{?n~<) zZtEvYWxoBQAy1x$c7z!sJi>$XzGPoNZ2$4}ix22NO=~C8bEF_j=xOM(ji6KchL6-n zr5&Lo_~X5Pt&mS48=WDaAJ(1`iQ*8-#;v@!&D3z@a?QO`^_2K8Y>NiQrzh{xC3e)b zIhH}9uTN2l^sXHg*pUpzK#~jRIE9@u|Avkp;6Hdocndw8KWI>XRwfcPvWWp`*1;m0 zR{TvaAit>hbF!sh6g@2OAId#c!o7_ZIj#d~8g4XXioqE{R2Da|f$C+hMC;Id(hIxS zRMAeSWsGk$m_q8s9#!g(6C}cn0Vl&1ucGxq>R>!)a2-o5AWcF8)qNp`%y-jRPk7Q% zEC|bkcXz%i_y-SK-M4GWnl2W#M3I<^(oSW+O*uL91hKp$^*y_*C#;Z9(Om9I37=vS zUd{z+LIo6ydF${^7u=9+YQ~rMw&QRKH^uLqB`PN|3;5!DbXQOARVBp;_|7gFD^#Ru zuDYEnob3@=fOCm))g$#v1dMK3$JvYkK;9=oVhj^WpDR|Y#oP*j@qa6$&M9J7<)XEP zAaV*|@gBX7!znY0_m0fZm_nom!ORcqN>!lpwR)?lN^wAToT1b|H4f`Dt2`jBw??nAaCBS| zhyLPaRQP5Z-p9k%Rsk$(>7S&2#3UPl?vq}}gA6JQkv?FI(8-_d?}I&`V@e?8Mh< zSmi!>Ig?}1fCDPKiU~UHzvpWsvnf^XayZetss9Xc50$6Wthu5E3ulEBk(A9WB2a>LqF#`a;n{<=4nc4#$bBmSw;|}&h^|9yr6L?m8fClA21cjDz zt9wQCJ}Fu?7atQmf%Z@Lq>0Z$f zmV9Q!ia;u1Up}c2RwgMinW|z~sw_Lq1;UqvV&dSr6Di+qZgMvu3G$LJd~93irt?y4 z6?5hu!CCyR0kDc?KbWVg+t58ZxcfoO%#i2;@sJ+T65Bjhv@I z8Q^%%wxNWF9)%!Axe?UbEe`$1o&7%6FufiT>q$WhGHA^30h5o4!b_qbjk^?lDWs5V zZeS@~kK8S?DGiIMOtH%R=8=NF zc0l^0KLXKrNTMeTRT_X8&;-CpbiMQh5|$Sb}{Pf66|V6{UW!pseDxCeDtP~mL)k!{F)jB zYi|honzntLf-Ti-Y!W{7yP%Ai{T=Psul~gB}j^(3OQI;m=9XtqvhwZ zpqp@pw_tnCHH$bmkhV9=+68lU`Ix`UWgm)#{P2BNcBQFazANGi7@$9!rfHE+8K#-$P zuCK;ghwP7~zvaOaLf&0OU)Fm8S!trtyjcv3J2lmvUkVn82u5iC3(P z^`ZlV!Jy#HHv*w7`rgFNW7cp0n-W&RuPr_p4#L7qZICSbU=YT!Ky`>}Wi+}`w*k~^GE80q->ruW{tdEVTIh@!!8hSRgY>6%&M*Ij2@UEJ{)FGhPHXep1p0ybaX!Q#@@ZV*xiXuAX&YjA z9R_l{H@K+(`RS6;Z@Q6jL$4MgUTrCa&HjhIsdjLJD{638fWwiRSwMOIk}GMAyL(Pr z=-x@|gxnH2d+wfny!>L^t=q)LWe`mo+0pTMY)O=Txina)pnQlJg&WSSD9(1v8+WT} zXwM7PHx2U`8aQ3pXp&#vH1cYb&5=yN(lX6VfTk0tN&#Il#=1GP>~1)Y>Efzh^zcW2 zp@Jn)zMGKpO-fgXS*^)AOeM7;O=VQ@46w+I5o|B}-mNV3{^{O0^TBJDTn+uh_s5#R z9G{ScpVHtRfSI|Z#a}S6QuAd_c?zMawrYUGi$=^YsmSgU3P1UCUM*Grdb(&?LTRXY z$(R3ch1JE|l;hrPwJQaGlR&=F1zG+T^)o=|U1bDe)Kf1DkuvG-+(nZvLu1&3>$gg`>H7;*2DnS$q?%+rdih#0aGKYR|0X@OyVa3?5FGy z(>7-i_ZNwti<%d&Pdn)*c~Ur>>)EKNw|UfZjKFYtF2W0Ubq8f(If%Feu!vYT@5QIM zaDkzN&}0D?^R^^Sc7UcJF=jJSa`c@ZFUWtB!%}Oq9(T=;4Q6C;g+>9_ZBF^0oeng3 zf9f$<)@3?4i`~(f@I{kk4e#rN?0$1`x}1Ud z1f@3E&nBa$ykH=l>J&ro`!ymApV$e$Pq`La4#ojM5CMKh@W{ZTbI-3Zu>>T9>f7Q-J6X7v6R7sD8N)=H)a^CV3~%#2C-yf*rDg=E@!< z4T7)cHnTmpfIH@j3v|WX9mzD|?NrrLV^&GUNWyl9c?g=N{QAdcgcIi!yLV{(3BM>W znD~*(cCv^%t@$W?x-Hf-!5)@${ROG{th1w_*0_MEKVL!}J*k+Sm zF2yIQHdF#3>2WcF$2(+lx&<9PGgn;15{8X?m9vYKAupHU_M+D6=84t#b!mn zB2+jAUbGRijIKb-TO%lMy#O6kaV504@VC4FW_IkPn9^sVRBvHe@rv=t~`l!C6 z>Y;LC%%+@?A^H&|J}xO^Ohf4r_C%zcB7}CwSOb!0^J4(SZ~(z6nE(g{dZCCRfE#B^ zK;D2j8xkQnl;DU0>kGvDpg}IlvoW;Klb>d^|G7D;0_^~7Zpd4PU#_r3CGC>kC%%Kb zs61>ft65|wBm4MR+@tS4;0Q1vVt^C`{tyJl<3bHv!5^Z)_+S8W*2gR8DbYWd=%tm9 zGj@}Vw^?^_bW?G0!YOfW$GhX6dDX{%UtJ&rIPQW8$iew$rg5HyS-|WHBew0yT@s5& zE@%Oaj8G*eP-ha19TSlx{qHkoZ*BdwY>5RViL9xtmdPB#m)z_xk4wLtzwUT-$?IJ_ z!YhRKQ$^+W2eY7*tJL$ZrId2}|04vfVT{ZB+ifq8vA>CyAlC)w;4 zFTg^pU&}llQa{FNfK&O!H$7(4Vq~DZs@?|gIKs#iXV<1;7O(muyy{4{N#AV^*6b5n zYyuW%6VGm$%Wm};ZuQ!3y}h;77rfO^*c!;*8myVUJAGXrd?%}U%==5-)dBXw&}>(7 zygOLyi!zuFnEBcy*KdD1QDB~sJL6}d_ZLRQ!HGC)pL1EH5%3gaVf%aH!S_YJ?WJ?u z%PQL|hTE&Q+iSPB*MqlLfDYsrcbgEbBV)c<2VNY>PVUz6U6s68!8?ah_kIQ6`}vgB92@uZ7TZzj&cB+SU$=GuAUYF2omq;`a*57r zL}#<31HI^=5IUGhXV0N?5b1!_xa$IhC{@pIul+)rU3}2!+cd41C3D?A<#$o>PI`BK z7dg8Nu)!FyI;c3I+Fg@6|I>1DCe&RWD(l~KtVRNHXLRC(p6yB)?Md40Nw)5u3)zz* z?xAw_q|5fsx9(l&-;;U2C;M1x>>n2{C)ydP}z^TnUpZ zAMNPDZ@zu2jeXOQeN(9*8_HTPn(5j{B5zb|?zPM5@Lf?lB=P_{1Ax3YPjY8Rk8(xbnV zow|ASvik?XINr-XUTov1u2+a5mQ4@^W+ug6whj^jg_zslH>8GPCF3Hz?mx*f)7xZ; z96ylXWU=**JAA!+IrqM^SD0-%t1X&U4}DZoc3jzdT-ASUdN0I6^atGUXk&l7h{E%< z1=yCAgbihT@|@ShHQ2k%aVqkH6Z(w-jvpBthKhoYi*RgDt<$tb|;#6~)v+wOV+OrOMv0cWpTG}(% z2UrjK!z{6EhPg53*mzazxU#Znd2ePgfTWsx4k6=BKd})x_!WHrYa?=r*;Xo5z>BZ{ zWd>j7S(F$ciyNiO`0PmzWuCWd@cpuPVk0VeO;$f{$dUD?R;oozUjSTmRv~gFvnOSv zeY$)Pjs+?FFWl$6)nsoUe6_ye_<&8|t&e@lx(|bcQ`j5ixldCC4n3IJ8KA4=1I#>bvvE^N>L$42}famn&#f3<7|n^HOL^N`EG-h*KWbfsva zdeynAuX|he%|PP=K_ z$h7hZU5suVLdFl+T8A-`C{m*5Oln(Br=2MRyWat!y;Z*aTjWOP0JSh~FMHW7jz_RdK1 zzwRb=`(7``z+Bma+2E1#pk)8~8vAf%^Bmr+=0tG|oWiCn^$n5ThF(Cy%!Rx50M{3NS34G?jTs#K^6}icnBM>>e2U5;0Gn+$^?)e=quJr+^`E`abupJuji}Z&vB$|! z2A(}ir?Pv6SauB|Q<4&eJE|JtFFZWy2+jQNgKJii~3%>>lA!GP@^F0T?fOgp;s})aNxB`FM4vuM^-a4v1dV z6A5O0>nRy4FlX2c#Y=Wy zITQ&99jz!buO;d6DaH3Ma~?;Vw@0A#C5DtgoEDcD|K_QqSUF*}6eG~5+GmtsF_M;^ zSu&u1%Op9>+^cRscjo@Oe6|fpTUD=Q$eEy6Qh3z|6Z>5Iue5dS`Kdy#ETJxPk9>*$ zh#%Ca_@j^1AEDWvSdy>Iu6(Z}(4VBU&!o>P4Y7yp7S^RVSKrdQ;P|d`rn!O9{KD_S z1?QFX@0&}BDwdrWTqEKhp|*JwqngnS33HVND*o;Q9oi=Db~+1l74i_+35>law{ z@zY*Q>+8R=xY!HxpC^r@ehbM4WI#@b&t*KNI}iR^CUm6tUNss}?7P2JF<&HEd}c)e zq}mPP^e5?cd<6qEnBge_nG&aG!6=PxvCqGv_&b()@2RysvfGWa>-dE;1fVNFGjZFW zBY66mqtDHyq7Sd)Q8=3|UCuyqaW}ULh@j}364KElEE>kd#!*KCw6UCFd^Z3kDpxP_ zHnzRJ7$u+NF0&%|uB}hywR}pTZwdn_(5?Ni-Z&gFyTWQvi{TR&!c5-4O|=d#{x#Nw z>T>;xkvP36U<7zly(SyjKJ5BWA-6|nT|T3Im!8E+ea{_tSp5<|3N^hU}d*OtGXTGC|8+mMa1;Io+ahaLuBk=0OSd>arv1|s@Ne*xT#+)qI6Vj-c=NA4kRN8vZYz37_0-18V zM0#Ir2Q|L>6y{>2Mn&KQoj*#ddN;lL@nYw}kKewrd?sM#x<`ONuRa5HRJ*xTBs?y3 zEO9z0nj+`F2?=ElzNeh)R~S1$f+f7iJk{6=HpN6pX9 zADuf<42?w=xuY)b*C#hjHJ7<-kKQW2-c5O^xhf&|Yw+spz3exd>&c3>zeWRJ|9HyK z+|<)qR3g3JzxJlckK?Df5H>uZB+JhWUL=PvH-frt*nm&w=z^<)>`wa>{AI4tc08Y^ajrY5ixJWb%n1}*^{2fr&A-#p=M9b z+Z)z~RS{@5~sf|;7!L@Zu5eR)^Tf`>@ejZytrdwyA1ylVOWvF%xnYndtr5x4Pr zUBvP~B;T0>Hk92(fL!!pFRYi3>KVBDACfP{#ks?tg}0LdK}%3y0OqIsZ;Ze0j2PZ! z_DwsrQBW;=o4F}${LLE%!^4Chuf_UeDm4Ibu6!{DD%5;Mmsth16vtz0f7O)lR{0X) zv}K$d5lKK55k``|mlII8E{*vzf5|!_`T9^RNlG)`EAa`@jYXLATA?ec7$Eyhq6UZ0 zYMSxhwVMD0m*kk~TBNsis)?{znsHY5TV0QB_Ew#ubq;f(2{w<;iaw?F zwXS&ViT_wTrxVkC6RD?mhhH|5ez2Y|&ySvTKcy8n*LX{Fw@GmvlR6gYt+}BYh|>Bo z;6AQ4yV{td={ok#GAF4|&r0+7PjO}b;lPiLs=7o5YP`B>%yhh>^l75E7SmME*o(Uj zdPt}5ly|8pRXpFg=JviG2>v&62vts>?eW&?c-`2~6%xu_UR6)Ha526)`@;B(q`e=U z8jRkn<2qkw-=%8NTYgw+?9#8Mq7*|jQXg;a2NK{+t1HPxyQ>+e)GI49taSRIO#NUt zfh1Jh%B|}9i1nHCo0_we2t9~fhkNP(nmTF4Crf@ZuAx6d{y(UD&%UPmc-=F-mqqUw zMCo8C($&xe1u<9v1vT`J0qLTK-jNPcGzikgfJj$^^d3+V5f!8g77#?NOuX;C=j=0Q z+WE}PgL$}K!TSBL^1UFqH*B{R7Xxc^EjxCWd%F5r()Vr z{&K?(>ljwwEUxF!*HibO$Xg&O#GaE{pF%uO7re66o9qD%9XhMzhk#i$08yH%xX$Ca z?rCz*p>g^dw!cG9#7(_j_etf@dbVq<*5|X_=*C%`Y%>067 zst@+bFZF1Cp9X-SHACm?RDYAE0^_fE#U`M8xXr75Ui|AsOyVzfBW1>9+Rslm+o?vv zJ3~J0)jkTJcXlEiZqCcuT<05Np!w(strKLJGU}a#Jj3LmH9N^Mnu1Yx?>JP&f+&Ym zgo=baG+E?G6%7*K#XN)25P-4A-a!PX4FS49`E%g4SnaGNkcR*W(nG;Ig~S%`RPiLL z?TM0TojiOnxg+Hor36p6MJyQd#GZ_fk|<~QJmM}p()EpeN6dQc@`~|RYqR)7;duO| zz8=j;m$>`>=MT81CI50T=a#We4?$dsm%q||t4?H9{Tb{1)m^d+OxhDMRs1-zyE7aL zP7#wm(tnq2C3#)<^!fTd*H7GqYOGRE5#P@eg1VrR%&C*0XLZdd>Yc1T#xvv>zz^s( zbs5}-&IuLyG|J04D|Cy1f$#omm5wNhkL0I+Xf50x)0Z0@eawc2T7^D7TH>O=t434* zu`=iP1v5A|ZK2yYqco5bE0kVsc88^4Ah)5Tfw{DJWHf9-T}s8D*MJG$NpYvjf(|B@ zQ;>exRGomkz?Vj!i$SoY}H|1TRlCcHY5^SsYPH19JX_UUhT5Q7R!v_K|4 z?l!N|&Y_%%U|WQjn;4Jr4t@^;R&v)@+CM7dgDi|ad6$kpks69}f`4r8xEf83oz-n3 zvCSeJCjgK*jLAPL@W~GLE_u}TTU#iKq5->YF{gaz{(?oH4(we@khhWcTc0Y`EJx1Q z+KeO1X1L5>{)F6QSl*9vYHu*dgJeIx7%$yMi^vm}*zg{+c{WQp^~S$D0q&ar%!=Tv9VOfW zLXhK&+5SV7Jz70=4hsc{?5E-ktM=PFLW9dak*9I4odedSK~k*JsbY-AEk{x~fxRzY3LhL^J(7x-Rvk%R zjI7WB-Q$uD2gVe1rKd*vQL&1L$CjhoBZd2!4R`iQOnOd-iu41qiocS9v%;MsE7}^B z#8>Ac#G%6Xm}=F~V+-f^l!#f2eXRkTOL&<{i!?8*XTJ~!*#J<{X_jAE>|NWCtP-(F zvsfi=PsRoX6B^_oa)tDLJozTfsdIi>4Gws(Q%0iW%-H?SV=4a4QD^lvnrLG%6~3er zv1z(Li00(HXY~8vj~=hbk8fB8_#T;hWS^PJ_sPc3HeAO_KCZLLc)imzN)%pz9ILjb-lc__t-bt9}wa2p(XZxbt`V2|8kA$DP3>NEO(rC^Zr}C=)~xciMBsqSv!0p5N6aQc0aOl^x>!A(VuUA{`tn< z_x@_+@$g|IBgG9oNY(Jo#3`mC%ul5Od0Q9WGUuZHyQu_*+hWx%BA+;B`CnQoXFH)g7QYl14 zW-?N=JA#~NHAz9#ldq}UTIHri>Gxf}N&<3e5eJs3U4R?6`{0$vFhW_q5dzU!(fn{+ zI5LJ9gKwt9@GphJ<70>q5VajK;?J=(?by%-27j|;Bnj{^i;XD0HU&l@q@umK0&1>A zFF7ttDmE32YbM3^`o+McP&^^0_DxD&4KZ?bkNoKu-)$AQw8Lj_XBLnw9O*uT(S{*A zSdv%s!i^V%gDWIDo?{=bVV_WfeW~#S>Iti}@enY|i-d$kB z5h0U6VKaZf4WqtUpoHc!Nypq|r7=O65*C`txyo0`mm;L-rFLda4yZEYzhQ=WLP>S9 zVsy|mWRC!^S*co5aYv<6pp}5kcDlVm2HGGqZwH)NI;*fIkh$*cBhwq$!OXNOiLT_4 zFlY&^qGX*h3E5xDWz~|s26H-#4wA`BHI2`) zdA>(*Oxjn3dh%V4&-WaKy0h1<1+*urkEj63I!KQUa32f@IsBUMsUvLSmG?Z?>(hN5 z^`pL+*X)*0^04FMk$()kVQX_`Kiq=voALs${4RAlR1=Usp6A#?5<7gX%mauwBz8HS zFMOGo^j@Rn3=nl9pU*V#u>8pgf8a)`_PsOt)jGuNa=->HU;MJbwme6zTW|wJ)U}rJ z@Tb*!C|J(Pc>Bo`A}+%mZh)D4<82Dec6u|^zY;3~WX8`ZgIR=6Oz{j}&=00${H8Fr z_)rPx2+ZNa2aeh4xI~NhCw_Dq!qX$bB;;*6phJ};rrSXr&S|Ehw-W-vawn4C0|7L^ zOBmD)oQKqff$7CahYLTVLKf0s${Y=Z6%LgSNnjJhc>}o(s2<8q1%X{qDSfO%0@M!y z9TS17-ntwBNRx}9U}QJb;GAhN`CGUsJn3Op9%}56DT&98>IJVmhw@V=+W;pgiLGQH z)k@;@w_9Q{cX%UiBh!l!JTw?jF^mVLNCm!=aMCk@FPp6<90520LQw$?8Uh8zzTyZD z_W-r3I?UNJFh@jlM;B-%Yu$(^rCJr2w@4|GfoK2?1Gv8xc#1I$oQ5VERaTz?e9sb3 zQviJo&lBrPv2lV{6b>QK-#QX21<|%^f=fNh`_T&KAm8aB7@j~1H&-`=GPVE;0VK4pOC!89 zAOfu)4nn1Op?J{MlxFWFv{M@<8vvyPATPZ}SOnTw3GHT&t^t}HlF-hIj~v<>Q>opm zV;y#Nm`pMpIfjg(bbHzNfN6bT8Y&}#(i}xYx#bd(t_Ie@UoYd!T(c2U*4SEU~ zMGz{w%N~ah^%V{c{Mx;^M%Zi};)tIqf+vlN4}O0y{uoNP`>RT{g=|cnzR@7j;k$}+0;M)$tZ1{C6ne(AiTAx7po0k_szH zE8#O;>Gy@qX$K=mQJW*d9|YWIB2XEpuT$cc=J2PtV8MXOlfCYu*Z;uH{Ccfd@Et$!fwh>=I{NIPhR6ks}H7Q&_#5ra6$pYeE_yjoXok@G{!O zd40IGBR{)a-Ftq_HM>z#@neI~n6xK%n?xS>U^?h0ry9(W;&|?ah%xRgmc81mW!Rnw z&6TfEyw~!@UX&dL@sPf$XzQx_`SF(tr{gU)o=wSjZr5Vgp49X>9oO6BA6)C==aU~T z6L70p?-39Fu-;3GQ~J`kC)fK+zg&6EmjR`w4_^k!y-FKH8ZW#zhP9V!Hb(Tneb^YK zAeA>c|8hfQ?{1D;XmMd6R8!@z&raF+e0^@~cK7RqeelPxFKBVfTa(VYK3gx{%kOSY zc{hFBdPVP5{x%)(!spxTkfpod-h_YK`S|TE1F5n-6D{PsJsU4uyZtU%>(lmJnyJe7 z`79gX?+bZhyu@*R>5})XTiq}+INZSYS1Itj3cO@e^c()FRf?CKugUz6l-d9^biI2+ni)LX{;Bt z#w5uy(#Sl1{#LiI_@YW_7j@2jyMqq z;_uLa907|tpMXbDz?uzC4s$!(>k^}T_ZWX%8#EVmCakYHk-|fZ0AhI=5MxGqCHyoE z!bqjZ&q-gmQ3-)>u*-{#v52TzTiWVR+kT~%hm7yQt_gDS@p=#Eu!QnYMh*DXvHC4 zh0Kag=N}Z2qXCm>iCW{h;%UDDi%-Y1-+HC!4vgVFg{6hrpjdKFG2So!i=)u1XZrI} zX7)j&61DS($(E{#o{^6H=NcpShbOQF3J&p=w#27}GWqo82t8Hn=s!lrL`;N&twciQ24>(qln7l}8gx{LANwo#(HzE;r(q|Aexp_#vj zR@X)b27T#H+MV*FN&+{Ax)iJf28NUljlCbx?ND{ApJ_WFMeqw3 zY=FMUd&J3_`tERCN#mfU9U9c!b|fdPcP7`s-WH($X$=3S_y3d|5?=yWUK`Z@{UzA1 zkp)*l{CW!!+h(H(Mar!kNiejpL2 z(867*ec_Z}_dZPm=o74?c;yV;h~~U*th%9RO=KKp+IIJ2v)7IE5}aY@Rxi>rs`YfpoQzwplPc!yx5FQUrMRmkY%26$2`G6UXjctL$3M?& zXdkBv+R^i5ZgMsU4_o0K<6FI)``%ilO7)(+q&!+%J1#T1ktEeSbyQfw{IjpmetW>E zOCv(zUb!(|*UcodQL?d|zP=R6k%?cidQczS3!Z7PZurg1 z^u6p{f&$4wXe&2x2w+L(hUUBQ3<``kv6b{KGdU&u{3%_TpU<`WGr+5v&Sz&V{bTc= zLsML(^^L0N8wL!_#lvYWs~fw~B^@feQoN5&Uy>F0r5PfpJKjf16H$C^R*Ty9VS?jD zPe9%rmmOEV3dUt;_AKg*wvL`~yI3dm{z=OiLOE>qt3u502~*kO$j7i`X2I`I13@M) z*HeOTb-yNE`~1_Lq7rh;LEq>cO0pTdQ+RCtnW3dn{QZoPkk{nbi=wUP)Y{L5j++5^ z{X?9w?{8jn%99MsT%lx(YsEU^H@$;>q1W>y8SMK5geL-KuT-7C)t#|7dic5B$8%`6 z6YJ)svPT;)PPnjxLD(E;rh|*qxAdk7h>nHVIXZSa>wmc-;DnvE5fg}|2_UX4J_&sQzG5Cv zYX)68JgNCOEhc(`w(3f}>w2MbjCN*Hi}NB}W?N0|1??*oGe{!Z1;i@PMLnWoA?b&r z7ijD~ID@VT?~SM?D)yrcg+8fvpT=!G$C2v@dGF5Y(Oj?Ws1u)-@DQO1V<+6En32bg z%)rzHo(P-!3sCc7{O{cT*?kG3>&8Txz_TY4Kaz;RMq+J60xu7dokM%|4q=yhBtlAc zotp50BbUSrI{FOI`J%FXf>zEst((1HNFDgXBCM_vGf(Xs%OEVi2z8k0nlb&gji9w17qwAuzB0E;#$yq>bq682-<1NU^)V2l?378 z&X&XE$jKmnP?lEwB+0Moi;4^g3o91SQw0K8IAs9T1joXRbm8fcPjWyz)$p4D4jCu7 z>wzq+1xV5cG-<|MRRwN<_+$oIQUkVk41uz-6fcg%j==?2VU3YB-PKS>X+qB}HGmao4Kwv5eG7ILuN~0-2e>U11!lQNsNRPGyr{!47%kLut z$qYah0LhWkHT=zRV6)%z`=GNTMUy#x@9@Vczy~%CHAehECCauWl*#c7rP<3O^U@>J z>i0^1Ov@}7%M+RvI&_2hot>2-FIV80g)AlxNRcHwa*AInY%;UJpcKWIJj|B-hBF0G zdC^w>l8rY6!s&ZkTMAD3IW;mFr+FjUIs#up_8bZ=+#~I{2d(!tgmoXEn@J#T%<=r(BbLaE4X4CykUSt( z_@x`S{CC@tc!Xy`V!vrOe$jIv4)UuE!hQMME$)TanU;|vDnu<#fdx_?mSFszc}GByP}0Vfw4xqX3DEu z*rzQ#H54F|fljCJc!+{(7-+v%%tZxPgSY~9bu_fN92$YH266x^RHOnBc@`BI8w9B< zF^WRx?SOcarz#-eN|;n-8WruO0E8u?y#~rrQk7~`d%3S*ODd0#XJv9?W#LpM)C!eJ ztAMLke17U}Tds3c0l3BnvKfGnE^smpoykE)C8AHVQRP*Y;R98u^s0qRW$~TmsiZ1N z8YmCLlbu!#POF4i8Ds+JSODZl2GbLP*tE*Pu)DXW_z7CUA*$$H&)Vojzz+ab1E4lf zAR`|QQ$@kk(GKq`ALf_&u`nCDa0m~wW~OQ>v34k5NNxrM;X!DM@Eo835^P{&08J1B zr7&wAIo;7zcMhfDu$P6naCm|qxF5=+!2smQ_vktZEC>0zqzD&Pv}eZw>w4Cx`h_q* z8-k&tn$A`iQXpS*ff;QeN~8+B29p6mQ6jkz1IYRc=n5G}rc{V4>Z@zkcd7{+>+*J) zUhX(^NHYBaTov6(243>s1CwzCy*zU<&`~?UPXu{Mu?d`3_mU5nr?rnmy`y0eUTuIT zPx8x!V4EoSc~s$+3^Y{{;G;nMsDPpvXg?VM=nr7CpnOGuz+r7xH6i^PUeDFlygOJ{ zz;og-cDU@0UPL6cteMEwQ>b-6&H`T*0BRDtNepxnKqj*>i~)2yr=prw?K6eCI)GAH zt-Quy9r%W=zbrF)mPc(62pcH(nW`9FsrS*nm%c-4hgh}K&!SUSnyY6}8Tn;Pmpzk& zc=!}V?W_6TYvRgvd9HEVpbmGT>1|LcG;|&HP%MW#6p)eD#(l*jl>ju3olQqY(NWnT z_VKvD>v6K*Pd?-yYikO-%PC-C9DMiBwhoPX&nxm|&>yPlKCW!z+0!mw7OQaeY&B68 z-Lg{Y@7YLF0*uZ0uGo=~!l1hXJWx@Qi(i!Vrm-uc@`Z-C`K4s^+5s=5e6$S(gECyV_xIsFMxexi zIj>Xcg(tg8jc2m_E;((YwUv{lRvFzv-)dAx-)mmD>?|;^$;FcpHeF)`kCSbxAg}~?FY)j2Pz5&s@ex?rUz<&4Y0%q>-7g4><1ge2b&8ATiXZQrw1SX z8f1$PJ<%WPvLEX47P=ljp4C2$8^}gK8*nXd z;R}Y?cDln;#SyF9nA(}{<-)z?Ow_LvQ6Go)LbONEWuT0|T{Tu6-l`E;UBs-4gML`> z`%jMsrl&$WMi2+~Ca|tShxz21IVr`c1OSV<%XdI&ENK=a>&TB^#4Oc}?LIKR=iInV zk=Fa5acebN9PYw@BsBifLd-zwpr??F|1(;MJf~16L+)hNe?OX-yx_a?Uq%z3IW>V~ zlm1O;lv7KN;@=;owS@E-AA3FUp!&rE(J<=HQj~1djVB9}-<-tNTH=&WIzRQ?jS=?4LpR0u&3saIa9%)}tvTuE` z`hw*&c=Mlx2K2@3o8h*m&u`gL*j@i5H2zOV6MJ`@WgoSF-}tMA5Wl53Z*du_w~jx4 z6nb@QW7X|3+$Hfh2q8DafC>K9LjFl;XfDr00f+xdX#Asv{7q;CEzkZC1y|~QKOkw)*i+BUvL`N zv+Z4*7jnQH>9o9aIWI}su4ONo8D|lUJNfk8A^drp<@iVAo;XGdYR zreVT!^=|WG)oN|~*2?NVHbU_Ot4q-9LtURt^@sYQAJMM&IfoT}E)2lU$p9bY-xGzQ@hGbqt6ew7hgTU|6^jX@d*1Py^yw|&h|5q(!RtoXu;iu&Ad;4WZlgvT=rTU-MqFTah z)l~<%S_l)t$5tDhnf5+&P+f0Q-oU&XukjGrJUVXj|A7_~67m?v72W=u7E&1e>H88h zPUXjPX|C^&_Z8)}KUQj*KK)o_^{V{*FvVlkmQ*y^qv2xlmXJp}@Y&UT{!vNavGpHt z$jR|8>Cy9z%sZ|CqW&yK)`RO;t|G)Ohf8_eb3?AHp#!kLcUKf&K;6cA zrVU8UkTN}~fJzT&>Qs(jE^&(s&$694c~mfp0=gTu}Aw=0tj zq^c)E7(Sm!td39H1p_7J`$>ttH58!*_@$zGi`}2`fHr6A4Di27Y$pUjXX4A^Bg2zM zuKM*Fe=tAz}dqml4Ei{2}$keG(p%MA!K8W8y$gB zs83c0oQ1%oQ-)&d&{+09kVAZrMQ%Do(hvq9`r|}`^Ya{)N|}{FpE~Ltw(OHDLNne# zhF^^XnknBkKaVP{Ihq>`BVGF#LOhf1v@d$3q-YbhdiEcN>I11G5w2t?rN0f+d&POW z;=+~8hOaKYH7Bo>snvB7(><#01?nLyybaEv#!IL8Qp|YR@x>&$NFbgZYi|E;$_?$qr&RTY zbvl$X=lz&D#B*%#i);KEpw;ExLxYWvVsjGrqx@b^@APir6g)u100x&v*kCCqn8Q-CapdvMw~j8r3t!k>}=Awl_k&@-Sa=nU;Z^$Ot-`Ep*l@}E@JF+)fsn9PNB*+{AmLun|LePKYl97>uTF`tfPu)*8) z3(P*rb1)FUG`f|7uyRv;5lXU`=_;3&LLV_ZFb6@0yPv9D7Z1T>oXbUqBM1!Hi%^W)kdqk%jGX5i6}wz0 zeJ_if&@f;4^5n?HjdlYmcbLohuJ@{zb?__RlQ;c);g3w8q?NupeY{|N^q`BOYfh`j zj^XDof4*6H9$1Sz{trX7@A#uHx&IwQ^?y5>NPOJ3-Fy7cmx7&Nx9@lV2)h2KQrt?g zJ*``L>aAcI`qrNlv$TurZw0QQ=J79|T=P}MuE;WI>F$VS!J=FSZj!Mt1C_|Yd|G6f zr{f_G5ePr*hG~Qem!6uA0#h9*W7tndcH(ltPYM9!Vd|*-ElUh}VNk$YKmsRHcA5V@ zfbkBFqDozRqD*)&V2YX5-sq!aI5PoI2^mvKjxgKi%cYn>{GwII5tUIW?Z{xO zKK{)Go&TD+H3MmYo{N}zi)4-=SuKq|JnKXo?Fqh{D0}5`wu4m z-^8s<<$Q+4|Gu}ikV}h|U(DlrTZ=c`%eW)h-i_}U3%K6aQenV^$5PQ>Z|i0_H*w4L zwiK4RBiNqH#qly#%eRv?SC&iua|F9G;{z(-%^mItcBRMfaD^&MeHa~SP>vuGB+Zjo zR?PfiJJez0kA)j6clqmhD7;`$J+QYKQIM|AUzy!0`b4H0ko4KE`oO*C#H@qItuK%1 zZ}i=-|}NvaKbr^5F?dRzZ-&;4O4m%iGq zo8MfTn)JRrw^H||a})QTYv}9>`{?v0wJq)p5WYgEDFP(cshk<3aA}Oc99pJ!sGO!wERQx)xgRM~%Dg%M? z(m+BVIY&t2(j>g!DIPCfi+Npwz{!_ni%hM>`bQuLOHPJ2Cf`NqSy)W&upq`aNaXkq za1TYh&mdJ}o%AHc5tJst5S8gl1gGsbl*}=S=2rzhp*Y$;(&jw}XK(=ood(w0X{X?{ zm`i3TvDc(DUDO_8NVAh9gdImo>mY@;mq>nR^`3`QfUGqm(4OTUP+uAmjEdg%Yevz; zu%2|H86wtgCTfVF@s|sCE5aNUP6t5vnIx2g&5fg{5fp(e&J!VuU*gHg+kE{bg#5ma z!Sg@H`EG)8_*X!Q$LtMBMP{xb-MR#jy&=HSFD2!pQJQ1}QaST5sgcXX_rFBSWp_$U z(&2jo3<#0bQtjgcW|k_43&WW)1MwtBoLE1@9zZvHX1N7wj+@p-ZJrLWG|* zM~P}WB!~Wih&@}5Auk@`BqB;~@!=_A6C5;w5OACSV>v}Jk)yC>2skfyA+Jl}uJWEL zCBI%WF4s)dYwjRa>i4KNEL)bi&t2P%E`^>9rrMK|ZZ(iR-{%aRvf~&E)}vw-o~^;N zxJ>*0G`N*V$Mf2t?0|;6^9qkC=)HylHRq32E4e#h?NM_APskGT2|W6Znhydlyms3d zXT_evHnqQDrn0La zFL%rQ2}!tMF?>Ju%F5XzI!Tz%%JHo0{H^gq^g| zTDo9F!tKN9rJndIPON6L>ilkOi|8Kd`m`jAc^R=AVn=(pp;QN=2Nf!M+_gTZ=)=4( zy+rgmOD!wAeO}GUNbJ*0&y6}i*L`+IJEG4SvHJ&ziT|0hrGN-`wxRR*X3u__Gvr@#wB%^_}pzQ}vPkmC4 z>yLe6HIM9j^HIutYN}$QNB;c!)gHD*FX2@-oZGXcwVtj z@hLNc7gxHq@~1v+H_S`yYxZ|Ge-_kqdFEO8nz`Gb4d$r+;)}a@vr*_6bKis4s&BWC zRG$&MY57Cm*Y2~^txrg3af!!|LY|JtV=I9boucsuVS3lUZ%^B5^|u%PTHN(^&|T1U zNBirs z-ShqE(&zWiBlTGw!mF|25N*apnlm&cys**5<*@T42tQ792F%=eQ4zRh0*8XCr!jIaD>`46UcF~D$EO8~QQ;3^P>!gcy68Di3HTUGm|=LV0J!dG)J+;zB-g!F+Y7to z!O`|A-;qsAij98F%v_7b-(;s*^jZV*g42_6q0GQFa%xa{`cfL4%EE7vaM~oyCYvy6 zNL*w_-IXC`x?Zi9A*^%oK^(*pCftjK{z4-@sYqzB4oGVZn_0|ulJl9M`eG9B1$4|t zul4cMSr@DVUxy%{UnYn0&6vavoK#H}?%JPBtkxaZT2Y-=* zo}|LVNnE-Ve3U`>z{Y=0L)>Cu9O-#>Yv@@P-l-=X8B#h8;&RQMq1w)CBnH1(gs}|w z(~WP^x1WOWok7q!F*b1*`OgYiFCntHo7dn0eH%-EQW#3+5z?mdmN+q$K4)tcHd$5pG z+(`uvVQbChYZ@YpQ^ef_I6=d!LkrXr^59w?AGVSaT7?Lq;4)1g@uukY#@vl2>(VfR z$b_mYdXjM&K?7QSn}lCkBdpJ0nrTE18*zb(eM94JSs=SW#C3P%Zdcr=G~%x+{2exS z3&44@5xp$J5{d9kAr6QODhZ;)Z^ZE}-8~@U8S(;MHG`=((Ukk9qnQ>{rhp`QrN{U9 zdQS>z2xoo*5!cv+xg83@G1Oy)L|i2kGjoWRI{4RQf^BHnJ5T|iVqC4M&n=mtir`G$ z7s&^aOvQ4{0E?Trx2r8%XyN8>su<-(|27LW(I3srIvM{FT7BxX<^DXs6+XZx;vd#YXJwvGHXkS}FPF)*bFmL0NvKM`dm;GDMBz_R=4{A%j zZ(Y|SA2v4GA*Gik-PCV2)*pG=T&U&JrHR%%dGxVu7q`BqWm3R>*SpW@QBBy3_2T~2 z>{Cy?294GqpQsqTjq^&b4w~XdYbF!ME)VsD`|NIcv|;Wy1*#tzvK~_!He7$~<~e*f zyw2k1aG3Cj(Kr9QM@O^DlFO#A`sU`oQ}CZ294X|senA68tid%ILce~1L2lgZuw?&j zjup0l(4uXUoFZj_u|XS(DdGJAc{}YR zl0|$wV&iKc{4WSz3R%wlL?50iY@cF|T2?o>YK^|D$yGmgvH0>+WAG#Hy2k}Gy#2T4 z3QeDLaRm#Mw0to!vTO!n>AtAmNa*FvS>30}3lvTKb8SC`Koa&L{n`|jT`y7)$#-Xp zO-NnxZq*D@ih4fvD{#R(H0JfdxQw50%817BM4l=!Ru%XNJo`Mye7zj!%!Jo7T_v<# zUN+&y%JHLY{0J5A*625$hSLqi^|SA_ZPg$3iru(8aKR^6)5Bv)DJu%we%*(-G4pEe zKJwxoL<_CT)~-h zkI%E%F%Y(kg&PDgHUOTQh8&r}^{~?iuHaTc_#WExdp&A7dM!)%#O5TArxSImxv$<& zTT2WJPo8+Y`I_*7Li|W3ex%H4pP$<=3DWhQdvOW*1V8W1xU5ZvUIpQ+?@rbD;7-qA z%m;8;B)G*IVgx|hknq$Q}_BW5rrX{bmNtepL87Wn#%? ziGe@EK(Xk!ZVr5QEiasfwPO&RXD}Dn5VIV-TN`w^TS2i?p$|DaIhECAK#5a<-Z4P+@=2f2OHO!D~02pXn> zmNY`j2qHqnCxo0`F25}OPh z90r~7N$45aTN_rK;~Ge}jM{tVa;@-Q&OR_rk+DX8#B`d47GEY|uCkH#G)xCY^QwJX zz8m2Q8~+9%eqrNtL8u`b@erKYzlM8iZkBX`$YJ3=&fwZX1T(wu$vNX{?ZZC`<3Lqi zzAShF3AZL8yt6|Fl-X!y1DK2!xhM*GnU1svp(5x=CJWa=!WDeXPH!S?eir#inp>UW z9;Exevj`xEgXo z)Xf?A6rB1BStuK>1nu{E)Ai2?_JJ#ZV4@oA^n%SG$+jD=XRyV(ZLsC0XnZZ`d;Wip zU_ZPH7qk9gTkkR)w$Ry2yr~zg@=$mG3a>`6*l-FTk}z%JzqomxKlg>>41Kbpa}|5u(}H2o1G(uaws)6yO~j7> z7B=YYH{Unh5p0B{y|%4>=;XV)x&8^o(?zAvhks2L>ZHXDwnRyuyL`kiq3Pn=_V-!U zHue5*MQ+}#-d|W7u;@Fbdo%3E*NqEchS55) zwi|JA$U;2y8BedMm-w7t306HkM)0h+-@2AN%}N;*nqOLfRPkPyn)%KjF%!yZPo)#m z0j-r~1zFR@eH~<-A9V)4HS%${_p9oD$=>7lKBh`(xW4LEKIV40#O19$4OAndN!HGx z#;N)_elS{tK9bZEeX>_0A*(_B@_gyDwj-T28Zg~6kIWu9BC&tT*zKfl)V!;We+|#4_U}QM-a!lmhTeW~(sYcY>I$-4t*-dmeq)~NhT)qmCQY zYZ3}39@chsm(OY4(kOeQs;>fN? zJCc^i*@vEG3O1-V1bsZxUAg#n^(x_#Z|gq8p^wmEi3dVa;H9229whQ%)9~u*!hDC1 z!}wY*-?s|8>weZqnxF57K>rls7mNPhDk9Cc&nkJtKWNg&cL&TJyWbt~^{T^oh#l^b zz0b!Jw{QApReUZR_n)a;{W19%c_@7C^~-P4>!a6;#Jt}b@46D)0FIft5RFDWn)}@Q zxaPv)d&JyDgKH+BflN&=cn`zG5UC}1pE5v?5`8uk3u$}GPCQMG5Ne>o#rp7fPb=+2 z?)pVT?CZmOP>doZVGfu>lPNCE2Fj7luD#BAhYCJ0xUv*xjh-jD^Ah3%3!ggdDs+`kWMjq{*XyUl>-)hX9rTpehP zlK5QFt0$*>)|PK( zltr$`9_&0+Up#jl48$FqRTh8 z@t(zbQ+iczCc^c%4X|#Lhqbr3O2{cgEIMlRs=GkNnl^0%YdIEy0P9l1tZp8KMunilMibwc~aKCufjK;!$EY z+K2Tf))HLAXGNaLMJlfN!5ya|*jd|H{$?xW(O*V{th^q9n`5cU%}*p3*KG3Nm1Ug2 zo3MML?_AG^{PFf${(z@ay{bvJ#+{l%aXVs3`ojq0;K`@bKR2PfnamU?rDD7<2eLb3 zJti=~3H!9KS2P5SGT^p9+_t;b9&u7WmfgnqfCH9P7=uD_N zq3>ha;n+WXp6|i*yo^@og@Z+o*&43_Cs+&5BZyLa-KdkC0KYdmmfSEy@TEnF?ASsT zT8rV@@lv>zyk6N@=HjIWDSW(bl=?wY*{>b7Yz4pGkv%4r`8w{+D9um4`Uc6T?m~uc z^<40J_x*q2?Y*L!4!lOokV;8NC{m<_4oV4vfHXsI3K2yRTM+3jN)-@8?+_Ic0U>}= z1R)gZVCW!-L8^#IQ92l^h+roF@4NTTUGp@vX4X9CB`bMIe&?LMcgq9zy>sJl`~07@ zrw~d&C&vh;7^^A{S*1?lc{3A@$#%F`m!VL}Bt-MGYqC%Dg2=DgZuxLW87=3vGunxR zYO+^Ty_|PGUzy3-wvdG5g1&w&Tb(<7q=C--@^oNp*;#YEij%B54Hd&z3Ic?aG`{Bp?sK4$dwHB0ofQ_Sr&{*EjklGv?s zDZ%1`0r#`Xeknr77MU>pL)P@c2ivy$8THdYmE#@^I_vp8eWWex<;JIWK{DwUSe)%a z%%rr{LoUgy(ZUOO=W|q*!TUd?rTaEGO!~M4a#EaDE?93q)&O#o^5xI8Ib47HL5(Zj zrKEucGx^LC1mllrk%=xbmy#1Dnt_QwSnRu{ro*4M!mvNW^NeOUd{~<-=Vc$(|B?NJ z|IqGkb;1G_&6Npax4;!P3CbV(liH@uZ@TOlOEoEfyu0}`@|L6+Xyr%9-m-a8l*{I% zNEh9M8MBmsqn=x9GjrE%iGnfTKST zA`a}Ju9{gfOJAT~{Hc4ok6DoCgVq=Al=)+T|^ zln&CRAGNbqf+%|<@jj?n9TKGGG+)MCbaD;ba+IE6ZGsUdLY|d)GP(T%Qv%zPpos&& z6acY;YY^u|*DZlQRWNM|i#jf5cK#W-0QGf6pl3J>+ISLcsGm%K%w&;j&uM4e1Axle zCNU9?vp`n2M22Q?Bquhu%uG-6RcGN!%=&`BJwn{M%!o_&v3qP!(@=4Vf6|u;$rD?z z*HC;xvl&XSguNT06-z*3hsn?KSp=9xP)w&RH9@nSO?{M&r-V(TmW@}STO8g7Sq53z zLttcsIi)9B2>G(i)HDIy+nYh z9{?GSFJw{Onyf^Ph6MRw!yKk(l$erD?aINhEJr=bA`k&|qiZ?cM~;%YAM`x#7x)k$ zA`M_C%~<>q_I4uK!vMY42oG@MNyccJPA6NTkva#FmjSUjhs=d$qnr|!pBw-*HGvHW zX57^@J&7{TwFl&*S^~PnpbK@@AM`>G_`GpIAqwaY0P5IadO97RNRaS$JDr)F+OG*` zd|;(Wnhg;%ZTUh!Wiai>KT``7wMQ@2AdzL2m~h< z)?S84mc%Ndz@cW5rvcDAC1QB{ScPc#6BKMOzu&7VBc%UX-eXwy?%NC;WcvVOiv?-V zelWPyTZY!j&IDeit7Vro1JKd)J8UNQ7ns^rO+47z6MXUq_yQh$MWOB7pv6%>R?{L< ziWVs$7iULdvBg^AS)uN72?+$0>>>JX`v5Heg<3>5)ZNJRie`Kj&-Fe8Lqn6d^{?6D zS|YT(-9EWFWlcB7>_RrJxeKg!AwJs7KE{j+Hto~AN^NLA8vJ#EU%w&R3J`K>2& z(nUVOp8Rz7W0Ks{qHNX&vzb%Ee67=#h{rK;15cX$nt>Y$up^q(v6LIF(Fp^UYygVW zqwb=hj%cVi_UTrFTJWrmQot)^$Oz`dh>G;(^@Ea5Drcm<3B$!dLG0oa014uV#~5%m z8c;^G6)#ASUG_B;VR;O(FpI(hpiU)uPDE&(nradz0os^r5-@5SGiq!M_nu2XnZlFj zKhkpMSz9Mq^4o~@Sp~7`r*@Q>i<+@c04QD)>P~}(tmzEZTnTrtwSO&q;oZ~u!(_oC_qsX@MbwPaXRW{Iw|YIBcrccN$7bBply(q+cpjAe%Flds zE$-{*(s~uCY)ckZIOJD^(2k*@Jj+-!`WeXNaU?0N#!H9p1} z&Ery%=}v%h-M^0cT)^W%CXugyAVHNQuQ!c-ZAGw&Z+(5g_tgV+L-`3rng&#$Mb@wr z&*DJE0XM4cK|X#Ml5qcR0CaKK&WjKic{c6_cQrFu8-RP|+!v`%jdY;IsV)O`sO11n zP=H&U79b|bPsViY*)Q^N5;?XG=s@mHX3Xr}q~c(nvml&6%q2}omf1|N^UPv5TWpv> zeszmc_iOvUNCIn|-*Rj)E^2%Vq7Ywhc>udS2`sdLdeMO1ax$(T`O)T@Ga*+@Vy>99 za(ZFt$C_l6jLOV|i>9z1ZmpkXN!rXUy-U|0A7OS(Y+Ht2@!Da4WnRic*f*}gQ zaf)tljnJULOsHZX(A7MVn?1cBQHJ7?j>*s3TeJPn2AUP=KrH7dpiSIra3cHaa zRS$rQX0dKGpb8N;4`-3_hoRk$bIhUN>Wc;hcIg z^VXoD%xzC|AA1e&Nr-1W%x@WJ9}i`I(ouJ!F2~0OVVeR!^0^~kh`qb2w^*um0JPpj zoDPTB0q(wWmy?>}EsOdVBB!oy1`W^T^ud8NFm-+nKLXFfMaMXUUg}OY8((V6D@M6| zql=B*gIwmko6>Ohemr`WCC*0xwr*Tds2vwXi}fSG)^+8yOxnSvFZNG3p5pj;M}0|4 z_yqaXPvvWiDP~IYMp{qhCfaEAt6MHJIjD={FNbiY-{qJ5pvyiW(Eu4Ve;r5Mw-dhq zbnaJO*=gnrGUmQ9md_v-xn-+LYZ(ZgRB=mXzWZ?F%YtK^T-3NK#iH7)>x2JY_Yq{lpRk1C;;fVF4WWpNf+KmTKKlfPv)bsiU{q;AH ze@OJ#m4z{aTx%OTPSPPS0R;;Q*SeDJ?e*9@C&K*D%KIpmkUsot!s=a;T+!9bB`fy6 zh~oZc{Cj>AI+($qCvQ|di!U!zx#_FP?eHy^>eauxc%yC&Z z@N1Ijry{hYdV{E+gvO4^?TnB5FBup8k`HvaC1b-eYB#aqnknd=NuVt$%84Fzs$}Pi zCg`$twDTGNeysn)Kte3s#q{}}Zh}AGzw!LbO$KQSvJ;VpZ)5C9kq$(N93eJJA{NsZ zM`!@**~j7*x|G&idUzlOS->N@@jeTqE# z)&OBvQUfn(L8Frt#t^w2MGy7<%Jnqvn8FP*wy=f(m>oH$2gS4T&Ern!X7dr z8O!5&B6cT2!E8_D3VE*Y1%0tbIyA(5?LEFuJATReaFD!kPkdsQe@fQUE=$kzhjkiY zJH~+?^D!u#`aAE0Ojw3S*Ff;?wFw!IdbNdLKAXQ%ZuTWOumZMz9RX&;(#4kbAgtFa zue@wB`gpVPznu7)sG9}>)3v33Zd(#P$tN|=T$%VdWe_l_UTU*vk)hyl>K+6yIQu`G z`0hJ0LpfSO+v_VkvNWy$_`1-KgAXiA}N1TaUdr7p^;8;#3GG6`I6P zcIksX_Z1wHxZlb1nt%Rb{;Zbr`K{+~rJ0tH&?$C|r~GVdB#cMtMnk0{qXLYOxUfc( ztgB9yyC}2WO<;w#Ax0Rq{Ucx3;TsX}xo?jBjzYkI zlczX+tp!DzJf>y?)Dvuci1hEjcYd8ev;sUhcx+14W#Kjh5D)6nQ30h=w9}P2XDl8p z<^R4;*mQ5;3Zq|>OjZBzt==Yz>BPTt1-$c%%h^h%`>RnO50|a8%K}kYl$4j zr)ud#|16~ad=-@Q*vMfK73TWP_*I%)Ra~m(qVZELZP7bKsu8l`ynzZ+%fAx z5iVfzUYv;EWCT=Yo}jvv^Nrvnn;R5ZBb)ayP|_;T_P(Umxp{#QxqP@_qG05Q;FyNif>m$__tl~uan+jmo0g6d-m zQHaXceGdes9e5p4)qT|vQQdLMGo|w5$)MA<^;T-9-;Q`lrYe|?=F1REat{?7LQ1&- zHgj1VMVObs9S$X~kOIk9DIeCBou&v+#T_p4m7)p~WWa9ZxWjYwmyiJuWwpBk_h8w9 zEz!M=T$Va2-Mk}_+z)Q+Mh|H&WI9>(3O{Ti+5d<>tK636V*e_Q@pyl7nM7|C{_%P` zxdSG&!p`Fan6^DqrO9Rp)^^Rg2W(;A+^|6yh(+-XX)Z_eSQ&^X8K$1&NVzdI?)@cu zJJwNKD%C8#r5Y+kZ811C?9H=bF5%Fm8{}mo%jalrso^~|I!hcG(wYq`Pu1S1sHToz z^Lu+RzWPEz{f9u~>qJGjQE~WJe@`WqQ=h+VuPn|@A?EIkQFc_mJj`)@Kc}5 z4Tr|)@|((9$&XT+<{$sv%s5>!Ssg2uFLZlVPo~MgrKAr1?b%FHA&;hRL2Z?l=3b7< z2igAe&Q#rfYSfUyx^g|iO}pU+@E+yBAqfJM>Lc^Pc%6Bg97_C z%YPnm(aN%pV9c-MNENJO70YJ@NSItwI=PKGRc{VoN$*jM@%MVT1?ZGLsESknvB1`q z8OxU#k*MfZ$kBy?A_Mi4m4Z8c7v)TZ>WI+WBtwxOB!`Kslev5*CH!v=IvPUcO#jVB zaTjDtiYA?IGqkRV6Hw-MfLb{cK^cbdKKdmB+Q%;@bDMO^KIz!_N`wDvj_3g#CqSKQ= zi8?grhKLjL4l(Am2MgyNFMZB#VkZyY5lJ8|h%8}xM3-^QfDz2IU>fD3bT4uCAyi<$ zMq10#&s6_a&C7bQ#7uO9Mtn3#WGUVh?S(TB@X{CPZHPSE!NPGb2gG)>r1wN71rg}) zhjc(e&NkhXFBjj;-egAcCCP0DN_#vwOQJ(z0dczAtj_q&E3+ ztZOhxBoYtR#odd=v_uH)^>xZ^Z?WkM4}~q2nCPxwLi*c-G*8vK`C=@rXoE3CnbtS9 zMpX&c_!DleSb5w1KATn*&VU%3INee4)O$3Bp~xaBPWOjOT2Q)Vg_pPKre1972p78u z&sOHO{FAmeE^0~z?#^~RLeDJauHLD@Ut%Uv$6xIYOZ;=_EBM!~oP32%GxDaSWAVw8 z0QI`sBHaybE_*Ew{h`XNKjj3B$A@$h-@Ce2Z>L8k4iCb43@IYzn)P?>r+HEJJ-SL- zzvW0Rh)XFX@h`q35?@(U_!`GseH8CCPG?lm&EGp(`@godXF7M44Lg-WMufD|Jv1W9 zQ>GtNg=T8Zo;5j`mxk<=eXn~L^p5XDg3;3H*R-h#%fGtJh{yQtO@}MON|gl2DJ930k=K;}a^icJ zi`FkT^y>XnAzkj{v?;h_Swrr&@z0-^R{dghvZCDhJ#;>$LD~}Hb0(vvMeJF5?AcPe zKDE)4KUDtO3y%R5UW}A43O!9pFT@&qrj~Onjx-L{%x!zz+WKi3eNEW&-_GB4$g+Of z3$JlH_>>iw>(OLm#{W*;mIJl{dMwQV04oCkVih){klUkJc~0HvqvUtSp(HJG%&H2E zV*`{tru(W2d(+T{iNY^X{QXb=o4S=Y!c%X2$T6=e`j~Ye+{SIPUi2vs8+A%8mY!)+ zh)j{@n3biz1azG!{Q%z^n%as&XkKWp?qhYcGGZ09reo2l(FJu4DaB(Ea}Wqv&cd z*3zJIQezfd4VJ@2R_}5XWnul>ADCWrO-KE9nnA1&b#nVd__4XBW2EFv5H4W%MeR&t z@VBaGXyCAGp80(UjpGs9$sgY%z&~a1fZi4ZjwmB;LBQkIU3Hu?74DuN1Ktt#2@aJ?3QMBO*Mz0D%C>p+B9%f`KQ@&PDJFIM;gJ0@fH?t# z%Xv^EECVNvRYbg*4TKxC>)0G{B)kN8}+O0 zXunXIN!`LJdVgn5GpXC9GC~L7@4%<`5QY<`^JrW3lf3&V>#rV#QujEa?Af(neNxOf zpm(TwVf({r%fU|rs2YWx0kw%~ z43N6ppLneis%-|c>y%G77z%si?B}QVI$=DB+KxqqrrjyYb_Y`tFaP=N2}#()vmFYq z57obgjWE2ozg)WhGT_T8>tpM4ncZ9Lv{4iBa^AfVF^AM3C&6 zPXScKhw`X~=I3e^RG96qfn~!B@<04p81uRtE(j;X^q1RDo~#h^Iq2YDCnT=_h_gMV zAS%YNUp5f%U_Lz<7I3@nBmHm&C!XE|$ra2OqKkauue&=6wc+&y`IKBIcILSw#@imn zOQH%S`%cO^8ZT_+M=IVm)5`> zNDV=Y!#C(XD#7>8N!#oMUYzb)-c-%?)*3?0lp6{+ll05>hDDFbohS+&sdbly^$$K4 zQ9%S*Bp0&2S75F$#G#USme;$3u=ZE8v5&mwU?$iOtxdT)l{d-}w+T_g>qOYUbG!HM z>9q8~-0de@&D_DCqHO{pb z`_woX1Spg5(XX}{x;bYkMa#AlP zOGht2_fav3Cd~6s`gcy zZ=Hk`1rr4|mtj0Vn&3jwg`$?k4%MV~P}JPMbMs(_Xf6xrqG&rO;DYy_PNo?a&r_Fn zc|@dVspI;Sjriti1CgBHX--FEv0iis9|6GnaKjPU-|)g@f*kF%Yxs0;IgWReI3~`_ zOV41uZU+5s!!ViO$t$SfiK5YVtrKp+T_zg;{-%ZKEIe33b)T{Nn~GehYArB})wMdp zc>6D;b_*CsZZ+Vi&kBUQz`Nv3<`UUzF5c>^q44Y0SMq4@`SN7vF0#v9v>m74T5RY_ z4PAF)PqOYajLN04fBB)c$eD~ERWj&KZUi@pTif1pxLq-LrK4b+QT!rw`+RLXSSdsP z<1YuEZJAXU+b505_toRj)!Psq<%?lqJ+JfTbg<`wI+2CA?%VK}OK8=-CuS{G`V6l| zBX)_;U4{N-bp{odr$b_sebj;&!zo&<^V~G9y%z_)i-g=MQmIuz&Iz+vwQ_O5oyYH9 zxOux@pU@1+X}eYZ7wRmMW`)M`?k7%8Lw8(4zVr>%O6XU$0y3?pTnuuzlOJx}_!z9YcHA#fAv=l?*5g$)l6ld5n(6?RY;5KK2GyFFCBNW z^QQoS6jU*zV2V#gT5;UCp|fb)-`V_Pl|9>!^i-@qf8fNDA31yayBA3^u)j_tVa2KY zPLhL6>A%XHdrt;Xc1?okk1fOll&7rtKQw=#K@|zRw=_oL#Liw*c`@@?G(zF^r$hU@ zH7P1fTKuptY3chda1l-ijABYn>Ls@uKrW)dR^rZZ>Z5hXlM4hx?SGzW{l2-m8l4-m z4?X-#A7njVR|>mz=e16k=UnaCfjGT)7?6riKHu?&UQ}>9LLgYOpTPg6mFm+N+gQ1K z?O&XhT)y0?vYAsSpGR#^lVc{7bBmitJM6Zck>_&ueqWpIW}Ne(|HT3Fnfv%SvGsPu znb8H|a5qzH#x26t?{nO{q2acgWzSM-SP;1cBjp{PLw~3`3TjP8cw@kWWUwvZY7qtT z@h41!dDWGU)WjiPqkz3Q4lFh-NhWZT3~>YKAO7Y!GDSVyQYX-$o-}AJny6-oaV3G` zG0-IpxR;I`!-D@%!S5&tLmU!IV%xY2TBRC?;vkVI=>32@yLOM*jo5+;d}T`lRePb8 zcx}}KqyrjuV1qOw!8eS+Gl1wB4EP8KrqGakM9@6*q>%*a06@GNlwTDa;p(8*XQ4wu zG1x6pL_IVB3qNyk=1>aaN=LHsU6^AKA*OVsF`j)E4`R@vIyg>GGFAht+I0?yJuB&Ld_Cmvq~v~tlW@tEr_*kAk^{8-=`54P^HH|kXV{$us4kF|eW z0Jj{ZSGZ4pG4MgLo@E53DVRToCHOiod8_twzgNt#YzMUr;l3gp#bzQgm$p<9{_xsj@&_WGF~I6$<~w1 zsb{oB7Wj$Y*i9I}q@l$tZpT;eN(&-KkTr2Iok`#f6#V;JP1@d-;WF;A)I21&X1-Sa6U# zbYwpUbclusOS7wBkv}jX7BsZ-_Z#Nr(Ao*xX$+{#9+D(yfnF)p9xra{;esCpN|eXoU)RUcQM#s1u>i3?h`lygkNL zFwqJ_GGY(|az%q33Cf`;pmz!K8U;)sKup|7+3c@mIlLKJ)okL$$T!-UPUOjP(+w)T zJoeEP#&w>gJ5IknLJXQlvp4X^_7W|QaquuK$Ft&G)A~x@plX?X^3}hnA1hMvrJ0bw z`rk9}PHU#k9%w-PZml=I2u?EjeHmr@wH|uUU{?_Ee5LwYQ9x-||N|B_n;B&H)UP8gHTZ|odPZ~r@LT92G_3xx) z{XomiT0=00dj%eL6T@!tgs>z8kiXKpmh|f5*S7vfzd}3*h8wVa?>(%FEryHdJ;8vR zyWxu2vwzthBsLEqOHy}en^�*nQbz>iZ9Z?Pk9lrd_DKk6~d%!ALAy7^R|V;E8xk z>1rKXss&}n;$4Yhe?AKfqe59GoY7vsn87sFY19B3)lcZ^qH`4Ec`M3zhGYR}k8B-{hW0OV3P^ zL<25s@d0}rO9lbnR$k=eccB+}Pl<}w5uIm$Nl4jdlr$)g6h1sU`^}krRiW<$TnwuY zbJ&Fl8s%%LM)9t8_J8RByK2LD&p)SY>&hym3j>DZpBA^nWLo&$X*zsO0rdeFcpV1* znX7|>&C+tp$M9e~0)z$k@HP?3#oM!_BHGUl=Sb$@o@Y~ONPc;@_{}V=nw+nGS#`ZL z@BMVvZ`1SI>O+w^(!e{J?V-#cix{09<#YC6N4ho2&>Fz(M%r5l?|+m&?N(yfTb4uK z?Qb8JO9Eep zoirk^%5F?lW}(1_iJ&b1!D9kw00!}^8Hsh`)T;A=Y<~iCjf$tdFk=2Mz=P_7??j>! z7$m3%9j-x8_Mt(J2~Zy@*d(*kK1Db3ch-}YF}&`mW{qX-A$*3yk&Qwnz%ApneF%%s$)a7#+e!HbF5&eDU0u}7!HTQ7bKMp#Ji+}^M2tGhVk6+&JQ z%%CZLYtt=6*E|0>F8m(wef;{6L(BIY)9!gfVKIB(e=5Gawe8Ix)^>RD8+LFOc()p< zH)|*S4PrGn5cuWRjqhK6c%N+R;n6GP3-{$znr(VG-|)j6ojV`WIxn?3u{TT|`S`s@ zYC$n>?)S!+%9lCSEUY`36E(QN7%1hB{9dL&iLjjeeV@%93tgmln9aD$H2;upn>%dH zoE(96;ShGScg{Wd>74O%z30n~O{q2A9}Jul0}Ho6!N+lRE~!5)hUWh$GK~_-gn!6( zBDjOe3((&8$q9D=xZnqY~KQ1LJ!QP-%HtEO)%+hBZ zXKY*6gVdF>^)Jx2m6uAPbUHGSDo{977?ipklDnFes!O1)a2q0Sq9KJ?#1I;>NYQvU zGy5lSExmjd_YWCK<2WLHEX9MTXW;_?1QY4qAzU~vRgK;ms7qb-A3W6NcIHFirht2>H=3HKNiAO;kUAtkU088V3ny=_HQV8K|x<%pf_<-nD{ zZR=T^n5G<%3J#`9p6?@Q41pz*-K*GAR)Wa zuyoq%OO>C7@>VoC|2l-4UDWxM%n`~C12Akoi;aXJM2#|W za|W@XKgT>U)=@cImRk^t^J%I{s)%klSkUH&*%N6drSZb%r^Vw2ui+6G)W7n}O;mxg^gMBtDHboa->IEd8CR%2mai8icRb9SXakEua_|(18(n5i= z2FBS}Hyr9DZujI|+i@9sd3$4~I~(J5DaqyQKZvkBy)W5z;m+%9yRAFTq4F8J+Vu27+sl1Z% zRbxdfi0=OX)`)+a>%sq(wc%iHn0%bVuiau-tf z15VCqnx+bA5c*gTpQq&o{F>DV?cW zu|`}bk}0*)suMcXRpz1$eb=Yjqsz|i_~>(I24Jd@p8d#|U{y8xkpKj7_SKUZ4aEtg zG|RF`r!yDM37$NKvcAg(;KbAK)>!|T)=91rUXn^D=Ys_;8GLF7^qS%6=~4KQGRNy( z?R!8LC4g-kp>|{huy>~GWx3GVV*S(4HfRNROZzU{!8+GVzN6M?opGz%zw!WHKhNf| z{25NO3*Y^N9E)B3v1aSca(zSb+Fbdbp$}!HcOvA?HE71sZk4S4@ivRbG;(8j>55ZY zjG0bihVyS_*N0L26OIh|9;k1%&}&u)`he`jQT0wh=XHj>2Gwu4Rqab4f9xAd=Im?R z8OOhkbLs2Jtgo_fZu1y%Al|}V-S(7g%)AAWf&hXf4;xDehZS;H=(kM9J zSnyIHTkxR2a|t`-Rtz!9HSdfKOJp_Ski@soKPyQX+k3+2#p>G0QllzqE}z!5h9OY1*w)Z@PgJ8R$nt6uy6wHx*SPnXup>&*Z6ZdCQP|G2c6otV+9o*VBbUB1dF zHMnu$>u2_VTQ>a2@Z4-%E-Kq>TCd9DxaWV|sAd1z(){0XqpBDLd97FF zKk#2aA!OmUwRJ-r6v=^Eh?Kfu*)_@C*YCf@MN~vT&SzJt#`z^1w*m|Y3~T#<@Q?St z-HQ{eo)&&0T!}YK#@1f(-lM?-#9581sY$!ngJ!t^VioWo7A-8Zz&_(Q{z*M2hIa3N zFtYv2Mdeff^pPh22FxHOW9yRd^iH^qaZ%-fY=sT;?ZO)$PR3hyZ7Z9?P{}{jFVEmG z9e@!IeV^Gun(}jwXiHkx4ZS!l^@>%4-JRc(wDWAohT6u}pDMUE>b37SZ$P&GHQ7@o z?}nalJ--{e#km)Cv`rIxggVcHRi^Fqp1=KY6XuwAM8BZoOZ&w__>SA1;Q!UK!}b8# z`lnr4S^L-U!25s4!=1?ROG6WB|2FzA$1|2SnpsZLi9fF2VnNtzuRT)+*njzc3B{_z zKJFXAH;4wRl;}e(Q1T*h$2|kH4i094gBhJ+y=11(Sxt#j3Y+_Vg_U=;pH5V1nS)xF z7#7&tj^&j zYjm8~!qyXh>cY=LvBUV=C-PX0v7)d1F>`S{wFJo5u_#vG15>F54bsdpC~ZnEk_!xs z#-MGU`u|usq4?RSc z(p@0fb$=-5zsIraIv^-Rv-4X8G1`Gr8D=QgBb19KorYJWUmSH|yO(u23LI4|bZO=A z;4xA}YC%u~4-SicwwQ=kP)?v0P)!D zDbxGrL*mPK(4qK_^9Ec*r9m`Lu`rOmr9CZ(H=o_Bp+j{_lO#r#0BDsMa1%)vG#IhZ zvX!OQoM4f$X|%M5gTcKULzmjZd84?e1XwjPhR=s4ceo^m&8oezOS?n_rfps?us1LH z`VBf;CVB~N&r;I%NI)$c%%!|jU3OD1WJ3B+Xr6WdQtK`kcW4u6A<%I0+wa4`jE1pa zC;qN|Pi^>3z6vHp*xtv3d8(_f-@sU$T%SGOw(Ee`l}3q88v&gJB&(+}$0z^JJ&6wP zWEt{KxTw?5n|DyhbwkArpfJx>Z{H*SKqd0#pg}}AqIb^wUP|k-Bihuc*QFN2mZIY% zUYObI zvjliMmUxHvp=FKH-Qv&Z-lzp1|EL3itOF>svq1b{>tYma?!frOx?`00QIw#Bt0DIgE)f7=5qh9d*sh$M z3dr)igZsLQAm^zB13Cb#P(-v1r#iLG&B;NWRwAGF8fzaC~0eMlV8{f1HzD;>$;T z%J28L?+f^8)ZF-~FV4AfVY^o+fNT4M3#dw)dofT;f3xl9h&6^$8RV=g{sRrr!~ms> z#yJQNp?~J;@q3lYE=x%tH$nGGe!muDh<*}_ZP^Y3R$2TF3OWuV3{0FBkpvr4&K9ve zf-UQ_$)U)U5I9Q&SEd2uxqfxji4&6=_D&IyhzP-WJs~%J5dpvnxyX&nkxI{rDm{^` z`jJYkVI{7dL`ozJ=JFZVaIWA;!B=je_9$KZC@XOEHC}+NhDPOVxNdy(94rO~_5)U_ zaUMk5WQJYS#5UGI_IUw5XqfJ#nwnd*-m=j$mhBI}n!Uj7mm1m!JRYNxp}Wr4^JP$J z;F#-uF|Y`A`#!_Hch-%5=OOv#UsX*(5jwsmmw&2SXfbNz{zW;L$(}zV!fXJLApC`7 z*0{J`Y=!KDsmr=?Y8L*PZZ1*@_HjYYY9MDUT%Bq)REVg3iaewtzhSkR8JOe)WVM_7 z`%Y^X400Z;o#$fs)j#o(9QJ+ZRYMfB{=sJ14QIiFjZuhW62yiMG6k?(5N%j62onrg zhYn}@4j=zuzl}y2&_Q>p4z;d{<{8O7HOYT4;A_~61t@?4M)d&>9MBCNF#{hHSuF#Y zaTx#s%^a(Px{3A$=#;M{q#h~F%Qn$8K6yJB6>Lf{#6hfyz)v_%RTAVn32ZjYX-u&6 zCP7)yDT^4eSRBtW8s;1$4g7`iy_9aOUHa*L3z!;2snp90O)f_S%`6 zB`R{C3OZL0RcM48;EgilAG=eRf25YfV&!#EPTrG$S#P!yy7vj{P zUt&ua1Uy3lQfFB$4qqmt08i1URcq8AVA$uW2#2QEH>O_SI(&^kS#(FM=&nPNi&oJ$ zv~ey9P!uTm7{dw@XM2JIFjFj1nBq9h>1@hbA1aKg03)6(iPS2Ib|{GrDT&W2No*=f zW@MEN;o)|Dk>@*$DzJ#p07Pb1X;#yJsxY~SrR0-u3bfw5IxJ;Q-Fi`_5|bKa0vj2N z$Xtb2Yn9bHl+}flHDr}FHI=nYm9=G+mArXlKXKM%_08v5c-3Lqhoh6R@o(9*%f{#&>KM>@49J&=7$d)ic~(1wl*=~5$1sTfrgyir z8;Z3`A4+lz$6d8qjIM*Rvz>1Ej6K;&2=rE0bQH3jJV3_eCiv`~N+WY7y)sNR4b3l-!{K@?*^y{IbH zuXSaiHE%=NO|o*Si*c2wnt!g==hJ}Uo$y{!qP*XM#oCJLF6&O$8^d|ug=x|=) zvcaVGqmU|~| z7W0L5YKB#OJK6eUTyf+SDjnC_;DET8#M+OqAEB^S66zhu;9gAoVF0kw4Vf*a06+TF>{*YAq8H*?!?5#+y zc+?VQuhDnctLME#g=A>|glA2Aa!ses<*d$W-bMZ$%n~lGR_FuIy@?$x zKYUX;eW7aj#-LZo;6m8YCcK=Y<5zI`B ztrrj(S{3ZAH260f=P?Z>GR&5{; zA>HWg#wgY>S@To6PtF8Is~u!Gj9%U<2k{ouFxq0~b)>r|Hj_O>RpZm`I3wY4+vHTi57)NIxMd zeYT?tk6>!1_A#JO6vP;F6$M~jqQW%+`g*A6o{D2tFI{RBvj)hBb{yCe2T>& zhv%!n9(9F?AT8qwm?%9p@+$U3EUAN-n{dFN%LSi%5+Jk;ox-!4K z3&&*UArO)r=iN#)U8UY%rGDGOj#rN$>d{};L?f18&V1=a>M&>;{dka3o4PL=Y>x)- zVA-hIU<)ke<8S0Q0$7U(9m1Ioe%l<}N8U$6_In8Sv#|ezx%Yl+stvewLpqR#pwbOR z=}Hqq550&QLr9h!OEMNNm;y+-I#Np= zUEv$4ff0Po1fIqdd(F`ora^&#ND-67KI4qI_khG-=qpSZ@4#jbfH`B1m8+s8B3(Tbmo|3|M>DK6Zq=^&}vD9$7q2&rqV z8L70%|8HKY|K`~K-@H=)tFY65_KB*0`+sAncO(xU{R@D$oH+&-_^)0m>?z36|DRr| z|2cN*O%8+4^xgETzn6Xp_}*cz#JjeAuJr0N;QXyCwc!G{W5N!f`tLmi&HCAbX?e>JmyirUn%{fi~F%bChZ;luMROA3?b+Wphg~ zp$i!T?^>*Ts9cg`Hb3@w$o!Q6?~6&_M#-W$5m)NJb8KHac19)L-0Td8Y5qQahxO~ubRu#A%{Nn?dcZ?a9MJ|@#IVNwMz`yc z&~_=^GClZR(Bzd}ZkTSdvtUyvN`Gdr+4L-T_1ctzZi)s=vir*umAI{?f17o-&wF@yKC?E zto47K-kHAw82B<~xPGWVtj+%4uHc6FJ~m@o=cBCtrl|6rjSbGtki?-0RMXnF=}_Lo z9npJl-|nn5*1VP8e{ZLDM&PxpN!qWi{i4#q91=1`0$BWo>s62w#|tC#VJyw_i1Z)= zNX85U=N@p8m9>!p=&-?N9ay@|%(O7jl#HLmVmcv!RL}??;@6Z3Dy}98VoJp~vA}YJ z(@A_Tod7N*te!lUgjm7QmVgY%!SP{=nBA906gO?MXr}}Zsv4)zRdpdOF=0WHI&du$ zupkGpas!C~F^>Ve>emQubX7R8C$0r~wvlNLxSUjV_HYIQ%0G!O#E^WM>8Y(}vgH*u z(|Ef+`$7ZL{#aRJ{9c4$`_5Riq5JMfE!?N^t#yYUkx8=yvkLfV7N*KcX*PyuuthAe znb$MA8QkJVZd@`f zK=&%V%}2W3S>eJr2$I@Ozc&J@j@WEE{3wV+vNx0k6uEV230A<*xm7?%{Y=>B1H8L!@Eao&>IY-x6QKS~|t~L`R*7Q-YU@oYh!3 z$k9m$R3z@dI<^(;rvxr+b%+izDQXCGpqsaFH=z4BDzngm(6OHv1WI=v{CePdQ74=I zz-ft-{v<26%SSIX{mS69^dEMQRAH!-g($!cgXp?5V-9m@;rDW#KMIEj*uwP6Zg=lqQ;E_p-l4xqzxKR8=vIOz@b9=)MZ`nqusuDcyYWPl{6 zY&P}mA7-1NOQoiXPwtP5OilEQ>r|7dWwRs^}mGv*g4}Y0x|1Py@uq2eCQWG!sk_OY7!_b16$zlWSE{PWR zY&T+Odk-6`U$N>I#s2e;yR_D;3*iFM9DU9&uDX?A^GJ5kSf%tpQPP2QEI58p2IB8R zMlH3c=hOl&Snk=CRbsbN zS|{eUO4~mW#SPHMm9-{Dj&xYy;Q7S|O51%Se33VzE2XAtU?xQ@3RFO5e+Y?eycC+E z%Okb*YkaEfLP1gBlGUwjjmh(!8~Id_6zF%-0cKIA_li4wlVl~x_(2i71(MKm*_HMn zfmP$4y`#gz=@7%%G1b^_s4}WHg_JDI#tY4hc3=V-las6De?xa~)_{{s?wn{73* z-L}cLj@^862zeEDCKg{QC%vvt;i|QaWZ(SmA@*wlCfc-yaB1?C`lVB6g3 zNU_|}-kW=Ufmg6~SoHpJuT467ZOvzij$S3AegR;Y*3g62=n8cZjf0#fk$%r#-M)%> zJ9_=*kL!FG(jf)+Rqv34@W@ZY$iA!olLX{H_z>pJq$`CH(rhuTB3bn+s;e;SbPwu> zmA__9lJvP`Mrbmy*JFhqH4V6ef~J@%rkGi!l)9%FS^2*IokCDdE&FlZ?g(10#^Z8# z$~8)A(7{w!nwZsAs>A`x66dnN4F!KB)(4jgNlHGp8AF8oXyd4brm2R_sF)(EOf}LW zMn9oQOtJYgxrn;JL8WkQFxVJcZjyI_y1)bhIZjV2X-T`qPAl6=V~D0#;L`89q?gl> z16Vj+F|EiUjg3W)VKN@$GMZd6nqx9riZWVTGTPV~&wP=6jC8QOAf-1w-yv-ri|lX7 z9Asw>ZDkINX1&8@jk#ovwrfHS*Ol}cf;2B*|DW?zX1+t}Q zOr^hL(GSGtit^LjZF2T~6oqc5zo%!&C}oVQBO7sfFN^Y&pXI6AX7D}Bk`faWiOt|q zvVL6lIG2=Gq?j=+nt}V6hZid_+s@;|f%1=f9{wo2JXdPqkl_!TUax3oWkMY6FuV}!hQ7vv*4!e1%F zj=wOmHphcM?X^oGHMDR>G=oh*s$szw)cO3Gs0laZCwl(pHN?a)8K*8V4Aa(f;t57?=XbPFl2xUET$uBnFtLG^fgORjSlbN@(33bx!*6( zthj7xF;7B?-dlX@w{MB@$Nbv!NG%LV2LSF{lR7aB#FLP`ou*&{a-IZABcOwLFoy}z z0zf`tkdBKtx@>QC+ZKK=7S&2CsZ)Z#RWG(6LMIszGYo1H12@Nmhlrqb0y@GCRLw(d zSj1b_4Pn-B8 z;sx1+JRSY={Uw#L9)eG_WNn`n%(OtN8Azw|0_JqEmpZfu3o*um)0xQEOtAABf_J2} zAqYAZ-*Zi`Oz}W85(S$XhVuKW7DS7E(~uL)8aCGr>H4hZ9kF-#Od3 zb}vQN=qc7XRs0S%E&FF$UV>QO{@Tp1G5JSoYp+d|@kHX4jn^l_WkvkzmW%&or->5^ z0gjlb>iSQVA7DLd>f;``i_zH~_X1__ceNO{Fa)7jWuK-$7+=b{rLWkA6>J04xhZ3A zV()y=um96>FZrXwq_|)k2GELmpm^rtbMZ&(`UOn?^5k`?H^1&5KJ)N(TE>RnBf$N# z7s`rHUc*i_S;&P6`~YT0Kg(v=)YqpYfAv2|ATwpmj)%|i!)&vLISA=L4Ts{hWDOq6 zUwAwWM~*QONgV!al6T7E6DoPIB`oUH`9>Y?g~l5tje4JuU-6B)e;V-;O=bp778jbV z44P&MNA;IP3$XUr%a6V1eXan&PJ9wQeO9@~%*3NX0bFkF6oB2>2e`cPq%=v{s}#$q zc;Xvs)L1aY0MCz2J{~cV2dO7 zS5EI?nua$6n%*zG{k3WFCt5|=(DS_9PF^$A0Xj)~b_vkR#-sPJdVlhj<5LZOlhCvP z45d`gQx;Yy2fbK|zQly`=*A}LS#&a7-9ji$0IPYy2Dos2(u?(5{8j-c+F`W^)tgjEv6uj==s7to=?5-h%i8*QSPl7rrZsI zU?96V0<#Q=1W!LehqwYjoh&8iQiGd#{+rBKm2?5UefDN}wbeLd6-nY(32})oLfTJW1^w+%prgk5*}~y{{?Lc)3OHZQ;eJ zMV`0th|<--ldeTFM|JgUt4fUi^%m+2SPaBC*G->Fi*Bv_*IU@9kmmVv!;KO1q{#jH z@s7UA;Q!rQSowJOai8WUdvU(%R#co1ErlW=UT|s-S9|yI-MXc^|LUP`=1vUUE3WeT z*F){UTqc*kbpI;trSCwAuX5aUZSRrzI@L$o0Ru<+*vZ-Y3upf$Yn2hC_k4+e=@G}( zN>z=wG4@TR{_cNdt(Lz%U+b25q`XnLo{sHq;qBb~XV$9id((BG*thmvqqHj3KHq7c zhdQ7$t4ri`VCZYnD-S}uB|}y;dV~VZPwMWlJ=gmbs~@cQD^_-?(BM6TF2&m)*X;nG z7wUcv8U9}R`8FzjddOr~Bxqw~ccXISoxSd=_LHO6m4A*=vz+CgJpwomz2u8t{q@0( zs;0wQAXcJAY^on_PFVf!MC(ts?y9|yfSs#Sn`s4R>U;j?uKxa#ct2ljB)BoCW$MCB zbLLp2?zayyN_i?7%CFXtTeC%;*+U%LL*HU2_G+}$?HEJTTZ?h~OP5rtH#}nJm_2`= zaD1ZwZm;g{I-b(q?GI94Vtsf&z-)eCEO7MEK>hA|lW_K*Rc=J*8y>=w-u)GV%+YPE z&-BPx7@!{eGxy}+-`%N^0J));B^{Z2e}ep8wJKNk=Cy5YaX+`M&P)7#+x6M)${&t3 zs|jBp^O%^bjQ=4JJ@Y;3y4;81UCeO#eC%g1Dnr zy1-tw?$EW=%O7)g_rc9z*=v+bpYCj*Dr)Aso5!t$%OJSaqWxTpYzm@DhBfG(U9XXw z=9%olD)U8!Y5%x#X4mz={+?%2>ubK;;cj&G2eaQoKQdiEO1E155P0b)D8<3R^owk= z_47b(=WdPTSX0N8m9wuz-mR1z7|D+8%1!$!N?n*+I7YnT4+n@YINbrkPhBI225zTOaRTOFi0KE-{6>r@SAQ zqwMb~GF4D%xB<~cKu2%>WPi}($s2v_2gIF4Ee$wRTmdzlr__?mJPSXAvMfOa=h+_- zRf)B=H~v{}*A9{ZGNE=Y9S7=}UlbqR%MSN7#e5p3sMNTl{d;A_mlvSC@d&}7UXbV+ zY_}FWDeHo2vMWlCqSMiC7qQYIIx7Bpe}zzXSQkj#3ErtQm`jmY1xfeCKnRczg6Hud zsjqN~T8)F6m-3je`>u@EJapu-^eigU1|*y}4AEXQ-LF_XuGlA(;}F;`4al-Kj2VF# zN3@Gh(18-;3`lUM8GjV}wPrJmdW>Wy?T1U2$}Z2wHJc&>2%UPHOt2}UQu>!mw^#=~ z)2pUju#aOUb<~t{Vo(n4*PDE(RR+fMP`eAGHkO>jdkEy*_YYW4(o~^&4(BsvF}}Va z%!%{a;azf=U|(z8&^H`&j>%$&=ywK zexRaSX`VbVRRowm_yTkKhp&5vV_StJsuQX!VvCB)tPteg`1I!7vsByKk%8LA+BW=eF52~)2p4z8~@`$lfAQhwU6+}I%Jzm88;j^ji7pB#{U=NPJd7YjYk zNRsGglO={30>KPEiQTnMg|B?nV`ClSmk7z?02!2?d~)^sYp~*{Ym_Ke5bCE3757ym zODC{WihQC|vo4e}m}r3Z!kbGmHQ2}CW|E<0oL~*Zarc9NzRL204{Z^71<@qr%>}F1 zE$zrfCy>Md*TzzvWr~WqH7z=fq4vIRK;`9|OQDt*Gzv$M#FepJCvBKvg-}+ky|ctJ zoT_J0jl_Kmi2KEX)<5Gz1s6m~%?(>=GWc>l`?o)|?UmowIJJ3W%^el&(s^)Qy@75U z=rPZM>PQ|z#j-%bl@|P}2lddgga9d`M33TtdvxN-<+b;AmzCa!M!&3;lfHB%&T!-X z@^wYziU>6ZIxw`I8zU=vM-rkoS$_YXL41I4BSqki%m?E$Kho;wKP*2|eEsp$-^~Z# zyN8c*mj|DIAG(cxX-Sg7Xw%D)1#S#wKfl52?I+{Hj_EyJ%kFHjrT-SbQZ<*Vxclu& z*MYJkbM8Ujen`*nAlHO|_`X@2y`}ioo$#`|-*vz5?KsYeY#n;7r0)PTyk+P!XlXVk ziwaWEs2n}E>U?dD8ap7OJLz*B(~H4w3N|qWs+s(CEMMMD*+l!=ysp};y2h9rauRQb z88c-6cKZ37B*Z4e8nib#`1c$EHg5!$gLsEUf~++>&L$ggCF6@chMCC+&)PkVjzKq( zUQ}OuHBUZ8!^{aMS7;e&>e?v3PEtN=zx-48x=!?{uruy%%14EBpL{}3FOaRY(BGJP zhZhpYWR1p$lR|%4g@BLCIwz}&khbM0%52if7z#-g;9wKy#7?-rVJ+;4JRf7?mP~ld z)zwfQH{h=^JS=iOAB;!N$|P;2v^i@gJ~iNLN~O#nyVr#btwC0bnz~q$s(GutMS3^j zQ9GnG?-?~dH~mu4q}#seH_-Hot;7&TD`*YX)6tGt<8hcB#}v+ZrIVrDWemQT#={C2 z7u?~|K+S{cl!fE%W68DJY3|89$ttq$sc}CXH`sDvsE9gZlXbKukslCou|wAIV6rA9|hSG=W8) zhiBZoi>&*dH6EQ3=0rM7O}S!j%;)Cbca|<{L0H40b!#(rIrP6Zc}vN9r@`c~dG*h% zxV^`gC;Zf&n`bLSL%V3C)(_|%YzC^zBi2{N>3o)RZNAI#oG@#oNmF5iuH}Q9i5}WU z(-``^LXmlGp_g2EV^>1VrU-k8k3Ovs=7wLCh?^(X4b6DGSPOb~e>?y^| z@l>?O+0|;)1^^w6%Y0;GMpY;|ACuA=ePf4S+WM@t?PKZ7?ZRCWGF|anWmEA=JDMCL z#9c$%hQ^ll>b~=|1<8e->_NJ98!&p0eFh+AI0)X&=n(^1$Q|WudKu8nX9^S9r6^RamNeAw9qyCp2riQqfw zCOASswbNle!>CCj^z#~jv>UpMg`DFEB&rL1X5<}L5TLD{e@{eIyTPbcNM7^pCAK`G zNbN5qpc?qA!xOH)XoDSDoZ#q_vgCNKakbxikK4Y2*L%@pGfE+;M> zHN!wN)*v^JSbrzMT+{^!L|&)^@*P{X$&)Pt1pEntv^7)(9kxk?5{dkcR}pq3coYLN zkA?9OFS0p-Z1RJ6J3DeRDoMY_$RC|LafdIZ=92@IUk1s`@@-=PL3qpwJO&Y`1#AcL zk!nxI-Mk|T2*pKX!cn~SRGE8m!*odL9L(1Z*;o}i$At9JVOQ3I*8p%n4AO;pB?v3P zS_7{VP_9fwJQmvHmLAquJHmf&#IHd-K<6;%;YjNpmzG3x|A&hXj6n=Q4~x;F^8-U~ z!0H6RruBB^wF$fnF4sA^gNB?Z3b^7)lX%oH7BYlERS!dW;DwD92xoaShmjS--tVz+ zG9Gb>iTuvwRSpGDbCB|KcRmC)#Et(1U^-^Mwgj1BdtwfYng<~LnUG6s&p8QN*fLGW)At6}F zYOC1bOVg&*qP#JI)i*ZV$O{mq*dFEnGL4aPT?~{sSCltcQG5FRGfq?f8pLuFY zH7RDrWw(6mO*`g;1nhL^Qhr>HJG4LQR;X()i&NGL- zKaOb`>zd$eKc`xMQ+0o8W&Vz4`$hA@+J(3?+Nn2E_C5X`H;s+CYa7oy%&hyRcZ&8r zE-mfj<+L!!NrLtsNoRNMG#8J47MM&U3)zz$)6 zy@vS8LSOiR`Z+l=2_W>ahQ{&eA0(cwHP?9?J<34(@&5mxu$Y@}NRSL%@Xc_SDnVXB z^H2h9aI`O`rl0_>8>Sn5A$({@ohbVhwM%rw2_yG7h}kvt8WXXLjcz-PJpBfxw~JOD zhq`i*Qy4*@=?$O*%y@Y8{q88rB23fy6+qD#{ytUNtEi4`0NT3Yku@}jrEwW(7b&CB z;Q=3W^u>qBw|MR9D&#q%asB&HR}AVOLisEPU`2!xS4TIt)5>;lB#ZPnfXE%R+cB5a zxVL(wvLZMnl+=rlynZzofSh1uD1Al_5bYoo!6|~a!A0a<705JkbZP?C<$v`~&^ct* zn{`}{ncf&(tT?gqj7dt2#FGcR3)M?pPT|gQ{wM~SoEfo4&?y(@p>8yraEFJFe8N#( zggaJR(RVO#jyfu*)tV3g;LYl!$?7m37mc^$HLa0KIvh}0E}|@VfXErbr$IZ%vVXCfv6|5%zgw=|hWM54Z8csVUJpW9vTp1oCP z21faIxBMNqMXj6R1))XV{r%OhqQzQmuXY5#DvUP7to*ZQe@7*oqbz^7`EHl)U;7KH z6TvvEE{L{*+KK9?^nNsBWA!kWSYVA%`lq z#IxT_XQm{IsYg$~YP#QP!nN;}+m4zjdL8-=i8qa`tMDC^2lqC!kzxWcl#xxriIr5CnK#(qoL*-O3_ zi(LV>RiCR@3lgUd7nns|aW8T-A5>E6mji>*_ktH$^|Nn-mTUvbCstQ%x9DDf7gMB{ z-qn}34J{B8S4+B<434HJd_I23X}SO9%Jm59D2P0C^VP`ZZ}UerCThMd2fw*dKc5`k zeZ=V4@zx2uW?DIX8{5>96{0=WCqN^A;NRQN6My^@%)h;n@X3g{AdozVGR>*09N2VU40rQcWuJ`VEWJhZ)UkK^OTu z-mRWsUT41yoSwJMe&HPnH2r89T+$pqJyzaX>iqrk%WKL8?NFBB@X74HM1vZ;gFnw4nNjUYI2G#I9Vn(f!S;`T6!cL1`1P>klDU5!5Iz#Iy-M?Pu~2_CQ^-LtX8U*;oRxFD01h~w z8|cz$iqxGUR(;q?dng%nH_1*?__apQZSTj5FuLw~`CLY@qMx~hZ>G?EhUdhHRfc18 zc^4|Mo<3J3>z_L>dH7jvm2CK+-jA-Zs(-zO)tP7Pf+w|lrGr|wsjp~TKcHe-Q;XHc zf7?W4QvuEVZV;J{kDjSw`dwP5jebX9&~(+^UIqBJeA6)01d+>?2)x?>l_Roh5fY~V zjLeFJwEResh*Y#S&vNMaI8z)s#!ty|p@|*7bmmfJ{1e(PU2`YP(h zKJ}x5+X_ z4O12&7b8DF1V-+ag!zvIS6Ng`Mo#MW+zRb@cDyoXEXhZT2)5EFiyJ$yAbH`#`JS@4 zf!Mr%s+c3)^8C4Tp*nA_=f(2sSwIdH5*5;| zH;+q(V2$7^ zs~&{v2R7cHVSA?h4eb$+h02Y4d9~T-&AKm`D&NV=*MLfE0&zWaxp^9`#7^`pKSJI+ z%eK&{&rafX8C@e3@!*vk?EZ|!&yuT+uY+49+KfNMoNM3Ui;@mZTgxAMCm zJ`}Pp_Mprov)7G61oo!f$pwVA#Z2c|8*i7&P(R2DSC2tUgUgP*h|9WB<+3q!Uw7}& z7{C8sP~yz8j|7F1c6Maqs(0(qK%Z0fCAfn=PrdPv? zmZ7h^t{Oo%{R2)z*+LQ8<$6V^KLGps1JWHREny-n*fr)73a->CD!W z{arQx;;?4!p-*gzQOAZV4*}8l{WyKLO9K_vB9|#`>nVR&&(<#3H*2V~$g0&;r@@k* zJy}|`LFB11Yt8Mi?ZQnrC>X?neUV*Z={W2YR7`KDR1rTwUgg<|%bV|RnmqGDYe0Ma zef#t8fV~&2bWI&yhc)6FssF6IqpuMfjW@YshZ>s8vw}!+l2h2}8sheeu)@(>^CGtD zpNce2=DqRg4a7R`t3k#~HN+1Y_G|naNq+qI_y|*|% zGVhdBK_f*{rJofSI(-6j@21rs{&zX!J&_wsn9-6}_R;2{JGNO>#t-*EX|qZ^mA{F5L-zLw8R z+Q)^Q#mjGPWEZhB`?RuO#;Mvkz|Q-}$%$q7AufIBM+d7bXU{HJ0eVM1j2zHaTelpLCAy=W!+DK~7tdw+ez z;6WLnmDFy*Lt}xJx7V6IC3??{t8a2^&&GinHj_4H0OpU}qT6PI7BMoIx^j=B)$*?% zw!a>39dtU-`QzD@xOB^Ri2Z$*mbt+%X<5CchxI=^8#2?r6nWYe6`**$&dW?J&-ons z`KEc}B#ttOU&|FD$pS1FV3NSKG!5rC`MxJj_JY0=lLS>=-71?JIbq&%m);ooAw}CJ z!vCE0cb!L+$Oqm=0c-4TanR)e&;Ev1|8wD3g%e_*&om!GyqiAsj<=6$CVJkE0JpjoBWp5+iOT)kbwCq^6dj}SoS;-@LJweQJli|iN+bAbsW)o5HJ zCzdgNaNMou#TbuSuXUhy2~@R#sqB;>M~S_-r#BMbw_g0@DZQi3+!k#}cegN$`WAmk zAy~K6E5bu~WEpyFok0usJ@EB3Ro`dF)FkPFpkHqI81uDF>-d<*L7x=KC715~Eqt_NL^<>Yy!AofhD_Nt4>5asx5_X> zQH?_rpIz(LMH(Q3i@4K8BdKb~Kl*<_YR-rat#_NR|1fsxJyyG21l5ub$psjGU;oha z7a-AZF5*5Txxa^u!w=?2MGU!(9>DM-Qn}a($^^8er0ZG)*|k zdkZehP6g1QTRXJl7>(Oo@H~*Yi;%eIVQm{@^Fo<|p)OQ!ufD>weK#(qzUb6`vScBTGByQY$$8;MDa{Yi5J++ z=Je}KuzgL69U#q)2F_Inzd-=*Y}oeh!p#V2U1Q2y5hnvi?QTsSYqSt*Oc4dYFPa&< zx!^^BTx&R4QH>oGUD57)`M`>$YIu&W5_Ivv>!Q9AF#lieG!rcNHX_Z|#@@d7t!c|! z0C6OD?d>>XSp3OIo?BTjQ95Y()jP4$#d2Or4qDJP9B3#e+)oI&SV+OO;ncy~yfn2U zKdguhP*1T@PjLe9pX+`58a!+q^L9IsoVze6aeP#34?f3F;-=#mkfo9FiW}+hGnpFH zaO|0HDN^4zhTK^MOB#scl8S=^)ZU-Tb0KNK0l!4jM7`et2q{W7ZGa;1IR?)nnw(=Z zXjfyeJv%1u1@+y%ZHcs>|5&Hmck9NhRRr*kT*jQ$Zy#`X(ch?$Vk;dg2K4L%ROn1mXiJkzd~ z@8b0Cs{~XLPzHzro`M4`p72}30dUM&*aFB34)A!>_vYew{QIsG>!yCQ(yX<1Y}WpB zuSYvRQI1YHnw}6VQf+f0L9AR-_U@Q?ey)ZZ|0x#|z>NZMNdfe--HTkfT_1Aa zSa6zX{Ub_=My1cU%G1JhRT>7If}EUZ&waNqY;{j9dD!hLMbYs70C0nd81ZMUIz?E1 zpo>ED@Xn>%$+kA<@={$_1golQD86Su-gvD9Sbju$F&Z%T@rLAEj3)S(JJjnu(?0>~ z3O^@~NpoT()gaRNV;%uGDVHKiHS*&CY?Aw7e$&~M14L39gx{7n(eb3st>j=RqsY6} z^^CsLpnG+&FSX#-``b>4vilMfV$d_36d%sG>$S1pxgT;wKlALEri_u?niL$qht4@| zi*<;V`V3eA*&d(#^w5w-5QxUZK&>U*<1)dujQb{iyfD?WX?w~k0eZ0WiVKjSiKJ@Fi zF-P?32|?q}rkDwyXQ(1JRqgV$<<%Lhs2OYMv`(UDFwN7_UrzMX@v|qt(&CN=m*xdC zx)p{9pPoqt*xP!F*;^52n;~gtm%ii>XI+A4&r`fz6K5|J&bp3!Uu>SeI5&G~bJp$K ztUL6o$KP4c19KkrvtveHVs>8EIlo{psjrvrm(Ku<|2b(ldGhG(^D+`A#XABz z7y+8|0qfAD8gxOEluvCA^b^)6hElg9OQhek<|kS6Q4_j-uFcI~+ngtTn@@uJlK;*p zA6Out^G(rNNV&R@8nr+RUf`xteA5#bG71;SD8Tc;s}goIt`&3i1BXxGrR~RtwKhdXl%c=|Tx+lh3k2xCweBsbL>7Ic?VC?(`!~t>*7owgGs}%r9yO9An2x1+b zWq#W!dL^2vTH2^5_a*G^%YeZ88J)d0e-_!3MhOOhEtu5sEwCmlS)~Q+vq0_$NcLEu z8ZLk@xsmmW$;WIU2iwfs{uo{g4PGd02zhm|Xy~ZF^0C;OBjKkG^mi{>c1ii;D9z7P z0C1`+AWe8-BmOj9t^V+btJF9qRc07?mk4$5rTVvkEYzvwI}`_2axe`hIn~1ThQqQA zR>$fiFX;MR%*lM5urHFMAM6W@3<9^a1OE=}aZC-tD7F?uF0d?7Wd`!P#&by&iO zogv=4pX(7vf?cy|`f?sN-~rW`?6}SZi7=XFXjA~Z(5r=StAx7Qyp>_Hbb;zwy=hb* zo*mN*GG)Suipe_g6y*gl?}zbbQ*=0~32-na5TwZl>$y-IYCr@w`H~wf14oTcei&L^ z1r`_c>!-@)OKBy+6TebpNE9(P$d1MrLd%b4^69d7Cb%EX%wG91;6u3cB4NcvW8*9Gyva5A z_Q%HG-v`sr9LRewFdSq>qRX^H@Cxhl{RPU-j{_Ii|F6A;SLzD%hd*A2P+vC03#Qg$QgA>j~lkIG7?_>jrk>*&1!J;8M@fkI6Kzf_!RZoJ8TBZdJErGJ3b2DYdu+M zJLsWY%>+;hWe(4Fc;3P*h4lstlQ#}tj{XH< zCta6f-@GEI$gBs=r879RIY#j$vGj~X3N!20l!#};W8=e(-(~4wkhYd zCy3#vv`5yQP*HkIEpjn!mAQB9)v{@Ys zKP8Z~JAKlSyE!JDlWVsfeWc{ii1)$E(xKrpWQo6##pG!``wi}Td9sUMME`d6t-6K- zvNX9PV_yTAULE`jgQ6P}W_!MlSvu^9@S)4s`JX9O-;Uc+swuxbZ2jE#98@*^5)}Sbw0TniO(wA<%!qMJ`)E!7M?;O$w#2)kg1W#386WPQ84H|9V*+cA0$-QWuv0j^RsoM8n=zI!#zB>8*&*A;24Q)p{i;DTP zs7>##-4P2MRh0-h?)TMAPG$<@`8l*l#%|+@>1SvUdKT<17u*n6vY|77JN|F%eCQva z=(ej*!pA=+-v4%p)2VM5^EJ+@<@^fCUlK68xA4;7`-|nFw{6@N)b95^&XZz;tGDHa z7Ty?e4L8ct|M`*&kuXGi-VbpS zSAW;gYJgqNg`&CEYBh|;IDQg%BHZ|^DKqtX{FlL=vh zX;ah@X7j+qd~DQzc)sIs2i-#$F@mgAe692@^Q^wPBkWquYi>jc-ZB2O5MMGX*#3>j zVf(N9M%fl(X1VFX338GqP9nEg12dv5Mja;IW#CT97mI}}$sCIoBU>v8>o%!B@8Ipn zTS4*IbUArBr9R31mQs4p<&S99_MHrSoL{ypuV}8+f2+2#;NGO?<(-y;>>rC}%;X8r zx+EkQQi#q?50sI6v)*gF{`lrgaJurGyWNTG$3@+SM>Mna?7I*PVTr14DiGV29)_IG zcuf_bM9hF?$FbO;-NU#}rBfBXl_g#FNAyQ)PkEQ^yWt%_r=lkRrfapEf{qA<`qn$pp-a20_Hw+if z;8xaLRf8F2PAEL{w<$ew*bkBa`)$qolScy8#IGPPYaT%N* zu~rPlbBzz}wU%sjDimVq+m8Ctk|Mt3MvY_f35KvbR8~yW493b4Q#`EJOQgC*l%p;% zQ}vse5Z#OIV$W^J5@$mlewL3kzcg4QcdE`6@g2y=42hZi{eezocs{w63rlepoO)ZL z*|E%Fy4@VenzI@^ma=GNG>%P=v5^s8C4AQ)ghE0y%>-9tC?Z3lP>0NFX`hx(6aR+P zm#XFm2_(zob?O*RxS3Qv%S?|6;1!l+C9kl$_1QZQNi3jh#UE6#FCQ|T0FrF|k?J*;jE?0&#R{QufMC)1 z<*Q2%Z?`U|IZE2R7-Aa!qXCjn;e!-WVEQ8KsKgXG$zL_rLQ%YI@L3C~JtDE`-s+T5 zGOpq}AMe3m4t3}?7yRecYq6bn#Nh}}5qBn4rK4+&5Y3Z+nKC#k9aQHsZ+L zk<{q6X~F82bX@O9Y6GnU`I$}D8W%!!6&yc~y1peSSN17=^u;&!vlau{gfL0mEYf5P zvX9J64H`2SvBa2R(;I*?Dee+&ie{K~&fNR%i{+#B+lRQJ(r8>lhxDbjsN+rlg|RpB zhB}P@zGpKt7>s>q?EAj&!`MoM$eOI#MIl*dGb16DN|AkEYJ{j%!&oC*NLd;Y5>g?Q z=APerp6A@>Ip_HY=FBc=lA2jrR9zV*4wV!Y%dVuNc_(xO6hd=1z{N zX28OXW{>Fe34AbOS!j((Mr?>fh<5de7&{a1ZfMQFk=gx;*AXyU#Bs#bEep?SKGTQO z{w2`#nfA9Zno*OFF49jlr$^_npive^`xH%ohs6MHZyJly6eCE5V?37njI+Q^MDRG| z&0P06$d@}Oq=fd`%h|#uct@sh$ zCIF!7Uz)@`K()(C(-cE&q48Rk2aSle^N%~<0S6qMm_4=$por&wzurGFYEEtpTKcO zf%CR!UUg6zCPa+SJFnXNk(|%dYM)okD}-f*is`c?FVy(nWyqdWUv1fB z4XpFfBTDm3_x)0vK6|z%GS4eOq9!WvmfOkluzt=~l(RwpDzLuhENC?nx>o376*amV zHB%F~C?DfJxFp1_QQ;rSRvUlhP7tn*lD`n9T-)k=CQ67$>hMDFzhyQjg{#|VpNfyvLA!xr9#k}o0yWKE@&J#uJb@|)t`2tEeCF*a=Gn8(r*Wc3r+PQgO z&l9YxN}#O|`ScekU8}nr^Yv~(NccgfekWn4t}bb#{Cde(*@f=cUo7=XC*4a0W_7#mGh<~L&G8u7q{MY8QYM6u+ECsu12;W ztCu%q@kc5{7xI+>s*27uYWlY~5>3OeR2$?so7ftjJ(^qsIJ(?)AlnZT;nvzwOXsZp zGYb{foH0Jn0#&p7J^9Cz6PwOUtYeiD(3Cg|@lERo|N{nY5$yqNAcn>|kupg6G6 zI87-ZXC_AA0a%$k_lRI=T1{X*Yl5;N*r*Dm=#Mc??crZ(&_QBUW5F8EAhiOFA@!?D zlAu~nPfP<%JIYFPzUrNo`qbU8!DrPS=!D;sIn#m7GbPHpQ(2vyO-ziQ@GOpR#7a+= zR+OiFlozpjOa0%2h#rvg+mc3lET0*g#vjkLd;`VGXd*dyohVC_k#2rCUWE_4c1yZ}^@_}OOG?n;n#nf&^Dy{c(ho1;hAou#gHs%XZD!s14r!^zpQa>}ue9_*VCFphG)vduyriU5?paTJ-x_UGaO{zMy z&XY6&JB+Y~j*h`E?J=e1nihs%R)jsqY!fHi1vK{U5l`(l5~2yt(nLE!7C9gR07w#U zRaVk%9Cps2ji3_7=vIXH2z1iKiwjk{y3;3cdSTt7a1aU$G9=QBvI@fr!2^K}92Xz2 zBz{*e?KPv*%(0K{qpa+!dN3I$RYY6fJZR9t`UoLt+HM%pe4IcQE+@-U)4EsdFIKz@ zq^U~NMd@gt#;nV?>a4Xnnds=UH|T!))SKs^1@9K$p{euX#MUudsX$YrrMzyRfHT-M zjAkN)5u^}w!YmC|XcC*<7S15vPMRpH$07$WvQE(H&6~j>79>F`u#v z_2a=IKQgnl@?U)vQA&x>neTQy=spRzvd^&!kW8#a#sPfQRo^}4IZZ>XbQ=+^5N-s% z0-SzUHzcY@FMy!eG=P}u;c3I^i#4dPQxSC^nJ-afs9|Jj%ju%%s2iSFZKBQ(CfG$2 z4C^YAEx`s|;2OUEm>7~FlU*Eu3A6a&R|wV>1J`A4Yat0*Q|(5lXj-xaBY#Fmi2s*& zdD_2!w&QyYq){LzfE6GIXYbpikc3x&pq1--RK|bT%o?PZHfUd=@$R4vHM@C=G2F%7 z>TLidlAs5n8aan^+hY|*0FrKmQ>QU{sXf9>%q$Tn5NTMh(;9hiOXR$L7~i40H+1Qr zjbR;F%MCLo8}np7)9Gr57n{B2&iUF_+BpE&Ac~-FU#3H)X`u#i(|+Bk*2Ct|mrr(2Bj&iXFYeQ)P+jMYB8i z7&RG+mSH&{K%NnRG@Q95={)132~W{=6fc+8rU)~_$qGmBuneVX&jv#=g3jQJ>IWDD zIL1z#mhlX10H=vvD%0|(rK@4!B^YfaxU6O-=5vAX2Y$?Q?D;c2a_iQ8WNU@g9tFS% zh4;@r!MMV27j+FWdI%iHJXJf2z+DVfo}~&z~M!PF->Pq}S89c!HXJ)=Qmct&u9Nzwd>(!G>iR?Ww2wR7~+BjLS7z ziK9PrbG_an-m7xxw-#%A5pP4V0+d{83TMFls8&$p{HH z=p<-_5hCKjGdE~U8eqLyf|fIQR*-+M|Du5^v&>(m_$fI##pp2%n_7yWA2wSMG#UK# zve1E$F9WKx1S_xi=xP!a+6Q&QRxPw?Z85X$15a7~Q_$SY!~lI`!;!=;=}m9F*URoNB^aBrR?{4hVuM-KsiKu%Ev=^Rnp5#ZRwsFhTQTLq{)Qfp!Ahp4z$4 zGkfYZeY+t6rAk|zaXTVrYV}GtS@5F4_r+IK0K2^Dv*H&qGuEOpBYr>E2EMR0MsAKi z4E>Y4cD;`BZ{250`hB27Y~=@A<*!u*+1H(WSe2T_d)T!`H0!G$ByX7fsPdBMa=&Zz zrNG5W>OvR4SCq@6p9jX!msD+^8)gZej26->@vB{0REaN*>u8p11!`5$Xo53M?tawd zkV1LRWXFoS*ER;(-hDyXiy|slxaNyEGxEaURO6)xEJ(v5+88|Pc!at=<_Nytbi4bb zM6cr;v%}4IV-`R)^=F*-Be|8IR!Q|+d*1?H9;XSw7XaI^tAgKmvFww8eBu4H~Tq~Nt5&z|780JZ@aTU2 zJO5Sg@?^lZG+xn|-Q}rI8DFh6=iZ~!-kf@P<|41)LZ)!cYyiof6;M!7f)%-cu~5D-$+9Coy_eA$ert!&+(P^`y@( z%CGhot{6Cpbmje#zHrwkOg1VcuEz5Im&O+JnUKPu?Lmp|S1-Lzlno_bTf_c8>_4@D z89*%P{r?Xlg%Ed%-3>8Jw%Ca$RYSKG&oumB1j~*2!^XA8582~@;wRhwi(nbO{!78C z+$2Tqe+ZVG1s`|sO%a)g5ro6jrVp)Q?;6w^f6CZ5$1cBl=-^Rv2KO@gT6>C z*g+DfIw=7(mT8vQfzFoyu>a`X6-1YW3@7}j{pXiuDQM_twaxRkukY&q)Bd9u;YCS_ zK6ya{`+V@ag0aB*OzZbgRD$51h%tJ0;*k%{Z?x;#ueI??iwrrv52o=OPa^-*{XN)Ggl>XP1+s^t*PFaA(na@7j7wW&kyv+&y!?ZIB18x&OCvz2bj~ z6jcT4BIxQutBA1-)qUah+A@;JEjOIYI-3?_r?R2pxNT#jkH6ig zvGH;?w(@(l#G&X;zu2&%TOqXZ^EEYwVbsr|_slMJ74IA-w@=DjIA%ci{YaVf`twWK z3Qr1hevYAEH~f5a60N9b6E7=5QcXlY%~U%PP8F9e*XJfj^Fc_+f_k`zek(3upG?*98uT|(&5r#qHdeg-O*8#<#9nF+t-E2< zoSm`f;J#P9X6kNs+8rcSS}h=VVYqSI_sZ6Xhzq9;$?_I7`cMSo#v*-eMMzu;Gn8bO*v5Wdf|wy)hd<* zKn1V|V`)lx24*QEC?Q@x8}6L^tc)Ez!iV0iwBeE|U@8UJ9PeSeH8|3UfgCp2zL)>v z5ORD=9Dipq>}6C|fth85Asl02WeGv8EDO17_6UsrxN*A46}g~l#SK~NQankyCBS#{ zNO#D|vB8S}#|LYPrvUQPFOMY$3N2smOfhZ*&ijkbP`d?Ps5zb^WfCcX9{rEq5beJ~ zT>1xLpvn>QEqT# z(z5Wvb-IyKSa*MO>qGR*KtI1Y8Ta_lu12YM%yz=T`Ky?lp`DgOQ<`9Z-#~Uo9gMq2 zE8D0fh{-Vm3&bOD_}^_3Kjy<%93UqovnolcO+9kkR3dd#k%uku<5d7DmB846w7Hn;?kI% zWUJTdazhS&n>4(GtJp_nW-#DD(bz3AAEcZE9{gFz^nlEBfV7iU+z|5K>E^j!&Vq7t zt2J?VV-a>}8t}f7*168285T!z49+88NDX7>vCPrV2^5wHv6V)$Wj68PM5)wn#YG@g z-c&~D^}ztr&;_%a`;?=n5U8;mKo}#nN!lgRED9&M{OEK^I{-#63rkGQ0*RDTyLFH* z94_-z(GU3TwKlzT*8?;O?;Ybl0B*u?vzDCyF)r}wqj_io;Q@wr7VXX~2J6d0ZjE+| zvlCn{#Y;jA3W29A|5{8;Q1aV9%!_Rb(PakAJxBMmu(d=mj%gy=k8A}-QQ2qKgSfn~ zc;&(@vf>6)1mXpo@B zF!B}II>kR%@b)sCDngm)3H+L!RYo5qy8toP!&wSocW8r!?r_F!!Gr}m*uxpp z&gg?Nh1dgS98AQ2C>0V(cMfF|)|rl8EQb5;}V8Ovfw$*`tFJ^c}nm{HF9uv2=*!J86;n43oicm4JuE=e>`^BCCY*iF zA974V*lL19c5=!A>}ZNvIT|*`lo-Ubl{?_*BH_)MF8XQnQTvR zUhjB@qTzKxuLAj-H#3FQ$c7Lb0E@v6>n;W2P6wX@c>C{goytedQz854XzwznIS|^L z0JSQEjDA7bmf3qF+1pW&b0|owKk=2FTJ9~+(jcyJ=gXBaED+0Sdw5SO?)ullf)70M_5e@kv$IICSjCtof zj`JwkFy)>#Ya!(tcY_C3OQf60|(No58&mY39^~W+- zJidUbjO)|DtXw+J^d-9Yg} zjMi2$FGR@EFjuCs_n%+nCX{qPi+`rixk2R|)u#x4Q2ENHQtygb{bgYkjA;dh ze2?Y4)&t9CE;j{N9p6L{d0U(6n{Urdn-s14oNqB7Vr zXk6DpdxD`dM|N0_M#X9@OE#XZ?v|k;r1c{BsyWy$KTtz|j$_%sWfL1{E1G4mQrEE& z@>dhmM&XPGz^t&R7!-s9-Hz!!iJ`D~<+JGQK!!EhU+i#U%OLh>c0E3GWKn$3QG2IM zN^XPr4wW}&MX@6I4J>6za7FpeCK zzF3fBjm32Kl{bmyU(OV+3j-W_(cjUaG-c#V>7IUvo`^rq9m}w3XD<96SEXj>a6Zc^ z01N*zOrsa(NIk@+y>ht4nG6#Ekmmn+S58Wj_ox@Gg>M`g?h!1Wyouu$$> zv2WH`Z_hfb>&!4Q@OjtXY+SM`S}eg{c|{kqrU_!AX2+e8IP_qBAXgC^SEXqITo;-)A`VgNWj$BA^dF1hOyf2r3Vjgn_Z)+?4wiWsT?)$ zHJ+ck{_Ep#3r1;xRV(OC*u^(0yWC+OzLa2KAmIr0$v_RFuZ+!rOALx}>n zTR;6BI`QJ^XI0%fLF1^k#0?7PR@dgP&4+p}oDHmwAHuD{)zAYZFeonl`#xbQ?ASsR=i0qNxYT=&i zy!Dy$uLp-8gI8Mm*5p{nCDX+ErtYF`<{*nrZd&aGU^! za~q&w$1y2j*4z2~l6h-f$1_eQD7FX1nf#^_=*$J`t~_#kmbfoyYT4+XI&qx(N^rAt zG2;NEP!Ew#xQiyi-eiWhUN!Ytv#c7R2PtAa^cB#RBy7883@By!myfe8}{$c*bV2iB~n;FA~}XNCwSG6bSmepTH?oOjUk;^swU`T zB$r5?_1k4^wmf~$dvP_bPQ!=zk5NKmosZLHE{jV zwo?Y-Hms<&%QlqXd71a7(mi^v*$5{m$2(^&`n?8_<+P~8l|x4}j5Fb{Gr|u(7;bom zf(_o+goN%Oww$>hmG$_M=#=*=`&L|BW*jNu%SIAO@Mv30RJS{|Al)62Ud>{Rg6dFV zYx!Us3UrtXNnvqP&Aa?L0`ZR8xE9NK? z31Q2DALxRY04L%`A3Mx)_9HoZBi?!DEv+L5lQ}ORI!0jp5qRf2MSIXOe+UD>l7&7+ z=47DDj+h z{lZ*H;H~M-Yo?Vv*Aq@H%$NPL$Lg{aV|U_^tUxrJ^)wF|%W6=1f?F~(@|=K#P{`X7{j{JtZ3 zU^4d3_WPR`UPHhLG)tTH2;c~)$znDRR**WX{ABK-F-aPmSI;H-^>f@_fQ5cK0HVQ~ z&OC+G-yJvph?~#-Nd4LIZ48lwTLeIOP{`tOusDS|Tpf_x7=4#Ku$S2N*}U~`S1Lw$58r*yKvsJaGH! zTI2YT=UC8v!>!@C!n-*_x3R@=5w$6Rc^!@#LO^|CjAe645o%&rk$3{Hgb}*A~;FfmG~ZBTD|B_BT1Y)iu?c! zn{(>&`LkdB`sMG{_Zq$)P7ts^8)YN)Xm4ZUMJVIdaq8jT@+Wd>srkR-qpd${-(UZO z@=>S&E{J9~uqcSq-Fk38)R(YDn8TzRjm&DBAJf9u(+-4DB`PalKciEFi_WIJQt zTI)`f{|n#~iA1Hjh@A?pZa?c|!n0DUw)JK}!s%%TT-1uq>ozf6*qpGF3wUb5C+(u)1l@$7Y#%v7EIcQAqKMvSpJzbsTR>_!VwQTpyU!j4Lpb?ko>ePGU#j#h#M0D#b z$yxFZF*}qX_UM_qo*x-mA7nV>D-Nr&d>LA{*>Y}&wI#awvlT@d1^vEHNH)8sUFlYg zs>H04LA#l$?*kSL^4U)bUgQfqP>U{?_V5up!cNf&u$T|h7n8aG?4)6O%j?rvE?Q;s z3f1Qr5T&!07@R})mZEpda|8XCInW1oC|7ijNfVv3tFT+Q69@KF#lSv>VFY?y*nfSY zrIEBf8y*D~j9-%mki#(mo;nM8{fYR;^xJdmlQ#k(RMDSVc4nwVmOCu|!dy4csYy(- zlyttmAW+~mnsvpndOZm4oJ3H_D<|;of%%!m8;*5uxYA#+xISROqG~7m^emP48l_v} zBo1sDMGG}QRf^=$Z%z-Zf znV9SvUR}1aSP@e;2NLCaojn1T&YOv>0J4kD${@WDUFk+v&wiM{xG#;NAhBY zD9s+l%4gLy47(6k!`8>n#nKhG5Mpi1k}38*7Tfutl+7hJ2DP8F@G8VPj0PQBAJ87X ziKsY6aVeFbEhnzO`rb?9>+*-{uTOD&Y=2i{(9X+9nr^(Tt|hJSj4=)p#9o15d4ORs zwQq5{-K@KMLaKga2j!#?Ya7vv{zE2Rf+WqUN}-E8GNQ}|jo))CxV?Xmj%|0hwxOFs zfm?Wk`I>mL7%gxONj4hCoq4stXV^jmcweE7POqY3n{boG2*WA`MuXdCnCL7UHgg7Svj zElB9uCfD}{-4VVWHW!n}Zuxj_Cu+QTVrL4Xawe`+dLEVWx`rp(uJ+W#j=fQ(LB#w{ zkS@3W3@gy1NU8s+f8Wiu4^IK3W~o!xFT^huOl~JM{qs&t0!YMW-EgH}w6c*HD6_rZ z@2(E-nC%n1shJ5p^O%EczeW6&e_`2m2X3-wpjAOgu<1RX@WB&e+nq?#c}7>T{J`wX zv=0~G0y@rne>Tj8_X`SwjS~Fg|>YK9tt5k05J-W4Dn@}R0 z!G1htXlF2iXw<2++x? zn-s?tTG5A}t1}H7Y2WRC&3!&KvY*NJDlYFzF?}bNY%-49%rux^s*BLSR%#ZP`t8qW zjnfZb>utw9ct5|oz}qLGfY%QXh)=qL{|RlqN| zX*FD+@uhtG^~6nkPOXi*C5ygHC^n-diAgPkCM8e(bXy`S`tf!M-S<2_fV57^P^#%MbFpcJ5oMh{KA$(FPabhl(JHq7u&{2+rkaJrC(NyYnGI_ zlMOp=@|#FXxF_+6OABT+#eL)MWfM&GdAp8K^~0CHABwVfn6BBXG}pN^zLlw+$oWHw zthn-9EDfvS{)WBjTj#}v^>Xs75}}Om31n00V=T;U9jA4tO$P8Q0!I97$rX($*>|)^ znkv7ZvO;TD)_F1GkSZim?Q&i6?lS?|bJ9&?6&i==i*2LJ&(~$pCil$~E@!P}!_&iH zF)8Xyj#%QLFtf*YH4K)0`{^&47rQEmeN6KXiXepqNhmVoV9>!Nk@_7z>x7bOR@0$p^5c zEEq?;F{iIZ_@LSMBUofUNuPoX!LmeS`O+yQW)HDcSmJ_aDdXieXegYV>Pfy@My)G^ zh1)}455eF>=$$gs>mdF#Iw=grW()vD?~wY&O+(*V(nQgcMC(<66{J|4JP6F1&6LeA z3SAcE;WLmBF*M$Ekf=P1mj=|!X@XP> zam*!I4GmI+gVP7`Qu&~$l*S1jozSH>!Dpq}K5n2Sl+luuu{x-4icB1$oBy zRe4(9iL`!}(rfQFuw2-ikdl>*YyjkgqOs5@`!f5utPsTpQ?!B@HghsS^y3MeA|D&B zQ*8d(Hu{}7cOzJ&KVE&EEb2)hH{g@AaEyT#a{3NX?||$wj`Le0g?0i@9*~8ESiDq0 zr9-%20E;M{98-w93dmFw8o;}lp9nO!OMR8FGBg=x2jR09E5re?_>a#(YC&? z%z$SC;9#;M;d`UiFVR69t>^ORXYD?!E?Iqga6>OTMoz$D8+l z8+s#_o0yZ8JPvfH3QEs{)6wAGL9$CM{1BfNRLBxQC0#}LHSTsc>DpI$s(Su~8Ni2A zskp!cnC2ip!w|%L01P+(;X15Tk|G{`03-cWOgMna6@t_0zzP?zY9X6Bx+cl_luKuw z_qY2+kSDfcIudOoKlpMdD$U8Bqzd|(FXI|&T2xjkH+VFg1&SLFMym~;EJ78XV_h%%LoyRl7$4Tk2Q1av%7c|j(oqQ>&I6aGW zrLO8sY?a7#wx~^k*uzuOn-dP_G*UVZF3#ys58ih%eo(L@n$&IX%51>Gxs*m=s@2c% z^KZfeSOreyG~`b=6gmi3O_#4XOZ&4es?ekGVbQ>-2Z#~}k&OGSt>KF19 z6Fcb}O$iM6$m6Lqqcizp_jZ=S)XRrh<&V zZckZHSVxKbTsyzlkm}jax1NTvV10kEHXZEsl~k0?r#%IY#6m++q^RS${I}h8bsZgY z^Eqz`CKRwCnqXuP4Vr!M&SqiCePKFeVJ2bWedfaKorNhqXdnvePs#KUV)5OX8{Qga zP^ah1m*+>#KAc%6x_FX;ofp4^EUqRju4OK+-&y=xy|~ftx3(Y>1b})AW%{k3`;_ZO z&(yDw^Q&ASuDCCLaR0Oy@@YTh{HocxzylT^Ar_wlznx6Br^lQp#pi$a%{uHrc3&<6 z<>??MywvGabIZbcy5FC^^EOlGzthj(-aCKlB}BuDj+miynESH`K%o*W^i=;57VqwA zI@|Vy1Aqm%N*7365_E#H+&#a|zr>wB0{@rGy6D2EKLc=r3Xqmi0)gN5{E?5AVlElh zrFra#`AO8g=U=4%5&O&}rb^c=0a{-hU%FP~@8NSM@P5eWe+hvribI8%Av1~EP2W&|n)bHi9UCzCBC=*UU%P6|m0lABrWNNn+VGTL>|Pt|nyZlY*GDd@0)nlhI|Fef8)v;~eSU^g7aI0L$}U zO7)MkDF;M#s(s~;J6C6G{DkFh88ydDKT>m=d*QP3BRbe_dqO)e_@Ei8mV^)0BmoQw z8l4~?b7*KC)X@*>_-`rLA7oHS67qvyK!4KV{30On#a}U`*GtvC6W7NBk`&680QK=flvP777lX)+u9_!NDS8tzx6cRI=z ze6{?-N{GRi%}F6)I1{Q}SkfS1$406UckTcrM}>+Z@j*y@>^MjZNkUVASF4C&Nu)cZ zC71qXm6;hSI!lltL1#Ae+&C@+fVXxg^DzthLM&3ABnKou(VigX5A_qm8EBHi?OCEw zVCJ||Hw$RPQ_vlI#R3>4)|_3gk)*_pByp4}z_QSd8kx z4}$S$;4m>P`9crg3y>+0Me;<~1bPmZD`x7T-=t%~!ILD>d@CtUk{J^3Y0n~xCeFWV z3mE+r$oY+zb9?=ECW+*C!Jg$d0$@ppJ_8c@6hRWRI5iYhbQ~mKhgYWJ%-mq|Lb8GO znOXZ4D+|FtNBwErEMDV5%R^*WP0+wqlClu~b^+cR4wH&y9*SJ82MLaJvcvjCR2VsZ zmLP>CxlnK!NlaiCISdJUt%YZVFvXAP4F?MJohwJZ)Y9XB(TK6wb(L@8 z`2FSO(3!EFIE68=423Q70A{`}(Q)_W_PN78N^Vbvvx<%|cGk5Hr=mhk@$7RQ&aC#2dF{|c@82ccbL)@3a6 z@eG$)qT@Qz36=IvRF**Gza&#yRfWa z5R6APYzJj|&gMXf`|^fst=BNpwJGd}v@KyEhxJ#&H@@Z!#?ejH@c$)JJo)q*0JNTL z3jZbVbW=NgwWy}K$S84l^TX}%UB$_&llQcvH+Ge#>RfAGn zhZui+X((gA?3k}MZ_&A;DpkFq}9Glp_7zmqNHMwPQw5y&5 zR!}NVGFTpzb9j7FG8qk!I)t$Nr&RtbU=XkZ{PMq%+}JWT9~NF^-$6<_jf|8zS!~}@ z@qbC>|34$SL#?%ArDy`%|3-4py=kj|SLT-WEWOH7iu{)y+qyPZ zM)u=$e6H5ajO5<)dwW#V^qvyXQR3($-8?E1GQIfLL|P5^IGJ5iebUP)bN!aed1fT{ za(r*)JpuWb&-bn$|2zI>kYD=yJDo;myml%{NZbOqH=ZAR^)h8ol~KQP_LceQ?}K08 zK8;ztK4$ptDbTTyBN!cbmcNdU2TQM`+!3~l0V!N(52lDhPGL)=Qz7f+crjAa6j@eZ z@$)szow|y2#i#J8WKgqWWvcp2-R$Gzgrci2S@`n%wXKb`uJ0t#&(da<7hvHYQ!8hAI`8W;+D@Le`nHwGiJ*MY7n#)u zUL_xb?xjALUD1t>*ILQnZxfa={@66MT4-|QxsrGU?>)sIutIyNQ_v>ktW|cPSX1b| zeIm59>Q%3}GH{R^%U8h1r;uBLW^mWuwQ==Yx!?XzrcWH$b~!{85zK=&v(Be;TxmDY zmc3)Lc=ba4_$}*76>vQ-RRJR2+Aj>OyLDOs#Es$V0EYd#p%{abYC_N2OIcS}_fo9^ zWj$ILK}G=&m18hg#s=Ww&x_VP!N+Y2=u+jTcDLJp+p&#N^d8rSeASWD(}&Pcunq4> zBPD^Ryi@`2onw^~^_j(MmSE zXL@xO&z&HN>0`KaITptmw`~Cq^ZBPmtaDo4T6nMT^xx&N*y^-C!+ChxOwC&7i?E$3 zcv$;yZ$pSd!!8nCl_iTgrDwx79Av&WQubBR3gX&Tx~Lky#fR8&N#BajEr*<(Alw7DwN_7rCNFR72*a(*1DiPvPc9U{JtBG z2#D|Y1rCCE22uIeh?Q7jU0cAmKT$#vFNsHb-B~QplwRpJQ93oI!WU3;nJOjueb65T zncy^cvpmO`rSULsp;Ql}25|PNgExGu^9R*>v%X!O;jV{B_V*2DbHoMmbR1Y8!j>Dxpz@a{yP5Y&h1fftO5?L}c_(rni2u$SP*YZtN@)s`?3mS6 zhPv7ktSdxWFWFnmPhQQe3X*ZywYN`WHb&c0+@74Kbv zxO$Sm`e#66RJF|cLrt$oS$8M2tJQR_4To(_-g!x!(NI#lWeB}&aKtK;nOb10m-w@= zy65zRs;R1gt2eVfx>g@_(JJJ^;SbV`E76NIbW7ot#!Ci2X@preUG8B7Q1>lfB%1rEu3V{nA%6pdpy+ zX}}E+$eLuoKlBQx2ml3v5oV|?2LHInih(rO!#bE5KA?GMOIkQs`iza5cjZ3cSFtaF zzGgYjL{a!jK86)YwKss6u~QEBX7&|#0A%jZ{(f_w16)=45Ya4xD2Cd@UDtOK`eV0Z zQ|jFmlpkxx7l4|u?|q#ExE`~KiU_yIn0n{esTOyO0%L703ec=U!8tcg%v7>xb(nVd zyDlD0con`M8mK90F)R9j7T%xGHxa-!(TPJ_yJRNpsshf35m?yqQhob;wpP+s5*uze zR2Vz~!k3Q8-0GqxB7Iol1W$s2H^9?4OiIGia8$VAWVLRWdo9nU=Iehy+z6S)vYw{n zP+19?a&F^X9!R+AQy1dZCp5p0tn2NkbCh8*@$!>4_WTwzS{jKKJ z!=Q-&L)m!-HTigL`XQZ=MiJ?R4hkBofGD9CQG<#Cf`%f}4JZnT7{ol4bJMYfEpELQ8$xNP{b6@AW+tbZSo9Y>v_wp666Ftl6 zfjKeBX8WSLUQ5Xa<}@tN?$?>a=MOR94z zQ?_qQX0DcMg5-#|%~^l6HzRP*@n&-IgZRMB+jvPYt9Nlj(8i`)gyZ<*R|X%DQj&#D{Pf---(} zsr+FwdrSn{#WMn;+?*buUU_z)1O`(MB36XDcM+JV(M`ECu8{E{0g=wtS#CaVhri73 zPzTZD&k4<-Mj1Re5_upycV@^_<6sF#YW$$X`7xL95aDK_wEXum##RCd64nAv9C3xk z2ZLqn8c_JA3Te~52$4x34PcjvnQ-Xk^x$K$^C7QoZ<=TwaQWV{{m`;X7mk7j#!<$Z zqPyefN3I{GiF5gJE@XMg1DAI79>8BVnbG&O#Ye=e!PfD$Y2mMF;bd=@#ZLiRK4-{0^yTR#t1?Gd!%kcIFl)xnS6ldI z!?L@peo+JA;87<|g_~++diV5gk6qL4Oqv&8wD?$ghe*?d9P>EGELxQ2mQ1-yL{HS8 z%SPHe6KWoEvxWzMcFVqeo=~)g-ulnHnO9%2Kk8B`xXreBdn4ya%8_PS z#csmEJ;T_3rpus-ZCcZ@m_H9!Z0 zHqKVlz`~udU8al8Lrf0n_KdQ~Tn(1XwKPOtg?~GHlB_w&2J;E3Z_=PT+?FbEP=%I& zdsbR=kJN;%d?$|20FQH^!TGdkJOCQD139;e@uh%IMyAP@`3U6i`5S%WHv#O;fvMpz zU1S;$Lw9hO0p=m{>JWLm>9AKgm>FJCS&!q-dtiCK)IdiYT;MgRGyx4?Wj?rG1TJlQIMW=?yOuf4quahsV zzAsmFk4TVJfJls4RfuhuV#?S2Q#=s`DxO6l?ji{JI^KeNyoD7Zw{S~lx3vmS@E1IX zc`@Rt>x$lO>U(bn-VX4Jq-7otzHVVB>s`lG_PZuO;!r#mQaqktJlR@2HBtPbRdU(| zyS0nQF5xkg^kevzqDxj0T{^g;e{nvsW4yaG?C3)Ac7Ey4*3#cz#WP-54yj~unZ~Cp zVEI**(~F2Ad$tkH|Lo9lVrAH$r99pxORW(KZGO=VdaNQJw+3lTzD!oXT;B0y4~z~9 zE!&${#>)>+T`0plmTTx&{IM!iv8Kc01^nKTCpihR3v?~9JH~azI^JcvVpP>K^ar}9 zRA{Nm&pRZ?J7DYBeJb3S50u}66&X|mEZw0w_#Wvr$5_2oN%y-u>ds!Z+8M{BDt zSeKuwD;JE9)UfpNVuZ>#o?O`~BU~yCwYD`4EIs$N%1Er5)NPuhViXr&;Io@iPTIGm}^f(Qbu`SjOEG3-+yG>sI;tp`G%4=l{96G4&j_NkwYCBYuXU`mM(zbfFkP!)4_CRYD>+Kn*C4 z2;j##C@Y99B^=~3dkKNiET)Taq5LLZ+HM!0aZB{+PU1gJs`D%nY*NFK>xzb5C_)S8~OURj@zx>$xDRrT3+2z^r0)06Eeu<>C%T`xI zbx;bP1+IiFHFOR{2VwPcBqRV5s(qrj$;TRdH!*AlkNGB4=Oj_4;nW(8y6Z0-_Nq>? z1d=EzQLOIz%%|T5GwE$;+!M5$TzbQxnws1t?YsXs@9E+?`J87xzgJ&b)ZK0p>EWSw z{qpK94?CGx)H^F$bCGI8XEs?cj!J#Pp#)@Y5oEB z?;*;cG0>5BPDh5cZVi#w=V~p<)m2^91A{58Ynt$XU7!p15?M}_{Osu}f-T324iwke$ zB`5S``L1(dzhXy0&&TdbqL;{HIkzVAC5LV}mxSCmuLs~%D&htQc5Fq(vp|lvn&H-X zzi6^{OEmp>JJ!b;ySvN5yd~WKrIh}2ZEQBd_pX3?{3>hHRlQpnu%xzq*sqxDJldf) z`0B$%Bg{|gDd-9ZChVhbbLwnLj2t0Q0sKPBwD$3;Ey{-D9-EiN)PK*G0F0<@+(zJT zI>d|xoxw|+1{tUma3eC1NUHCXl!+gbEaIDqZplc;XDDvbUl1F0iUe`x%#?CqHcUvu z>{Uw+Y!`>PNrPCCD=SG*Nq?0f0B*)*pGn-b5FtGQ^JaqcZg5TU&^pcO9s6kqztSxl zm`XM{$3zcNFngjg$PpS36*0v`iGt6z3t+$WzjuE=t2!_ed}L&uU!{@=;bFs+iKrPm zn#C?f5_&$SMUw=b2KaQDsOwPlD+1^#gUj|~ zDrjKUia{%f>Fa@`y*juBQ9E7Y!A4DGSz+MJFiZyrn+jOmy1#hy^C)X$ma(N1c>pfE zgI%OU9VuWU9#glH^EW;nJH)9`3yZQ_^)7zRQG3_hD-p>uSVxRw-^P9!q&x>9` zYLQaF+ZT|VOzaH`gog>KzyVL#N4jXbzZsAc)_$}i7^pR21r*FOBI<(XV&Pf8gEN(Oc2_aYRX5?zI*Ja+rf6Q8o1O$Uzp!k)U;W@3nev z6)6eJG*RH*T4d%TRv8jva3WUGUY}|P)EkpE|HA>r*9Ny#e|4BK`&FFHe`ct67)P9UeCeaU|4f6 z7l;7#3xJNKNrvFjy8zOLu5T<|ODkQR+jT0f#7h6cspyZAr0XQp+W%C4{4SI>B%GFW zwyBW$PWLN6pY`t;lA@Vmj%%&?w4nb0;PSTQXe0=_(03VI)*i(RM~=kN*#C*-b|u2r zd#}cEmBc>dpx-9>r#`(5-v{3G*~z%{I#X$dwq#TPk*-QuEzq04=A(@XWHD;msy zkldp&V*enycK0v5DzIBUTkrfl9Lo3oBQf>TzmVMfN2BnA336T<%T7}bYsDwR-+#Z7#lzMvhA0&6;5n8WNp7kQE^lOKc!^4G+Vs1&Cq@$LLky5X|d9h=V zQO^qd#PqXs-oBI9b}c?~k=!5tZ4U$5$TKOQt3n+yN@=g%&j!0mmI zClG^M?wZ%{%S+T` zefcckL^26FrnqZsw)axgpn0i=BK3mj#;}Uf!9U+f#}9oHdTDvT{S51bg+lWP++@$_ z8M||rf)1UT^VL4m zD&h8xn+jEgev3!BvFNh~?k}5dCk6!GT(!G=d$Li%k6U18>T|x1RpQ26hL?q#%dboq z5~9vtyz`_P>@WNC2p2OVDutuL1O;rIUW`tG@XGS#c+qFP`MH!wJC{p>;u{uA-HVL8 z(qtZOR7nOz4=(N&xt8pxlw5DJT96Kn^s;#18Qp57Ky7x`TmS0#cLgqPU<0yY+z`QCMi1V#kqgBrOk9aDs!JK{R?qV)E4zZ%PAXZteSKZF9 z0pEulIetB5erT2~hzjBlC&de44O`lB}b~j!;rX=2%-n4oR7!T2vZS&^0qWWUZlf7+1)7dDZu+^ z-_RanL#kx79N^4qKN%jGD6A0$|3*Cvu=s&sUt?Y#zyfIE2ULncBH9zY7aBj|6?9H% z+4Lv!=behHG{pmz2&#BhFv_E-9C5?GOS7CGaI>64PT8C6jh;y)E5C*5iJawk#iaq; zr0BbcyLsPn-StJ~F+4cqp=cMdmV6oX+qNmDqYdo;+k}r>)+m_Fjs=nf?GNnMCd)PR z%6NFm0QcQrt3w)+)G~a;2JB?b3q0cBok#)mfW(Vg$83K7vTF)guyBlv_20Crb3&WGfzOsFScgWk*Mj-rbVfSK;_`C@@Q|)+%rLVAmPdgSSTSFY@j` zRy%VlB+EqNGs}XXYj7puOp*_|`s7aQ+kfrUuDtrH%Wz5t<7mml8xFj>rFcdrd45!x zp&{$*(JeUUW;2IeXc0fceHPkXYZojYhwRJwdWP5ekx@a+`qkMdCslkSc+HgK)M9z2?C-3$gFUPmk01|GZi<=ck zlmj4kq;f$fRrY$RAnsp@90K40RR6C;4u3xq@&BF3DOftSIK3{idRXB~0r>^ER-QUVhr@5=mFBKMCZ=UC|pZX&lj z{_tOtoEu;MKw@_v?f7O@DtaqR|m>xImB4WZJWGPXEpC(NR z6d_wid;p>K$LS*Ht&gp*<6ZVG^JZa9bvI37F+9P;QrH_cd2^Zj&?={bFOL&wk)*MA zE|!T1Ay;68O|~$0HgIt>m{rs2Aa*wqY;q`=Xrx6J{@MVM!!uh+%&##fi9>j0SyDU_ zMl6Bm&e|HAIltDW3Zq-RT#MCN@8!w>tAypMqU%WEoRV1YjEeFc@0Hq`s=AfBdyoE2 zlCy91-oHz7>Q?KYZLO?6V8ZsVF`B$g*6IqR?yfaXB|OB{_Ip^(60H$h7ER+G`z4zu zudl8@X2<>`$;t8g+`3eC_w$pre-@d-;8}Ivh8O2)NQ~Y}zf#^DJQQ)k~GUc43|-0A+HsiGkC$4d83E z-PsVJX7lp$13J954Y9`SdcQTie&RbDR6(EksoFe3GjDRe7&0e;kSTcfTf;*NnnrHM zO%J(;rI#q9$70T*jKc96Bmu-HumzCMYYIs@aSMI@6zFNu0uem$yl^V?$L{)%k5u@9 zZFclt|LvK0rTXpJx%b2LehwsU)_(-bajOfhn>3o{VjL03>Va#iy1xxQ6eAzhQvR?wqhH%kRraE2ZfF9u3~Mbp?z)oAhDHzQ*wuZ$3= zOK0gQUbEgl(UP~PkrP8mF0(zQ+#%-8cjQms=(_KC-PX7Xezxbsh286jyQfj|k>F$H z0=Ye%iuxM~q~vm;YUNko5SI8A93qf2^x)z~R3aHwA<}KxrF0=c%3(f<&&94w=gCIO zmFSbK`E>IaIR3NR-f2vBPxsNE>IvuW$YE77x{v(bpv6nL;a7Eg66C+8)3Rn|#Z}V9 zL^U$<`sd|Uc=^knhY}VeT$MGgtd;yTGSM!jx&4SXQux;!R!#~6$3%Ni8_P$3o1q=J z(R=KI#^=nN@;&YCnOI`ElHpf%_h8Q*%k$RJ=l>L>N!fL#aaaV(an&B|{c(bmIibKZ zOF_RVmZ+B^ATMUXJpDnq;4RRfo^J5IN4Qau z_7lo3xIO%d*}0(bjf6PT&+ahHJd0CE&A1bwRckUVVw>)H65%uK^ubA#%Ko4R97i$* zAVV<+WKGG2(0vl$mxR5Wk2EBh&!gFbuj8ZTYa^okn0b{%4P|qEI6QKkjS6 zquVVIs8j>60Y05m@%n9B)*Udm2y|x3?yAFt;qHYkYi?W?oL6nwHrXM;*XwK;8JoTO zs;()kc=;wS5>8OQ;?Z>XzF*8wR{7`C%^qiL1++iC$p<1=R`*^W^-lf?o)7)>-u&lhGs&;PVgaM8U7llpFMp%mOzz%vj>YRH zKDF_PeC#+4J3QY;T2p{1IkA!Fb!B=!F~a^Ny~ZWkKjG8)5*L#&Bj|I=>?WFuI~P{z z?Y-TlJJ67Nqkm57i@nQlM%8ad5Q^9P3Qckz|S9~LdzT-JIJ(&ulkkjE#msQ+u{ zEfw~)xUcQf!9y)?BTh7xzcE-ceyInzUTC_bbmWuj+yv`gidN;JH(oIg1+0)qoc)UC zPnGy4q_|zPhVkzoDy+J>6sKxu8m@b0sQz#`h<5ok`SgKp$D7fE-zPF+u1OsM2_J3z ze67OddHTUR&!dKSCfkKi^(XB(_TH5`)#1T!_xE|IWkG23*E7ZIVe*ATO&&TH(SGSX zCTo+GXY-C~Y{6EFl{~-9eWa+%+sG8(99r(uQn;lSZ-CU7UU(FTZCX4P5nLf%N(99| z+e^K!#Xy9Het)@Fl9FuTBm`~~^*q+tb(P;>dU#hDkpXj^@`uyKs`hjiQ|NEVhkWP4 zKL?wiEiuSoNsyJWIyBM1n38W`lXxnNXgU}fdQ-(y7uz(Tk^$`zxD&BUi^SQ$^@90s zO&VdCYG>TjWFT6A*gD)Z>be|}gBN{b2|MI};Z4nA(VONfOG8vAO#%VAE*^6E!Jp`* zEIxN($OQN&x8}$%dA5>g38Y1N#OvPzx_s^N;bQUo=!iq|&p|HTb5K{(%bSp@^{=6s zyv70J8uKWhyg~kqLmqE-LskUxy@_w+&TAt&zw^*Q$vPTeM+=HL%9jHh&ZP`)&38}G zuo>$-$5#iQ#=TQGF;wVUuNF@vSZ|b@ec>C@#|dj z-|gy`4}u^64Ql%x{wwV^`5VEVJ{E3p=JwyqH+Jb5A2OPoX5^aRj=oHR$5VTmkc(^- zuRX@dl&Yf@_*W-Fw;H>PL*>#jHVo7hMS7vz>Lr!WG)n0}l^rM(b)AD9r9%oCC>HgC zw1+ID?K}@2W2_r(Y9DPL9Br8wZQT-WGahX!5^cUjdH}%P9-)j$6u}PZW7nLeGljZ1 zF=UZgSKU~5``Au4DvSZ!#bdUJC|xS-I*WI3@pRgl@CbnL^Ko-Oo2uK=phz* zixCqwA91xIK8ynYLqYbagM-NMFd~`-pqFR~1)h78T6nqpx1(h4tI++~@D^qCEIrYn zGx3@cDu{!8PJ?_RAdQ&tFg$vUin-XCq%ofy$a8*xhGNknbSBo46E{Rhe-Jqqy(HXC zja?9doW~)CNa)W@(=Uj<&J<`Q1>UoS`oKz+$47#P zrJmCHJ2P(~Cj^@~$XqtODmdY@@_Ec4k*^K&fyni7YeQy2yBHX715vE@uye4`0R*yw z`%ONqFty*q|GYyMF?f|v2F61H&*5>uuj}tW$KOYew^0{8-YI=K4wu08w`Addvb0e$ zkUJh>QCGpjgIRGsLI-)=n>?=@l8OAFH=BG3`iXm=(*)6yMhq>X}a!w_WC+-pMl> zEHVso&UjTUXIt``S7>QDMSVm}ctqfHLhf3KpxX`8uX>g{q5?mbvk1ebglot&r8v+= z>AWZ%sb8|+h0a5z*9HloCh0@`xc^PXDbMBpj)DG*`(x1CqW*2lm@zt!`Tykp5{86L z3;xGb#%jaff2lZ+|GJwy!DXOc7ysJi8aw_^?yrS0(-AMY|3d%2sW^|7aHot1_BAn!yS0&nbnbNdR6m>|HTD@QtV**)F!Xq{O8Nnzvp^wk!dR~(zj zYeHgx=1-a~ZXan=aNVdxN{BAzUF1cg_Dh+>KILJuR9hi%Xch5^=UkQY3XGc4oKNpC zFYBgs$s1ioUIVKlMx#=UbRbk~?M&gUfHq}#;}}g zXpj=Y>PEb>{V-Z|Ik+wG>T8>md)RHgFnibGGZoF7rZice@TMA0L7j@Bf$%`}ZkBYVYlH?~j$T;}4Hu!x5LBe+eTg zl>{4>Y*oC`|DwJsTDAoUWbuQbRjVyZzJMJ`%P2j z{`_d=cBcoA=XRDBrwc$bZ5u!MCiHRQpf}X$pVtqcaOu&T%_IiXjzl&^+ywU;A6@Ex z**Syfv($COYbnquI0A4ULB%Y50;{1+;Va7VlF?*1cIQFF6|kvBy&26v%mxqr4XK5E zttRnCOF6E_9(8StbDnywd=LeE-zDW03x;13HIXkDkTZs9sct0j=|P36TX2w58;SP) z<;2LES4ywl@PSL^d%+|*b>nmq51R_HcRl}_GAPLv5{s7I`jZ=}!Bgj?)W6~1-hUPJ zRd0NzDY7Gi=9Z?;L%L8hCKYi{$#841C`o@rsGT?3ZVVT%hilCk4DLzu9_&&KGA%uD zT=~c*{S6C69dM^zC`@HnXm57E)EaxiDsr1Qf{h2BovCaDf&{H^#UOZq0^)B*J1}C5 zU(AcR6-uCKK-dyHg7HTh;|9vv^jOd(-Xs1vKw9`4-A5$8${X?80{svl-r}hQ@N=u& zzz7%;u(&HU49r_05-m@X$^>G)!a$HGmdjS1mmq`LnO5g?9RXt;5ORlXC|u`tdP@tZ z#+0e(N3b+NEKK(V-f`L1<5Ypx!P;_D1P|52=$<-c9*TGDc1yF*Z%+#q>l6yx7uoDT z8Y{DA%&(~`xxXwUEi|mT{<=c%_O@tQJtY3f(I+ao_Gk9|8JUw5>{+w6F4#Me7=JVu z*K_z@08DOo52^X;@LvBLeeb7#ZarqA>nU-C#TxtECFbz{qmLYL6#S3Y*M5#vc0e*< zA0^(&2L!gIKU=ashv(FsRfGe*Es>2xxIg3eLH~X9vpsky&xzP#q?c+z6Z|cr zzS-(fqp^_4_tlvq_@|pbxhA=%5yHu4-WD$WdIXpjWkqj2odt%&A|~Wh&~hBsEd=A};=r zA15)i9}k@3o(w%Q#=5W_1`|VKD; zt47oK2m7709Ugujn1!_WMNCED-Ei^s%X@q`h*^d>4DbVwgvvqjaA*X@w$NGX4B7;5 znjzT0ADx&0!=w5G)gD(y`Q2ZR!L8~f`@qGoto)Aab^U8CzoI6xeFvTs;1EMx>HPAX zDZma8^@fviaDHt z%`PCBMCy+h>vb*L@rw(R-f(p3u(gZ!k=E;HbF}_P3?Eqh}G2SLI*6JTMxB5 zN!Vt>PqoT*Ii+h)^JGf7Kx6^W8k0j!GVFVt>L*cH)a|VUIE{No;>p$DUPZjv`}|jg zg)=Eihf#KL8~7y$hTInVOBH(1FNM+sZKQ=QnMiZpY{D%YC_kWN$Fy~FSC2!anF>O#K7C-V z0V%_fIYwNEF*ct|%$+H65qjIxsI(1)-)W*+e=oOd*b5Ap;A*Z5kD8%jwvdxFlsOL3 z&lP=e)p86_4S|b(L4zoyKT1NUu5281i4# zR^lHY*|TT%IJ6C`APA^(&lVWa^8|1c1I@MNx#{Df5F?||7C~ND)YkA`IajkUw4*%2 zz#1Jr#X=9`&|MVNNC)~U6K!zHBU@Q$>6(}K!roc#^Z}r!eMyW@hLq&SDv zBu&bk>-5~?ek1vHOLG5s@)Jb#fUX3qX3x<;#hTM1eYvif#+0e?l! z>OwqTUE?MX8}o^U&hJc#xO4NXZd$KMimDNB1r@$0H=ivzE3il8uN>BQB>YwPpwE zdo0Q<5k$91%>3r=jWM)8Xzn1EIb$<%Hw>YpeY&?_uy&3vSiW8r`%?xfl6q>T~K zW@|NTN@RmJI`0L)5axknCj@Tw6jx zhgZokcYI`_rzl0jwP}O6vM~;73Recv&&tX#)$y+QC7M&tOXE6hKjASIEx|(8*@HkS zi*mC(!BbeJ?3)$(XK?W!d-{jv;$bFgoQbaJzH@k`5FS!6tzF)lUp9nCxZ`1wbo3ra z^d4{YAf@QgGP0X}CqR!5sVzDbTHP0tsV7#D)>=GDgP&(XeYhQ`cvQSFdXR&%s6#_{ zS5V?VONI6BV3*SlI+l%7i+<(RJPs~qkt)ZzJOu}ZdtK?iTsa7>`kPnAh31S|P=U>Sm0N;}l%s-498@U{tjmOrld3yj=QmlQ!uHX8C(*z0NF6e^ zngumrK&#mgY`Ah&7WXqlj2Vex6!0My^gRvcNPrw=^RXFllU*|S6bCg-gqcmU|tY2v^H3YdjM9V0>10LT~(e25JL7l64x<24}Yc^sI;dL-~Or}1gN z;Q0n%r+hc>u_h67o(Ty*g|gcvL)0kX89Mj|4O>bEx5k3qaolwaIFOFvc0fMGq09gX zmn8gvd$PrWs#9R+Ss+ge@BDd8{VCKT26_Y8jP$DO%q|c|me`3S-ZRjnM95_(`aB-; zo{o+nKuk&KLv+MX3QUKNjP|NQBXa}aw`*8E9=rKepy07O6C>J$9w$N^nP@T{EW8O@ z0}x6Im~sY06F?iWVBZ)hH8xTQfPcV4t(a&X0QrRu)#V_wD9Anr{17f#505M-zL=yx zMETNuRGRZbo*GTGyl0i0vY?Ncb#FPaHU?Y`hc+fds_A@c1o%@LyorwHN6`+1_4MjB zJl++hjo`}`>5ta{=&eY!4h8m#(lSi}2Qo2{1n?jS_6k7mr=g4p;AQ}#OF(O~VAV9x zF&0{l&AUk8Q)9vzY?8Y(PW2$MM-wpl?Y?6FS(O#24LPY?9EkuvS1&&4D=}MO6{LKIm6mV>JopLPvWO zkRLe6OH7m_6Kp`?ogzTkAV?b%T~6c{1i(V*=!=A&DH_s*0VdK=^`y6BL|82o9fCXH zcdY-FgtM{^Zp*vcr#4MMA3YXYd1mKs#a{F|>z?xQig7~W{$0K22@dy4MLQt9HIEl* z`<(Bdu+ARC-yN?*>(Vsy4&5(DWVJ2P#)F)HT4s;pl1He{r)RRY%U!X>i;C7%lT z<~jTsG(4O4Dr6w>)@ ztH1rygQDWexHVLl<75Bz+=}CqWqy+_pRB+EycOh(?C0;VIXpMiE7;8|n^Jl2Wc|J^ zX1uO=Dxh#+v-kagb1p{3M@G!K=Kj=JajEv#{M4PPsUx|$yT_d_qQ~+-e3(aPU&zli z5H09@K7Gq;>g6ZiY7+WU@Q2MmMZZK*jU43n=O1rO#!NSR`LJM~On6dUCF}s#uER!_ zuu(7Am}xfdFIzxrM(F5_U}^|265WUAK2|Zalybb(tnATQ`3tj(;j_vmv-@7mDr4>- zy5RFlxCkKJ-Wh>TD^5)MY?{W#(#<0 zu)-W&Nj`w3A6R8dtz8UXun4bz93FbJY?b-S`oW7&FH1go)MHjTYpy5O+c9fRN0)q3 zmwW1Q!`niyKc8H4f%eDrS|i{_e#Ws{cZ^ zRB|64-EuTiKT<2{)MX_By{J3O1LJEB{+JCMb`FQpmcsfT#R^G(`9l9R!`iTyS{izR z`JKA%S-;Lxx>6g3Bh+aNw!1$CFuP@EKJUU*zI&$e8+~?6#e8SLudvaJWNbJYeu?s8 z2EgtxG4muY^uF=sz`B|LKgQ-25{7=@tDN-etD~VxhMZyroIl3|W~3N1v<}{o`8b{Y zykyb-DCRpJsmA{HoeU16GgrBjEEPG$!kiOJoMdB?etiDUL~*&lJ;vY9om@G+`^Dz~ z$Eg&jiAR~8#&wfy%Lur2A|_4%u)UB*2lO8K z35>Zy1E5{A9c5SeD|WveUcq4&Sy&eU@&|xAaIkiG_*)i;!A2irKs%Y>Q37L_4Sqz% zE&$)ZlTdyP2=_pobT|l#mNLyF%^1g`CF@M$>YX0@Pcqapg^B;DIKjzC)O*B z@;f!=L)T+EiNp5T!mbRl$9}2;Y0@Lg!=Z31)t8(bk}&TJCskQNAP)71%i;??xGt@ zdgjP8Tv@WzavfORG^YNTFSi1+MV5L-XV$3VvrgcmKw3R5z2ef>4s{F38}kho!;UxK z&?)T+)rHOrbxK@?mrHl{5h8!Lr0+GE#bVb-`EbdrkBzB1(3$N#Yz|LD1QgSJX7iHTOU9 zJgjX8)v*W;*EBnw^M0Zr?c-hL%{op2-3ogR zeIJ|c{or4w_SpHx$Cw*+cb7ypoo{AqcT21>0%G4@nS<(*Bj968Q#Y|&LL(PmLUYM+ z(y{jTMx?TCiTnMwaJLlAg}Ek zZkbIwz2NYvwm->{YNR+f5#gMUgQn0%o1jI#7{gy(yiGw6={OUN_>TjFI}_l z^XjtsCkeRZC5pj6X*%OXKMh~MoYlON$h^?E_3Ocw;T>nt{O6%d$Ea%OU(h0u7WBdi zUKKr)fhoF9I-R&@Q=YPY%8-Y_;APde8Xf9>mb44!?Y9S95eK#HqAbn=E_1vG_yDyR zf6_+^C;7*98*e$h{h&lPwQ`SR1@PP}6B6Sg=+cS3h_CEu+Z)kn8pA?YTM{X4e{`WUbIbW6qB z`HX)nT2z8jHJU| zu(h(@Zi>Z$$lAiH6}z%_NYu1(8?Y;P_nv%l&B}f9k;K*dgOgpW4<3FWKAA4fyI<8% z9dviiA>zR5+C$dAmvXH)k9*u*e>C-}x4 zaoSOb);JwF3)PKIp>w_)uS722+vt+GvDRQT6{h;NM?Ux2ecexaVFHbRFWgOiP3Ttr z*01%>_uCuY#e3fd41TPAd;4x$k-#$LvoACnWvQD3TS7-ZGj{B+(hN?-`5e&UIeW`L zecbcI0Ueo}_v^La24yym&s#@bfAXOIzexgI^c4@2k{|Q_{ZYTOCIT4Nqi=23|B?6E zo_nStN1BD0S?}Ec!x1G4+d!zt(jBh6xVwM9P?Why)!o;z+Qx`zOT(!mRu@VDMmJkc zsdJ!d?;jB)Vt2Cy-9+^{M?JstsQMk}-D>JE<)^P*Ft=-mvELY_D1R9{0NQYi*4Z7Y zh!(n}%1_k&L$2Q=mlnKxcGkz;IaX|zk$G~9x)7Bt8-PQ|ftc|;FfuM3K?H$Gh@Aw5 zz~3wj;03-ptUpTH8E?YXc4E6_DlPvCk^wN4H^S0Y0Hc-E@KdJkKwg|QCq7-^GZpRI zZ?aEdq=Z<-Oo&h}$MWc!B6s^5+l51wrMp>?!oD&om&R%P-pfT0V`XqE7+W=U<0xHL znT{IGNSsB96=_a4sWMH~{)6Zyim@PKPU&juKS5$Wc<4=ee(^rsoW{Murs@_CF| z1c4^wsA3SZ_>nv&F*F`@LaNdMXPR>$U4h`d0u#E>Ew9I>N+Y+o-=myg zCXoPELKrcPvfo_+zt@UuhkPUXHHsoK{pc3dddrek@e&hdMl{TuJIch%9Q7S?$0{4Y->0P9by~E3_wcBk7`S%HKE?a&eGP5kte?-tKi1>zVmgdrYAk_c zodOj5Juutx)Lpfnc09ERqld18j~VH(@u2PJT^I0u+=m)uBu+7p2FI9sVVFD zisPkYb^*KPTaO;w`2mirj(3>XA7$R!cdA+)T{9+J>!;@97tlBLMA5E!pvK&Y$&)$_ zGi$U#FKRW}n)upRh_Rbt+AY>oUh$gGtWwOi>SU(9?B_&39=R8`cz%=;d9EnYIW;IP z()n@ZUa_Y&W`rV_F`9LUXg?Viuu(Wp@QxB2i-$$Ox;w=l`q94m{DF2+gp{MFiFf3Z zqi%o0#ZvO)`-7A(+zUXkcygrpq;B1jguV;@6t|}zfP2BqyaV2zCM6?;D_7(0jcr8! z5bfWtH7el;0rdY4B;tK3 z$B%XeEEUU(Jxey{LFE96BDgt;ab_11?n0hu6NBCdgq|?kgkKY)$k$B7 zUsY1>b$>YXO-fWaJtQ>}#EDicjC%L{MQ_63z8S+`ZQ}Fn7;}Vh zPN{=07n$&J1D1W}Y+ngaIfDm)1^+lZQAF2GJlQE$XIdR1?<*%Z#?nnsx#!uw9gJTh z#fe#@W@h}@^URdkNvLb%le+g)Ro6l-MG~xe+6Z;DJ}yM4=PO;FB$r zE!LMm2X_~4x{tJo&l5#QgEX!*Mg9;85?)qM4og0%Dkq9iglXP!K|!TEzDzNo3f>zi zPx`DtH!D_)Q1T=BH248)$uSlFWwp^G_sd2MC7{v;?azGoeEpTV!~OJYUY#Q1?394$ z>|>v2FF$_3BBYJjzZJauGQ0XRT4i(2n+-boa#IZM1r!;f7Y=>=-i3X+yZuLO;1g^5 z*ZuAnKi^#(0}K`$mL6NpygRuo^Vsn3vh>TpKQ4ZZU`p?5s^9*8h*}eL8?X;zci%?V z+|CT5>d0U}<1qskR3Upu&xa!Z>8g72+~L+8+jZe1^n$FXyR3brVsNB#UgW-(NN(T# zf$d0z8l4MQdFd?EK1!5sUX*@Il)-q^(d{UrNHmu>($7P66H)Cfz6Tt>&s0poM)W6K z&C{vX~bFFvs)K6yMob$2^HH9jgD5!VTz9#N2u zbc}7VXwFPr$#w$0CyqZ}ht9g}he)W&ORQ^2yk{Suu@svf&zHA^DeOro3r=duOR_`6 zUvNuIdzZ)*Np9~+yn={p=kRgC`$l3?(Rjj>?POL@+_NREm6@cD;FR&al(_BKfcXDK z-kXO*`S^X`=a?~LnVItx30bDJ5NeP;HOLwoX+f!xvL#Ks78<*(qsf~1L-t)+Kr`(xe7?i6P49|z@eas@us7{v4%$7LSP3_M7-8WK{~!1iHu^dp{soTi z1jyq6evl%$0Lv750-Xe&O+p}thUb#;V-WbP5PvcoKTO1@O5)|0kJ@VEe^L|r;I{F^ zvn%e8^#dMX&wgyM>dmHOmAFVUkBGh46Y9KB)B~4Vf>R; z@1Ri#d_qT?@aTL_5PHNGzeWT(EO3T_UtoZf6mWrzpD)KRGx1z{@&W|Hcwmlo5T+B$ zY;ci;UuF5NLpK*8{be%v9ze}NjA`gug?W(3xDIJJ@kaUMS{=D?KD0VbK#u}Py@kz1 z0ZkGnh0do=fP5*)oQ7i(cfxw&qaF%ABDx1n(eTS$FpG%dQDB~l@?;8|z_gf+TVi26 zDJZ!6$>j1jZoXb%~xO$JW>`yLTnHo8C`d25kRcu1B#dn& zqXyXc&mQ?FLh}z5X9mOv4DxC)A6XYvCe05ra348(gMI>Y5TH&M@TLj8<;FhQ^QtB^ z&eS{NS6C2COJMlA%F-PmgGLPW5*uyE22JS9mt5o=1jaOWHC-f+j6O;+FeG8xC`etF zl;AxfxJ>(mj4K54jp^`y7QZ2c*M@`|*?h+sAm%IBNJJ)bv7roH8UZ!H!5hG52_Bm- zl!M)OFLQrSnVwN`O?-d@SFjxre)bqSEebO-h)(GIg!W87P z(5(QtNd9}ZAXDHQE9UbaOalpwrJ){@GsQge)$Tp+os4c|9rKYq#wO$1$#6;ZEIqTn z8NeOV!TIcB_1?+mPfE8RubpJY+uD^bGC*lRwZ@P8p({gO&c&>VMYv#MYwlFi6&DOB`h?d5P@V80T(whJVr=`8G z%{n}=_I`M$XXa|;REfvt3E0Ae}XIfumOM^iqGYp()gCTtN&@IZq;7{z`>19l1!JOewV(? zIg@qaMn>a2v&%C7ne|2&S?2RG{m;i8KcDpZ3@>JRD1r+F@K&Yf1`)h=;L8QaFD^b` z+@62&sQTjB|HaGd%L3z3g5A+Cglpb5);!Gq3s{iLX}rJjl_t~euiqW$*d6TC9s0aG z?0NbR^3k+RO%>#pH#XL1of~~Vbj3aINvP^c>hDS3=wZn8rbYH#bHr~_xZ6KQ({Tc0 z^?M68dYLlcie?&bO9MoglR1&11+3oU{%_SA-HBk+*5E!al*dp_|MX-{Wl-%UukfW+2AYPG(!Y`ID$*G0kY!& z`cKzSpTYY+jYHhagF8h2T-$260A4)&-Caaz|B6HbQ5ZoM7Qk@$4h|fRHX+d~@YCJ9f`#(gWty8Fi-RFCkdf&~b8gvC*$1NWW;Ez@w9YsF*P zf}c7h3fMzDnTdVY9BV5Osz#=B!3qL&o(LHd_zl^(vzq`D0#rT+!i>F*iPEOZ9vv7c z!uOT550;*VYKxGKEZhkKg!sfCMl9JJBUDig-);E~Sx8S2nKNEcHD~Ctbw7VW!%yl~ z6O!^hU>kyga%J4l3&R~^3$GJreNdRCWK2i#Y)k*Fg%{-a2onZi{0IW;)#JjcxKFCk zUfv<^M|%g_XS?QD;8G1%8xY2-~T2?!y|8Y`@U~G zz;TR|b`~T{Sq4wh1+*@>K^=V4)NSfVZ)zOkOz4kJb9K~G_z^6uIvcl60o|0LEP_z1 zDDXoCf1iZX1<;Lj&_aLdo#WC^YiONw5G5jej3YQj;EK+fb@(g`@w$2gCTwK^Dr+e~ z7APb@1o}I{t>7G8`xHgUsuK)2x>9|41?z+~Hq=PDVbqZ?^5nsSM-P6Q3{K@tEHkk? zlE6v`NGCA*2-vq*u;b=yKODFI5(FJTtOdz^e~{cOI5*qMRv%luK_r6xU{Jr6F z=jJ{6@jg7*0O0L>i`$*5{xyGJ$;a~NumPZId3K;K|6Jprw<~iat%*n8$o!|;DgXz{ z#gYG2pd7}?cz1*URwVn0QU8qS{J+#zT`kU#eEv^FvSBj+cNqDE9|CFle-S8G|F_yI z!zlbeYODVdD97*lTU)(xZ=wONt^N}zAFI0ee;6oV81MW?B>Vdpcepj>=)3BT-~WhY z-@W7U0JH)uk`;I3_zCQSMY34UaZUhaqA(aJcG7JyNWvv+Fj)H5_+SVjSYar1$1}Gf z7$av5g(;Vg4}}vO6ow=Ae{ma*)E>cVh z<~|zlmXST0;8{8`nn-O>980?K#eM9#_h|N5^8MwBu@oA5&p0Dc++#cy-o+YEi_n}L zPp6yg`M26?oJ-E%+Un#)CL?&yWY&xSvbO5b3m!VVxDMwqa|G@FU^#EsSpJSCfu6n1M_W2ud+`L|4~~_I1;TtSE&@G%0@9F zHQ9sbTZ=W!i`(7-7-cRCkPEQd(#%OUR$~cVZ>wwEQEaL9pD}XYoLV~#dktts(X4>} zP^9(svXYnIT8Y0N?biCE>--N!F8KeFr2RFa zyvON#a->IEIDw#-ZL3y?3*m!H`b^n}X1C6uw%P80V3G8s^H^5&?b+2ahF&#Ry+c|3 zL)4`g1-b^8OPt74P|dctrmvc|FIZKv=UeIOo#9Aat2D3hPJ*;Jj8E#Ve>nayi>2n(3*M zyUm+b=anxsuuQbbrA0uNv&=9-V6C?X^o56mGW)*kvSV5fJPLVuKMyTKnv1wda+Ye% zG9h?FMHgOlJWG}^R--fUt^|bGLx5l9ut~FvZl~w=#{*qr$M828&V z&(4Rf!?SJr_ne9e<3v;I=9tdpgu2v$K!vd!)d2l^e^k7J33i?OP?BOKpqXW| z)dlv1ky547-27CN2j9zl8G5OTyY%Ud*}hAhBLv^N3C)f|GUMP4N;^GHWP=gB-ECO< zL>ZrgCj}=T=(jZ;UY?7iem<|f4Q))SS5*5YT&R01Z(F!Y7phjkn!+cV%TnHD=O_54 zWh@aT3Say{UdLYPEY{e$ItSXd(!x z(hmu|fP%Qn_esL-K$DZCD&1e4Ou|~Uv80T>Yjuh$A~Z^9*id?{ER%|KeX=*LdP(JD zvO$D4ihz%>GrRU!?;$`qMOcz)+Myf%9T?Fn$7a8xZ5-hswwAF34l?~k+c^AsWi^m5 zGf>`gkYCiUT*+xK3l@I7yp}Fu5BP6q)`aUTBca4`&epI}j6xD0*0`*8Z@ZEzGvid= z6t2Jk?FU(ooO*}gUUlUObARMSirFft#|&U3$yRvw}Y`mt{Fw)rSr10?(&8m;_lY`ARZy83Non5G$4X%|3b z+#WSNx+%HU8@(H4c*g&D+9r(CwUp-cL2AZAkfvry#&bJtC|d5i}BTmo>F= zTsPP?F){C=m1mqq$Bhhfsh~-}r|WO2UcK;}ubrjT+z60VHDo5&w-u1M@lF3@!=mMT z{n@yKbCNfYmy+(X{eb=3fF|$T_pjf2Khe|Dw&Z&mQvIR8@qnz&wXS}yAuj8I z?hPQ`wpl2!5$V1dqcUstxF1Ny%TZ=zU}?mzFhitW9DK=NZ(*b)aCk`s({cspYnm5muWt;G_aC`Il5B2^$$1n zXyuSFxVQZ4#^h6(!|zwElkaW#%*B1I9M$@Gr}nM0EQfk>e~FVJ^~R(5;llgfdLP%m zyd79tFw4~tn78f99Qc|0plbH^$9pwzjbs=68>TOR|JC}-_ssC4d&BoWuGjN?&mtra z&b6lBEo|&xJ0E+myQc;}^XjbZteq*ZdkhhMC(vh_W_qaa>&HLKk7ZUas+bvN{*?Kg z?laj@6mozg0v6Q;{O;T0JITO1y}@&t_$f#QTY{efz~5T8P~*OvwEa9V_wN}!7 zcDFJewYlIJgly)57A#C9o3ECIHDaRgGmxFMpzYeX-<3seZNlGJ6oiY%CL_8i1N?h$ z8L6_n@!F_(YEUZ+`3**v6r?LD62?)cbg+w#Y~zB*2m%Zu@*I_auM3_+LF!SkGZ45$ z_nj__;x&Tpn~{pCjHXf#@1r!Jdzse6~_THg!xdCC!m{tmEkPNnx zP$mFM>o1<-UuEHpxmX@dkGUX)hO{K0>bZitaQKOUU1Z^NcRxKQ3679$Z~xHxTJm(o zE!g!G2*--Iy5r%j)e;%(X9+8u0-rSFCmFb5Hhwn-HZ9_cAlwWW-%Jwjql4Sc;^eY@ z#1(MGTEP*`PopLtIA=a+aRvAFfD0t>ovH6rR1>=LtchT5-(P@FM$r-Zv6^ z25+jD-5N5zmGb2IB`w;H74wgZPp|VZ_v^{0U5%ed-g!P)o=i}@4Yww`sA}U66DOOK zmj#1|AL6e)Ik{jjv+A7!cm%YZ!e8r3nUG`%>|x-|7`y6I(0gQf@r+GEw~NdfU|94y ztyHNB-(mMu1c$LjYID8YmIbDjNJXl`-CHsajBR^1zeOrjj4Tw!MNk~!g*xXLpvQr*gLlMql3s*n9({$?P$-6J@5?(q~ygbwU z@~j6q{`iG$hadt{mA#(fmXP65k>M$&p<@OWF_O;eX5MhfymdG8x=_Y>-Ob4maHU0j zvu(zQP1tuN;in3j_8uxHglGbp4_a29IL{dxP&c*7JJ`F<<)v* zX6EGP+|AC{-EvhZr>-}zeeGqrN1jDZ?v>u$W?jfHVY9~#=-r;&F2kH+sT|v}{Exbs z@Au@J%?bI50$pLM7j^BugkCjMGWh&5j@Z~Dow5*&2d6xI&)WI^_?17reJ}EeF9Ns) z#|K9e?nemtj;Q4dZdI8gfFehjKXP6^3M(*4E#T|O?Dl}$e5bp~xGlq(eB1P!$@`WQ z#6Wqd9>S_EWS_7A=SUIeJPClu0x@<$LMwOHSg*R$9?WrQg1`3;tlb+{EF8H;TY?V@ zEO3LX)#zCDwmi)khGZXR6=7>>ebGBVhawo?f$}RVObrI zm`~j>Gzhp(!7VZ$46^ZW6`7-3-jLS(w~x>k=(Gh+{9G-qZ;J}=YsoTGYlc{Oy!GYD zd#{aRUdx_-C1$%HBck?NOylZ_eVRc^ksmK=(tnG!5FGrYs2rfGD z1)kiBw^dNFv$L3GgYYqgwHmkvKL?Y+4Wf!&8NN9i|MoXHcg(^p3q)`p&#>|H^f!;g zUrJsoH}oq<@!-~1@gcssL*~b!Gzie-Wct&P2sXcHK=zq?V!6MIyrwGn!qJ1e~UXq;k>bG*kx*X2>WK7ma`fZm>`m5RS(cJV8bwnD{{|<}$6Ol2$|eyXTJP zLl`Fw|BPy;2SDyL#) z5BAsFS8ZVrGA$xtQKKgWFc~=I-+v*a+vsa`5IM)wTZq#5kAI}MS^K_j9l^(&@l)g5z}CoB!bLuNO{X6qfqrYO=8grMzwY>vX~9t zgn&gm%(?qPr;4#8s>O+{s(TUleWn{>h0_*W+goI)i^gw2Rl7%M)no|R_3n3 zRD4)CBIcq8)iCShJVWKzz)OJgG81)!0aD2*9{YU;0ky~m&s8EPDJXxM+73~`p8+~D z_}4keiIcD1F5nH$q#;O+8+34hSWsu#*5T3CSXmGsUa=B}x!8i`_wz*BpkfJ-?fusM z7wf<75zAGAl3VJ-E!xwV)eZAy?&N(L5j6-NN9X`6MV)~Q%~LjJ;}6q6BB=Zu6l66Q zY^5N5bcO8lYIn8>AKnbye9;I-=5CUy6RUci7!JXb28UvlHWSHb^U#a{9i|~Arm;I5 zKOMaK2|@ofdUrM%$eis2c zl7P)s$+EioX>h%?ts)CP8gS{L%@Oc@F8DSPtab+BRXUyZpyBO< zj>w?5GAf6Zz*9}Hp3n3!cq(GDdQD5Z&?nK--M>F*1od7_7_fHwRz?tBx%bj4;=Yw~ z8{$X;f`Y}$?4y149^Q28&j;q=-v02lp6@=QgZYrhhs~ukU&?)QVRQH(-(I{GhvUJ) zoD~(sZ^1=<`yj*-m(6>hG$>U)FjOTzJ2SYgddN{IL)l_Tvv4pzVQ5YzZ*%)ldT$j` zcKF4I!4;w6JyFAk?TwS%A-#j5YO~_|3qBbQj12gUXc=Vu?9DiS_Qy%z9|3*Y`)c~F z2S#-9Khz63?lnpdkM$6YL$+%i$AO+n1+Wh_s!@acr8ais?AR^eG4JHDe+!hK9owaT zuXDddgK%iD?|3LLc|5FoJYrz{Z=hUuBC7q{ZS0upHUZlvP`_d#X<#Dx&xD49MG)Q> zZoBky!7A&Ytf-&xCiYnS%m9A&XS>vV`_I+cZ_CzPfmhSP?bFkE z?tN7&#H&qRd#BM4xU{UF%fRbuTf^ze9vp;eBQbbauM8WA}u6>IIfoO2w zxM!a<@B7@#ktt)l@xtT<-9svrOshUJZr68_vTO69F&`CwPDNSWl>7)QR&Zpch2ZMB zJ$bd_SNdxD=k!vR@()h6;};J{&yW0>-++Wz$3WQ056_d`{2hp(R90Kvyj8`nzufn> zb>88@ue^g(%419C&Pkd4oRd5Bk>3v)%fapG1KCvJDK@z43CMx)8xWqun(t!>3;4`k zkN%bLZu|^y!QdyGJ;-JtcQ23SF1p_*L5pM5oOV}d^Q*$wIFn> zDxyqcPJAD!`u@h+b783C?7@3$d(=u|ZT<$z^?gy2MZ+*yZh1KDf;)W}#>hn%M1j^L za{De1)W_S7StslJ{MUi9;|+u3y;e_4luC`g~I!H zY%h5rZanZl@zfQQN3-nIczLB zlISdq63N)5+t>8K&1GrTyCQY(&wkJV-rbQ@{bG_bkbdBuLau$?>d%yt6yGP`8&l5l z{)%J|{b|gJ?EBpvcp*JK@zS3cXLOPnSAtNHS>CJRFV1a zpPL?Sm3;c5$U^B={k++(l#!w%*l$z8QutyREUJGzY+F{;cfQz4>wBQOwaz~x+5T%$ z+wXE#a}zyo98o75z=3i$BW^)W%Vu}bbVGtFE@=NT^WCpMJLk?emIkpDePzx@AzrJw%)jHN%=;QN2W(y#vi zi>13JY^*D09bJ~#5vBbD>mje%OCA2-S^CR zA}3v=d-2~DkoDr1rVE>Pg)3{MOy)RiwEQcQ{dPLPeN-U-^*@p9Dzz!gQf)8cy_zqR zVFhIMF;QTD`J*E_6}_Q#k=fIuQ~7Vp=D!Ns`9F2vTiCnkz^tkDF#52W5n7j94cVTy zQbV{o%Mnq6@>h-`F_$7Wd$|tWrie8MqE@L{A^*<)8`5*F?;UJawGg2J=ZKW0O{^mq zDk7-q=z#lNbxd^I2jxp6>45|`YFNFE{43#7dLPY5PN9Y~-=c)5+#Y_aAy9={_+B~P zO5v5zb4Ahi;_OCT<+Jfi$y_ZLnzUh5Y7A3 zHi6QSQjd*ALOqMyWIWwe1M!PDimf$F6#N3A#J+pFUAAK(SM8;Sr89;;w~++*6NpZx zLMd*}MiQZIL<`kTX4@>p50yAa?Pn9u9+pz=DzehR98Gzp*-85{$p@z?I77;1?D#mb z+fe{;UQ)%|&N6gJ z#N?`wedTt^uz-uNE8_ftBxlL;uAMdhE^0RrDt1wPjavW_K$(TulF8&Bc(Iy){dmBp zVIddI(_&W6`3te@bwMHuHoQQ+$|12=c4)ni?_0fZIwvo-eQjJ}2A^egZq5N3^f3w~oP@}E2Wd6hM+i+q2xl+TMLbZjmY{ag1Ib>dIP&#f9?rhohqBAVk z;&eh)}|q=t9w)!IZ<0RhbK&&z8I$YUOLa0>U8X>?)DVjr)i(HgKsEoqd%}Y zp~OyjYS(D-r6}R%i5gvWC1W`F)vX`ShT;E2vMYL*3cNq$p8b_@%ET{%u>V5Ta$nA7 zPe!_Qs8!ziEv?-Ry32+1$h-@?kMuMo3>U?IMysOEt6sffbi5^%-|6)+X5Go2Da{eJ*;1wf_sY95yu0<;ZE21KMkhfc01!jSY90%aLaTlE zWBTFH<@*lzvA#!lr@hf!4N|FgVf=jbizOiIb*)Y$>N=ZV`g*5-2c)K@w7NSV;Jm z!~(RBTh<26Kj|>QUyZB#v~O>SEY8YoGZUXWP!OUkno zd*=+++nH*072>JvfGw5+A+8@fTyM5*mzV)eb@~RQyrPkPcGY>h6;9Z8A=C%{J1TBS zVA6gnu{(yRS$gfe0qU@~ylgL>qj#pCbGJT8cB!m(OJ&Co50cThtcI1a#>-fDZkUU# z)f3VgrE7}kzI@sJ%c~{ZGis#TSs=8@bgL&VU~iL=grgls`UQa6dZt!NJk z6Cq+-H&W=zN~0>36}2}oRd%eYc5`e8{&0-%`&eAado>Zjn&>Z*%R0PlpX$?nw2Af5 z7{k*Qms_>!Bgk#QH4e%k(wDLg%OeKkyXR0Vbpdj1c6B(`wzcv@=PI8!Tt^uQplk&A z<}eR9J|c#$$DW;iFe*4iM7omEB3;7T4A2sIa8L{%{|o(!$)Cc8von-yTW;_|927<` zj}m;s$Uav|0#S76F$Bbs0uV&O5CWv34aE@ybln29y5YYAHO&G|>;lca11;hLEz1I} zy941U*)fTr<12xrEE+k+J9H<0jtr_(h1LPw4K6B)0kR1~a||IS1?;8@_H*%REOavw zbBt*?MR4EUZ)~YQSe{!>MTY;lA9Bq-#4sFF zdiG6RINw}&Ws{JWf*>X}qTQRoR`8f)fk$0D2UZ?%%_BdQY}w}gkMiKgKy z9S7i>L&>mWAUY3Ocn z767^IXJT7o|H@hHV{hGw^^T9dTONB~GL}mKyT9P4M*UsyJoU&Xz|e1*85gt(h*R8UquAY{~e{^5mT6xUh!_+|^{dVoCxmXNgbA zPy{1;_D#eSI?5BW-4l>fNwemRLGxrGi^OI2b6z&#l{xrQ5L}=>7j#Hiq{7oP2~qAK z?IA;0DvjBkf`AA2xR=0+D+Trn;gY}tJyqNTEOk$mNJ!0&XGFxOW=*7R?@iA&PgBex zAbOL7_%7!l@pB~ba`UsfXD_nd6K9yo$d)uX_~#{=elX!>*u!LloU|Fm)K!-!he%kz zc`#BEfcxyr-1FZ(o}~EhO92Q%EUQ*e#tgxs5`tw&4C<}YN$Fim4VYx zggyh9Mjrj%I9Ko{1-De{97@Bh?MYR0$n1*G)(uO%Kl#$PBK;!8rTYcyIu+{BPe;O{f{>#${F$2(&D6m6ENjv z79hxvUsve9WSW@}Azuh^=j0hvpj8MQ)M2XVJ?A>8^QE5A$d${VNPQlfF~`EKHh^Oc z;m_Ka`WUa_6n~5}$m8tYBnEbO;no=$qf)QyB-4LT9-W$!)0)baOaQ}s-h@BQbZLou z*c`TGe`SN7ssn$ZNT%FSN|KdI-zfzsB)s{ZihFe@HODC# zp66to^9Stw5yCP`M%5-MS_z@!?f1Mfr*)J)EK>G*Y4!>PRY^yc@D zNwVj#@$iK+D6u|b6`V_aZ`~H>mIKPPG)|Y-&*f&U!B<-zxgl7o(KhMb%}QC}1MlsV zgs4;utlYiAz+GG~xRg_GoEJB@^&PA`n1?|7GYt>j)0JCN9)w?~gh!iVo3AT3KlW@i zRIWn+7z_AhMT9&qT|sag;KEZxUgArbrx~Ddl#J3jiIRC!QYP4;RmCpL>%>>JE)zQV{LcBd znO$M)SaJlB9UzY->_A5@(@=#-yf$&~6Y`ZS3rKBw?N)+tqJ~h}?F`fA;?n!An>@b^ ztF{N{enED8xlG1s6Ho|ld)f(nA_b@S1!qR;)Oe0OAL#s8cn<@*!&g|cPC)5tLNlB< z&Q@QdaXo|EdVGaHG*EMM*!~E*k^>cEf4ihe9CU>MbF#3`E%c)2tJBb(bt0yd1^S(5 zYZPOzaJ_Dk+n)2N{COTt-_Lw0!^uAS(D+5A?$430ezo8X%-_R(11sBlr5*j!N+Zs+ zdE_=w9opI|zt{DFku%*tWP056<3D2?Ubn^BSisK(m_|0p$m7uObZSK=ypHVTKf@Wi zI>0AA0BtlO@hnc;;HVF0erto%{d&oRLyL)>yOL#OXIUzxKA%vVpe%ez;T)S{H0?WWBrM_r~6cvUd5$ zNoz)h-U<7Io6DY6P;H31o3X9%U5(jx?co2;(r?e!uhXwA-yO9zK%X)G8o^8YUs(F1 zgA-2*#;=@F;AoHnqhyLG8Ljslj!uuka+VioC+}J}g$si6Jvg;*W{C%7Ua^}p4o;Pv zohpf%^t8w4{h91ZZ7ltVrQe#3o2O5Bv`=*)*wuTd+XkkKXXA4ALXA<=9f-_!n59>b zvD=ST8P0s}$mx-t9ojqgZSPFZ@Z`WB>DIGjsKPe=)>&9`f46$(q1w#Efb`VCG0OuK>Os}nICPPEa4e0_-1@^Vl=xK!X`V^>&Q*-{J60DJNM87X(hR_5m~@E4_N>K zqn6OhkF%H#en9^N0xEfh{(j=h)T!?a3h$O$1{<$iLteBFq=*ZGxcA+Gy>8+~ha4d> zxnHl7<92=I-r6U9MtvFCzjU*pRQILoDT0v2<*qBxmB4`IvWK(xh)8|vO6Z}fu;`_T z?<-B)Rt=AW6Q;fVgpGbc=%3*(GH1*tChVR;qS4%l^(#pJ5J_MW33FBx5 zr2>e}`k5ZTFBL-z)eolhwUzk@w`WqlC0{Q1h- z=CHM~yTVR5;a%GtL43 zV(G_5%pUEu`Y$5c|IX6UP`yn`U8>Mhk5bDkw_~AyN7-74H2pAf)j#$BG0L{}BH1uYmvP)E zPO@LU7MiGZ>)GiuYd0o8=b!t!x=+q@w7+Vfm;_1dXM|K?ifPK(jWteh`Gb(3`s*tL zqdngnf2tDxr}YB>0K^r({Qt)KQJD5VTtfXH>xXH`x?$M5S<#LHnXtEB=JP1zuAYSdgW+SoPrx)S4 zHiI_F&*-}}xASjYyJ)|hPkhhrDE)Q2;_v%vu$aN%#S_I5*Kq&DwRIN>Ay4dW9kovO zI9oy27Pm(PD|`t}&}{X*(5AHWZ(KXP!!F_W%x11ANgSw)Vv5iW#Np8bW(obBE z*e{u1h^E7F?VaR4fjd3>d)=II7tK!A;j}*9u+7lEXx)GlAK?~TYj^kA1j-bbsinuK z@#pl$AMbVBx&M*ljpkT5uB~vy$tB~1dT-LOlU6?^V27screZ6V_QRq_lD=?VtPc#9 z)S)&pvgX5-3M6=<32u*`n!BZHI7pJx#Czt);gz8yHZS5HYDS8wb0|oKK1!XH*5^ti zQ;`7JlbW80E{}!ceiR&)$m%PF*6*LO$c*gv@GGtPJ{#N@Y zbvUp~@T1v&*d0%mzbrD-M`+Tlp>%#w@>8zEh!>C$!dkkX+glYNmQEN6s7TvS{H$D*=2Kdt1a!az=ON~#Ia@+v5T_xfgelRJO8KC?v zEAoz4Z_@PYVwd{l`UUm-gCBG|iAIgMCym6Gt;TWci>jL1^6h$!dE^$!Q_7EPl{PLI z1a4O$*IJ36_8$JAW6!M7On$S?L&EvgLQXQ@mTtn>i5v+9h)>jkjdp3H2pDl|^tvdh z)NTF}>WqfXIgB7*A3wpLbi+>$1c9N;wFj$)4Yp9({8R`s{1RvKL!zlpwzlyORnS(3 z*Fp_bI}w1t!$xaGTot}Nyh}Muu-@2h_tI!36EAVZX?ByCi;WI#Q^iy@8 z9WmK5Ku_@_G=)$jhMfx<6+LOr(jSWYwCk_FaJd@b*uFhP2l%WU5>#gi?;Og>xI|e# zzpC4(9V}K)jkt_rNndMwu`A$$R9Rn`S->&eHMH>#axK43;GT;bq+e!3-U>j5c7T+o zd8BG02JVhA8m-P647{2x^8TgzRGPymihFpwE1)=Hva%e}-xLiYth zwWrNioo@0{PKY3}BJ=iZ2^SLkEnN#CQQA=n)Zx*H%mdr}t#9@&nAtg4$&5DhKKg!I zNCxzA8li(9{iTj?Tf(~O_Si=T=ys*{OVSVTw&)0R*na>m7OE-RV)GzuIGupYHZ%Q~ z^+Ulb+u~Hhr)$&zhD_wdfx^_NYm8yo`jKsYyQMREZ84LC%OQtMc3#Uu9#Z_4Wf>c0 z^_L2hBXf>tT73SO^&{uxo0iXcvNs797jx_`PjnR|{LA`L71pI0wUnRuV!{EoepK{+ z&bW+II`eC?u4rKC6%99i{GA7(YJQ0+w3vJ1Lyg^av)6_6%gVV}a6b{#*4B`T0K5HXI#hjvD&z#4*HW>;xk%XNgXPNXef3XV)&>&5` zL>ZrV=VIGMQ`OiCjyFamPJ>T{oW`H+-H7Ak3T>?);z17ilyxiNSP7V#*5O*4-fxJ7?wc*L7Fbah_w#};tC9u0w1|d(tB9$r2t9q zk3le1CIEkt;-uGpHEMKIMM1>tLZ>ZOQ?eQfZ+_4gcjsIUa9w$UPj^Ge4X{kk-A$KG z0sOV5=lIn^ozWB+Y7WrBlcuMNUY%6ZX>uC&NaElWg%Nu_tY)F+FVa<;uLE&T0T!;Q z*xa5Vt>l`>^DMY50b4&Peo=cp5mM^3R-r5${#u{rH|FTAxZD{3YkFr6pDR^-5pIK1 zJP;svxyk6@VbwrDz)zyp&QZJKYVbDNcJK<1(0vu07h{R3o2;?UZC2L0dC0%ZHM_J$7o;h@{jqYv_RbOvl9MNq&e zeemAB?OwK@5;ii1NSFg2O4p%bv7A|=$`^!QRDOy)gv>UP>Q-2;?hKy34z8cr`YqC( z@bzbCERMtfai!yyykyAH$`P63m4?%@uXGYBN9Al+Th#~3r1~qzH+SCoh#4qrmIw_u z{kWE1@^z7^<)Jn7d963`$5P?1N?nKHE#H18E0lfo;cQiE+WF_tieajvZdc9v=+`G% z?C9#n%zZvX>FFAr!_~`Iw}al^yx*L^){n-cf94Z;>*Gh?tu@L;FL&0-ju1^+N{{m5 z-JE5=$A143<}x3^SYVR^ILY#x;^5)Ibfg(L z+ZZy-hJ})#i2%5hClTnS9cWpIN5WPLBE;E`M?ko^3n9tckhesTv;=r!&}a5eVEc_x79HfBn z>8RG_8*q3MuE;lXoM!1xCf)cq$6(bI;_=tx37r-iA2++zBdP_r!Dnhe?o6fU91doXP z#sd3D;Tr;vh}~k@-T^!9=@>wI(A0D&jl zCj4iZIGC>++ehiy1r?V)VReCebLeIU681>)#oS$H^E<gBj{Ld7QRaicnhFka`^?)Lw|3H!z=h()`U3O zLjmNtn_0n!>^37fLOeE^Pb4vg1iq#}?c)j#(mcI5SZ@fp$T{~w5InAsfK~86CIPED zp$n2g6eHn$R&ZJwewmCjpduO|qa=+-~nZ2qIRXPzb?>ClCEhC;TU&P|vbd(!;n(wy&dIT5fq7a?O8V zQyM`M{7DJTlmwUrXg>kk#YV&v5o%#HF^6=rU;3Y{2dMFwk~aW?h~5t%(KQ056+Y$; z!ADwNyixFva07=WfH*dW&*>!+fw*AKhae;E*Y26;Y(6XWWR`OXK|mmFUN(_oxhQm~ z_tBN!yQjl8U+;}vAc8ZdaeS)$wmg>LFLMDOYKlOrz%NNbzlu9&CO0QkWGD4zKbP{m zGyXrgyU(bm7Pei~GldXBk{PO02~E1vrD_001k|926p>;BL=B39f*5*{5)q}U0aSVj zO{p4+^b!yd5j7|R(gZ}MnmyNA-}~)%zx#}{$2sTU`OV0WWDElHdG6=BZ~agqI66Ou z%kuR(5gyzuC_W*=STAHs6qOql{T0`~SyY`-R2_FOjsWAQqqmn`AlHr>rTO8b(4!&Ci-ZVBkT9dCcE_jp$u2UG(HyLkh8FQnI zg&D@&hzGPLNKhq&YogB?F(%d-o1>+F)=T9Y6E|6jFd82mRtzH-uCE7u#W3+3Ou}sO zbOw06JT|X+JAY8HKwX*CZ0S0uaFc^ylFJk?x&;M3m4iyACCZg^ofNy6Dv}l2k|m#1 zpsVkV@|Q{_Yjkk3vskFEVn(&Zq^n}mx>BdEOsy_!IjlmHzeKp}0hbNRhB9F8;Er>i z(mR-NH9;9;=Ki|!1G7vS7m-am9;!N1=%_4y%j_!zzq4?L&3F?R5gEzIC8OsK7pnG1 zJ}SjjdZ;~DGsd@4uqHXrpSL~lmMBHYB0HE5oeVQ~w1UO~k4((U?9(5mNCG>~ftDLD zwr;+F5%3*MZ|@7$8PV0Uvdq|XOc=Bsa>w4F%3$9?@xC2TS-i6Z;2OJn+YH}zI__IR z9i5IJ_pW)gQA3if?O5c)ov$s4t}T!hgfSI6G;i0vN99m?klCmMbc8FL=N7jRgy!oM zP2>m-vll?SGO=8GRa;l-k`c4_ePxeC=|10bK)6pWMhn1zIABRsQt9s{;nC>{n0gv%m( z*v!R6rYMve|RA2nlrY!cs{Y}~pn5GR()Al>(FjNI+ zsF`?zfNmDX!|32oCf-=fFX2?m;nC2sJTQ?NUI>)q-ZGDVCT8n$RjeS!<6$Rk^0ww0_?@Ux_{Uu>Mr z9l<7w(i>&G@q1h)KfXm$w1JKbm?|OBzCe@~^(6=PgR(63xVoG%-VLSFoR!(--SZs73v#BJyw6~n>9+GI4 z?ds0S>*1(Zs;QNKG`Yc+?49oJStR00V4^B^y`Is%%VWjGV?FcOK68`4+W;B!oHQ-iE-`zGS`Rixq7c3{C1OZLaIM}3|!Q_?G6J) zTrV}U9`<%VI3ix9lJH3VU+Rap=^I_H>l;mtD%mAa?t_GU&($3tijRo@rGD&l9kjeP zX!UT=x?#}PbPy^OH2rY3dhreE!{9&ahx5Y$$N>S*^V|0nyO{o^ew^q5kGQg}XNTfY z!)%{niu7AbPqBB;@Yl&I&uliu(9_2Hu`0e8Hn!o0eqBS3@OL`^G@pj+)mEgA8fF$}4^%!V$ZCev%a zOUSE7sJWyIM*CzeP`}>u(0IJ5;>K%dLjp1WefPtUNv_TF^B-}jPiE3p@Nt{_hP+2L zc{|wRuJlir>Bx&I7%R=OFg8l4z#ckgILk^5B=TBvuwstL6aruskA_iDMzS^2J)Fby z9Kz1iUDAWGlZPSc=cqW)2jFO;C}mkBhskreAbr*yYg`63m)URu+}2rS2<;xi1974f z0ly2cqhK{iDSfp2CLx238=Sq2lY)mwV?}*ntbl7-Ja#ICgG55pV)cF+uWBfA;R)V= ziIW@}M{osp1-m1#;y@sapTxX6bOCAio^|2W;Ke_a0^28!IJHQhpIE>6IbgAx)xy7? z5NhH6eujn^AR-^L!86Pz-b!9|U;Z{y^wA5*CG&5}e&5mc1h(0=xB>^xZeaR994Cvi33g$f>Gsl0mQ&z$#+$Ba3)8 zjn^cUm%Rw)5_wQXU*;YS{Gg6~-!qqWstdl*<+S!`%4wOq^=Us1Qya_?zSPCTU8r8| zeOU2s$+Y*QEZ4bGGt>C+V1B}AwRFR5@7O7uGA@9g+o%jP8MR1yW1jT!X~GYc`7g#? z=O2tA&xG$jhkph&e7qF$Gx+{br-q+LzW;RlzTnyCl*RbzY5LPk=56}+_ZPShXFk2X zEdBe+!*ADaI|keyzES#{V*2~ms}r{`59z9{hF=DWZmXxy^0Nkiot0UQJ2D*nef8{J zY~_?9uK}T)J!0;*=9M(O=kV_|8DX~yyOOeXqrP>+KUg|E+!uPyDXPJ5hV>t2wraadP0rt*w95 zj~9Ng_RR75Ei}i+$S(6!43^Hc#mt}j_3lWHNyEXefe2g2zedc59zXD|zB18nig272 zr9W=XN#?4lU5|GPXlnb#kyX6o{7+o_)2j9J=IAx;#I<@pTING>uK2mcG`ExQVC4%a zH$v%UPVwD;M$CDgF7nq;sh@s%(@5V5Bp*s`h+q11<8)rJpYRvUH1>1;U5$_8*DtF7 z7zx)j=Tk}{*HlYg#cO|!h%LsF;PeHI>}d9rcp%MPj=D>kk7ei!7xTm=2x2dr#Y(Ki zoB!>95BO$kPa^W?RU!^N_T)n%1$a-+eb+|Xit%1?#`FV2@m6gHSczr?=nuQXb20^b#OYbcucRw z8B0&&rFTsy0?z?0DtUi8rwS16$CmrlaunN-2h8>iNqIkg?tG!IIk9FTUsxHqgv3N8 zIZmp~rUkF?QBOWP`TpQz-^V{^*q=__T67Nj{`v$n;@oEZpm>Q|7cqvzQ@UHqqi45A z%StPuWAspkREaW?G9 z|8a$2J#m7T+xox2;ZH`sKkfp!sGBDbRy^y;{HsFr#+y@AyQ3{zU$))L>(8~ir|R0d z@_Fx`m|6-yZ5ONi**`0UqJ8oj&pjlU_s8Uftk)O*1&6!bcX78C7y|9%411e+tRy*O z@BdmMh^l|ZCm!0YJX>3C;{x3xp#G{5UA8mpt0Zkqb!Y1AVDySqc+^yWdy}shHCwL6 z(!RL$NK3^bp*?l5`s(bk#`%N%hq=!qyS6Q0q%XZLLX<3ym}x2K&HP(@x%MFUyy1+$&gA3Uua($wUBdq%zN{%G2UYie7*ro~trjTsiDBTT(q)ILoM?>@2uG;`L^RY1^2a zXmHFBaj3Lg|1UUvrm&FN;t-Tl);?M7TlsfNy@25}Uv1ndM0(yiTv$*%+dIlg%xvOc zs9$+zz0hEoeuu&MUMpEz`hHlAQaT{j+@`p?!}i|GF|Q&b=^^T4*^gdlqxx-U4$v?!37YS5wFM0!h5#4xHsGC zjxKI)*BvU>!0C;+%lnW05Y-?L1R1Yjc0PY{iTr7s#pxab%>QB=BpVA^$qldm41avt zQHX!4V9t(ThqapAt((6(-mTMtJ{B+2;;7T3MfFYI`R%EsG%&-EkFW$PpNw0s@}zgG z^u9)t`FE$CxQfN=SGu5`bV?sbMrp z^a%+oIM^h)C*NF~YX!tzn;_!CVj8udYbBiBmwS4f|M1x1sm6#2W}J*~dJEej!9Ha% zqT7I1pjHzr@^Tz!zIcy#T?^qAV@^3ia1bSHAskJ@@fIVIxR}NS`QRf&12R&7n5XiX z_%iLWwzR0^GCvqbb7i|n=@trv?+gadAne9>z&YV!YBE+fVVu*L4`pbEijw9~kM;)6) z;Nl*YJ)DI$gW0o(%>vKvO8yDQS&Gyzj zn~CF<<@Nlnf3($EG&$pQy4IYL(}4#+%jvjmhlh3}y+-Bb*=N=BuAGUN$QTaKKQw=K zuP`;2+b|qHjb=T%{%;kcP)c3!1ko~l?xHI%7{K~c!%krM=h=LiasFL9(!;p^;(}{H zcdk{Z>%zy3*~I0H-}TdnN^idH`uMB%cf(@B<)Crcsiml-`sJR|kl$UO{*<5C{w%VzNOE(@%j^pJ6o5r#i2PAw?;Zwz$ zr}g}z?B>QryHa1a3om^@`+8o_&#mA6Q8T22Kk1t83F$e?fvjQJgjC&X`wxwyK%&Cw z$h)g;OB_GrVXd#%km=2{jt5LWHzpE)PMPiXVMleWI3-4Ph?aeWZMl^9dL zVo;6+ug5n#n(tUP?rlsMr-lh`lA{e1+`eMB?bG^!haW4c-D zszaN}TsF>sL|!UsSMcq}?-N-YPj@AhiVh6foVqdi(Q%Q6Af zvwarCVS2Ne=l9id$*bH$Ba7uUEVZS>1j6&uSlqI=^?v+SKh;%%n4XTxl~^VU%;5yX~^;xzh`5 zTy2U4@iSaKv*vKid>d-kJP%z z=?Q8ZghS$se&D~s;rZb!9K{+%!e@B+!R2tPv^l=XH_47xK@CU?1--6)qm=DkKqxQ9y2P)_`qo2bx~xHK&kyLfhr ziPQ4K7YKqOU&xM~F|@S&@OCla3Kd~OL@{JhTV!b7jG%M2 z=}>vn6p%L{Ob2Qk&G5qeH#;df$<9sRg=r$25i!siz}7KgEdlW(P&l1%dW#xh@-F7_ zHsEB{nLDB>-htsPF`$8nfiHpB`&e^=&?#P=5gUAPhQKA?PjD1TXWf^}p&^&~^N3gB ztV4+p&wt;xEGJ!!NP6;^}ErR65RH6kj0N{sb zqwJyEvu{yuVt^lw&yN7av(SkJG397Qefq`E+E^(qjQ3qEmx9lvS)W?LQrQ(w+Ki%~iSreU1NVVvbxR85y`!K`tFU;q5LzK{$%S#WjCdAbW?^9stf;oOs6H;= z##|VJ5eBKc9{Z`)84?W{#hpflw#(o$*}1K@unSrt7!~w&`uD4r4Aqv5W#li@ZAj@Q z`2qzR-MLo`?Wt|FZg^aFI!4(c8Td1_X zGk=Q}Hf0X(T#7#;=Y6DHA^F$YH9`@>t~3j!_@}mbj)aAHAcPHbxiB7}$?h9xQn$sT8XduYvY~EAb9;C$$N-oY)b&X(=Z{w@iqhpPZA%DQ~%~nJdDb- zpPK2v(U5BmUK8=0Kk;(1E`M_o|AQmA3E@zD{cPyM%W2H%Te9jWuy#W@I2-D+DmsG2kPF^{B$9o8N->p?(<7TOpU7?&aVK=s8 zElVWsCLxfwU(B_Pr$0?`_k$BlipTFFwL-h{v1+R({rY$FZyFMMfqQUS9?QiThbH7f zE-@WOe#0d`;B7?de!gZ!02MEFCH z&ATo%{f-~8HtRijh(KYtXr-cyJQ3e%$e1-G)SOspK`^8@LmA=d`S569QX#_5~m#8X0ufKPJ0 z9GUICiiZW29)123$I)O2?!td5xBaa1Qjlk>OaD*dm8}EnkG{w?rj%q5^bZTbV1MUc z{~lVQfhqt*EdC#dR{zm;C3zmVfBl?}8z( zvXu)KZqB83NFAFjWE)ucmUgJiFKEv;sqLse!wB*&oq^95rgiq7v8jL;jJrv~)We0f zcprw5tGyU;J&(sUo4d7z>M|D^`mE%O)0%)|OEqU5j^XNy4(Ik{vmKicH7sK?OY1h4 z-|w

    $tdU!#L{qG|;d&U41b0>2A^`^W~O#IA{s{bpaf(On`^}|? zh;Y7}EZ+0#FkXe#F>IlGxF!LVEL;r5(V1AICmhsiF-xu9yOB^FN-8J@hBav9m*tSq zRcuRQ3=poSE-$=0jsD?qRV;w+l|@&?Xu<`k#%QEiw_MZDNy_waoRU(owmtpucb ztbmuSKzWQSf7;?5u`Ca94Wh-oep;l$981Key$S0MZVaiuJw^!5xG3Pbf#0nJ79!O~yFmSvh+si>KtG_OPp8)4+ zGZ-8yXNM_ydGJuE&A8`w2|)a3e3z~zHjW)Bx;i1wP!1y=wu?Vk$q^qLX~tGV{+sWY z3q$!$A}N`SrlX}u6e;5JP7f3rQXv-JaU(}x+d4H_p*3U7;!li(1{taGvEUSp z6AwqM?}n)6$#0#ZD{!&$2z0M%hQK4OC55*$Eh4Y&6FiHF0=aKm4GXD={T!Hp2okOz zXNEjhpUvCuXo+p7@ySYs%Mc=8;}*zR&88-)YiXhSzQmaGG+q9qL`&rIJNP+bBYKxF zOsQ7@v!jwEI=0v>z^PH4(weakBOnz8;g~%qWr2&;Eh;AC$;XO4h`DIDE7V5RMV|Rm z{&Y_Z`nZ56az()+YgQ$`rF_I&mgh1lLU?*HR&1hCTNw`W56)aGAUu~Z#@o7iMfj!gQP+^QbeK{dgI{n->&C@zc zpGl0jV>WKTZWX2}${T0R)BNhU(LJX-XQ!u@*81oU)=F5t!ZYrtp?-M_fsoKdxm6G0 zha*o_TlULXsfoqe zLqkT111z&s#{GBB-BBIoygaD1v&`Gl34uFU4HupCX*e4sd8`KiqTWR=(I=wgcvE+H zc>o{g2#`DWJ>(u~-Q;^%>Jv%e#Ng9P*@V+sIYM_T_Or$>F2-d>NJ`ikB-#c?+o?Gss9WlOeS8Z%U^LzUP?dXJz3tuKj^J{todVf6nvN=V1wbmSQ z>FT4Y`YEd;wF9ZW{<++fheI$_#_7X9p%T08i?jp7UmJfig0^Pe!Mc&U#GhqomBwh7(-(OzmYoC$8s?d5J1 zK91(|^z|XSq(*$sVjK7g8c;h$z=Udik>!2lXJ1YGkwK=nU=6Xkg02NXVK{}mG3at9T~!0!;ROU3nbaJ?+tX9|`-EdZ)O z8HRvbYWVu^@Ery>W~g|mGOv%93WtSjTZxlWq@D)^8;F6QnLI|&moSkZs$0{M!*4Qq zZ5P4)bo8h@5~@jq_`*4;_KJyG1Mtv|+{I};bcDW11`G0_AB8$|+rvK7ETHl{|A1R6 zvbX2xpc4f#4B+qFgID)RxIRfTDv3liRUd?$o*`-P5SM&{2-0hu&(Nm z{%ZW()jHROU z(8ydW&TtW`G(+exQCk$0KLy(*oOqmy+s(pp={#rMK}Su5;}HIR>OG^58;}@l^6lQS zP_;8O;)9W(Ma{6EB%}vH?lT1s1CU$@#$fWt(2!7HdmI&KOu=um!68TNMG`7`1*?(F z^PYkjB|q??fotyIc@}~m7<6gvL8ek_v|g-#hj0jUH##|0wG98$9qYr#V?g2kKte)s zB1<}WCI9XS9RU?>IlG@8VWC{e4=m_B`a}~G(gSCJx9Bx$F9)?o3mA*e7)iZ0Nwd*A zPnhJgGY&LrxG;%&X~B@6F+t%=Z^6$~@Ig#I=vrR>4ZakCZzO#BfKdxU}2nbpx$Ze9sRtR!f zFEAku^lby@+(B7SaDkrls|_4QgDW&}Su;05Om0i__ItzZ^t^x-DsHwC`+0H9wh zg7i#w_KwW^c>&3JVGig}f>(SXFD>xE4SUrm#cg;`A3Um=|GXvzp3PH(JVC}>I*NHl z8NE5Gg5Q1&^WhkQ%*K1MpIyp$Ob@ANSd3C>@Q6&n} z+wdZBbhw!*vXLK3C&qH})5oo4o=VVE3!dBzxcLGfmxoJrC-f)~+&BfP*{4d!^PV~v z9h<>l<;(m4WHK|v-+G2jy_LxIDSB#jgKSTTI{_}y!G@dSO^d~Ss*X9!I=3c_qxtllqg*`DqZPhoH-A=Xfq~MFORx| zKi5kENhaKwxu^=R)|R5)mLltz*!N8Q1!h7tv;P?r?@}fjRQ7B1x=Z;pLF2MNGo@mZ z<#JujOD8nn43x1g%jE0I)m=*WhyhY}%9AkV-+dT!T#T@^6(}9Z(0E_*qcDe5r|7q% zqW)R={Cb(;or-CniUT&F(QE}dlc72qI!z;grk3oxbH=i+;s>X48Ur4EAL?0GX*gTy z9Kbl0Sz$L@aVZr$Osjf$mt0U*Wg{u9+Ij70P^j%j8OaP>B*;Ped9%if3-2owH=e__ zs1$xv)jJhNHsBB&cUTgfW#gwt@w;v^Qe8k8F=i9ksVfc!c2!0im;cgy6!RW8!>mqO z(y0tn%(1SRu?D+m_@F?p!a&SANp6`2R=<~nhRBoK0J#AWJR^}X zTRBe<-lvI~r-Z}+!j4Bzaap)r8m~K-^2nFs-9ZE4p**kX;E_A^azRY!URS@P{$BQp zt7>(|F2YXQa5sv^YgP@s48bBfda{jSRP-nj<-7=HviJ)K07?S5+5S>26Z}HdzS2~@ ztR^lcQg?Kt+EkV>rHMd<@;163x-A5--J$8N@fL(uEEZB;o5oHH+1OMIN-=*?LSc(| z@wxN;MHQx6$fs0ANC7MuwHVSKzzlMpyn0T268Z- z$Zj@!US(iRplaW9(&TL$Z9dF9agn&5BmNRR7&9ByA>W5b$0K4Q` zx6EHid$mm2)CX{>Xao$opN1V+M9#a1T1{YL=x2HZF#CxF?0#MS~oQGAzyoY9| zmC^=PP=nNDZMRKV_YXpb=lc$p6tnpxn8JKEL_=MsbU*ZLUmm?S@6+s?+Ow@FXIc{n z_bdKv(mPVzyHd=^n|%(qYgtlP={VW_vewmHy7I*r?%3lMx0o4!v z%iN5CC7(As^ZkaVRcDJTMrQ^>bNYAud+ya#I4{UT0yC(YgWICXZ;^)_E)E%A8FGF& zuxl;w||tPMvQ0i2s$kq+9ROa3l1Nlo;E0mmdDrcDHu` zye9>8F9LEVaJ`9lGUX#WM~C#_?{iGwCrQ6Uz~JNEqj6hrLk_)v`9a>{;!8LTxtmZ{ zn;`ojL4F;`SSP$64Saj%!&pzk@FwMLz}EX$8t)=YOpn|e+s6GoT6#!c3)Ayf8mtO@ ztJ(>QVKeSFyc^LNEqDE}MaRQh7`~jPYJa

    Sqi zBE5L@)p7}jY{y0U?)BY4bOelyQvCx4K|aSd%nZE=rimM~sDF$5lCuRyx_*&v8h?4G zv81!66iUu-2cWLaTpEJQ=Gn9Jrbg38Tl}XbY7_aT?Cy}^fDamvN%io%DDef}WEJQS zEvjYql`E0Z<2srB0sKfudov~*G(L4pU>RH%6q@D1pCk+skSzYGDGut%x4IDgD0R70dmgvYyMuG8Iz->wmp*Qi)TBYOC-Y%TN=N8x#T7o-^<*BBoM9)A4xXJqcuOFshd zz+rR*m2U|zTYD+j`p4A>bZxX)cXVh_sAOUQ+qKh<#ay@PI=XCNSv21omD32$BEs5B%Pt zS33!}+)?|#6AvVGpd2Bb-%GefLI>=6^Rq?HG|Uj3{HbQ<`SDYKrlcl`;(CX|ZZO(YcDUT4PD@s_Q_`1 zUuno-?pqiUBgieA!rtCWdOK+^wE}a`6Ob+890}0a1Sd6h$;I_}*!(we`yO5Hd!ugV zWo}{ycl{F=fX=G_E%%C(hT87zKJSYY(KywT_P^#{|LK`Z>v z-0RCo$rB4F|BY7ouiWc@Fvb6ByUTL=ajy5F>Az@&Lys*V{)<+)wc81z6}T7qMLtjc zy7aN(Jj(b>^KXbLwn+Re>KEG@(WcW(r;H6$6Y^~ zKi+<;#I@q(tLWP!$BR#t!P8!Sx^he7&*rU$xLqXJhS7fF3Ah1S)QK*XUz@W2Wf#?1 zLHIO@e^)WTNEjaLZuZ+TBU04)RQ7&zk4^w-A#x)APID;W&u8h%3Jl*bd0DFKaTvyg z+>EyiDClXDN+ukVzxgXcJroD!+;{L~u98S!}fTHhsGb!&&?#aBGL za~%?KtOJSNxZSSTB$xA!UNJ4d=6YjF+G;qyeLmu&2A7X6bIa`J?;I-k>&)ZZt80Za zksBS+#0Uf@H9LlHc=~wUT4%IdID#|fQM!q9&$xtL4y02IEUPC%c13x~oSZ-FRGPr+ z6L_|Ow8JYwhjK1gc8Bjy^i-Pb)9cfUXG%F@_xMm;yVhE{W_2r;IOkj~i={fp!jJbkO@6x{Z?b(Q!^(o+r zRd3+;Z_BG#=N-d7pQjKc1u79KVJQ3hPNOWK$ozDME{PlnOaA`5)J7(Rk<>YZlB*4k zIZYJekNAdc!nZDky9Ecj0JZ%lK}dSo8;%?5Q%-rIx-YN16f$E84*#Dfh&i+y8G`>m z+>K0_T~i+V-%OCR1N_W;k4ztvZvW{%SegG{f!_b$??&21_af|+$0Osm!pEbAzFj5n z{f`PqH932HwC1U6o!b9d;rM6THh!Ojo;A>+Q1B$VP50ZxJ+h_B*A#mP@2~eAJ!{Tr zcL{$}JbqBF=Ig&#IPP5gnt3?1-1eV9Z(uUt)FYd(e^ofbJE!QDH?+^wq1}jbx`p6O z{-LPt71K{r{;W+u)fIR4ewcizP&qj*3Ulnq>9}`Kv|#=>ZGo%XeV&oJbh+tIid^(N zeA0@x>r53|_o_V0^Nv$hx5>zWuD}Kzh162(2QuPydi^sLG;5x%&oXKT9I+M9j>boC zSm8$zsbS|g-={@*gdjZQ`-6SUNwbM_ zKlgX-tntxOL!UXMSBKWMz24PX*_ z{D3iCXU~J37m@S}Z@Ms=h1(t=AZ?ztFSbQH-aH0+F6Hagno5s7=aEn1OfI5=xuwOo;#3$6jB}%{SITw4r<(R~l)Y-2O-gOr~5!jPC9jSgw08o2$&_PNl z^NGFU4tv*e`Z^0C7*fU;+S0r2;7nGfiD-Xpl)bNWP%eVsnXFCNcld1FM~e>O(ytod z)31$1D4FgY^1L~<|`N6s_&4s=+)c^(#bj4brpDo60zDaj(?qF@o= z)4ab>b=pi$ve)qkwVw;FuMBEEF^e+T0}B6GE^rhO0ot@GiVvyt>Y@1t4@o!U3yGG1 zNq=mF^A*O8!ddGjBh$eAT&byuvZH#~e4f=>DbFJOzFIMc0Q}6i|ogV31leg_d`w5?NNe%whygJiIMre#Mjq zPuYB0AN~Du^}hnWGpRDFhTlnI8HN|TPj6o)F-=6fIjFw^y@|{SCEIa~%W4zhdE1=_ zvr$0xc(Zhr1)uR411YoGqI|e4?nL)z(Yn>wnu%rcZoVK)rbYC**XcT@2Pm}hyN!e| zr$zgIx-mG?3bXod_Uc@cxba#CIk7y&yWT_LLSowv2fw5vn?f3IPQP~1zw#i@c2c{} zvH4n6`D9b@q?XJGSIP2^cKkcvNoduveSJDAqty1i#`&7I74%AKX8dPOq1uj1&nt3r zeL;UQ3yGj#5=m9T?m;chO0(2xlL?!on!k?tXiLb@%t7`J~1>;Vjh9Bd=2ZG zrLl=s&(-F=T!IqVm;YQbp36?$g*8L(&wpL&c0MsA!W@%n&$F9GH6&EY1J^0ddq?gj z0lMkiH<<_as$V?g_T}dLYmcg4?2kGtf5M2p#SX()mL=N7%W>)nC-%Yt8wG_hnW4aF z(+8m#-w6vzJa;Zy=TtvFr2320Sm6HMA-57w%$Z9sQ=*#%E=^fV<_`03JKijP$vemZ zFUhU`-Fn-rBB5Cly^JTB{vt-GS%pepb9|(g&P1flQu(Y{q58oAJo53MWtfv|DYv$- zTo)g0{~5S|ZL<5~2ch`-cQ$D59qrdX8v{fPOPpoa8p6sv33D{x{^x7L?Fqz)xm{iQ zyN}XyRihpIBXX=KFKx`m$MQS~D>}PM%PsRdajuOI8!rLZbH@iCeaq zb$Tq2`zn&@M@K*I#!TTa-MxMP;PmSGUaQnY>m1o&Admw!4${E39DE*yw-lN^Tb|iB?Y7JU@n`JEWE~}} zL`Dh0_oLhoSo&;DUWTTBo93{CMft~FPL3@!xO4v3 z$*cCfa6h~_`i`dDoyyfaD(Aq@BrNGbAhZb)ZMw5<;LJ;O{HuJA7B9jCJzjD-qBk%> z!}3y#*q%W#`B4_ACzklxAaTMmaWXJ*IxTUgI&m&Pap#MK4~`0M21zT9Nl@wHYFg5I zb<*ZY(w~teNU>NHOVWZTasz4TbQ-3Hwg$Db8Pbp)vZxN4u+v>pr@MF+nybiN%`11I zlrFI#Nu2Ml)D2nL8_CLRcR{CQ=>kw?Em?CdN!%ODW+kYL%W86CBeiPot&7pV2?8J7 z<92rt*Yoe~bV_m*OWdUT*my_%Vy7JFxObE<5w_-fM=u5ROgfMbZn-DrNBN9ys%<)=a{%H}UH55OcUxm~Ea zhp%ygG4}ytsr*-xjKqQ1Tv;z~Fhv|#bH9aHLP{iK7?kwHfHdQ8_-nc66W?I7`H44C2l(dHT2rY#t(T>1>wLJ23nFi36=!d|^p_;y{_Z z?R{m(1Mq!`S1-e}WiL=s2s`swrr%D()aiqF`@{p1zdYI(o08vZf>;7i?{jzFCvUQ7 zlsS0Wiv<+s_0&Z^YPb_ZI6l>vtKT3m=Zf!)|$Oqk=o@|{1$K2BwBYof*sauQSXIi=^U*Z|( zXMe=fziYxS*5<5<<*ZC6bGf9fJ4UH`(-)wmFS;XTYY~s|zz>snPgC+QN#q|8FU*lB zOmfbm`V^)(-*s#cuAD01NiJlrKRf=dkXNwid0f)W!J?|0MfFBWurtA-EAQI+Hl z)>RzeFlstyoyk0!_63_DUbUEA=B2_U3c4MiO?Hiaut}G-cd2rHU(tO&<75T2PB!pH_FsNC1o4%z!L*O}_4{58h1xQeH>MRkmz zTEBWCLEgW955@l2OaOe`SpA8ALtRBvkxX&slOi~eVjaq9(B9l0b&4wixG-_99d&Oq z%Z4&#-gbc&jYW_8 z+m6Oe4MWtx?2vqFzEs-p(e`^$?^#`gz>d+ZFe$R(X#2Sei6b0Ey;8-7qXH&_m8zrF zssrNAP5Oo~aPh#k?eXg?_iy%2+*vWpWK6JOADxDiT^^HcXmU^OeN{6)I{&p)XLQK?K3nd6wzBf<&F^PSiD~vV z$hyb$yVU8;+Uc#{>Ft&2&%dX4B%XgYe7@)Ld_VPh<}AEE>->Q&=3G}NKoX(9@EpR| z0SSk*^_QRm%mV^kHy++YfO8Pxe;+a+vhZ#UTuc%GYl{20dxU>*-Z6Ty@A?)=6ui1E2 zNB_001t0GU@vEXZMsxM)mtGE8144kwP?2|7PSX{1%;Zb&Rhc#TT-1yMzuIM_4Ad5l zOvqo1D-a6PcYm?-@U$4OfVw4DF_Z=vu6QP1<9gwL%(qIhcQ}W@vj5wBYsUX)zBMf9 z|Dk+qd+_Ri=38w>vTXhj`Br{T7N^jY-otPI+k9(_Kon3Y2xHeLpUCFAYHu=0PRg*= zOm-=IHA^I*Wi?wOesh)lUv@aE-J9%E_K4Ek|C(>bL6p~hCROF^)h96z?bU4+W8_WF zu#1VsXB0En%S;27Dz$)W{D2A`yK28u&hyn%Y8EEG`NgOXQDTYPNRqG^pXA$owIS@` zJM~fGp@Oj$4D?JP7#n-zYP6!5Fx#4;hSo%S-?P=6#^~9xQC6o5N{8)ZZ8d@Et(z^e zOGH!C^NR%1Q3l(}go;dMJ)BZ9i9HSFLJ7(+RG!0P2XRkJj&8f2H}T8oiwrRaX=rp& z$BsKrqlw4W!d4X<;OF`2Vn8nbK^pTecvuj5A3r3hHaB1@@@nT+IDkfYF@jiT(#ACw zjX=RYzZ=e5nraxzfRu(0up=6mj-TW1{X*xZKjysVn`yQTnEf)0FHon5!;h(%o^rEt zuth{7N{`fNtJZfIU-Q{k_qavSvsWv_WWrROA2W<6U+(Nnwhy$*M8~T|7 zE;t<6^?v+Jk^Z|D zIWT`?ZN?F`5iILNV0Gu#hka(mF}Zx9pDm<9{nugjV5Qca*YeAkE%Y}2$qc+GwBoYE z?x?Tzl;$I25~I0mGS1yS+zN~OTV(W^aBl?V9=3M+NS8#T{>R>S@B^XG_R+R_r+Vu1 zjyy>DYJI&=hgHGrVkHAUm4S_#P`K(5ovT`E@a2+Q-(p6AKwr+eOiW!EaN@-4%U}M! zJNJBM_*6W;o}F*Lqnud%`01C+r$-LXSpr1>9s=Gdi-Q3r{V1;UAPUj3e}$Flj|_Lg z0)(ch5S_7pR0Ku5ox+LD-{p24lNAx%qjEcs4G2B5C-KLM>HM835?iKav&QOCafyRc zpLfWA81;IrCJtnvi?7rvkPlB}m6_D>nQXhMRsMPrbHxEu%yN#*tqB?QrNy^b@V^_3 zMyxE13{Uakvo}+s<%#0hwRG%l6pYeZ-<6`XTM%Kq*)sA9a?D>I+X5D zy%(DtXPxz4c9i_+RCat&c|35Rv#ta|Gy>9#($?hw?S7l4eN{yg$)(b}Lq`lJdu*bT z_ZrtU8{Y$KTF$*GE&hf8oCN$VO5O9Nusg3BQeuTks*Q#CZL)ULs$G%~UtL~Vpy65W z*#@!sx*|X85);11(*?^~GvAF?zkBhxn4*C&-xe)cQ9 zO{;bb@_N$((1cZsz{>$#h{t2N++OV$zNm2+#+>H*cID#lHDTvrq|v;{^B4$T@^_G> z!S56_rgs3NCt#%u`dW0fsb12O-wFeyX=ck-KK=Y`$0*W$>;ST0(6`9A#EJKMv+Z2K zaX_9EIf_ruTy5sCHgx zNbZ8qM!gFadK(f~%^^a^6B;R_rSQIz*gVj$zk4lb`?l;Nho>+9wY*)_w;g!)*Rqa-)ZNRMio%}%dh_eakFRV1q+xrC zV`tL@NT+_UeX}}bb6vkwpG|%LkJZn`=YO}VBmYPSv$?L3Yb-czptOr!MgulUl$B`>+zqBnmH=j^qHcr@qi_Y~3R)=htqQ=Nw{ z>#kj1q@wC|h$815!a%-gAwVltO{Cf4To-Z7l7~%wJ)LRFLBNA{BVpc%{OAmb43Qg_ z@r2#fZZY%O;C{cyRU>5fo)$nu1DH(ibbBQYI%E`!43R^-5D=QNXKdw38dfCjSu^7y z9#b^D=LqC3mXl89xz7jCAt2u0hYT~Zx$FezeRYKP*|V^$UP~TF-x$Y5*`_1tVf%nL z7<2|!;if$t*x>|o~HOGjd9csG0Ky1loVBKoHg;Q03OjkPgJwAi!%K-qp5b#n~=4?yV zdnX=cdOmh74ed{qf;qg#Ionm?C9Q}YMAUc1!naB(#&cITH)ZpbE@%o|HYjsGJV@E- z(dHna-p>~)JEq*+ybR7wJ=ss8i4+ShnaTE01ePemOT`BA8PPq(@@vKNhwLb;Qt6Qr zS;rD7Jsu8f@ljV<)urMdOQc$otVXnGv9UbQdP1pmN$FuwhEZ-Qt~$rIEY>tw)~>9~ z_Jgq14fA1MAG;*JvmZ|7IZJ?|`CawO@5sR&gZcY#aHX;Ga8jboq zdH3=Ef5vbMkC^F<`Y5){4{%yhj-fV*S@#2s+n!!8&vq~^F1=t~?WZ*wn`>X{;}aZ! ze+(1wHyu|s%`XO@*F)C=6?Q4Lz?r0Xb!o

    &9+En$K{H2+)-}E^~h3b^os)Ha+I8 z&Rqm(tk4+ZoV!$*sl$yOG>Vhs>t;(XZ%igG5TR)b=#z-eF7*Vln6`i^rLuKYc81B; z-MEv*SthSwP9Om*SQDpl8h0#8QX5~&DeDBWw*xp+cJ14=K@`RImCh_>6D&p!Et<2w zIQTnEBfs=2LD#}wjKP0d7RW4qYH(3)ogmo4yXqYY2+fW~O zdOM{))0L}HX>WbcR%={S&%WedN$nkD2W$SoDf`Cr{#EAA!T0BFj?V=wcw2nB@8L|A z+`r~|IXvFOXHt28DU4OV|0;a6@8zr5$?zYZv0j&cyouXj6&(48XgdGZ!sDIf!K$tQ z>lyat_UD7QwikzyYieh080%F~%Hg}3gz3X~%LM+Pn+=ygAAY!Tv+(Cu>x05a+Q6v6 z0^PEY?$bEd`rVYzT%SIteCc7mdHm%u&soDSFv<4EyDSj??DoBvsNK(hoFe~xUkq&j zv%iw?<;gmmv96&=D(RZdpqDi;rI5e;dQy(4=2$5YS1h0lpghgg+XV zPl43i=ZFL+Sp*f5d$a%VcapS{{67e;o^Z%Jmi-eKHuK_ps$EJ zV4l3S1ki4p{W#pogn87UuV=tpVtIAs_B>C4W{VOj4w#?JQIY$*MHmxP=`Si?Iy7EO ztyTx};=MINn*+mi(60HA2uuyAXEh8MRBBTnYl{B%)CfX{rI+~tzRnn?W9x-D>|I$> zN)$a?zC7zxCQ{|r=*eVS(L8Jo=)azQZykTE3x-pL%EDcD6!Vo3bkRig9p@es%uu4m zcNpK5G{W1YdFC+Zq)efj&!Dhlm*vSR-u&{tMydO{7Df|+)_fPSfYw@Gg<0Uyk|uBE zpq*#C1SJZ-Kn?I+=>nh|O|-|!0C2=CT?&;|bW+3^?kwUf4rD@X*xj(T17pDUT*3Iv zi>%k{jcT<*XZ8ScBByz?Ep#SkI=eWW!_-g&!Xb~c;w?$m*eK@@`%JZIjMzOjF9i(aR&C?UZ`!G0*MA;T)YLxtf`B=ngZT= z$s0@^)>xgE>PD+y|DYsDF%!UADL0=eZP=*8P?8a=&Op(d;a=7W;cwR2-~)7qT<#YA zeQ;VSzACqN-B00p&T@JfUy@wJ4(Rp~^9ZX|IQKRx?9{g_$M4po_&YZ8fMZ1l`VP6; zT|Px|2X7?`X`?5db^&cac#`w)AXb7y0)_ONz8yWB;Ps0(OjIj48~a{ZL&)xS%N;ot z-@_@OU+2jIc%EF#AS>NnK1Ui9?T`*KrTL#xula$%DS9zFIh7-8!O>t6AlWkD-Mxle z&QIbHZn8&AyXu7Pf(`!;N&>5g8+kHjMzSj{bMIv~yWaD0yunnqs`Nj zslv@;#`_+VgLN#9jE4@KZlsupgG)XG5CXN3!}$Jd$65igvOEm8k>Ds{z)L>Ae-PK# zh6-MXXSDc2NURh`K!zJd1O^za-vth1lxqz_yDsD96abF`j>omt^ z9r>IKTt2AsPK{S?GQeE(lA^Qx*NpkdHae}vt$^Auaxo}?Vt>@w`%4^d&VkZwMmS#` zs!7u8?61FgXd$6?=#!DRrQw{n#Y3COa@k-qGewq?l=|Y!3(vqIlw!S zQQZL!)a%=6-?0@WiHUk-lF~)BuE5++mrkK#^WXkpc%O8CO!rJ|iP|40KOr`q7}koF zDc{+ovG%V$`_p#A8@@o#HW<@MyW3?wuU_)xTittzCT>vd+gS3iTaL9r(S1c0S$ZXq zXT%a|yu&?9P5bpyup1ky-tVLzFa1>*@R*hQ*FHq0XfL*4u zn}`&-6`ZOMSp#^Qqx=BuU zKy6Zzfik%d*z~0wsVxkWK|}Z`q3eW2H|e%E4wq++4!Vv&c%VoSvm zhs9E&B^bRDsSlK22Yk~(BAHBB2?1S2p&$=S5Y?1@B{bIu7zc~UrGKlG%29eGS3Hvr zgU>+GqJVrN7nw-G-YP=&QxJ!xDQ`>dABN>IV1hE`=c>!y9+rD7m0vt8$BS0@oaQ~N zSD{)=3g9y7!^4{s6pOL2;M07bni)~K#-j|ExLjj!NhKzu;`}Px<6D)%C9a`cHG7W> zSg(?h9>_tj%I1;|$nn+97EZ)x7r7c#600%@)#OHpg5bE?aUG&)O_OWQjij2E>i@~$ ziZU8xC#u$mzSt36`-=||Mu+r|*UsLO z`%OE4e_T6Oxhm90K1=UfV~JMchigUqJ_VX%^}mPL0b*33J{9Cfg(Op9HB|0L)PRy}h@-Nr^VbrD5OgMyXG`W9 z1>K0dB5W-ijfF~wpktV)C0k{){p%HK8je0{P+e|dW00_7jq3W1#j91C$&I=p=)0AT zhRcnhRjSbzW=pimY=Vk&YqEMo{8-T>_?6qH6=EwU({B&;WWb*g;0{}ujd}RJvSx@0 zyc370_|OdN6n~22!dl$moOKelhFiAYAn0HB2#M>*_(yF?S7dQ>5StUYF^{O+SVctY z^3Bh@|8W%J0&oCSvjJm(D&WSyjzYmR+&CJwp9JGS>M=&EA0(sYtZS|Q2h-f>|AdMC zuckRRCU*SZ&FBAansd6@meE(Te{|wMQ>9|X;@Y93`CObr2$AC+Hn;whxS^o`IK)n@ z!=b%U@}7c9+v~@P-?m=Aa$IP3o^0|iE%zf!htD1S%QWZvq%TeHb~e&o$5=0K%Js&l zj`z>0rdOt`RjctK1KOTjvG1ohU;dkE?$Yj}dSH*ALd-p%D;R?=5}Zxk=%7EM6S*`b zaYTSzDpB}f#El!>K}&0H$)ZZ)asfN6rP#iII|_MOyGPoIKZsbVh+FPb7U|kM`1bLi zqFq#tW>^m|T}W>e0}@T#+Y>wvRT%zQ+FEUF@i z;cPbE*pSE9y(t^!h~>orr@82K!LZo$k+V|faW-`AL2$dF>4{# zSQ)THBEZC{hyxb9Ucola*`xFrJ%cE@F6xkQ%!;={(W##zM3QkoKRxeXm{^tMTkq>M z1dSVGv?(%V$y5OW#F=o#yp1A`-+UFu*5*e)G?iTlxz)t|P~%8lZG6a)>(p%PStU>W z7#(I#T^(0;n{L{?-EP6M_~6{98uTBSSiD+Gv&Qc+jpwu>q0sG)F(GkcM}zi9Rf~RA zx%{J4y8mROc7N-q?!vEIpB^yRd?tJ7u|QSBx*NA6>YjIhylaa8-XMYP1}wGQUU>%( zZQH%L_2p^lzW(RrVu3_e;KzP2#}b^K zUxw?<59NgK82VMR3ikgYdT9n1xjzd(SSA0{b};{R{bc+<642uhGl%?M-C*xf?>@xV z2Hrhfqn>@;^G4HD>Ttc~X5rk`lC`fk*t*c;zqVt^X+JjKe+}0(+_Wg{+M?UsRdS)d zi1@wT{j$K|)XwIU$ItpLSwCJ3Nk{f=k309Je)IeGrelwJ)$Y=XVXw%vSGA9?{h2G& z_>%gp_eWat!Jdxc-@}8)lD`%{MzYdIcT1%Qwk&Z8-&Gx7%XUqqgXq$;$DJ`-}91sY=#*DjO zop%Yk2V)2HaVxVEtTNdLdrRne*%wrZmvFvRaQmf|Z%iJN)vz!ZNo0+$3i!{+{iaP? zYNW61n&FZBi(!GGU3BpFNb~(aaS9>#`6UHdqiWJmXnBcc6ln_%gb%t=c-cX2rI%0i z)}d91M~Y-0b91PTP!R5!Yr9a=pq0!uD-^OV`|8Pp84aUOj@e_M^QuN2x84gR1`P@= z(zx9G&J=s!5q9qW+KKmrQhKPBy?2K-Z_EG-Js(zlOiLf{-iW6si5ls}%DM3D?t8QPV1%jUqzxRW^8rPi3d9#X_d>)YP$W z!gcqW+TOreV-d<_eS`LL|3?T1V!h( zAOEyD>)^pJzg<@S(91eH^p(uZlexKP6J}+Ld)NQLeRN^O$?V;DvE%_$E3rAN_P7itniz4Pqo&s7Lx8|L|oo6E*%HCK! zG@Ac*V$DD$@QMSI14Y=()Gg}o^7yJ!nZM3`B>20QRs8Jj2u{V9e~+HHq0oHy>zedS zlcj-<dPR3@zsOwLEiAqtAO&QIWm{S5!#JiTV6tRDtTz%IWe1?S>SgT6 z@C+Wykw$gC-geWG36&kI=_XJ@1mt@mq7fKwS@1FRQNUF+NE#>u!@<^`l#QKG0Cm(H zE*irf7lD{F#`(TuF%P=SU+e8cF6ht3=JgNz#vc+q4ds;pHz{C+yF{q7Q>Xw2)sbU~ zSjz}YM{wAi=Nfn9XE4Y{I|{H%I9{SnsxfyQH430_OgVFKFnX=$%cT#GxvW8Sq$3O` z3B(uhaZgW!0FDi^Iu=x_iX?c(^gT9 zIbtZ84=*hnx?d&*nM(0ZZ|TapM@+<0g-+!&-FLjZbyx0h~@4UNm@jqBVR|Wv@$uxXPMBb!Rqk!RQL4U z)k@8cRRKB$u2*zvH=it+rgcAflvITYdbP@T?rc}W0)gA1QEdKZLCSlfV~Dn?dibIh z#At)-@r$&dU3RLpBlJG5HhDEN*|y=>9gc#F5+tEAdrsZ+Qu*G|p&dN{bICahl#LT< zfPYDO#k>>EIqAb6L*SG+o(_LVU2YfV$$lxh?QR$ovMm*9CpD*e{jep#s1g9iG-05E zq_si$Ge$YLoAcNxLS$>=u#!`K-Z__le$L(e`~AV?ysV$za5w4@OU1+cl5>@p;5!|b z$+Ji#zE<{U7lS7Dhz@mD+7q0)oTUolWBvKzCG_hDI}pVcPlF@@xX+fK`Bru|C&7FG z4}UrXj%RRn;hds{Qtpk0VKP%>VxdAK{%!sK(M*W^BBT}S9D|2OP#|pmN*Y6qZJJY0 zgvR4YZQjsy8lp85yr@Mo5+TK-GgFCBKO)2hcX=j?WZaV}Q-ye9LDI_cWJ3|XsNfI+ zG^9II3r2EFggzaCWb%c&;j$bl5Em=bEhsdanjNA9jX20AITGFIpbWk<=PY$%D$)z) z!z4sZJRlkIG%iSYh-W6;9+kVK1hVoark zYZP}F19FXE?)5^>%G_uLA1yDSHM9e#QnNGgaR08$osgJEjz#Ey6P&_n)2*2g;(EU9rUeR29kt_hpxwyzKghpGP&y$ToG}0ig zcm!-jn83$acandzG>ZC|h-I3#pdc(1zztQ@BJ&%RYjcMKppEpRdwcM4 zD)OF_k;ScuB4NomOc(@`a*i$K+pz3oawX6piT1@0vy6lnwJQY?rvsrfhun0A&mPFq z!_r^`%RLD(mbh8Mzeg6j0JT{m@n^Iujy zo`*L)Jq2O~PNwweKrehYx z?lR+ZvfZ*>a?;8WtypLyMz{c$o1+-AOhtA=8;2-}5dbU#+mPnhNEQmNh&PW`<2Fv@ z9-t!`_QAPA2{uP-Mt9(4xC~GL;@e*Qg-1bK-;x?CVhIGOOF}VxtSRBBXb$uy zGx1$wMQ2R?!08mqJ>~0b_57fQW7W_!;!V7Tw}4Q9e?UMbx`m2{4MDjpaa<=VT3Vx8 zrdfdI(H||8WNso29Kz%pd63$;(^9wNy%Kmy<{fuC2Ijc~o+BWZ6I$6_#J81ccP8vl z{{V;V2m?Fpmvbw+G$+D_|m)f2@4RdMP>WalDL5#?n*rL3yk|I{c44t zPK17~_|cnj>PKQ9l}HD9C*io#ab70-ZA>wLlXq>Zo6tAbcQc3qlSJ#_k()btH?41i zy_oEukLSzzz(v6ZqXRP0o-mGU_kxhvhs-zt8FqyhvEvqxgM>1`j#NlI@oK1jNBtN? z@M?!xXh$eIkFW!FXMmlFAT~SMZwKs&ZS|scs$S_lZqVA82jMV**b?OuSq!eW(K4iF zo0xTNcY?-}m{I&zdJ+!))u}%3oBkfT&|Yq6ys4t@Gn@DK~$FW}t=NZC<_h&7$2e{7x03pPGc}EX#Cv0ah1B zJ0%QZE=4msIs^-zELk?v5c^cr4imMI(zkfEZ~1ZGXDVvtYF`2CW6!Hr|GU0P>cP4n zd=cFYNCuI8{zR-04O=RpcZQ0}H7z2!${R#A;5PV78~3qu!KcZXRy5`9*E2s~$n`Fp z9euBtwk~|w!`059a0?q)_(hFe!1v&|3bXzBQ>hd)1UpIIO>I?79Z;$rI4beP#NbKl zj^K2rI>XhBd&@Eb0PRL!wc9K5aWaS=6r|`uL$M9fLT!X^@JS-_4cAcX?P^Gc%gDL# zq698z3YXrt)#G3K6J`kPpw&fC!N?B0l?lZt!!}y359d+0I1TQ^bEocv{?d+vCv#5% zcs7WrEy`$e?`Z1EC_71-HZ_p`R%r+Wvmkqv$;O1(ef1N4QM-(1{GOb8=)oO0(mEW>}bIz9I?@D z-dL%_AzS}IT<77W?txQf27yrh%B&r46S8joH1=2-NF!@V^XN;sgFdy65D7SG(Cm+I z#lXUGN-rKD<|U?&|Cz-en|_5W`RRLe$XZ~0u7~1i@ZMO@x6C5Abpg;9fN^(V?q*M2rg3)#D}Nvh-fGVHAPih<&xE(iDF;7 zSX?CxrZE$rVBrs_7M*BBr~MPJ)iarM=0i=6v0 z_-FB@;fo-C(Yx=UI?o{P`{@Zakg^?1JwFSDYNPfhT!E9}mJp)jo%JjZSrA)f(i+|7 zg3l7kZ7oM!qa}~xLLYX&>RLcfQeO3XiZ!nyKGi68;>8D!txRH89=~3}S%-Gwp#(In zi}|=yxabn7sUg0&RXfgsWdl#7LK11UcSmz5iEl25H%8BJ#UYkH|CufMqZ6}pfrHJL zuvdCC>aPWZg`qp_MKYDEpf9yZ?ujI<5>rM5=Gy|1Jan6>X!i_&&fM@%;cib2@y;MZ zt#Oyj0I*cZn%5H0 z?d2HXLT>d+Pv&a%4*15weY64^iqE=Ay;NP3I#qdT={@)S%iF4d-ndLZ+x?@{j=@+H z?Ksc@An*1BbXXk~e3ii6NPUM<+=%#mi^}A>%HXPFaA5-8H`2H;ir~i&-^mEQKNMUy zz1xy`M!F8m-N0%Er_s3fo4tMvLmTapKKp)qTABKv(o-n`ZWK@ubG7IdX?(oxaN;KR zjQ4)Co#rcWB8@A3hbi=T>!tbDuNtUN05q8B=gfo@9p4hjW~v>eAGkrC>o$g@mfVfx z#~skKY^hxHIo^KP2z!ttvw4W{oQeg?VL)L_?kxzn9|m4$YSc2^6y{N+pHkeQ44))$ z4G-$ceRzE|p<%ipR6s%aDiabrwbJa3m}4NLi&t26D?l%?wIKF?8+@9H0D67l;Mtk> zeC1*LAiwuZWx3$Jf;UDXL0tiGkPGxe?JMV>!CoqblUSbNi`%1hnl@?Z`$8&YE# zxy)k9YiEG>yQBRWX2JeeL(8@LpoLTa=&ljCf&m53&9ubB4V)^i!vmxDIuQ%@F8WS) z3_#cGh~ZSiBW2U@bDr+8_lCfb#du6vgOJuMzP4QXJEzHzcqZ3wP~piHiz@-GpFB}- zQh%)Gqc#bnDPLw2iheBDemyMS21UU^#S%{_2cQmwW${67I~>yQTKEN?bM|lm1NWoC z*~|U~B2vQ*Wo0i1q=QB4#>&9GehTKRJa4j6`Pp@FdrJiuzEaBvKJ?zvyLJgH%p}37Dz7@Vf@^My zMG|_>=}H?8St!qk(af>x!4W%2ZNt}WY`@N#m7ei;kFLE{oIp`=Ni0w}{K)4OT>?n2 zQNz;y-%WFtbsmS&@19*dMV9jX8M`&#<~3UPr{}pBNB)PSBcW@@y#^|0l3k=4PI!Z! za>5y}g;O*7&$JaQs8(x)EYMs(T2M-?#8%6^2r@TNhIdS?6@4<2uqM|O?^p@rWA$!` z`}GNKAKRN#WsBQ=FLn$TIOne_R(DwmL=E9vfz3!=3y$IwPkd6ZC|=L(G)HT1 zZ-V-v{@lf*^si!hd^$|(x}Z+j?os$3SWLK^^9pb=rjHyTOEr^FQ^7SehvTilIL#GZJpu%lVnYY{D9?Me7*qv$25 zq3GhBz-LkEQ$3S?5>~V-SKwUu!D+k(r?5L`GfU09dZ*UM)=m1GYyiJ@#GRwq$kHv9 zMThN!3?8?=<=vI))EdXCbH53LDC@9WM+Y1#s>!tpO>Bxr1dzAsiq^F92=v%N6@)ju z8|#BIQ~Hoy>-%}^pf>sMxM}|7udV?_T2B^lIFvgFJoK;h%66Ukn)$1_!aeq3R;8=h zz>*9(R&5_;kWoJzcrjujOUQfVBv{y2+xmW^uY67%3*sG6zaivC$2GaM|Js^dlvi0+ z5ZTY42fOmjn_+tJ_Xgo1fW?tTEYz7e#Cw_DKqg zYD*NK65}g&bH=E2YSvL%Q&gPCDk2v>bbKT#D_ z%=IROCd|bLdO+g(^$(!Mv*jy#4DjVuE}bzBOOX`{c&5|lVuN{EDu=}hh9%-W`vNqb zV18a(VBoHNuKOjukzA$vY%Nt&$!o08v+R5dQk9Jdz6#(x*#yW>!#3uYC6Z2#^yeQB zPnWDqDmb}MfUqS$Le5HLT?&rktjbxy0tMl~ZWh(J)}(<&LABTpWc#Ovr0HLx%5nl=Iya@fiQW*JizO?B9)(KjGKPQJfgG(s7p9JR>%JEW3Nklvn?2f!BESG4?{~5R zz3HN<_)n5RELjiszAJvw1n}AZmEK&sLd+OR2!GxY-9+zE9^(+2qh+a3WXx@eB#EZU z^Lp#)2p-?u$Z)wF+(9}Iap$=7Z|3V=*=^Lg?y%$m2DaZ_*>`IQh|!jTSfu>h%$P3ltU-P*e-6@7MAea1z;5P!3eT(D8Z0dfc9@%izs9 zM)8KHp`jQm%a{j`8IT%9a}FIakl{=YXg$C`A^KyJ;qyd5+r*M&?V$WnysX+a;+~ST4Fz zdIy(%Vv)lujB;FR-JYz4Pv^_o;S5I?2Yr6@pf4R4mr$?9eTtwn-wrXm^q87uQzkZ_ zL49`n9P-WX{-c)}F6g`+3e*S$Z>~Go~xp`SEf*y*sj_AY6|o z<3-p6idNCU;*aVp-dX%8U8H4ewa6g9WdC@)bdufdt&a|(X9#rBGgVsBXFUOl!rd4G zD?=s!b-C%mBObP$v&U3oqiR(6lMGMP6sP2Cyrtoz`oh$qL5V%==;(uo`6_@0NhW1G zU}UH|nOG~4(Q0Y9*B?;xa^+op_(i~wzC_1olvnS2={1oaF-r|)sEKb{IN{+XvA@3X#&I+uZ7n=`6MxyD)384Ifyb(?+O zqzmZ`k2@sIf0O!hkR`mDtG2D(bZ)2h*d(I3+%(#bukWJ=tN^3mvMO zEN=HOAJHA=RPCdg0`ir{y)_K^gL6#b_~tu&0?bl(ObzuW4D!A0a-!ZCFOj*zTKVym zodlmdu=hmt&=<|POO6A?SG;*07#X~?7=)+Pm{4t#u*42N-{aBw zQTk>!&|7yx^spXzm-)BQY{~W}fz$0>!%H>&dI%1KI&QsI*sXrb#gTf(h0~q8;$C7i zctv3tknMnm8xh2AqwAmIt~*#k7;p2D>vYr}ogxQKppl>L(D_#AOw)b=C*ulNxwq*0 zYTm-P-@rbwOn^vw(>)I5oD3zA47s4Zu0^oOZP-~K&Qm#8Suyp!n~yHpxKa_li5Z`7GQ@{4n`EgcZn(ig>!(% zmB7BcSze3a?oLeICftX>Xt)4R;DU+d$o6GsKczm_uOcP5-guA< zcWD?z%br4(kOr=t(vlzPrGu@5NZOm3F59^m5i&kKrbx~H;HHs~b-MY`NZ8zn`3ICC zCP#lULjVupz!SL+IAoN7pIt$on`USHR6Oh}s<9Av9B0qWaPSyoWqpugw~6+iHOIz|@czujqbnb8QZ(g9SPmvvP*BH z`SH+|ky5kqvRae^44|-h69-^FBjB;kj1w?`Q4V->H_J_AVB)R3v`n@$h9qb#J#bi_ zM+XNjj>@g_R_Q{l2^BrX6{&L&cP6h76>LZ#`3+D{tedOlSMVuMIB{F_)eBwe9rJ&b z>m$Y|kuH26T~8?+DQU6^aTODfw2d&@j-pwPm@K1#EcfgS?*6g_ssNv54G1C zB9=3?Fw(U&YL|y;n@hf35J`)gd68Jj;^;ChzB9R|YTRcwy*@Xh4I|3hXUL17La%C{ zZvnsOsId!EabLaKht0Obk>JsJ4J+n*AHX4$?5UMAyn4J^x{vP)6klXO*o{Tr54poT zq~vXrt1fW9nPzmd+SypO>r-cZbVoF4q=9?fA}M26_7wW8PUr$aMN`Ab;z_=_eE2W} zp>?LzX&Uw2UZ5*o76wqJv;hd(!3GY_XxN8(@HzZ#H(E7vRY9b&Uki{uv~tDk;7J#W zy?BGr#Z{h36xZP-+MMzegQ;E&A#eT4dThR5Crm!piq%CGHt0w|*bBVicHaT%R*?qa z5Mf`dmEX;=#o$veBt84vtYKZsU_UNNY5FAMA^FuH&-!3A<=n~NjFTJZX8E%9VGbEI z5`SEGz}0RqoS+X?zT=gC`^QJV*lhnEkYVDSAGI8P4(v9 z(q#Y*8Z*D#W>;rJ1!<#!Rzn$v*qQjaZs{rxaTrBs{`W4m6$uO+Y(`hm+NcmlLVb@MdxnmHeR@nh^wLU#G+~mp^S>wD}=qxo5PR@GHvv zea@n19pK?-B5=sr9+DO@du8Kw9n$T(KQwL=s)6R<+#yEbmXob6ZWQQ#@+W^d>GNU! zVsa2vF~AM`=#A3nH_A7Bwg`AlD`2n{hcpauY-hwoYtFERQ)V$;{jR(CVn0i?heLYI z>u=m!=>rbw#eeqaz2s@&pPzuP)LZ979~((MzUi9nKrd=lI_g8sK3CJ)Yjd=(v6WqH zy+|i%Q}eu5JL-G~Y$|MNv9}w0K)Rc)!##Gq4ZRME{*uPmyQ8uL<~^?$TxcmLzb_yI z2tZCW2hhr2gI6OFPmX79C>?+EK5p%O+nTrHyX`U32^cVinkhJDtji<;M4Y~PO2{i^ zglK2H?;4ULq_dyq@8*9ZEnMh-I1XQP+#gPtpmE6Sg2l%;r0E!#(Gu?<`Y+Q?J=A> zrzYUr0U+AqtrQH$uHFTy)Da$+PUqsQ`NpW;7vjlD#0&Lt8*wzUE}DaPhZs{uPSAyh zpM3L=LTMa~D0c&zXb(*u^Gs5D*BlVCDFQaeWkk>+_Ezb#B8yMu=L`UuXP6qSRxPVX zB(u$Sz)mKMyYBB6hy_$VMFs6NfKD+@E_t5_xYun6J7Gls*t_ttH(R^!E>cHH?`w(X z5v10|S04vQLhs$v7SJ*Xe#>b>cm7x2^x$sSnJ2aA+sfY)s z9r%ZTT5u_JOJlFs?4eUX$w^FdTFypw=+^c^M4fn^3R|1FohcM_S4+t~@E)gL7{#9p zGI&S2!~N)~IzHpS$~N~Qp}K-L$BzEk_dQt14dTl*0Ayd?qC~hr$}NIh^Kxsg2v6;8 z&Qp)I20c6a-GfW`1=j<@^OGF{DO?^do?jn2xZyew&w~m^4D-{#TruF>8=ycYc_r;a z)DEXT%uW2=LR=8kB!{GoB?azeN1P{z7m$;woB}}{I!to$Pmah%k_e1wyZHGC`77Q^ zHOVF0pAI=&#c>SHIWo@q?FPuhzQdI+h8_ifP|IeyErRPjin#t!m^5wH$8oz;AfZ;a zXh%4H!f&5{Q1l_leE{Q4dn(E0$Q=z=_aNbRPJJeNhU8AwrBZD0wSm0Zo_Xgbzs=da zS*pmskfH=NMqhiIMNXtZ{c=dc_;lgKbX_bdfl3a%LysyGrc>1w)UNA@hU zLjtrwm7x1Kx+_%}&_F^q;ud%p@gtxYV|9VE$CYaS-`G0qx2FHFZ?D*h4MvY1jpXQ5$3}xl zx3siKhaxT*0@9!$#&?8BNehU?Hc~=DKvYyxP*G_M<=K7z@*K}`Jb%L{->>U+o#zdU zF!h@cu)~doJ^ZR0{Qtb3Op8AF`#N}o35p?~jgG&%LpntTI9&${`2u4@Zk!}V-AG)% zA;L<&&dMUn3gGjFuKa|hvLEHkfAs5wF=;x%dMql`_-)>;OW(H&T*3^7Kg}tN?>%ViFc; zyL>~llz9DT{B@pRjPKrlC>E8UH-MVy0<0vppPhtTI(F0cd~GS?uIgGPGuJjB28ua( zxI=@n|H)NRgSy$Q$;*PLt__l9Il9@bwm??cfrch**bGOsF`q#* z{g;nkh}k9Xb-A}~s(Kq;&N9iUu?GWLAgo4u%o=1~Z_?ol{(6wKk4n_n-+tEna)e$$ z*msEAqa&52u9(f)$KgLz-}hYkvG?`M54B|)3C61$@e|{7;_EYK5!$jnpRHEd-@q2N z`J&dhH#Pd(alK%pH%jHo@sJt6y4MRRd#v8?C#If@xsS_D_5`<=R9x9Lp+(Hl2(7+@)bQku-MyG#N?>J_s=iJjaTp5+^d@EXo2ctC3hULdt(Zix~yaJ(ca?PBnpC>PGfqu@!n_NX82-ZC$^Age$A1jms2VG(*wDlUm=+D z04xi7iV*)MS^h!t=cn@j#k~ei2#GL|6WyIIU#3H+5vg>LRgeTMoy;g_C>efA!@HClE z6NP&dvC6F@ZvxI6TAhowJ#%nSl&3q{ssWWBovY+O`*$%m!tl#9KCdOD*EIOQPj$~! zpMC8Pmlw92XeM)e>MaflC#|=HPH52hQE- z+HN0~@*zKXdlHroG_qGif4568&u|7`WJ?Rw>}k z>S4}ZKR2#^w>dgrlTr0pC(aC*rgKN zs3iEJ=)5iNZ+p=WR;bu$Ew}z)cE7gL_Tydr>ncN!`aXj%kDr}!6K^R5b_fS-O5Uuz z&m#KM45}Xomxx5ZCJKOclIN9(H@*0!B z?~OiQF&NW0%I-V!rxK?9pJ64r(pImmK7dpINFd3CN2toi}`V98hzPp7yuE^Cf*Ei!$*z|SgIA$bG*BTWyOJM!V!Lod8Y8FG!6mv zv=%n42oh>^<^5xJDH+4;CaK4vlj_rt&cqj2GTEU1Cv)_(vVC}^!>tc`!;+ja_sF8_ zNZ84NtI59{>6_4FDb#?18Q_#^kXWe#MgsG&*-;PnUl187ye__5(C_hB$+ z+;)@bC}9ZYQa%_>z>BWxjqr^Zn4ZM)sf#WHV5cV4hcE24mh>%Ir>T-*%wH!IXn>-U zTRU;4qDnRrIjA0D3=huF&bu~9VTMYlb5Uf0$YtZ2D}dp7F0wVd->2XJA}c(jAI_^TN(nPXoD7G@-AoFoOm?JNI;E45@rWrKM&(8rxp){rB^H z1he%vjcX{^4^mUTvJhBya*ia3V+&qZgnQ(#@C{f)wJgRayzL??yPk3jr#zXA)@TY+ znt2=JWY25)?EpQ@$|HASCEHPXKGgLEUs> zxKhMX3uZ)9eEWJ<;Cv+9Ege&5)AElaurL0L=SE$YmIbfib80o)+Nf(O&kapx9x7<0 zUQmjYmqdX|EsZKiY-{}N4eNpef=!SkEkv%8sA0RjEzS@xoT$m%w!$A*&dZnzwuVJ^ zZqrko^JZ&jer=m+f0pD-h^y>?zTj0|I=l%Ml&j>l4L5sz<-+yokEQKVYr_U|UAet+ zeBsTMAjmBD5(?gR63L&gqqU|G&=IXUxacV+bLh$2)RkCnDJK%WT}V{f7Mz6)i}f*w z$of@!MH3$iAU@mfJGJ>k*lybCGr+S=53u|yG&gZT}GMfZb@eGw*y$3w#*el zNU+Qto)4ZHd!Im8)$a$rAU;)j1A(r*dqZO6N-3$1vbPd12;v_rvZ?dDW7ExNMJ=H0 zE2LFESvtN!jf~#X?4G%69s5TA_Q!*VMJ@0%OGIYFRJ+djQnvH;vX`0PLK;ak_M0*u z3oI=whaa(3UiRIu`W_r`kyRpkL2FOP39z8N8qVk>63>#IIp6p$r_109%R;L0?Jv=$ zQE_AmkBk%G>2?ArdXT{R7C=7*@&y~Vd7kZMrIFquhFz!czK@vK^!#$+vS(mYK)@49 zpAY?Qixls2YV&~DHZ{uO&x##^wk!wmy8+oNUrpHo4{J6?XP;f-sygBq2dqTj+&5kq z9O)VY8fU69b6--Io~*y>{+*Y{Jj|$D-l#nG{)gj_)X`rGB=G}B)@ytw5)?(-=o?B9 z&~lv}MX5qH-nj=S&`KSee_j{=*i&q(^IfTN6*=O{7#Nkn++FMQ;!Hd!hw^oGz}=>E zF2#W-4gq*>5G@;(L4xSg=xnps(o!cLqM}|Cdw4IGFpo5Z??+eC(Z^<@=Svv`)o`^F z)g=!1<7a}P5f%mP3Y%RvgO|{ihBhFkt7NZkGy#TW4J27htQAU2p7y4F%co_IPoUyu zl862hU=-f}e#WCd@^|>cYy|p$4V~}Wulz7;Fz3e^kNx@euFnm(a>-w*gubH<%#Gcm z{^N~A@b8yRsfPo8#E6gq;d|;_SL&ou2~;RIuLsxFBtLc*1ptcz0X|C8Ng4=^$Dg@J zM;;6)XA{&LXmS%^-I^ipX%^){Q=;|*Xe1RVTS~q^pL3r-Wal>J;I`?ldCCeyiApt9 znV3Hf&+8cta{92timx7=Zu(WGE(2EgCF_(5*FW~C;b-L*SW%ZDW9E#}$|vMUPdw@# zdsMKL^Fdddawd#L@r*?}6nN7bE1vM{j%N-N`AM zQ!`CdnWWhT)}6+S7!kO$Y5Y52F$jREE-{1IG{|0}`hJN_up@L9t{M;npbj zG!yEJ@i+7p&|3tb-NNfNkPWF|FTINZyA1;y4#V~#&mBCV9j{Mg!{*AmgEC|u$jTX5 zS(c#>+b{Mzxp{uRgBc|WXX9=hFHLWYJbsvq59I%h`W{4?yWAQ>pXy6oCgi3K@q5elrOcOcfL19ypax zSAu|5M8Vp~GPA;bow&gmTn#0TPdtBYXYiIa+&t+Pl6iY8wHu3#f{dacC0A^oE-1{+ zoi*$k(4PYv!q4d?4d~aA^>`45ODBaYm+*OGvxd}xqTIq_T&+ScnBTeJ)&uYv6@`+7 zP#>+WOQ*Lo3Ts}&Hlp>?TF}Q)KvQlL%SZC*LEl4l~IS{2SCnC!eQ0w@986@67 zx2WPBmwB!TA5d&&C~7IS8z{BwC@DFGKRKh+5fm=d!02cM$u)!Il9alxC_PQDe|lS~ z`$2towbHZ3`ez+VJ$>~(!zW6;FY0?2l=|M+_c6i&Y2h*%b*{u(5x-&@`+AedyR_BU z!AP=LJ3V$0Z=Y*3yHkLp!&_*~($m8jMz?px>lA}X2poRy>bQuUu0!5m| z@eM<>Yd_ZcNh#-W=P@2aRan#RHkPV{3}`IZ&3~?IUZe|qjlHUdj2?wzB0xe1IjdB5 zbt(e`CqE_CKTQvpP5Clm%V;~I^UYyJ4^)(#KrdWKGDZw(U(%XCNydV)R@X2N#lG~2 z><{`TBTDk{Jpp+&Y z_Sm%`thU4L_2(BsJq%iQZNgKcM2OuhgNZDtylNC!`fp?AFYC9gcc7naZ78nqM;Xlc zwrLdcNQQ0fOykc+ob18ZP8X0;jj~cRpcIJ}Z6>X2fTWQiNj;J@h9s?^Dz_ZbuMzpe zBl4x(B^e8x7gl8hik)qZ*s5cZ1VoL0R`qrQLGZ<}y~YQAbJ@2ZhxCx-Yfw?{{-!m? zAAWN1=7z+&s2%iuy4hlkHX5G^-lc8cDy8Fu!ea$f*Wi zFaT44i>B0ZFEW|K?<@wUUkvKuU`&z`HGqZ{>u) z-$qO4QP~*^*_-B{2bCbVmsr6%sDb~eX?ySm^nWJi%&C4CeIh9kBO)a0Cn>r_Z$K+W zly0_~F($^8m7*9Z45orOv8R%vl$_Bu$N8_7r z2SWgGIN5_rI0K7!?-TKAZ^iX#yxTI7-lb~O1EkhKr?Oq(XX>gc;J z7B2EnY^QPJqx6^ntPdlonqp&DH=Q zZ-YhAK#**@XB+@N2!ya|2k81M*A2}H+k-`F*ESVT{STn72mcTZ;DZ>YP!h#j`jRps( zpBXU~r9Fkb)Nj!(M%N6q=(#7!KsgL({7m$OIK%oZZbGrqLm_gVG1Nacw4B$oB4Vde!-AP6DH3o~ zPnRaxa8wS)wtZ^SA0V3b1h;)3H{aVz5k37j#_9&@QEghjPMShh391fiFUU%&olty( zDtfRf)W5qRyqhfX>!xuWPPl4fH|?E5T9b@m&j%Nr#DVec@^0Ri`d4?y&H6zS zXATqRH3o+?^uSD_Mi}2{tv+51fEy4k#|HLmIpMXV`n57fkF3dBc3|zU{^O~$e_!?g z{m`#jwJIu#uT}22 zjQGglkEGa?Wghz={8W#BPNP)MgzE_X*-$ENaU4kZE7Pi-wW~BkIQu_|E0lb6{uZZ- z)~zt-dSG+VeD|%BaMvaudOE-1?Fjd_;F)UYXSXkTc3xf?zIBt|6_DE=v0-|rvvMRS z)ae>r$IZ<+Gg*u@c#B8S+cQb1L^#f2AJ6lae_f<1$g+<{*46G@ecRGhXRc}z|BiqD_`2ED|6l6$ZY5$e53H@Vw=GM?MyU`hHx#TVDP%|)YX8fM3$7^h&? zQ9a2Y@AxgUJraqk=6fWn*anA*sl0M3n$(?#(CMv?t#Zk6DBfEq8mm*@1qI?*M6k#cak9<8Pb=Zxf2<=kSQ zFXC=nWI4;^dOOZr2<34PA_5}6##cV~HrkSvF_y&V2gvXoNmDF57haW$8<+{`E=O$? zUtE%T|Zp=_4U<< z>%f1XwVySgT(PmR!;jq*@E~wQI0KBbG8SH?&$Z0G+5?69NmzbaT+5UAY+7o#tv5Ur zY#*T`_iCMac*+vRZIv(CrSA&*y^#SV1+XGxT?v%fz-pXK%Vr`E~440B9r5ShcKOgdw{=T%I8~sa} zD|o%&)xpbi=E0(I%YMRuho?{kzQFctzk`!|?+YHr^n82w;{%b)JKSh*8O*i1Pg~2~ z_^v0;W%%s`^FDdw7rK(e_~)qipRa9#CP=FuK}bH9A((b-tz+r)_t02q=7QJ7 zU=Op6wRpd4UAA$)954F$%Kcd=tue7@z-piURoR#y=c)Uj92jjYi0D$hSm8xpV3!G? z2iCWj%!N#yet)pDd_%R17?=6rKM>vm2<|F4oGhLjvB5L z3v!lDymvuBR!iH$Lc&jRS(3aN;gaM-z#>@G@L)rYC}h(#gHQ_96j5JFr^{?)bB*hnX;6hGJI@uBUAp`B zH6S>ffhxM|@0hU|VGOln1F=EswVqYJ z%B@Go*cmor0)v-|*)l#I%|=lzE@$UoMUD%yo{1_*PRb{1E)fk9^`yBLMr%He+A|jK zV?q^EM)Y6Ub9w)i6kf_0*6Wtci46fOY2^rhPrKuI|6B2+%kDOS10E-GZ@Lri2}S*6 z9gqbF-jpt>wHd_-7L;8|Lp8aPl}PHmv!amb07Lh61)NUg1H|0`mA8w9CYjo!tEf1o zyDTeKx@<4_FUM3?s~47MT}(NM`%GmKZ!YJw&IzE{;LE%9n3uGtQsjV&hsR;rOqXdQ z&82jGP&4U4Et4Qd{H3PWE7|AT{iH=seY&QwHnUdW$%;&xV8jK7LigMK(q~~10tigDreBgV)o2cSW zgr~ka;+05%&=krSRBRKN1Sy{u(tE;a{Z0yy;pS&jv)m~efdIJ1W2?cw2bH7I#Fcb? z02zhl)QFK#R*NR!knfNUUGM!kFT(={EN_wpmz+7Hsd2(UzyNz%3o)4H&r<4)2gCs= zfPC`swWIz2v@gCGdHO@!=`mT};o=61G#gjV-)L7!u}_2Q?saCrC)M`|P%qI+i>!2k z+uGf5;|%Fa418awV+F{<2LL)^huJS$aK?xDK~(_cGp+d~fs=M$QT#IgY#o6=7Erc0 zq|@O6Q38SXffsKZSx8B?w2r6MQ@1csOosw&F?f!yM#|)7L zNdwqp%}&p8JH#*};E@{W>198z$dCci(xI{Gx#$QY*S%$r(C;}ppG!W>Ny^vlF**4n z*;=9;OH;E)9ht@)+M+i*kih~mr!x#t)s3DX?QZA@G)IB~bde8IFe^brPR-r`v7IOn zfZ3@=()W9t*CMCsrrKMX=;w9qyLw}`ZBRQT9{=N#%aEhXMg38tj@^$qvSE$a#=i;C z-7PxA;RPjyFd(`PxY04E%o&$29j|-Kb!tWY$HBkjljUy@Z?)wIGS{`XxBBWVhF@XW z1NATXJ6>Z`|4Cp<#e2W2;vzq_M|Rf{*F?9MA#g7&8DsD5DcM`1-}O&r3E}zeq3$)? zFNNEH_q`VM<~oap_diQTUHJpC{A+d{>$aZ9g0`QJmjAr>4W7U!7D)Wnk9?hT367`^ zypr5I;dk8m--F-tAN<}a6%|SyGEg%CJ=-eR?rASd&1iG%Tr-v9(AfcYL5e$ezHfwNBhOo6U39~v`{gpdO?FZAmGd8e+^9l1SZMp^0X9Lx6o8zxM_{1Hk$3nJBN;d ze;=)wbd9VQveIooqv)Ep_m|K*12$H$SjTo4QZA3AvmfxD2Y8`N0sRK?9Ypg=s zsGqcpZVYyz)nl8=8W)C^$$(S^3tx9mUo|FZsmT==1zEws&o{HU|IaorG<=6=C7;tY znvWa8DiQoTJs$;F;q05_%1J|2z}|Ks*vsv@LPe9>~_FO2#6mCc>;Mp zh#)>-ju|$^4Mn?1;k*LPzY!220qu*?=GY1o6FDz4Xmv@97+QT2KOY+Ak zH*+)P)UFU?&e2dwTd)ixS~7!(P$ho4V*0}@Kqjbu`Z!!Ra7EXPA>-}ej;od?0g;h1 zYn*E`i!;&@l3-UkAs`PYODjZw1|6`2=8lo1#3(#r@STzgK!F73mieThvKLG=Oai6L zn6KbrCo^M#DQ+;olniNI*R09~Rjq`tk~8-g4-QaI1MH|2l?xI1+tXHcPJ-M$#9)dE?aVdtN#7=fsc3}epeWqy($ z&T3UMsz6(WptmZ^a1e-CQ$PK+OBINy z<21WHA@{T{y2`-}2i0{+LwK#kM0`1Qc}V;9KH_pS?(P0*?RMDOOSLBdJ0+glIPSc9gu)6+3u4AG#TCln?OWy}sHxuCwRy>RT1eYD`Gq~N+|iZG zoCbdSO7Yw!G!eF@k*rJ6?q2I&|`Jbk2!icALkKJEEM32#Z*kOLFEX zeaoG=05jFXKT*b?grCr=M0A3xu1;`bLb(38 zeSw2u9-VXXdr($~ZiXb6%pTjbc5mG@6r|j+K(I6jmq>kxqs{P{klJ9g=Nlb{Z2|hP-IUo(8{3x*2iJ5atODvqf>7ws9 z!$}|;T@pyxJ>m)NOpdO>YYIllD@LBx)k@RZX`b!RZMgD>W4D{vKdQ-G`bW_9x#USf zp!zF|5TMUM$<>oR{@G?!@Jw<4o@%hX)#x`rIXdQ!bA5{SQf*vx3QTkJfD}n z-U-^8OCpqE2CoDpA+NZuGU@>35eL)PmG}tz353&b;RbPviQ~pxiNq80O4{7AZo*8Q zpu83wyvq4Kp8yQ|bQFK0n=o`pj$icIM*i`|yPF1JTmm_>r_=t!0I)!}TUi%|yCx(#t|4C9ZemDQ3yYZE-Z>f4$ zuEi?Kt_6lDnT$No%=sxzp(FMHIB7mf6KlK|$b=E2OG=YFX;V}t(*^e`bd)t^LR&ST z9mag~<;<74Ia5TwlX(02FKmP$t9%zRt1N3a|iahOd1~Z*h&GAZ#Uty!7v}=@Z7ER;)2<6h8I}1o)k)*8G&D z%XlgEZkZ>|Mc0tm>uV3czb~kErl0st&#F#4^>1el6vY-%Ij= z(+dCl%=<1lt~(88yrx46V8z$X z3^%Y#ca^DfA+J^tV_H5iVHH=EkI{w40HtF>VXJvz`{pyC-__wq8SV1PKM4h8kM4dY zWN%YBZ$IMvh|XX1{k%-@V1iT@3AuA<1Ry21kIKmd~kB)>Zp9mD6B}>s$6G<>bpceu6+>F z^T3Rl>LvMviFZpIyW?r9Z@$9eC&c&oD!lE_=wwA?_w$IJ&ySb0o?rTMadVmHjhgPL zW2c_U^s?mxyFU-MY9Ck`rurIPgVs$L8fSo3c)nrT`^+nJjIOeO%CC-m!F8(du|<}` zy{s;UzNwn*)w|ih?`5z1<}9Q8R|p6yQKIIqs^I;Wg5#N9+@Z$rrpmh5kY^pTw}J{M zq)_tFgJI8KLZfptpFb-jagL&lfLw*ZJ9W=5ReYK+DxZIwP6{!b^GR~Hs2`chydPE0 zo95Lb^0!;^+M<}r2q|jTk@sRM9kt^dbn*qIdpb?uFzE5EZKmVf$!s_&T%-MWg*993 zoB!CKrzEG}7osV@2iwd;=u}iNSzNWo(=-y3J1MvM_&-2)DO?`j9 zWy3G^Z8mYhv*qKZRQJeXU~f)VICNbwxZ_XB`nkS$WbduEKgxnT!`-KKzboOpc|mv1 zL}%vu{UF(*>0Uz5}m&FYCe8W-NASZZ!g0F18wK4#OZnJzcEDSSGM znVdefxodEZUAu0s)~ViQh@xG;@Yr4GO{=L!!(vO|c>3Rq+q0qp3X|Q}ICLAmTKl^q zwLeyKs(Zqpyx()4Nau6wj(dGL|3y%30C)@tU%9cU=A;g}7^ZGDdMnK2fy~I;k_82l|qzN?}SA_j?VieY4zeRKe&&=^NfIe9H(Vqfu6>z3x!=hdlYp4D9;CF z8bpI3GD01(F6?k~lT@RjN$#l^Me%U7W>?Hj0z{*T1vxyrYOR>kW1l8qvXgIt>G~<< zm)v^X>IV=@wNQwZ{M_zek)=8oQkh#AQk7$I<k9jHpB-ECH7_3XWYAQLQbT&-nC z%7*(g(msnj66wgH>UA4-qHu%4bEPIDFV{Nq>Bk4-3aY^NQD>j7gy66mnpZ0n)7q6j z|Lpg-@yq?SwjQT2kMe<5YHyQ&XQ`*86nuSb`KIiPGCf2c%z0KO))YDJrA|iRP_gD5 zdJ|N3ZhO4P0bh?Sh?l8trRnkD?;#Zd(tTEK~-7$;4?c_|Q zXQTcw1$r?|v#$fP#%8VkHX%0Sj6`nIYL=n!r+k1&&ga6&SJvax`98V7o?UoXGw<45 zZfvb)x3?jT$AxL1RH_dH@YZkZgz#`x`VtRZz3-SMKuvyfR6Egu1JSii;kv%RIxLZw zveyTES22BO?aGQ;xZU3R{(?_l)3oPIhKza&b;WtkP5;}~zSs|+wcjpXaQpSsA$Y?h z(c>xNob})bwZ^^Q->0shoK@$d0a`hNdQmJwWAZd+N}Bw}(blKgA8y#d62HbVTeZ~L zOWkNBEfx8=Yz3b^&Ww`(r&P{%ezA?E!t(dpJ zUx*GmN`{8T-ff4cD|KVCUPs5?YX?&>nVA!Db&mN{fl``a(Ek)WnarJjjrotMX&?|1)uXBg}1*9tzKpX_-WORui9zHHOe z{qj{A{YC1F-e-v|3j;S#N*bO%NnU8mlOIuNI{LvB;atCG+n>6+TdWz({9yGlwIVu! z9|(|&g!f^Kmlo`=0(G{~1c(_*43n`^f{qb=viY7Yn(*^p8d?K7k?}()#M`www6h>x zFaE{(-}8Ip`r45VO1OAirSa3| ze|oPgq?0cgzjg`yG;i@bdj(Ne6Meq*h8(rnC99Ac)mJS*F*Oj_2=OtfUVJoDz%E-u zr++NCeY@jxokfB1Ntt*>bcLHl?F}|9u}13No11rn`xLjEQN2=d^?nnx@<-#0gmC|! zJ%hTM8kf8Nh1YoMzjm;f`@v*eS*2AU1C>R1?Fvs1*JKYq4ljSEXjP`tc@Q~%TjlN& zJzb=@2bYbZv1<9N(OAvp{r|I4@+|4vLhZ!fjeRWa>^m zdGs;tF=H+(OCx^Qd+_rhCR`-DYY-A;qgH9Rnl6^w6T?(%9!M!iP)tD?Wr9e<3WtnIWNLlyO zT}s{oW}uUoPW(nhBbTGuRYzFKH&wQTQ?zDf7VZVU$^Qbmt!^z8pufQ#FGkxKM1tcs zsUp1Dio`CunYdTtI}VkMN9ISN(hggCc?GY;3mzed8n4pmkZe0^gBcvhQ?5y|=6eRK znRis$k9lsP6B>vxg$~yJC(%ug@{hI`-+a4NkjK*a%a4gr ziPpu2g}{uV_s)OlJr(<+2~_V*b^)DWF=ZRb&3D`DhrLiaNGvA`a2vDuNhk_QufF;sH zi$|`Q02cnZoQYbEPI3`lr6&DgKQrpb5d$buZ%Dkq&0TOc?@NWE&>lqwvdo+~k(HTh zMUOYLw}H)gRWJsIg%A)P`8cs}b~ilVlyiQgG({_Pw zzyIuk-BREUrqea4xHr$=EKsEP?x{dp)El24 zb?n&s(`{>&rcR@nuyC+K6y1m7a1;);S?S)GPB+ZP&DR=aH^z^I`xy2}rtS>9uQto9 zO(t>KM3Lncn9!J{<2AJ4pvJ=2Oxw~PUfGkTH>eguIv^XwcOSqKDEWo$b@t3gz(Sh1^YT5m+Cw(RL;JxVRyf`%6S2c9|G^NYqIm#UeRI|e^tS5l>$U0 z*|CtgOUev2&sSqwD6guk&tKpXa9?-tik7fV%!Ggi-e|n2}+A zk4v?m{7&Gq?$dY1=x`cNa1W3XW$Lv_?4>K-Fb4n*;o9F zg^#D5Gu#3!G);j1&)7P2wD((VQ~G$R#|1$5Udhz)hWUMjj~$6G zrHjquIQ)H#YwWwu56G#%^^{Kj^b_@@?Y5!Yw}XnUp*Hs?Q@^Mj2_}@bY`u_ZIx>7q z>D>>Jp99>mkIU`Ipm_e&C43UlDsF~eva|GVI}Je@79C#xO1AUv2)U2tz=AP&83HK7 zjj1TlI^_5l0AnJ7?_$mPV(`x@uPt?wSPT4er9|lfb{{O8@qj_*ilH+Jtz!l!UWA2h zdY8?i&KtW3&vV>uhDKu8tJ3_{EJWSr%ww9N#C+TqNTd(zKwIW0kn~KDL+ZX{i=kOl zr#V`+jhx-InhNw%K5ECTGno>UVII?vk8;XxH)PX-PGm!ysL)hQXoZVrnYK@igX{ts z7K&w)F2+vc#0sMAmrj}~{e(bEHy418SGkUygbe%<0d@fmTV61x_=kK_mpX5J!FcX0 z%mQl14;Saxi1l|UB}$Ef1imD|!gfq!AQ@~XHxjz8#W>(Y<>U*Y@K_o&@D@7lAtKA! zRF_9|aECoA9~xw0g0DWUQjX}rTyB-k1aUjwW|e;~$5F8Ed4vz95mXCSTq%X(n=uz@ z%j_x5&E%*sqX01mr)Ja=(y8?gv~OT;^D!=q+yW^}C%> zI*=>XMyi~23OTPDq?>AukTg?h=abRqpy=2Q0{2E#F^EmmuT8n4Blkvu5Q{W249Pmu zEYP(KU&L~h@%x{@EgS}eC+x6L(VoBQVWNZimb~!0ROpb48$4b9UWEiKn#plxWdg15 zW319&8nswpHY)_OC`g9^C=kGYOjh96P}rX@K8ax`(x6e(noQOykXmg0Jjg%5?+aO%hkOb}Zjs`_%ncTlI_72oMgxFAn)%Q$)H z%0j0M5|YAP5exZ+BZasV|Lfa79t=jov&_gXEXH@q`Yp1^;T_G=m;a3*sUyws5e&N@ zs|Toz%Eqqs(;X>(5k8&||FHp0plGR~9I-yD)3}jDaqR;c8CDd4qYpeo{U3-&_dV-BJ*fi7MWG|ks zQ0)$?TsAX%6l+jo25qUyzEa8r@!I&FzKe{_dc$@%iY>0L4qRT>_`9y|b9BivTPoI^ z31v>A>JpHw+$At78j)n4l&)Ll^4lt|2IfLfGC<4{@4lqo=g&!dtuYa$IdbCDi69L5M!&>v<&zJQR=bL$ysQ<0$ zgXvU?G)G1v?2Mz{kyZ0Ac7lpb>QoZjYp1gmO@davkoHLt6DHdfUS0ahAs7}IEV;%9 zGG+_eaZJN$eTxzDeSLOD(;=hHA4K#Yi$&|R!0+Zm*(@Y8_IdJ%3YoFNT|53Gd+elT zXv~hoC@uk}p|b%jy1yUyqn$0xH6V^hzEzW5PlVh2PO*WZIyvNmUNy3hstB6#xR^cuX!Iz{}n0S5cR6&}krn@b8BEqCH->v} zy%U3~YG*#`CHJQ}DvI*rmEcJtfORC`015a-<2phDw$MFWv`!|R6I9O0T2MUjw(~jz z8l{cI7)ueY{e5D4**7`5?JkvNKvN0Iawn$fAj*Z(AsF+#UYW)rx?U3eIxWh-4H#hH z6`NbwlCf_pFVCvuUCHh<3=K$A{wg8{;SKY~bCgik6PDTC((-Psls%t*2FzzqvP-U{ za=t@zE)zIEPWOPyjo%;vUyz(2KTZY*=lV3FxEc1MUJgBNzV^~PRNZ6$4ayY-==LQp zQIsPAuoxa4_TjMLj|Qj5ptM8!%FDh9Hz@;w%s)6}qjX}~0n;8(5^G07tq*)i%A^^G z5t`K;^&I|?O_Rnszf(D#sgMXX^Umkg7Xf@l0=`pOhN)chG}sD(HFBEk%QWY^D9-QG zoGUw=AY+(065zK3ooZ%;p0sj=+vTq53qK(~3Na>OoC9NX`tc^yD5h5ZgARsniVRG|5cb;>f zvwz?^`{BCI`~7-7o-E8=t-j$XM9>m?7{?I=@7v>_L-z#ewo<`uaiFXJG{vmF_@X(} zs;dAoDyu7KL_DH>P~dxT%%OTv0buU3AARzDbdx%i(_M6zdUceCy3%7o z=rtUrV(xzRwz1U8h{@5yV@r6a=U#^m%$1Go3*Xykk6`)Ii>_cF@}dn$bv&2z6b;oP z?1w1+cSP8+O?ZG7`aK1DVhKwj;v7h*nOv+jhwt1b^vN!TFZIJie~!R1hfDeL@VHL@ zy`Ui|7c)RYzlj)P6LD--g@Zcw{scy1IM?4KHVi;Md238GcbTB^b$=(jqZI5jKZr^ZyNasxUgZ&P59s>G~nSaZz|@e z7M~4i@KmnA))FE(ioc6{Q}{W|?1e%-1=m2ql|0=0Ve6@AkQQH%$HYEYEj-^oo7;vQ z2sW7wXNDR=V=Loha?@nzY)j|%Sfg~8f(b#(le2D#q)4&6Q!!G^JJiU%apfQq{1Iss z#DU%y1ODIu7ZUbw6zVwcHY6JQhKTgv(`-Ld_#j)O8|+&}e`g-);~F@y9uk&K#Ikut z_3T;e;w(QEI~ZN0UAF?kFyaE zmK+v0;YWFIN1`A^wcDk3s}@PNCS(+o1H#F`lZXaUGY#=e%PzEQu6M76l%Hc9h)y+V zo6%ZJHuw+)F$hBICFg!Pf3kks?4xx#!avm7?ml9x5qg4yxFpxku0PVD>mXk5_|&rF znXUy5qG!v3JsO7JiA!j-3GOa|ciUWWdwb!o&4rwAFc%WVj(T+BW+DjCgWrQqR>FUM zx-js@^AR9mU-mzl_)G3>@G}1jo1c4ue=CZAnJVyy&A->zdC9rm{^^~&w)ue$>>)n< z7`2RW>fqnqpC2Z0EWIxsis4537T6cmga0Os_Cc}3&=sNC8gz$+BEh7*$%)R_s42=O#GC=nz#lYT$7m4Ier(f|HdeCzGq+# zuVqr`f9uc5FEe_SUR6fYm7v*T*(XMzew_SU-r9;YYxDkIGzgRCC#=mc@5?`;x(&kp zNW8pn>?8UxkkHBDYxs=63&ocwrl#YCPvs(_l%<9_e6o)Sf7Ve!ODKBvNY=8UEmoK; zbh&PqM)6da(oNSw{*1`}!_%Uh$gFQbYm9~jyxL9i>H+-nrnr3dXL6>y>r%jW_3vY3 z1`z%Be!1pk_XL`!$}wl~Ntw|J&MOwj@6up9Mb2^>RPH=dHpJnzZT=nFU*lqSiCw<> z+gHQ-KE`|UDUxuIgr!I$zP)ERNZI=Z^s&Z*jI zhUR6MstPmvYI^X)Dn9BXN$=js7k5)7JU;mj#C?2O^gMIELG#b`*gWfrVyD}&7rn56 z%({VmC)b5 z%WSDVpnlc#XMS-Po$GjIbx#2j_dtDqj|C*WRwmyn`up{#@O_Uk*En!3M)k9N*69Fd zOIOy_DCI6k!5bC=hoRb*_>Tjh1l4!Qh)UJM`Je)iT=Bf-VIA2`MPH_vRkla65xS&K znC8Z+oJ6HoMlyM_H%}>R zviM~{P?wXzD|&%OpyP+V*50DOIm%u?{jt;4?rm6e{cJrQtM1_vvFl(NoCgV!5&SxAZ$c9R^F}UB=0v*CgWlrp(b~(Suf3gQTst6uRYUU+OX7oT<)ss znYN!{IBaxu^_pZHPb?U2qU3+JVSw3DcRkQWynnSY-!47h1WYJf8wN);-1F}LbF}dV z9YoJ^1{2k1v%th_AqS1X);Jv{|InW59>H%7y%G5J5(ns9^X`*ADmX;Q;O^3pNdFQ@ zBH|p_^JD~D&e|lh2QzfUetl^6T&&Qq3);hT3gM-x~jSsaG_UU;nhZ_U&T0d0R#CMr$hJ z@LG%dz2OO&>r{adVUzXE-zsUVGI!%wM0M^~p55q3tBDsWM|?_M^17Aq{>B^8TN=au z7KG?1cA(HL$QDGHzG2L`LIjh{GXZzTB>d-_#uJw$BapO9l4qALBeJq`!S39;Y+n+S#oL?6{FB;fYvz|0 zPpOj!$7KrCz+||7yt(Wrf`sJ)HwS2w#e>EX&uR?>*zIx&^A-VuGH{_|P!Ps`e(>-t zNA~c1w%}yhr1Cs~wf_S|VUqSsFHRr+pXU7c3zt8NNT(9GaBpUjdP_r7*prSNSs8}p z0#LA!H7qhgEvkJ$moABA5R7hF4k*qPT?HjO%T_jmb&t5>9?%-+sYL*foOA%Y^WPyY>Ie?9&nN~Gg`hCxLlFfr@;6|>bBBsSr3j6SMsBqk2!2f2kmM&S)MzsWWwwzl(o5^>V{Y-knNAjOOQ)-ElCw@k zI+)xMd-Pv99$_}lHD48_$p$@u|L|c-xrd~g<_h3mV=Vo?l|Q(p@J106T9_$PR$%-A z#N}HC!eqAQUR)n!|8~?du;@I;LyE26aSJ|}aO|p#YpT>{ZklQ67mnz^8<+o{LiER! zUI!5&LcMGq!*QABGr1|0C3b+wjZ!tNwr`fyG+bXzo-fQ3B7U9yT3wf)FT5`rm}SFt zVrwuyq?r7I-NaQn1Qm0FWKlR36-c}{dvo}8Byc2p*!N$r%=oy?p~7?bUCo|8IC+}C zOe7%Nb&q_h!qJHUNSaFcs^%OvPKuQAlP4r$FOfd$KTAG|(TS}Vi9jmxNLhh|*92#- zwU+lf?!5RAuS7aji(d2ANoYtQCZ6a?=kl>8tO-{?xwjlUWLMJHsDm-GQaELGHDn?0 zWH%@7dR(@*(L3>{o$<~9G>;+P`gLD-u2tuWj))M0=g%gur51}NkCX*?Nv~~6EY2_U z$1mkZV50~1!K5o|p9CMivHsyp^T&jR4iWAFu>GqS(*tk8L}P|C)RVag8F>&Y2x-Zh z`7N@0VqhMM^C$Pl3>7)vO0 z$)cZfaAH3DlkBief%`l)4W`hT+B!PheDnowgo-9G*T;%Zwd9aKL`a*`$27b)!6Hx& z3KTDWbmmZ8%X6QaF<|uS(Ikvb*BSx;*D4Zcg;CBm;Jd^NS%Boe8m}6e##-rGs8wR^ z=aZ_PYZxJqYo0^U8R2|FEZp#XA{SF&ym#HKeP3T=71;{C>}Pw$}uz2(wG9bCdBf*<5PD%=?% zDEw!bZ!zu?J4XyTChrqy59$8X~JvCmV5TGZ|2#fv89kB*LX7 z?Rg*x9wC#OTim}>Hn{;?as}&iG*)h@n6TQIO{v~Uns=XppM|=~yB^cdTVIx$u!N%D z7FQ-q@mDEbsky8Y$h}PyW!q=jsCq6HpsVAcj$ZZOZyiQg5Cz_4J80E744{WDkjW@u z6KQ-3Lko}BW{jtujAsB%NsLX}H6LaoGtDKOqoZrlw`7X$CSm2xc1>y3Kq>jf@~u42 ztgb+25Ftx8mYXeG5Eu_DF)xIxRwAtS@cxl1XIc06XNj8nAwz- z&nr|~Jgjp{npj&U>CK#zY6O^8U=`ZBJorhg94;QC7<_f060nR^s#ts0hIy)@*&=_7GD!ATFR_T<5P910=~J7 zV6FVHdW&qAgTDwErxbyd#2U6M^P*hJ5nN7OwC!%ml3?IQs>2@b+ozNd9IhlX#s_p( zWe%3rBGO5WOF$aX*Ibf6R$4gmiv$5$Ac;`bnRmn#-Mwx*#PF+lRl4c%2WC0m%)map z84q9OMGTW1z2B5Qp~XP9ie|^&&s@xAar=z>fEuT=|Y6$GlU+w)GhiU**Ri9L|TfXsAlZvlNP5#x zu@|Kl*4wB%8!!?n#dSHaRd>8#Gtbs7<);w;6J=BfmL{2Sb?H*~5X{m}ld9OZLxfoho_v08(12ZJwxJW_67784@CnlGd~FSn|+8!cW*^ zK}XOUgsDn-A8Y$^Qz9T277$8-teK>5WWm5Sz!F4fudo{FqN;@iu0rE-cy zt)2j!eXi;V#yB0|K;0wlVu)$(Ju^OW8n)oNoAZLlKcI_4Q%Fc)?+{sJWo+UCGE8aQ z^a4zulX6bNrN8e=0g_Q{pYmtLsupF3JCy%2*V2Tk_n4O6<$3H3AuT!-3GQo-Bc(y1 zX$~+$Rwnfq1197BP&McgXNsoPhuJX_t$!KE54p}9ORU~)bn#luOpt!`1mxo z)wAf(38*hZ$JFP8|Ltk@%sg+D52mJkpU@-~dCEBjl>Q<;Rk#h=U%%`Mx-VjfrtPk+ z9%rPQ5Bn4`KcwbHEC24hp8@lH$w@s$hyU|o4!mU)9P&CtOoRF&wV*z+q^D=J3`+f( z`zU+6`d9s!yflMi*4WKK#mRu*BB(fGn7xDx9)ZZRE<_~#Z!1oL&O-|EF zlh8{Ogx7v^strBkpB|rQy!SktZS`fvpjwz2k8Okm{*_N(kFlWO=FmR3Pz45P*A<0z z$YC5C0C<2;0J^|Hxjg_TL|5+vlaWwUL+{?uJgs7Mb0~f+oLT9Q+|@NpU891{NK8*T z^{M2tlXb6yGhgB5$wmVP4|#{*?nA^I&WCxXMFMGOn$kcKNLX%Cci~K~lmgQeQ zyDptBG+#INHey0^+(QjvTd0bk%y#gTv-N2@Q z?v?~P5NWnkX}r01;yR?E6QUSZtr~%$T8Grzx1=K1gZ!8@|BBS5wG*eAMtj!M=z7Fl z$e?ls;mi7v*Z&9rT_o+uY^5=CCRz)Tprqie20$saYmvU=wat3QyQz5P#8R<0Tgs z-_)+3EVl})BERc)sx)dTK0)34AK>15l}y@mocCM7tQQx2?nW$!-}wG!6{p)(+Gp#W z-jm&z@bK{7%UqMmH!;tx(dFY)#7TO=U&bP(6VlFkA|XVYhP)Lc^p1NB(yeb90O-KD zcbWdXQHBt~-{*JW^9Ntu8orl?)X?L)hMkOF)c^E${3pQNd=(hUB}4lU_7BUaYw0ty zF5I$29v>|sOx&tM-aU=PlNdm5Qta&F?t<>g^wPAFxDU(H_(J{DJy!4Nge+j=k>N19 z$I0T-M|`)2TScm#F3$bUb)V**tXRA+OwgnGiSU#U9LG;PGqTt%uc6_&cgVgNPtr+?O``?B?^@u`|jz3)ywkGhK0jiSDvVjeu6V!|2m75)#N zkO3KleYy>Gvs)}rLQy;!w<9JPq0S;9%qT)yd{f#!KaMsP9@I3&R!2y__$+o(XnfSs zNuPDQqnIg~s>!x=^ee*M7h$eOY@E#)v>IkD+HIMcqO%l_u`)u$>NDx-&Yq0(IE3LH zg2>vopnh6HQ`%k)wAvdH7oWDf?u96F@)Eg-hz(?{9zztai5Gm;@)ijx4XxuTtRwwJ+lq}_Wb+TRPfnfqc3Sibu^RKht5-PS zl~O7)$0EunF9(9ArOIJVKfA75EuL7S=yFozVKIkHv;G7kZA+mRT68mDXAhR9RnyHm zbo$YqR7!lfCLO@-?2>mN|24*Mu(t}5KRx-DCw&nnYvY)Tlg5}ckA|JNg8xdcM*8PM zVnn2W^gQD`VE=mwL!#Q2-nctTfIW<(hg|+{n@g`Qq1!jnZJBgWK3e*@fm8p*JC@R| zn|2znMe729S9;NK1dFq|Dsmjw#k0^*k z3yRWQHnN%8>X~{nekT=3up|DeK9EqG24!dgcqGlP32HZg-kJ%uru`b#%qp{bn``nS za|6ou+uUzdUW%)^zdqyr`M(>{FukReCRELnsPj*QWv;$r#-M0iSh?9Rfxw%nshLHa zQfPQJ^yE4EZnfs0=bs@jKD}Qa_zOhQQ{(A2yt88-m;8=}KWiHtK$MrRy*|T>VsU3ELS|^%q4^Ce_$M`RwvlMQ2E27q$G$-E67y=B?0x06kl| zmEGYC(SxTy>}Us#?l%$F^U?{Yo!}}tquDX_$MX8<=h2%ja#~@7W`RBXNLSUUrWP~B zzg(3&oKEQc_~ZEd$JC^ZKU}D{Idea?^}>(2cklZ({i~t&XxdHQtEBjk@Y300D`4}o zgq88Uyw0z$@1A!3_xYc!O>42;%feK|H{{~}rK4Enz|icsIr-e%4ddrasRk&&J9Z6>9WOp8k2?#&Z;%4mbVLNoQGvh7qVoVQlRj)lTl zqpr@}fm3CD!(TDP6BI#5EeCs4xu%o#%{eOg*op@bjder%f!KniI*>4pM!Lv$@vDaz zp`1lPi=zfQmZzILhwVP|I-!2T79_0jO9b`=ja(}E_&{tueE|nM|>rg_lSX{Dqgy-I{8Rh-L7*shG`G?+(4&sS}kY6%Sb!Wi!p1Q#{ zUWuITw!_@I2ME1TYQ@&o`4mXXQsm}fJQ0u-VKs>aN6vmAF?fFrmXgNW3f-K*7Hzc7 z+k@J~L|?(RCm*M8J-P1qeQ;E9IHEl3U^lKVJ3_$ZkDg>4R4F9nNQq_ZM$B1e=KgSs z&S!hxi_Q*G&gO`ye2OGECQcT+Y6a*h0WZz-3E+tyu(nIp(v-vDI|&XK6&*@%RCJ;g zXp0BN6Fdp#2Uh0E(kwAucA4POPqu`UJL!;LB_@lgMQ^rQIf zWaAg|X*vk(s5h7c`HzAea10R4=UDozE0&Ne+1aNPUt5Bgu}PAz2@|%X zI#6>yI>|yDk_0CTS>i$s<#HLO@mf%FaJz=b$`Bn*X--EK<`%v@#Ut;J~0$abJFxPygSIdu7V=B0juv$EgY+{p@7hP>Ed;?XY; z@~@rkXxJQ?9=)#m{BR-C6U5jh8d0dNoyNY}B-Vpw2 zy;k49EgnM)Pdbu|+5*&7y&t!@cjfOsX#^1vM}@rWTiUNh@KJgjx+->;hm!tadP2VEWJL1u+$^2J>BZ}4V~io>Eh=Ld?yY4 zS;Kt7+xcGatQ1-~b7dM~rBd^5ZB9R1%D8+-j7$PBUYo=G=Yx<(C-4Gjr2GH`$&tN1 z#h27qbW8f*X6_#xO&z+zzpJRfb#XfvVY*mzGAUl02wp}U24qKRAF&D=HLs;U#|u^M zXy>M2(f{k}S)0Y=9mNCw%K@F&<2zNM+h}h}|9$uCF_$K5{ZiOB4L9Td)6w9jkp3L+Vx ze##JF&-M1|iI3A5$G?<64cagl?ZtiY$6Ubp5L2#ScyUUnF9~Z;vS{&FKjry+d3f%w z{{GJPkC7)$aLGHn`h7!xKT3Wn9lJVi0jxXo$6_s|7I~vpXEOL>Id#YONsqJMaJw~4(;d8bO?RQO^fr%brqgwwB$-RsUsQ5`dS)84C@RDJ1DbucV-U$er zdZ0R4yQ(-sVm6yCs_>whs}eG|qwmp>#J9@l~SX!c0zX8(yAp zdK0Quteo%UEY^D<^+ZIrZFT=|Wxkdr!=Ed$T8vQB*CDEjqf@e2a{cnY(LTc!%`#wVb13#;Hj2?h~TJ<8w4kRFibSowsCgscy)kr}Rgke|+QBb2? zt8bU9h_o0&x;sFL!h$eILKjlSeFJb_xNXe?rBf$s@C9m5fJDw+B_+ z$5j>gix>@mYafbx`|t?g@G~j8$>JIN)*+9 z9r`s{qA!V}CVX%j@ktFDf~Om@Q&1!lU`PVuAxF!GH2(!?-wh-u2`Yg+v}Sif$}R2& z-f~BQ6gqV7>f#B#v;OT!i1eNq?CGdgCIIj|sw~$Y*(yAQqZ_a-fZU<^%AuO$`%O>F zOMZJ|Bk3saC>T{#gYST9RSb$&494Wv;}xVihtLWlNJlTxvE=6CP^&1P7B5Hne< zC$WbN+bj%sSd?pP5_W~5N~v_MdD~9;D5#JIZT9N80)xh&jVDPw5E+etIaynpQCQw0 zisbY4x@%miMG-&m!X}CpumdWNqGR<#gpa%)skaB3l7%iYE-CH0YZWpqH-|{87AC7h zRPk%!`MIXGu5LW@*LLY{N7hm+U<8*FzA9@X*ZH}QBZuc24m3UXeBcMXq+8`Gk}X%m zHQszBu7__WNfp)xTR+sjPB(Z#)=8)Sa}(b8OOcGNQmY5KFziC0if5`C;o=2KQ(%eP z$xcBt5jugF+AX!3KrS(Ik&jT%79V5z=+&{%BBc>z`Q2txsZxgi+xpyek6v=hG=*DQ zkg`y#5=(XpS}yWKTI3DWLtr-ZgQCFTu!)mj!WS_7u04M5i#~iEz$C!T?=R|FZ{kY>@b}3Yw`Ufew)jiB9f&KN6g;e zyQ}h0Ij8?D zKcCx!ys%=F4bImoZq_ zASP?%lg1i9&FDX?G-r-{9vp;TN80{wQ4*g$id~5W-BawCO_JpCJAb%g@%6^8M&w%1 ztkf*oMcVngzMK}%JXeLe?G=h}O@I0lB-WI?p4(#JcN%u`IzG5v)i(WouV(tf@YWO$ z{P>DvGx_hv2OHZc3(6+uvDy@{`*dZ3i~bxXd~I5^$-E=CVAAZgWAh-r)aeOY+X5Gj z$Ef|w8x|);zboFW2oRM18cHMyqWWF$#T2+Bp7O?C1(g zgg61|v+z#*oZvNCJE@^s8)yo#KB`)yQ}XfFZip@asdoEN8KK9O&23yydciRwHcN0s zcz>xDD@gYdLqroQ>Yy{w8)WSamaMnGgwzz;{p1`Tva$VG`2BX!Mw3I9j`N0ceXyOQ zrH<-_XxSS%G}-7Us}q}}2gJIfwA#qZ&P^5Qca@3d z%pNHyRbGi3yrSSZn3eqaZ-sYT1aUk$=wgqGQdwBrqGzVBmaF2i)6}Mj2EJ^|g1(YO z?$eH@>mj%lmCg6@e8a^JC8W@6!-p#T0{zyUqv?XNvpA3}fChHF-MOyT=Jv-a*tXJ{@x9#CVtGZ!Y znm(Y{m(rS~E4ln7<43%K@^ij0ziqh4)CqLwtD_cY>?EraWuQkrD$FUqBT_?(^W5|P zRUsM`gNJ;}ns=WLH9TGBlvLZMYnAcw{KO`r4b&r&iS5m#>i9N$K1{LgCzsQF61qIW z8v$Hs+SeXPrq&CuvSgA`T7>P3i5C_UrIY2TQxE!%QY)70@6W+#G2tJI0)M8r=>4p? z9+f?Df4bXjfAs!?tA92!p7e30)HD|dPbNjbpTGa&Prj;BM5Wo+^AG+Rv4)z9KO@$H z+#VBunOtGJs2P}F`z4!_OpHrtO-^VsdE4}qp|uq#9?xj~652i+>X^~L!dTDW{@Hdl zzWwPqaG@}e|}h_X;6Zftht%2v5~Ca9Z>=W zYu&lyn7|l6a7QKc*0jXB(Yc5AEV9#|hVDkS-6eHxsORc@x2BpEKpgypPd&PmOp4%Q z=K;aR-CFHfE*5F210BRJaei3Y0a{4{1a7%)(#Y*Yt2y+`rllQ|*IU0|EckcmX;2~2 z_t3H_pHQ7LImiu=d^fvl`c`20p5(CO4|B|BQuXX(66qhQO`M!H$p2@Mf3IoMw5fLc zV#}kiq&}6Mw0k>W4t;EG_;?ceO^gkg1FvIcJW`Ilq|N#524 zFsYlck4EeOlE8h*R=LD(HSBpY6tM#{1Pq*hF&H;l+)ia77ci_VL3RZPoQu2r@`D{p zH2p^ljS51Xt{OzI&-NFbJX(D?NoP1!l|!ks$x}QQK3hlBheN)48~;yp_Q(@Cw(x#e z)WbVS3Du=H`&2!1A{6hNpc)C}*5<%)1rG>=z+gz5T7H`d+v5@#IB&b@(Vhh|UI4F8 zcma9JGB*6i|I?gHv`^06{u!hBxSE_Ma>!Wsdd|JMEO1C+?5U?W{KtyQODy};*SGb0{FPmd$leR51v!nA!8Dm=DUUPyMN|=i5v}zHJe)?dmsW!gC zuK2`gr?b*yU+*h2q*Wx%nz7S2F6wXUKU9=?X?d&Y#DXlP&KjQDe$>O+I&tb^8NOfdz%U!h`|Bfp|#)=RVJW)y(H#0d>@8G1EeM)PsR?39g6 zcHuRVxCh}60S$cXv{Ur#(L2qawU5WIuIpwWDi$wrdveSx^2xEXOQ5yP>+6NxRxDBv z(^fWGeBZUv?eoXx{nOR;51dHKII13)4l90kvL<`(2}IS^ec@EcL-*&A{U1d}-0tv| zJfH#puk~;q7zbG3wg1O@h+?Vxz=TwM$JsSQX*fCi3fqp_kxatD@c+N{;5*UTFj=A% zc)#NRV?8uJt|q0RrT%a0;rRXT=9xxH-T!4h9Ni1LF?w2`-k=U;ys$gf_N*&(rscRQ zrChH!>h=9f2hk0kq$ls*y_mfDpCy&^NB@IDAA9-#v>y68UXSI8Af#4+A~#pRxl#kEA;E?pY82eP5`&)m09(Bw+R*NvvZ7!@k*Q zq63w^!aKR0^KYkw^nSMM)T=$~;m7A{lce4KM_=~rY;Vk*QgkGEu)n-}J$c3P>i6G2 zcfK45+0QwY_!ofNie9+0b6_b6*?Fuw2|Q7-l!6PeBBp>03CpPjv!11kd?6dlX|^A& zYf_2Dp({r)Ivf1y2YNSZ9VG_GRx)+xm@Zk6hoP@?I{pSoodp4Jg>$5~Ls#=8@m@0d zjspxF*(}_1f0~1Sm_j%QCx=tNvtv7->soblr6}n7_e}La+70zN!M$Z=65zN1jP{t( zG1kSEZ>|kj6T^G0fkvxi)Ff`aEU)yUV!2l&!(4BT#8gpf4)&g#n`M2%53ko(sJKf+ z{?#6NS(kQt;cYVmRTpeN0Tm%h2w&Vq&1k~D|L|>YS~nJyH2YbTM+8AvcnU%&)XZtv zoLBwz2itl!eWeo$r6 zt5>E}J{aZC{pV(T3FKl z`t27KFKm&5!x;odKE@mg+U@!h_ZT&^NE((ssoit9u|1v~qx-4v^_f|j^FUl5*9K61 z?w`LJr*)Sn3VjIbCB<<32j0doU&1T+4oLv-4?VmPxsrM7{Fv?Fss`2rI?+)yM9AKj zu+X$=a{`W811cbHy zt=dM0q`#j^%{OKucQFC& z1!V@3wl3nL3F>GY98NaV-K=6YPeVEHr@~Z*t~R5C_7mq78^B*9CTV&0`%Pym!VjNb z8b{yC_>Q7qd5jvBld;o0KBt5Nb0L~?vb~xj4Uy8$BOi@LITy9%_X0U0;?SCm7x*t3 zXKnYcOq_R*7W1J~Uv^I!qFh=p{%n^m??&H)ub8Nv&1K1b6(lFi+yUG)(_T#~Nn6|4 z-&Mqr(>Z@s0(r!IIV-5E~o|Unvs6KjLXRkmE zWuyMu8i9#9+!Y4}rIC!d#FO|lP^z@D+TO*0cFx|#fK($N$%wMIxf(y$`O3>8NUzIN zVK*bFvw0sf{Dx>w98C^bZTeuYw1xd|uc^sa$k92JGF{;w)Q>hAGbyB`YT=;WKbbZ_ zF9~}I86=q;pK=bdy^tDOCpFPtdFGsX)`@vH`F-l+v8ZW2Q)mFj-*9X<=K%eEgGb5b zib&_V-+2jcG8D*LbKUF2v~x=Jn3+ z4rSxv%1m-bB#$n9$&>D~pezi&Vu^NmQV_L^2YC1(6o@b+0p{c+nS!L1&OV4Xe!vGR z2tp1hF-881p8uHpTFQ1Qtnw`PHJz|534XgtqE6+!Qv9h^D|B3HeUou=YTs__{wZ@< z%_hvRSOd7GTHozbQksc|O@MMm2t@NPpb!)WMj?!&F08X@F~onVw#sl9v?VoAI9o6s z2c|I(XUG7YD2S-&8I)w*;%GyHO~^NX!R-HX#GdUNfAjo9nf*2=P3Ce0 zegw&wn#xy}Ks1PsdK%AYc1d{mY`-}afl^@}$?*HIV(gcOzV2X7(8JEkM{N#qJ&nIl ze#H{{3>o?~jkvN0vbNE$rd{W8Gr2$|p=Vk7rcD6WYt#86QLKH!>E*dD-hGEjLLzcx zjGILyqtBfXJ;-RscgW=hbEA~(toQX!pMqA^sL0zaItQh4Akv?r(nyzH{k$>GFUlTG zeKqXilTNqxvSl(?dx+-?pWl^}?wTiEdVxCxqe(++5W9y~$+A3=6Xs(AhnCBBxn+N8 zvigJx96O+YtW}QCC#XKW2)fOMyai( zi-Ot$e{b@Gc7)H^NZj(rJYwEGxY>7OFbJ{dJJb=e5liqZGlmjL=k;omi6Bo)vVjeV z2GRBd%kZlVr>ve+s@4-A7^d7dNHIqW$p|O$%V4^-(5eSkxj()>*0(`TZ=Z1T6I#udK0Cr?9137UH z>uk?|kStBc!tF$>PvTb$FPo7Q+lz58H!nh>Ay8)l5C?TU zahK)$1$UaDvqS-pDA?YXe>aUhBZp;u)%wRUMMMjID{z@OM+-Ww5`D9q#41fEWFOuij!m z0Tq)RxYZ^snS&T@wn+Eb_v3(sS*gG;W!&qN0WX6EM&~x{|ySXl7mRfWnmUr ze*V}*PT7)7;%lDIott&K{+^duusT-JHU%0^LR|uoB`mZj!RgEvOROe0zs6tW0B+o> zL7iLGzJYM$2qaUXB^(5eEopBr6!`8)K^p#qY-%LElZQ1X zD9{^hlnD;0fJS%rkx@Yy4RN91#&jZxF9qGA&{3|DXS<{%{OqS!BaDBA$p3q;NsVlA zmI!SUMV?4N-Jq3Q;5D+|y71`=PE)0v&j{YZVbk8>k88O($yDw&LJujo>UNZlk}!Q} zB#ng*d6x|$wlpu`y$AJl@nJSo7i5<}gZuDraFJmJZImR%-c5Aq8X_qQeXf=ew}QK@~iUXE#t!O-Cs?o5Mcf+2JyBCf} z+TgF^fK(Lvf|82WR|OCT&!SvhC7%LE!%!g zbS}!o3W--p=vK&(c#h-mhQlpLNy=1+5e}#(womF4q0amH+`7i)r1$iTIv$E2hQ18m z!&WY!mTkgYdmk_)-m$L>8RL`z^tM))I|hIFg2<%n*=Gj$91VjcS6P#cozN1RAfO2#0-`4LrqUG<4TwrriXbXt=v54e6cr3rq-X+&h%FQ;0vZq%R4}0l zhzfRWocy2ttTpSbz1N;OGv^)en4t`OuJ3){7a+03hb*JSm6nucbSj-cK|?{3AKYF+ zU!a2Wcno}{;~Vboy^f|Xe;@?}@|V#NAv%wa&SiDna6JjvMw=-r!9kSN?~ZdI1_EN} z;&w5;>lFi8@?1$B1P<}}a9$@&8AxV!zk!rq62Uhyk+*!o95VRFsncUG>4TJ-{1P0p z3?;q>-NBy96|Lidol?jBl3^5d_@N6E3d^ev`>l93pNnPS)%28PxV^2!4Ie^Md9*&v z8m|*kj!s!pyj8(_Md^UkAW$L_T<*I#yfw-~u@p}{Pw&6DwhfAs~xRsqsafZid%o)+Lr1^7P#g37Rjil9o1_xX~} zhKpUOB%gWyFeHKxFZY`l-hZJiU*d={L8*&C!YscQ)6t^oHxle`bA4^FZL1$qXLFP#OyN(!Z#LlB^N=_4RvAcrBasf08`={wX)fE zAAjiB;vl%85S-=)@nwNUK0z1}z6eN8FN;U6&&_cB3fGha;r@rtZ}OREzp}hHQ8*^i zV-q^%vafR1r?UFq{MHMv_=E}eMBl@gpLbMG^9lE={mZmo{c5D8luFB)1gtV8Bew`& z20XRO%e&Ao{-D#ED3ZEg9$7Cbmmu<}6De<~|Hc)mZJW~EH>I60rBgPw{{EEyX`=(72rcKMH&F@cJOipk6J55)evD`Ley>G@gVaC2}#_|4)^Ywn_#7wrk z-VKS_cEeeZeTpp>@?HsI4cex<&e`+uUPR=eb0n?m5qR}(JadxN=4eFR4W`%1L{r~J z-wzMHuHq5>*7NJk$w~eATvheSw^Y}h@=tGt#Hpn3`=m8$H>Yh=%_y5U&ZD2*rYior z>r)ocO=LM^@Z6DwUMUJ)OI~CJ$Wm;vbq;Rhi{g z!n@n*Xu(ZNnakqs>+h~cA$pfLDka^yuwkh-zzuhP=~0=UPxhTBxhAdq7N6#tR3yB6 zobX;%3NFvX`> zE~hR~t>81_@00hvV28MtH$oPMci(7QdRzUoG({3F!p+tcV@eI84vAQFPCe&Td(Yf8)DX!vMoq$Z z$@4n8E6nM!l*~K&(`|56rNNPzp3Bg!tNNZ9x(K_=uT3i(tdro`d9<$+9cgvbA=TEd zS3QbdZWDK84(C?+x!u?iC+N#lJ1%ulSi2j}Mlo*t7}tp<0R?dBU?w)?W+UnD@S&nW zhtVQ^BskbkqTsX`&DdzH>gvOgKWjb zU2=&Ry5ZtA!&Yq5YW4_%$3P}dm=_p4HruWuRcrn1^|1KQ*PWV7grY`{9^4g63|3BV zd_F?1J`HZT_hs$V%?XpdM&g4bij~+GFObU$8)9IS`P4Y4s^Wmn($AfybL(6B3str{ zk8SK%mL41}sW0GoUpUiN}rOqq|iTmX7@LeC?>! zVpo7x8DHM;=XBoZn6JgX@`o%XRUbJs9=)31r9BCnPMg9BM{c4$(&+8f?WACxGh=K$ zzEf*1eV$cGu%x9*CxqUacXKk(sms_n+N(Hd09S=x>!c?bK1fXwsX-OrY}sSPhdk=^ zE8*?)o1=n(r5XTMAFbBnl6J&-NMe7~kO5r1ax*I}+H=8qWP^iw%p-F zKcHw6vFG6$eB>OElBiZkN!5kYvw(sCa+UoRsjK$pH=S#bdj|X1Wl%OJU52T^6k)VZ zN@^CoPjxpijDm3_lgZ1*X(Kk$L?U2Tm?7h7Y!6j1+(Pz0cM!rNGr(cQ$zpuc_fJ*| zP(f~DSb1KN{-ei_0tO)NZs{K7OBS007Rh!pTNg?EkJ`FCi>gw0_7hwvLys) zIT21n{F$ZckMT}7ecmAsX(p4W`%v3Ec{u=8CKsFcHV>|z zgQ3CQo!M7u>Q5aK;g86G=_c6N%B?bm&@y98JR3iYoJWzfux zcw-l><(=R?0Tb#ZPvwo8r!SGFt(z*RI#3sI{;p>&w=RL6gl)b%hzEz<= z+-g1Pauh?J(m_(UjR#q6F0-_^n;e2|+|-tjyj>UJi9UtMm*;1E-*^*$?$j2yl(qYI zs`qav^OJx)l^HT%^245JJp)sr7ia`?J&sP+US9nah=g!*B*K6I_G^LZJE~?ZPfpgQ zwo@V|sc*|>+MO+AsLZj;eRh5)QEb!WTJrmFNs=S`RDJJ56Gr^U-s-fVDF#fvsAGr7kxAPP5XK|{ZrLP zw<&{dUWR2SDh{*1v>#i)Ap@^H z;vRn4e_iFyZ#T453Ssze46HoFYKgJ0OgQy&?6FDfuh@`7(g#)1VNeL342l(p2~HVz0h@#VoN@Zxx-*##X7=5$G0jQcIVEe!Y2#lrT`0P=z;jiKU3Z)--2!!p4Ua z{TpuX7TuE}M30e|YJ1&*$B|)&wFNBKo9|;iXQyFXfDInGPZ`a4qZ>2x ztvpvtU_a=HOeXnolZiSV4}Y3oq;&GzXJDKcL~+^W-ZKYUa&yuttw3jzq75-W53gM7 zPf&ghKP9Kmb!7#}TzT(!(P|Sl9?2rSQgGNW+m4~!ol?6I)FC^{UAIlgk6gQbXbv;7 zBI?fW1c*%m5_n|6<8C+h@xGm{99T&S!j&oem!Y;LqiTC5ceOT}W zFsmvkwUf95yKsS6)Jn3E@D9Nl<}PZGPJG8zg6IMP28&j5y@la(^YA>sSBxW) zSIMnwLhKD@dUaw}ivm$mS4D*kp63VJzRfSBZ80=6enEkqW?>p!&|lqBM?RgG6shl% zS5Bq}#Wrii2{%)NvL=(G?{}ycf#>7Tvq4c(;B6(Oy1~tg!th{~rnn%5JoD%iN`;UJ z`Qh*r-U>Hvg0bU8JVpfG6@zpQI&)j;Dv$`LVTxJBhz{&|COT4p%3n}UT!<jzo;5@6iapB_hig?X6x$C@>i0!mUkNQ%03BpbZKdjoMO_Uzp z`JQDx!zawqw~NM=CdeR+4bG4WE6W~Gh=fQw_(Z1qb!Kth3O4RGIN`8GP8Ogo6PzNT zVt=6_%|qq|!XlIOfsBhu1>db+`ptovlff%2=(kvc5r|EKA02EeX-*_4nsJbkghh_~ zTTUsI2(x>>-*C9BE0XXO1Oi;_#P`2;DnoNoNmv3dx@?~`14FsN5TS$(7qu3#an+^N zB!o0etwQ;q7k#cc|E-KhV`wp=AY_8b%ESF4$>t@v)df`hLioTXyj~@|6B2A+W*z)V z@@f}f!P~XvfqB8zn4e18Afk&;n2sQvG6&}(%Fn!1db>u&f5Z^j>j{UeYqNcnr(Im< zBeoYi246TS`_T9@BQau?Q&oCWmh@caJu9O6r!2Ww#<%!r{d(m(QvJh3>z0%CZ5Qj? z+w1SXtiS)Wo=mhuuJk zuKXo&pxjbp@>0|hJz^p39iH+lp6V~2VGn6Q zK$VI_So2{Ju9!q}i$vI$kH8MPuf9@gD@PTDxmKj4&Rb6e|4ULt8Mq1jf`0xVufzW# zDU$rbt$oY?mK2E(+DPAZ>I(}iK{|HzUsjO++jZ#F`tPL3Kx^ZxTmMRmh_Aytai9N5 zirjef;2$f9^Zz|5@`Ph0PKx{w*Wu=oNB?mh9?!wOSpLuJ@aan|QhMy&?XT}1m-~y8 zBCAJsLwT6BFOb?htDkQry5c}TCgIESbk|Nf{>7U>(agIy+dsXy(a|kPAJF@P5ZI7^ zYt@nuKUJCOO#*G(6v?X&L88>N;f8Euh1hw~{$QDuu2cKtgQhZBoymj999GUZC29zAoNaZhT`iH!ob}LqZW9ID z<$7m}m}$Cm#es#vb0tAF*XAyUwJywEis;dOd->S&;J2l5bJyOM#eWl9K{~#U44h%f zg-mf$NOkk6e+?FEQ+>CsU#KeZ3R$QwK2*1GG*kQb!qxt36p-43PI0=*sad=v2MMZO ztmj`_>qw!8d!XMnws~g0yZ*@L(YqU0-?xI)`_Rw^@9GUPgFMMu3Mgk!y)&*=+4JnPK8@(J*T-)Q>2!z*|ni{a~PcXFHT+9YuVEq=Q=w! z+P-IeiQE|mrqKEcr*rD6@4s{_8Oo+ruR?VCr!u#P)Xt*z1zeQ+i;$(BqC&Ehau;&N*#&uqG0=Z|WU0xf; ztZiMS_ZW|*X6-rP2Pz|1wyrQJNdBVhJZZG;+;txrL(8izRo^Xd=x90tO$zI>$+BN7 z;@%eg93m>>4_ZjSY>8JT8VF-D;;f?vX?DOJwW^k#5iO@d^iup9 zj$U~;iv9&3q0s^KsO&jT^pDq<2v@L~G+Boa0J==IEHcKCZq)o)P?IvvnY=9eIi-3n+`ar(pjwLc+u=qG?7$$a-9`3d*9D~~JW7u;_AXWK_P2YVoYyJ5oO$^G%EXPB!2<@@ z2co4rZ8Mq48Q%-gybUDayt*|LrfEy9@nT?Xt;-Dy?0`|88;$t6rr9`yTx$k4MOvvl zJgh|%r`)rg(QnC-eLqv2}ewAPjgA~lV)5C zJ&V8=tS?V10yo$#Jw$E)vFq03DYokp(>(?7Qh%ZHq0}0e|IB2@7frLhRzaLh7s_eW z4t%iMJ8!81J+A&v@PV1VY177VYY)!yb?fz;*^%nYI7@ZT6zz&gBEUZP$VvE&ZH#3U7CXX2i3yJmNeA$btQyFk0=kvb zNI*nH9CZFP$%0CiZ!YOuRMV-^`ON@=I zqK7r+x}F5P-6dU1QQd={k&yd9tJ-gsRTXxUTveO8A#CdsFfSIf{Qatt zno>P^vWoup;G^f0uZWH<$7(&vX!AqQ>I~34dCR3w^pjFRB-(oD&JhXSFde+_aVzpA z*hO8bNFpSs+o9k>kA8e4PD`Tdgx(>0GCcTjbw;ClO30L%Fr1yRH)$W7mhLdE$KDX9 zp*%}HZZUF}#EgrVfB&q9X1HT>((jAv*=suihBKu_qv*9mt9F|FS&`-yGb8V#DiQW! zj7N1`N~>q8y*-SX0=H{Z=DP2ka%%F2YYkZY;V$dl@Lt_ekK9-DmWx%j41sU8) zgJ62s3?Uz`Ki@~$A2jo$$L{91QD7I;KYiC_)!Z_dy<`y`)uVKVqv%_IpjJpW}%q0+_h%Ny$qJ;UHR=%(&+s0nrk9DxC5W5VlcOTEu;7ndG2{k zI>OTV7{}@bgdI6}i*&V<3KQYb#espzSVRYIojeh9i>5`4a1sS1ZL(>V!IRn&5k=sv z3t^7!Z=nsoi#P+@qx3f~iI7Ov<%8bT^;WToNKvE|1J7ATl!C`x{SCsqjCK=~C_fUB z48poG<(`$3;>qrjuE6N$nucxCAp(7Rl!YWvlLLbj!}`49j8+Uo$veCvG4q|r z*9|9n%~KpW@aB;%PXfru$YYy{=w&;plFw@H_F&2g?y(&vI3irLJUKW>LnI%nfsm)T zrILt7NqxkMwItkG(+vHQ=(=T=ctqMMKYcR=e=p*=GBH!lA9X~0|7mBM1Z+IcG=ws+ zrACJB%uECYoir+Ym6Jf>X(q_;A(x+2q@>hjsJ40fNUx}&>|~$K5+Mg%RffHc^Q0aG zDWPtH+E0;3_{cDDH$-5O_Rs!v}o`9{JOvd)-m02)~2Z0j*lM{y$ z<-Y%s)5O#4{Q;U#K?4QgmnqSllL`^S7RICyw}~~e#1^L8X&K;4Ex1INgfWgnA(99Y zLC!&PS(y8YOOOgacU^Q!mI${5*$^}0FZ*2gLoD%A;7^3-T)@VWuWYQVWS%kTy0#fy zV&;ioia)WAkjF_IgF#ak44w$v&dkU2V3=XEEo|6+HXEem_)<_=$FgM^lKjo!X2p2L zal(GDJcgn|8X{v$9(-y})d~d6`2{lNdmXM4PcUO$%JbnO&DG&(*vg@xdE!qHP$5Gh z+yfuz=a%Unp8&}Z5%C8w3YLc1+U0x23!#)~%=(9jN~-^;2{>wa5-MjW&O)$+nbJh{ zC3~s;^diuIkL0jDO#|W3dl5#-SEFH-yg|!Z!h8=lxEuT`l;}hioV_OBogb^;;elT< z9M-}2xZtb!cyT-@_F)h_5 z5vM&ObZe79p2^2&Me;;6heh~ee+0S$B~Uz)mXA=#xho|KdFp%mKhdJ2@q&II0#Cm? zMPdXjCv{jZeJ45vq`4g|msz1*@|Kb^j*+2)hJ0vFI{1+Yv=&xWCDI_tA&NZw7ao3) z4VoPXpRw`JID51sw`@*!R*Nj%@ilX35AiDtdRZVTo|bnpSJ+l8^TUio^siA&)Jd)| z>2yJ@_td9jrC(bo;z&~Dlb~Fy1lB*4xkkFmhv0RO1?bask_-)1-#W+HSF1#_o&58V zt}p}>MABiWK|tv+C=?JZtuN(fY08pn@5$C`tYm}{F%k?(wedRUr@Ci6C4me*^&}Ar zi}XpXhmhkTOaRe=fhIC1+3hA#o%JCl9O& zBu7ZV4rZuSu;j8XXzbnilXBszN$n{|@Saff>@oc1mvU_+$=mIbz@_@%Y{_p_$uF#i ztLtwNE0C|o&F^My?{(S!#W9<-a%0IwatV}N;qrj&JZNIx<36su+xm_IV%(3q9f5^` z6smANaS3dOmh+aFgy}Utfxnxe)Oto!iNcP%c+#FY=9n92e(hp2aRx|v3#6d@50Lv> zwuZ`fJd*ujB;}O9v2)q%G3$oI*E-FcH?fR{V4|r~M~ih^+#K_OP?+tClil+4Mna-R z3z-q2WK$?79Yl_GBqpIDjS$Wu#apciN>X^e%-=#ycV7iI$!t2MqPIX=ySm)LADEdv zljT!LBLyC8iP$Im;W$n0iX)#E6Kl?&Plc;a$)81npWd#Fj97@e0I+ zyh7@n9>d*WJ6Littr6H3jw?L6ZC$yItds1-C+_oGf%260Fbe9WKjFhEFiXg;$?7(Z zq;`PjunPDZ8*eEnrer_sAO3kvS<}b(YK7}9+@{?Spd^ujh7Cg?OdDtNxjF62xr0)d zw)B4^6TSiXVr8I`W8-Mq*G#j7@%Sex9ZPu)=#{P;%F?h-_%{||3Xtqz!9v8Clw)*f zaDXf7&&5fNhY_cl;8#{1%>PJQ{Gd7n-)`9di9h(7*>5UDCQ-4YgGQVs`4NQlTDhIA zKOSfF1iL~|{5GU?xP6gZWgSyHV>Dj$@|_XCq-(W zzEX}O2@Z@M(Fcd5hKGoo!IgstP-mqpmvN0-`q!9**L(@{H6}bBM3?IhnK~+Vh9115 zZ*fz#p2 zMdT5P#_Ne4Bu_)^B>;<9di`{3nY#4|F>+l0gyZ88+St}NwY=LowC71LC*R-Fl$nWF z3l|naTV%>7FRKV^3{`?T*mKo#;_PI32$iaYsb-c4m_t_8r#6d zNq^{Ca^n%4+N;P<6d-He-~&DU5&q%l7`5ra1_(6<*3nAarEr3N5s`Qq!T1uZ1I8rC z_}rEL`(h{!55R|qgzPgvj(=r*ROmj&j|$8_3rU$15@t35Fu@Ac|45EQiXMX?W%k&6 zO}S$kYq(Q7auktOCUZoA1);Y=DPQ3$LvQIRrOh`7S?$-BzvZpama=8gTBEj+Mx-&B zXdrY7AZTv|6ZV7Kc7Y)#u(wpW9u=0crm*9T)WeZsbN^4!VYb8YAS`lO`#l1^LJ)!b z<(^kTK-m1;u|Hznkx(Lj`_HuUMXi-3hr|>!|7EDFs!GiWW@QMOho&6xhpwD^Gxn?V ziE{TD`P8*;!Zbh-(o_2A;!i2L$o9vfLYY)>c)4oalY2}9xgrPAY;nicQ11yq3%+N$AVkUj?!(ZB+o^UI?qNo19{<` zSA<9tTA~9615q#$L%I0t;(xV*cupz@<@y0=*llaLJUIwBHaA&*^U|J`fS$7|+tZY9 zFFXNOk?kB&xUyMgGOV~V=eyCt{^}i9Y)gH zy?tT}Tg5e2G)md}*LO8)Zm4woM#UxG!Bd6h`+Lj$e#L&EeHMR;d%xm7%?@2DTCKhw z^X2`-gSV5o`*y1_tBCo{`_~fw{`s?cHvQfjQj^PXOQBI22>C!R<5or_)e^I=%H@{p z`fjR~#O4|9zpWs4nmlXiUDh-k+1-IW8~ObyG+V{PRXkgzqun$+mE$u!JGC=#LwicP zW|O_fIcq})t)jpthjmv{3>|f^Ry8^5-RL%SGPpI<zPv(o(luH+#%_+cKJbF3rAadcE0B2|6M7Lz@Q6OZQWyySLM85n`1JiaO~Wo^1K4G=oxPmh@kCo^)0S`-V-bvj+GC;H4$57e)gKl-klWLTYD8w zCCY8`>7(BAll?4A-V{4gecXC=)XHF@K9+)hb#m?D*+LhkQ4^M5-`CA7U*J%jvoCq# zq5NLfLh4?}yl~TLYAD23-Vv4&!=dkU*mL0gH5pCyJz3XU&`H#7W`_(;ug;|V#VgFq zlpODoDhI-JwOK02&Z5JWmC6T70Dk`LNadA6vA{PY!`@*yU@uZWq%m{QCmoPU1m*n& zF6u1(2>$p&wGs^yiP|ItJJFWEC>j5hb;*uQ$H z1Fhj5`ye{kuyg~l32)2mf4?pmM9MD70Vv`BtA~2TQIF5-|5p#yTa%i?S`1rs{^xa} z23G#B9_oY6eg9<7Vm-ScAIAQbJ-e6yZCTy%Pxg%5KX3c*?3vS*`**Tc7RQ=HU&NyX z-#-46JyY9t|L*GN`KR^!pZt?OTb>@cvg^V9Kfiu_e)s0dg9l>gI8sN*g3ASod#KvA z!X&)Oyts#It0PL0@e;o-C>*L4r74SF7t+aTI#U^%;vQJs?{9yNi3jF^_dK|^1p z-FZ@MVye@|phMT@?Czlt3G`sMPmFB5!R$}Bdw{>Tr|d+6w%}k*HLoT%8ZD#b7`_-R zwO1-8Pp%S5BRL22mCbcxqOiwmDk!TZph3xzZe1(ZzL2`$=sb^kdBnW{Totur?IruF z2S)mp{Q0KXN7n`$c~Wu+iOry*Nx9g>)90p{o?MA;3G=;x5a1f`9yu6j8E*Md>N4c6 zdba+=PEDseSHDmCp>JDf)084S>Wdm|Z%19ACAGKCy0lq`O0|6mK{#KR=+N_^9(Ie# zAvet`%8)82UTr+|GvLA@&tR4w_rP&-rr_M@VoFa}E3xZ_Yo%ihEwHm7UPh@T`1Ory zJkMuuZ879&_M@-2@lBR)dxve;{gG-mN)8Al++7tkR43 znmB>yP~$DDmvgbEcHJ`!WM|BkFD87rsKI?5apR;wF8~|3+GXti<+fe9(U-~weR*SZ z%g#Pua8N_5a&<}RcF756%NreOBKhE@^!sh-*iXKj-BkfzWT7VE{or=%emXJOeR!F4 z+W=JB5o#U1&bQ|t?P62i^WQ%yXZ>5CWUW^338;dngR(3wRXj z2Cd48yt0!F_2;+A%t+x*s9IU@>Qi#kl1=Ystg{%-bTuA|Q(k%ed`+hlC4C)^@fpid zSz@OHgqfYGkIH4V)LWPeT`^EdfRp3R+qpsPNG!4YXN|pWIu+}mIgr6*CE8@5XJX}O zB)gO4Hs`tzIlfo7Ck@0={C+Hm(?-5!hMsm8#|ERhT~Ax!>a|<j%uY`$RF_wlnCguH$z6{ zhRnE;-;Pylzle6+d+d{4`Aosz!tq-hyz2_Em6?CxQMiDJWb%Vb7d7+q~6w5b}-5M zkOn0gUo_R7rwrpDiLlMaIuhGG4rF|3IJc2$2JVaVAYb7nUx_0E$!S%Fx9qPuhDPF2 zT0F>igP5NNy`?tfrxnI1CYda8QxETfT~dtM6=vT7RurlO)+!mgXv>jAa(|xeinO`Y z$=XLA({knIq6-_;sHwqL$iM7Tu zt~;>j+bt^%jSpCB-X|> zE(Gi88`o~%18TD4-z(|n_}90eOi|#P_Rv~Sf@5n^$qK$d7wCtSfS0*dhWDkg)P%?< z`)j&)?O`1TY8Y%y@gB`r5Up>H^ZCX)OP*wu)0YI*8$=?UuTEb~PIlgG%R9n}zE_MN z{B-R_ZCMRXd$Re}qP&%NzT*FUBK!g*uchuLrzmDb-6Q4#+~)Rq#)#j?^=zf20BQS0 zxWFRuMWRcR)D)~g0$}XlF1STzp?M+Qb(4h!dvw&S3bQa#<5}@x@^FB-& z+OL`P%3b%qiNFhwd22_iV>haHDVP}8=Rf;ow~dj-MRy<)jCx&DSg_tXG;sEWH|YPt zbn8{+KJjiZd(?17!eLYWVdv&Y#l_QWL*Cmm%wDg|{!kXrS2U_MaN@!J!V{W_%Dc=` z%;p&ynvY|4vVV99*vw+HVKy>{h-*UoEhUN7E5`ftnbqm~UQaoM>}biP>O{WSYfa$m z1}HCjotc%;%I(uCUtIKY*Sd!upL182LVFq23ih>rJ?$7&wYS8JJg_GtOiTUV_qHyT zcYD$qLWpFN#U=8n+_!`eEL7pM8~Av8xcnnNcvL<`qGKpqvZ`8fF){BrwmhAM8p(|v zOIH0vwI5%~I~tDaLqNC;Ok4y}2~I|t3B-o0@nu3-ePb5IeDIWXb@#7T&UX2 zeApZOh7g?sm4r^|O!|5^y}RORgKok`ZP8obq$5e}OlJe#SLSzVA8%eQZOXG7+6a{| zuzK%KuHw``!w2NNQg^wokvZcuBX;1Ph1W%hc3;?H+1A`SJwD0&Lr){J;>I*op^CTZ zi|lhi6&(%r?pVXi5KldhQ`NapG8eMLJ6i`uj)MoosPUGCd8sLE@m_<(xq%OxI4&=A zL@H3m;bqooapMQVhr$z2BNYG*7YT>a{g8+q8Uh@2Pr|pzP4&7fQ%;c30TEO&-aP&CFvxZBHmg-@UbfwM0SuCsW_Rk^1re>Jc5d!k zH#|e!YbSMm9Sltcu~cw^oQN1EX!0?CSQ37HY7bb!5z}%e(}5A96l~tQqd(+)QS#Yq zKR{IwNS6n`fqoDdJVJExOs%GTpVZke2}?-11~KJbmi$S^ruu^!t(o*G{OeB7+z5BB0ov8bTQZri8VfNYR^1Yw=l3i5fWfuM` zGjm&dEUY}U$6oVox)iro>aZ#C3n;lnjrz&XeIYMdKX%rm$uTD%nILeu?3#lN$|YSr zZ9bP90<}+XlaHpKP$(xXvJXZcA}p~E9R7L;)pIU60Cxo`XZ7j0!ix7a;0z-po3@b}_6pc4X#C^K*n zgu(J)JTvJI7F>+U23SROTaZV=*LYv_o{TNMxf4bF8SEIeJjxdz-Dde*z8Y?d=RX>t&fmZ0#38hqb??2=}wU4?9YnQ zb#%M~hcG6#`*JarH02(lG+`4Zol5)3Ya zBfx+%7AdQhshHrqwR_<_r=WDgrGw&cHG6tF`@K%3vOlha1D|psd=lcf3lK>h#0`OV z5~D(MJ%@8M2};Yv=Xo8i@j5C8e1=z3DAkSviA9&{$7Hy;HC!pE-jA(eKC+vm5=M#+ zY7`v|Uj&0s=7*YtItw+*YyQrWS%g`R#5`ZZBmz;u#T2??YrhHzLm0_R z&%DLN!|qzv%rapnf>0ll->_Jh^OD#~#z)o>W(5)h0Lp}eDBzHS-R8xYPipi{OPyg#rLnH7B;vZc$lU^rEg3&Wh3#ftil<|S zl5VVqG~6dv9i5Ra{c_d;f`PCwZ-4T{K{fGcgxC`w#zm}g5jH~12>@LutQL`K#{DZs zn&aKq5^=Sw(m8x|9th+uH$y-!<&|UbXWVr%d_;)czFeO`#l}lFYiFqdFSYp`iEiNf zxCos~2lL6`)-5e9j`;m9a1$Y8DF$-@eseipcbiZBOF9+qsHE<4K?T=p9*K$In|)bq zI)%JBCaS&%8te&GI^+V2y(8Vt#T+N&#C_%jI_5fAZ@KrX(JAepQ`IfQD2yqX8qsD7 zLAe`Z!5Zw108oo`^J#}pP}J=mx{8$j^GNu}Z=fRMyN%CQ3@FSWlW-uj|#34PB$9dny2` zLde}dXg&Gf4DnXdw3)H1&Y6@u#uPimdGJES193bQmsf^}yuOH2y)ul;4{qMzf8My` z?gsz(@J~UIhzIAF`9HT{{Pe(M^$(!_$Q!u(a=#ypCQ{oWR-d&LWeTq49Mny^1%A(d z03l<3*57ugW}RW8mGr^LWt7oi$9-NAI#TiF&A@C1QYVm~Z3xN~AW2GMdWm-2i%#Qq zr!J$`NZf|yJNEir(DH7}?5+pAjPe)j%w6vZ<9N4xW&Umfi}_eF>Xf_O16giI(lCFs zF$;QNv@#GA-wR9ZJ$AV_{%&tVSnp|k-8KTcd7Z@+0&!G_}PE@$hRJ%U6Wgc1o6{X55m_#th=G&k$cv4gV_2Zhvu z8s~x5y#pJ8T=s!#1lsy7(yu0Y*tTMeS)!~9Vks_T`Zt!9Yw=7-? z_ww;bq_3sb<;^RPHx6sZaQAPZG;4_@rd?`(>#MA*kv{hKKWA?(tl;1e|kG9B3A zn-vm6Ci|%&`)LH#9bjZ@gWA?2fC*l?2{x3B+@X|T^0!!6yDL3OXCo7_5N0wY0*XXE zz0boS!%58F(yuvH^Lzn>e*(&YpW>&|hm<<#kHO|v2;1LDQ~~!#zI-8ZL=o6F3f-#> z9=afDpz^FKl9T8E*eLJdB$xxC0ybE}VHMzl2w$xU1_m70Is4qfZIsFggs{Y7h;)fO z1l$!KCy?|cgS!@Av=-Lo`sLs{&ccUZuuGGtsZoSwaE5-kROmoR}ETE1DTPU!pJb=j7zl#AIly zCVXk~)7Cd%{N8*!{pLsMo1gdI{GNF8_s<*gZwqvr5WY`{Oc0{WgxLE+{G^cZR|u+# zq_&A<_KCy|RE07T>ApyLQlz@=spz*zva`gk9Lc!$T>U;dhU4c|jwB!J*WE^WWsL_5 zWLe7snkwb{UK#zeX({NoHrCX_dhmqI)HVXy-w_%1N4hg$#_od}RAa`5;l%ng^Sk4U zn`p-C{_Nflszrw!SB-c3J+^p%*imcNPV=EolIdJnbZ|lsj@N9Auq=vabj zfFGz{`u3zdd^g7zLU-G?jN640B-k7=*&i1Hr3`0oGxi57$+Or~AYcPr`t@`E0~CSq z$L-JptI3vgjSJoZ?svcv2-VSW_FfgiuoIB?npg~zPBWGIcW(Dztxk-XtocDF{!e7B zD;*Kc_#bk+|IzCF&xJSo-nOvC*Zs}^b>R(uit-=1-MXc(PGXV3KVFd$=Vpx}_*|lzU(RnMvV~mp`a`EGBE;t#obt^uCJ8+ELKC zKtbH;nwFb;O{zKMwot0{nzxS)E>x~ggZoinU zJ$yI)|36vlgzq~?Z~u<-Y)1so#C)BNoynhE=nb@OP^_Lvi?=ZIrgp$*FVH(Z>>bv@ z4;GeOz#ej7mju=vC%u;UDa&qv6d@ctgFNe>9n{Ij zKP$!R+Prlys?f@z3hsx)eG{k#%m|sTGZ7q<_1+o(muMU)k*(S|``ycm=gM z96mv!S9tC=UlMfGT^OW6tb@zQ>yJ0e?|)G^D|;`#f(U4Z6r~<)ws>J6r*xLECgaSP zKHj#|+2CF2GXsQTGcRpce*3n50trTyHi=cQ$~rR1Nl;l zw?L%2HqYN#h!V_6%$*j@9EF3qvs}AE9fRfu`&;y6T*1NZt6#R25F8Y~{GX`n0`(%<; z@MwL8e`ywTC*|4C0Q>v5dj8@={XG*aUEp7{trcAlL^K5~_M!88s7>c~o|thLR9(5G zSiR#=WgolPrip?euQSB49$31`+F0i6<{xuh^J;3#Y{|@$yj@8*lv8tW{ZtTod)8H$ z-jTS(L}}2{bn7dLyGVM#&tP9h1kJfrV8wzI_gXALcI=IsQCRAlv^&W#X}1w*nUgW9 zKTN?RRZ^62^&TDD1<+4@CKE!wWSBT*8k*Iu&}DVVarFP8>^-BJ{`YO&^iKGN-VMD- z38Hi~6afVxbOezuQpC_v5kv1Cq^d!XW}!$IH56&022nv2rHd2^MMXq8`LDI^zWbg# z&K-BZ&g*34`SAC~u#_*ZLPY7!=ez}#F@(THV31+Y(bVOP05?4}DR#!7g(?Yx*o~a#H2}x6^{kr2 z6vfQR7KzghnqCJ_`_6+ouPRo8pmO)f{i9i+8bjg>ok78K(>V-3Ud!u`13&-(;uMf- zfo>#{cdRnT_9yL$_YzE%S_!n5pX^g@T}++CdpKhn=Gv-X45(>}1A+(!F6pXCNJiS3 z4_x1gpV)>s*wTksuNKje`^r*tge*TypV*J0B+xM($Jmj%&e@hVgSp?%VMTGGi!|}8 zKZQXdD5Fk5HR+m_wEf>6FAW9$)XQvG zk7=+k&_w4+a_vsi5$Jyz`SM_9dbdx%*g3>^sZ+wH58qzWFEDInBph63j9B8aJmG*5 zQRdXw6TK+lvT}yrOJY38))Njn5dbpUka8BOz^gM2NL`!Qqq-gTE_H9c15DDLN>PUx z?_UTe0-!!==$i{JT%~zAh!c`vfx2uyv1om)v()4$m^3YWQKFpb7%%X;d{cj?tLR?O z4Ad9};z4+0JwD7F2nGyf)khN@wk1ZTdQ+;Sn!vc`^+AM19{8Xbc|7x zu1!EW^odZxk5ky(jzlj;5mc@-bX`n1o&Y8?$bZFwX`FIA6g@Dl(3MGzued3&|74W0 z#mWj4>4N9lAJ5Ihr8_jZJJ#2>UmJE3xlA>LK}StAQC9(Yp+K-S9yAzon5wf~A^cGe zDHO#>GOM{gbK)=DIAMnO#@3fI0soX}&dvAXv~1BqfnJg}N{d=HL6ptB@)0fJR=_Qc z-v^ND%^O+jFnyrVEwcBTxUc)EM+~Gyzw4!k3$gioaeU$IZ(n)VEJw%EBH3gSKJqIf zd+wR~p(BDU24`S$obU}wECFKmU1Y9@udk?Ax?SvI{qrQRD&aKJURMtA?Li;IA!$fQ z4hRkvyA{%z!pUE_9265o$q5DMjnbZhwNsemA z?<3;*zZ)ZCC#ButG7t*-*TWtHqPtH4(t!E%>KN#6+ciixX3s>Xy}{u)5l(f3HZwU4 zvXOWgic1p%4#9*>Q>WdptaqP-j7FacI-DqOPTWAT>mXnzlFj5@rNx3ND7gDIh!tvI zax7FF&3*xbN$5a@(fqWt#_3|p>N(O?_S zK*no^@LzILe3paV4@$&uz+l~H;x;eeIvm2mPh#Xs<7Mph_|RW#0JC2}5CxDU!7Z6! zzfEit(de-wuUWjg-Gs@$CgBhbDB8(H=fok3xZMvco>&w*y=kO5P~egx79_|o)Pd0) z0>s$LxDBMsAP7tXLq_2=U&vi1)b>5BN8JpnpI|$R?IG#gn{laXSwdH`1YSay>@lz}$G^UF8l@VJ*EVF**%j3&er>~9iX(_hM>zp=bm3ffnF~(m2Tg84!P%%g zGziqa!oZ2UP}N4Vi7iM5fk^NVVUDwI6`cTNly(!+ZDHd?nj<=6+<+vwmNk3ogA9m7 zRH>I^f^8(k4j+V+2klD(@;)3tKyL43Tx3pGt9FNo-o_i50P^fF4;!~xr|3#7Rwpi# z7U?duOSymEx`Gw(?=*l6r&`sVQb7;SG7uCZ?tD@k{{@8am#xcTYsnbSO~=oFaVu|d z(zvy7`}Gn0^7P#fAuSK}ie90As7`h3dxHwvdkoHBOqb_=l9fVSFNN-FA1Zt|ELHgW z&{)a+rPt>_2|bwAelYL!V6lWNfAjE{y2D)E?kkgOT|XZ@dM$0!@kmsh`ax@ zQ}XlJ{XfIJK%8hsQvq05#g&Rq3UBb%M~F@E(BJS}08wyh#CDK;)TjrqzjU}8GP$$S zPr`^@y`MxhmG_tn9yuiAOl+mpvyymPAtigAO?}<`#rp<9rYSt@8oEMe4`=le2h=W@ zx{DsLDLHyY%;+S~Q>JuAWOLbTX;+}x!dX7)aLaFZpN&+}tKKcnjfmp@7IW(Z7d`4{ z8f8D#d3s^_9Ze3{V_F*;8&Yyw1F!I3VmXGS$-0{HhhJ%H1h-uZLO$+mO9nTDfy-l` zO9fwP4^w@Z`k_7ZcYFVEd-lo!Jd*1HEp2Q@NKLK7d8X~5etVfP&jI1i!gI)*W}R=3 zbSj7oq{emH&+x_^apulNKYGk<-9r9fznX;F?-tEz!=O>(go{_k~rIXv*(IUhxuYs&46DK(5UME!R?O z)ga#!@=}>j$3o^uS_w)syzJfyF2~_4=s7CX;rMA&KC%XwJ+w&re!&J%uSQj7NPN&+ zNI4SP-6p309TkzJ-%=(8i)B-!Vn^PO4wd<_A}Gay6En`c5o!;!g~ zo0YNIe8eFMrb>m>MqIArxuFk{W9FV`jkj>NLR#As+#p?8u^>o$w`hn{n-yQXU@{Bv z+k{v1f04f2qRALnWPn4*2|*d?{P7#}+4fBBrBy*W<2m})OERZL-PbDB*P7=| z=cJaiE6XgxylZQ!h6`d7WNb_88v6GYR_+NmvXSwPGbdLbbp04Uc=xGD-WUD(F3(zh zuHCxTrjc`}KdC@pc%G|*J+8plzBqSxt@U&9m_Uo`9Ul3%`Ro4Qf|ayR0*-DsR=z!A zZT7o%ZNKxcci!lm!|PT|t*k!CSswFMkZj$*3b+^bxO& z_+K<$L5N@2er=9iy~)$7uJrv4>m4^u-qz>-k$c-wWz2yC2Ooc*@bWKKG(1>%|HmZi z@{1oIr~^trKZcH9_&F8%<^Io4Q9t+BetxDQm3OA&`2%-ml4T$4%%*F6+nLKYQT{cb z?-2NFp~&aKuf?*6Z@<3KlazOtDhmU5zt&Vg*j>KY_HB2iVLV)$Liz1xVJGVTfetCqOrcW#WYd*v;D^5;-BvmKJ|Zoe2iHC^K&{$oQ^A1qS-Kss(zSI>K$EK3)FnTna6X?%P$XU( zkV2x1r^Q@Qw;oK%$3f7r=+uUE^ybBEh@z)KB(pB2L09I00@ll+0cA0{sfY zTJepVy&{dto|ZAR`Fk+nSI`|r-#eLC?_9Y47vtSy4CQp0-7I9_sz^yEMm&VJiU!TA z4iyfKoYUSaW~Nsiu0HX?&uNQYbg5Er8+s9Vd8>39SFJg4;$?8jR@stywf6YX%ka*v z8?5wd-7hCzU7p;!xieCI^ykq2lW*j-TOf`avb0HhELVj`VDfu1f2x_M=5{%+FwXGO zIM&=EKT@!(?|4e}XvU9Bju6I472V4k2uC=7qJ;eMD>>E$FHfP(sb9a50NR@g{i+Td zL#NBC)@ABSV5ne%g3~Z>{%)x60~9$4!b(djNT}A+Qy3NF!^Ifc)iwYAa;$Oq?SsqT z@49gu#I-FGno_@qBlYfnB7=pC(j`C_?cn`tv($_wc}0ZIutt? zFECes342eUUAT9Hos;YV5&457#P{t&yDz%Tys=&$~H(&m>M}*J#3E9W(4Y^G^ z)#5iCB3mh3mPc?oHG$n{rSPvjk+(lji-s%fhMgp71`y=KB;v||q+E0QBS09@squ1gb%;Yf6a#h-hV%yoN-4xKoc4`t+D)ZPB|JX&_1DXv7JG}~P040z&o_gTH7tXY1ZU+^8NEALUNegjvUoO|Zo z=k=bRc*MaKoREL!^p3@4%RoP*!GXSIoAQm<-TdD-Vonn;iav8L5GvHE`GIvlhRs9D zuKm5L&)2u}Y^+$1j}pKA)*8v9%44x{cBhA5(vC&U$uz{S$JWA%uY4+iFYv(`d`*Z% zm2j(JP-LfM;F9(j!P4&~XVY4z|7CeKUBCtC#m9jYXSol>p601sIaQz=yZ`s+Gvr8Z zkJVMsxz^p}y=NN@2;(nif3U7z*jBkVJ;Qj<(K4TSE{n&<7w+Cm+oEspjvvb+2aeLc zIb42m`-bc%u<6RLSfk&l+P{VGRB+o^qXnN|(H7_Ivm@ld$G{WMJj-64b!R}t_r4I) zCg?RW`D?+Xc*U`3Of{B3hl%cY=#M z)UyJ?fZcpQp%BTPF^k(~#7!?q)sQfESoUm>_AR>YeYkMITl))ehh&;_EDhzlUkGFj zB1QUKp@u(B*XmObd(ATeHe z0*yDvK7JhNW@VI`0HN2t*c=_pgb-;0crG7;s`5cen;SZVvb-S8r|pxUvE zj_naAEJkE;k6zMkOhdb~t%;YvpLfTdh-z2_Di@v6>N&AK#`J38b~1v$I6Jk#p9O1S42;UPX;+P*Q@sRiGXpHck{Ik!d; zN927uwEP5v91p(FR@8EpK0zpozd#bd7O$FbUXbe~T>umJq1?%Lyky_b%oE%o1&|9! z;Cy3y_tG!v_Ll<8E)j}&{Cftn^>%n{Q?Oqgz1jca8B~fd$z`(rQq1^uXgT86_d;Aw z0H+C#K}A1SFO(Y1=Lw=ozC9BX$)nB>ip=iphg*5=q*3U~NG2o{A?}_vj;*cA=Ik!u zyAHr!mkfE@+Kd$#i=TCNcTE{AYvv>Tush8aRLr|SgR`nQHoAEn>~i1#I~O9qQJA&yADb864%eAmW^$Wi@EI-Ct z$`-V4fC|o(L$$M^yqy3Zk+IhS(8(dlMk0LlCPF+~a>Kd3pyE*X?JcGm6wGrADIS!pMSI9I!;`aCi-@&{pFohnvjYQ0tDNUab;;zd#th#A+3%^mvPq2GB zT`sUe>T=?$pdVcd0#>Q&5GzR~#tFZ<%Hl1{P9g3BH2q$$2(TvzXT78;4T-EUpqat%iIM$c1P0AEv1>IW) zO0^r*(f4e`D^R2LKo0ubQiC>N{I_#lUwIJq(pp07m7=Y0{>C+z)x(d4ljMuOC$0R^GC1 zHYSwI26=8Z)(H|E?=O~HtpLk3{Do1zaR|Ocz6BNAB2<0`43r`o?!1}?a&B{#Zaj22 zZ2hkD@RI~AYlbKIc+0kY$xx6Fz`oxTfkU7J5xKw@7Cye@c-|#kH?`(TR9BLpu!9tfO!&phz|0}lRcizN#@2#xk2?YCd?H?Ad9na8tO|$ z-vC`|rMMpSz(uDKBkmGvG=Zi`LJ%L<)FVPbL$B^gudpfzOark?jZ`9Vk!$EU;ffgn0qsWj-sKP@1GD6|IG!FVi*u8Xe@=(%v)DZ_#0e()k*~d7SaV_T z3wF`uZu7|vGUqCjW0BO=tKapI=g|NY5k=&rGdP}-pzQI7Kq5R0Kvgr@RA*sc*h&(a`;et@|ieC+L{vX=niZ;7dgtyW9)EbXC+-JXrj-wEJDG(u8<8 z&IN!)PD2ApsWEg+c3}|xwCYo!*QeYnhSft5A0P3Od&2IP^@$x}eq^l|l{XWMCB-Bfhl3uN>Q>n`8dqc&*z1t5or4pthE zXC1d&z`$e&PV%B+h^PvBPxC&ljOB?aptBF`KpfG`>NvKJWq)7k(Ku4+*1`+sLkuqH z6H!rHTpIn1%PB)WGfe*13Y7iT9O^y$2Q`P|<8O?9&O=AGx!&q|+a< zP1BMuZr|NVV_W)XXu7Hl%KMTR2MK{FBpAFV{1mftocr%Af9I3!SS;>=q6Y|!iouZq zkQx!#ABUWIBbs<T>SF^!tCRw4+wqK_EjL2G?hbgFF)4?b)RoGxN+p=L7PBS zB53jjyV}G0rwTX5(Ii^XD_Q<=Cg(G|C~A2Ykh1_f^w4t`fLs9WbCi8q27X*<6(Qi9 zkIEKMzksJet$m)a0Qyy-&d}FeS?rX!-u&XUb_VseK*@qkDG4+HXraqm7}vMYj*ECQ0cvf?Re0&Q4%@={&H5Zril zH6R3E6}38Oq3(nMK^d!%pw1T$j!ZG|>&}3Re=8bKTJs0`gMkVFT9SFfpSiZb*$SJ1 z+jGlj7)Z!)gG5+3f+k?dg7ulJRG zSst;w_T8q}z$r_?^eERqH744Y%PaXKp9vnWKWZSu(2ehYoGK{-p%*`^iu3ihsQ(m^ z^nc=47?AmMvd7w1-6Q(*p*%a+tH*YPf_BQ><>)IvlAls(hpfZsh$h-XmMh`WX}QeL zB1_S~1Y)k1z7nn#1|8<#y}9pOazGBY>1T6om#>jgz$4eg^h;ge%`Hwj!F;1=qC&D_tsg#TEo=k>0dH+C=d{~f(?O8_4J(`NJ+h(Mku z$HFpT@`$5_*Q1g?U$4h_Q=4-hy^(3K`>(rUf zuvh0=N*&f6+#wG3JkHzm(~lE44j7j?ZkV1Fd?5qxXHIww7bv;*cfIvp%%o{vLx?(U zpO5c}b&r4ehTG&OdJ1NG%IQbIWXt}{-#+%p1nEmQA%L zosA-WTY7u{KUC|~<7>zRXZIpEIqz6-5?l5z|5%&)-2B$;?;fc0d)>92gCv7ryWf#4 z>3g71f+^!C-iXwF{d~^F&MnMC&U=u8Eot#HJ-f%-FvY@4eDGs1)xNYhD3AcM_Tj-p zdjh*Fg@Zg8nclMsutYN9AF4Gmeq%_#{_pbnry!5~dgAYI0$k+S_{Mqz(OdDGhQH4$ zvJ~ByYc`3lyLBkjSX!w#O$0J=oG2ZOnpW`$NN+l&G4N0Yh>gEz#;;uLCMN*71MzB# z^UyqwioJ;@=M!T`WA+stx}qLhnY2AzP#rGQMe(}?z`PSJX;|9xgh(_aIo7y#!OF(+ zStf_&t4 zU5L5`p14qkK`H1afGYIB7~FOY8jy~VIFqk)LD@BE=p=ABe1rNdaDmq}*{i{Ekk@h5 zOp_(;(5`TRn? zwStzh)`GE~jNIu0*F>#z#XeOX=Tc*5n9{ql456-kZaq{_lBIfE^EDpi%$xc)-ro^QZ>bAkY4562Z(`v@>|Azc#E+*%fqUoso0npGkyAkv<08j`x+@Ky#29 z=l7=qK>;x@0UjQjB`xC8zshr)E+Mnu68&XgiaY|%z^b&llj(e9=+NnZ&!cKTs=Zs9 zj^d6`*K(j31sPfqbqKW9G3LX z(nSmjlPkCASF-gs-zsi1jS8i*p04j$=X7n2#D$DfOq7loM*x)}27ho;uf}X5*1nJ5 z6w)6e2a0a@^HSVAfpNFCHT4%c2n~wBMO1SJPjcvqYyn93z66k||5RybT6ApdeKdCg zfzceV@vVJ)`W`pvLl!$8Xxlq))29~r9+=aArnvEHp|bGX1NuXFxS0A21pVa8ssUx4 z_D%4O@2l-!zA5R&A|9~gfw4Ndh3@|r4_HR_y);p|>itOT{Ho@X*XIMd*PYEIYw5Aph~N)ixD7u{JpQrH&7}^7`+cFQ4-wV&_%k)Ydcy9`{#2g$S`^Qs@c0 zmw7?oL|HL_?$GIXI?EpUqV_fVIdQIe)*K;Fn=6uFxkdMNKPC9Mo7L8QOXbcTmT;9y1+K_Vlp}_opOsihe1bby^G4smUC74r zVa}Xt;V&uuBlmqr{uK`xMH=OlO!Q?PH7EEeRq=|9Vnwp$^om;Y9DR-*&q{Hy*>z&(oNEx-}J}1XYCbz3J zU({Ntv`ZL<#fic{)Kah#S&@C7{#|oZ!->Oh;sVxc&7+oe$&+u&kB0eMO*z@M34tO_ z!-C(vQE*6_O0m6Qr8AI0m9@;3&KqjR4qeI$ZHg$9MBej8S7;vY)i zNYcwKfX3}f;%+bH>&Ny!3fV7jt^8|EC%<#cQsQyv1UtqGVKzHJZ(;(*yVgu^A=1y2 z2xbRU6Q$r>B~gc;3#@6C1>4k3bqPsX$1a;3$w~LVbOqy zu4JB8LA&Wz@%YHOxtfms7u3v$Wnav{Xn**{F3+h+W$35JZ+F~GmOi2P{iB{`qy*^3 zl92%;E*?a&m#ij+BGxF?WY2hxqNAq5?65{9svMiEeBh1=*Vh^Ryg)z0r{?{aB3E4} zsZzj{B+{|G^me8lS`5{%1Px}jcjN7J0CTy=z81$SU$qz)^BEjUovP{KJq%8`eL&)- zSD|^UWNmdFG&?ajUL7>AINHiBkre3s$kVR>I4GSX*R5Un!zcL^)st_q`jue3XK%Pc zX8C%E*$78S5metW7^x$m3xXdz5yxU6j{$ug=iN-jM7~{o-SO3dq_tfxYw$9)Fpw#$ zAFgloZ6lXWn#%24UJ73F@-FaflN6V#6Nb@BKN`CsW4ib#cwVv~ zeszgpDs=YNnB=2!j+>M{c%B9BjFgySA7DIkB6sKdxXq5ikpR&2O?{^dck`QVrYa(6 z+_Ks6@oM|Q{kGFj-oE#tv@+=1(|WIeu7-I30@rN5;QWDgAN;dsO}GqVrTE9SU;Ddv zJHkFEG8#!cJV*5+0ymlHL>bBj87b)9u6U-2=H$$~|t;2OR4VtnMnW|S=5wXgS{>(O&I*?e`&scXt+%A{Xicg$CWuVSroVMzP>x3(0IYqlU zld^Gf+r1i0Ka>+&!cl(0TO*GVd_ zRhF>H9~$VG$iwaRgnoE~-|Lesz?jBdnJ1iwB%R&5z+hrSmJ+?>uE5F<-!Mqx0Yi3G z2_E}PNe3#howPW3IhH+N+QY*1E|@+lT+F94MMx)DHim~oln(p3|LB|1FP&ovbs6~j7)9iMLvv~3s--dy3*YVgnuRu%tlEV2&;uck+K)R5AH6AA ztU&a*Vc);k>~@QS6I@-2fj2uk^=`QDJSD%20d_&rpOq>eTwZR1wz#X;{S=(I!?O{U#fJj6Rgf*9zF9p- zEt~xQe3X7pbap;TwX9b##@(IMOA7eGRFq(X!3`W))~-W#x<|F$BZxQngU*D}5F6Z} zY7MIEhHT!Lo#levH>Lw@#&yWET)Cz6z(!zbN>bSSi-YHG+FRkHhXD+)JqHiG^i%CgIFn#}l{hz!r9<{G_zzzU(CD!QH; z`Z`tjI2A*8gIbfZ%CYox+gm19<{W&eA=*Ewknuk^?Hkf#5#kDU`0`@Vm6|nKZsZE! zIuQ%|a9?FqaMQ2~)~(tmjq76|U09qkL>L?O6qB#!uBdI9y!p5mSStqBlCYb@fRs+d zQ!4J}^bIi8OUjuhyWd#H48fnOe=*3eA>MGcCjp=NTxmG==tr@7h@Y|pdaI-N6G8{j(V%3d~!CL{Kl99wQkZCZ0R zg|>XIWp6VXYt>{Q-elq2bPd}sG}^@Fj(fnmJoTkbCJ0@n4zQ@I2!iU}+xQ?7@QPNx z>x~Wg4c})E!%X8NsLf(&p%E*gqTDTV&uh)oI-%k>ZzcR%&C}2aYKQ2crRg%nix5BGyrh&zfKt#IdfX zfbFE_#$qwH+ovy^Ayv<OAW+Frbs6hxBVjs{#iYNXToBSvQ;-6&^W_p@S3|9Mkk${r)%_Tbl^LZqo6_ zL}WfWh8UF_*%4YI*npgq5#}%B-^j}#fDS6=IGwrE7Vcm1BT}Rr;YEZyHT1~nBOW*b zEYMXE8xXV{^qo@K_7=-FS$a{B)^429L|9=qlEVaD*HF0kJ3Qhy`!9RZ+x^!m-3?8c zQJ=s|z(GI4r*1~vI0Ml4x6#1(kqTwOy$Ephib2XDmKdTcVE{y&rN9E&P&N5Mg5TiT zB+9EpM|oQcKm4YMfM1DLto4^ zCI;2Amlp8#66rCHtHX>?s=zh#5$os2qX^tXP%8GA+8>R8zzxAgI-YnK?`>GG<~?BS z26H6G@I>ZHuZEwk?ua5j+_8BgKydov&ocj6qx76P`!V>{eHtzqxVL5oEcYnfnEPjEz_eJ;!${ z(G6ht@WG5pHh2sHf8foT^t=;zf*)5%M&whXOvfY4Wm`MF-lO#2qr^XOfYAjP-Vf{9 zPu;6|)Qt#txip#v^yr>SprAOrQR(FOIm{{WKKX<5+c4HRHsb0v-*?YHl%6{0hAJR_ zDb+mUXUXWKK?gAIuc!hz@jz{{?7M7E;yZ>VaS@<{Q_#4p~!^JveCVr9j z_Lu>Fa#-%p<#}tv`Z#zNg(~a5>jvMo4S`!5LQgkDK5sN{uZkU0uoBw*_S#?S zsY)OfU8Ku*WVTH98h14vLD~PaDP1{#_#zkL>eib>Q`%3JbU$ys-P|JAD_V(&hX{nw zCxF}0xt2V|UYXbwljJTOHNP%)WMNH_LbHf*Cg@LTlH{2*-R zn{HYx@Pu{l)Klbg_a&qihb9wVMv;0qBanm0NIxK$Q3a%G0<}cIyCJ%cAJj+SShj-2 zs|1W_?uL%af0n`Vwg1EtBvllE8e*`!n`u&IU~L1^Bj9JN3hxb%55HvrcQVfHDUh0E zNfHCm8Bj2TLvt4de+6K-!ClZG@q4&)D(6*(X>3{DlWF z9qu#!6AyUwBW6B|8?StQ(f?08P7re@b^i4~(#unJipsBQT|)5xJ_rAc zr3QgiLBi0>|2YTq)WA>OAVawo&I~q`_a*_7|1(SB|He|A=KX&zq}qzf-20_TQr zm=zxE==}Evl1gvT)ZWoE><&ps@1kj<+0xpr>49uXvv5;=_o|p_NP6iAlR6udr1j4R z(qUr@@PxE2zsiJ6SQ)?MUvq0wjTm>xG~4Ia%wEWSdi$(gmYRf56X6=}2J2&I%pRnu z0;$vfeP!aI%5m8nt)`3U?wEaHlgvjy*p|W%wr`Z(lQg$6$L#r)H+;fMpBH$Z4s6_I zTMBEe_4Wsu-Q*yKeUVne*v;*#t%+fpcJtGoQhlT&L$>WvX-DH$rLy|gqw?K6G) zA4_3V{%O!}yDu5!?~EhGDGQYovzfX-l1H_E==O_&y%WZa;7=KYrM#ZMezcfswCe)RlXL(Pj+$ zTrU?0Yd8fOVnI3FU&E-Sl7Lv5=51lli-nF%VVOO-1Fq>5_Vhs ztLpx9tDxX-f^B3>v^G%v<dlD7n1k&-P%d=7@w>^9&F|=?TYNf)HCb@TcL^lx6_M^90Bc zT+>gZrdL=^%-ke}1N`iB@FBU)qOpVjIR~E-=UJq( z&%vEWV!?SI$i%PDJ%qR=f6z|}K*sKSvfJVU@&fF(_^ITN?A6fIpA1SIUIg;l9QX*t zjzIuyqNxo!Br;QD{JohzF5U~QX+lC+!|07$Hy`dffhOJe@8Y>sK%Y?7ii5OQv9nyt zCns*bSrr7y&%dGrVe=J~A9wL7o=%j57L|^IqnULVog%hsO#M$}UE)C&ti~BTD$VuO$|HNf_~#@751I#Mb+`ImXFnEsGx7s> zqgz@O^X&s#n6(0I^M0CQVoiwY;GtYrH$z+fBuh^5csQ#E)F2Lmoib{L<-)?0mm298 z2)bT(`jXNO_&z$CAGUyV*qt{cPBa^9)`(|6-B0|{3f>*j>e>PfF3y zk)kUM(ZIsz(zW51qJ3TuLgCG3nKXsUu@?`*+n!H-yZrOfG)H~pfZ3i~Hw0 zHT-=WA=G>a-6pL|)0-hJ)mwMs z;Z~xhcuVr?#fR}Ru{z`++$zG9FZPqLdiGo87}HaPQ2_zI$(aKu&xa7RKQ+=)g?;`>e_ge5$JF|kj`=?rku ze%h@MH1EV5NM|HQ^?gT-2n@30!vMtAOa@qPTe&ahjDS2$jKL7_v~5g}eFhZ@i!`L& z6MvDSXxKFMAb-lJP4O}vs{VHfc`RQsdjuwb;KF6(@={Kg>kUcAuQA3?QtU-TNNGAu zm+M-v>Yzz)kuwc57j(Nf*0*?^B#ifOM&23Zdu;G5>8^rGW3`9HR>_CGMa@?oFC$)V z-CXw;IgTQ~jZ$`3nl`U9s;3@VZkbb(67BUc9pr%MX-yt|Y+(OFq`v;9n5xSBfwNya zV=YrO@-Nx1qLoDq`Hr|YTRK|!wW%mA9*tCLjex2w}#`NNxtmUs^=f9gpueugBUj2G`n;+z%rV$Ek;jiUW*CSCWPO_2itgh4-n*V;xi>4kzcXn0WV7(q-lER_FJ{)0 z?P|+E%g)Cd3OG`$Af(?b7g-7K`G@yaTGy{~1m4)wuT|WAp7r?b^eq33&%VQz#^_(y zT0Z^Q_xrQy>To7&Y@>(l7BwFEwD($+BpEt$*+JDis}Ww;cC;li+@FE0L<*{N(`ho2u;wqTJj{4WYlxwJd|D9^LTv=pGwXg%> z+J}WW3GquDi=pV82)o3X!%GAPDcWH0Ofb9jq{(HOj2KzOw1a%5!SQVi(XH9>a!b~& z6w+fVMr?^-DTkz!XuM0_0z22V%L8?#)qeAH`D@1A36GPiN(fiKY|tI!T66UBgvUVk zMY0Sa(Cz_WI@eD*jZ5~3-k(l#U33Cx8+#{vbW@Y>oI_&tDc2lr&rYO}j?n0)Trrxd z*R5knj!G%ssjflDRv<wlkev)}h#yE!KQ4~KED`cS>83NsJj8MB>Oh!jhGh`Cki{;M@qE1Q_z}Uk zGI$|?nu*)+ojorO&%?1M_|1vPNE%W{GYiy{Rw179S5thfonKZXo5uq;lbpR{n;k07 zfgH*P$70*$a`-Og2o&cCb>xV=&k_5@F335;m$Lcw6U2*;lGQQ86NG9ct|2nFhntol zz%}xQVR<^2@_PA0wL9{{QF%`Pi?;U)YdYT6brTXu zNP&b|)S>r!%3G)H~ z%y9e6IluUO=aM3WblMeCCPLvGb(u0^sR&G#RRr8yI!oW~WG#{Hk29RBG$Y%Mi{i@r zyMbplfSjd~{Z0&V42oH|!}9(1<7O$#8aDn=`yIiziGfJ^WbAwVIs8QEe|` z`n6H`iN&-B-eDIq-A63GzFt!P{_1fJeFJ)=3MT9*?^U zq_kV9ybH=tT+3-EWDyjvKVvV*PVw6)$=~VYCx0kl`*QNL8Q&Fl>Ww6}t&MzV#W+lR z6k8K79hZGmKX=TiK;=}SXe9hCUVfSh#w_;WyvLP6D10g|H$uAn9mO%@t!8@cDk$dk zN$&V=8*#~6(Mph~7>rBTNdCH$IQyt%cPZ86I)~c%lAi=oSkH~#0LV}f?T%Q?8d}i@|Ye)wn-+2vw)j=)-_29$=55Yk`g=wRpJoXfLP=zlFTFW7Rcd%EhkUaI)P;^o*x(wo|N%J)v%DBA`9cOKKArInw3)+_zn7HzeUx>=)KvxA6`@?M4cB;Oc^Co<0vzO+Jt!)6WZz-K6ZL>{H)U1*_ZGs<8B!|3Bz z81d5I;{S}hQ1Ar}txHa>A^XA|b=eTj2cH|OO)b z?Bh-Es7q+X%q@i^dqB7^2|SjSr+&w*XIBAwd{_@8{nF_=wRFUkxZ)mNJGqkU zayxHuJ2tmnpru`Cs{Pd$nn?QA?{kzuvru6vxMoi`jx@OtGbpo-&aK^1G&9r|)&zQAtg}GN@|IBS|EIrWl`~N^z zeCPW=bON90VQ^84zdC{56wFkTVdKU(#v!j67w+sPb5QqS%8HwrweJ5Xoj^fB=b2lC zA{St4%4Z_@9yf=+(b>lwM5>%K({-48&XUCKev{JxhNGAPHt7UI>_#3}mQ(rJm!6!NYdHrIR#OhD%Z{G#4JlYRFKCECx~*!D$vS4)t^= z_a(w50o&mU)0ceiW&ZhxGEbapA~W2}S)w(Us#=DZz7tmIog7+Am2)%qmdccuH3w_^ zZUAPq_rKT0Jy(8zYr{p0H|pjGiA0@^al?@amgmlv+I(D(;&oPNcX+kfJ0vV~B5gc= zI&BO-$%)!3fm!Rm<`}b7zsahw+#+&y-$LXl@7?8A)aNa5Cx|_5G84FYM_&IBH)f!_ z!obwhfq{nH*5}!~Ec$_UBtn}S(x^@5JL`h|g{^UHbIX^4<+~~X4IAKTq zPl5M$RtA+hzu@s2b-(Z{o1YH0>TgaS)ovX~k zqbIcwLjSfZg*+7?wypoNbbP{M&$i65el(KotoIdrN^PE%JZWbrwzOIRzT?yq>N(*1 z5lTFc>fpFPCP6?9^t?N2YOqaR;Ni-m_(7du;gVqp|M5t?kr+x9Ob}oxj4be#(9%d- zjS@#w!VbZ&8$-v!yh%7yF80^-D8$SIbEYEk9!4MMuqN@-G*pgdnmv^4Dtu?? zSNLR|DD%z$=dfUqG%*CH{4iqMx92;9_B7MXq6T z>+aa&(7vGvZf`M&zzjaMB;hf;k&ykw{O!&6L;f)(S6Px`wZ5?n-=nAeSFL*_WKUUa zUFsU(_!kbpsf_|?tHnd84J};rq}G>v&ISZvTa*L0`e%VDylTK`g61~^L+=kr8*7Ry zn0Oah)*;xnIGVonI2u&bjT)S30=TT+yyjhQ5s;EtfuFfGTG_*Ox#msLHk+xCJejM4 z7;!~ltGrrcp!@h;F@BD_xD8h++ZPqtUh%T}ykSunYWm*R=9`GD({5_3-FR2uwDoic z@%}|62l(dZRnW^c1pevH*a&7ULZ5y-Ww&K6!mO;V(PKIEn#L zCK4EOfVtjKlzUg(q=1_2ESWmV?8->fl>jyio<_ZUW{V-A?90T^v#d_TbNAj$Z&4!g zO*qtyW4Q1X3L1Y@nsO<5sd+WR{1%9S=qL=u$;Loo-^4h?`bfANa=rI|U7XqxXgDS~ zbzCcXtuJ~i8E1U(1X{px5gdT6sK zRA5O#x}aO%966bJ)Li`SvpO?QvA1@(N#7{^Bb6%XaGP-DQ9=k)#6$9`@!CeQ}N8)){kgi6W(u{KaHsV!_UqzD!%Eq z86AggJ)@rHTF@8VV~{QCiui^WOtkh!DG7BY$IdRAU)p<}Ib8QxZD`Tr{vJ~&@VxBQ z*(IBty|FTj=M@;6YJ-BCK~Hptc^crNx;=ZE+o)3~TNHKH7q;KMLOaZZSu{4gc*hwv z6kVUgk1;zDmM|=;PmOpGqfxu)O6y@uWyrmK;mUHb>H?n+<4?YH_>t94`*}u zp3UuSoIHw(zf?lc>zh`*T<*8v&HW9C-@`|KXEVnobDpL-8>3VlhI?CAMzZAU%M0zT zI9xbt$x+YGy|M|T16Qq{_hgP=oQp6&Cp4ZLqj~kDPRK%WQK3eo(I7Zz%1(x`pw6&m z=*xu@qG>4Dn|GPJ?_U$eOeQNU*^(Cqq#h z;o+&U>f2Lty}`JGGRk3Kqb0wG-7Vu7VkB+F5a||Ia1h6TL!WLzb?wws+S-9EfiJA> zPo`bIDW>!Xa`Anw{47f_D3iG914r}{VOTrn=!)JUa@&!314%k0_;wUYXq+U%{0d@2 z#d}S=tU`~dhe~CJHaQ~Xq^$j~!)35xO6p+?pfDiO;J9fR-*XU9K~>Y$8q0@qQwTRK z3vj0fKuJuUK-h{TYj$UNX(7l)J;I7?rEZ0~*eiU_Hp1Q7=twR4lDg1oDKs~8p6iMD z{RO6gMYxV*1$H968%Xg<5nchHbsq_JC|Rz`)?oPYfQ3REg%l$2tV1urlA6> zqqw%>qS7v$gX<$aU4`m*V$;*&TU@zK8-%Y(8FSaLcaVjn$+7+_k!CZnJcjTgtBM~z z0S$y~E(nV|#rr*qGb6F7KSSLqPHYpi_EYfU6{Ac5RX{b~F53wj&$(K0hz~nf(c^|p zy8c=HIJZd1*X!uz@!N=`ur|dcFGnzE7UqD=^K$31O1CS1> z0rDRN+bGF|c8a!7==Tc{l|GblH0tz8lu)07qbW)&%gUb~s~mKTjzh@ppklhvegsSq zGlyZ%ACEzdHNo4TEnqt@DmNl0M!i8BBATqq7jCZCu z{hpRHzgKj2dH!BGRiL6sv!cYIqV(va$Nk!7{pe%a6<2H7-KLdz9Lkbmnzg-=R&Po~ zfu+h&1f5ng)cFLeU(%bAtzHPLqG`!4R=j^xI@mArTmTa`&ZE;<344m!npN&w>AYtZSP?^ zD!8O8%zobswsL-&-HzOr;YaUsce$hbqM7r&d}q%M&I*^?WteY8zCfH@_peIDFd{BT zU0kac-HAMJU2_z!Jn^Qcv$obFh0{pFl7+-_`w;g~K}-IQqX)~{1C1Q@LJG)w`&sR* z1WfD-NFO4Pa%*Z5;e-oKnJ}#*=-;?|M$KGwnt{(nl;wRPB|1v#wMT4Z`G++)9S~NG zM|ilwuY4B-djr_op-%{a{Pa8){erLUcj}1uJALHA%&nspYL~!qP7q+BpcAa*OvKK^wR>hhl~{2QBPI}fIn&%q) zY3#9IIfC_ZZk@^jXIuO;9Qo}Rk-(DYzFxtN`$zY6Y3auyi#DsRmeW5 zb0n$L90(J=@4l`jB5RJFZRSQcxl2u3r^TvYazS=e;(E+*12p7htO$QFA(ar{L4<$P z#BEp^^L2OfkyPolbf>H)7lg8VOLu`-M-VBacdM@W#6~WG<$R1C)6&#GICU)E{B#{Giwx9Gq zLbGR1--qQ#6)>2vV*PJlK||r7S!|0&{SzExSO;@>oQyz<)j+0q zKgJpw4`2@?4*r}OtT3tWnCd=R)2AZF+@B3HgGZ58Q0OQmg%0~vIT)q@Z3;$}RJv|M zU{|IqKV%K_twn?$a6gwr%b_3-DMKlQ;q@9=DIz&)JSlU%hprE=+JL`#OqT$jes>u& zaT(fMc@j811ha!UsGu-FdgIjt&A|fy+}lP7sTHo&>9I34 zc>)dX`X9wl{2pO(MBHH_5KM*w)=#Z23z&Ox2N7PY0;4dC{SfOB7JYy?3ZNSbU=ag> zS6^5#AZylRmvT@@9kj$y4v^7IFR3bSX9v>XfqVv2yx*c`-mNBa276?)kfP}6{lHrib#$Jg>6?j3J*i^Zd@t>od1Kuf*-L4Ke3=z)0xv=@3WF4JALDgxaeDI?*#K77iy}0H2O72{|c^M$}WL@()#E zWMmVR#Qx{t1Jg(`J_wtY*W)U!*Dv?$c!pS|=tr^0gU}q&wJIkd?F+?hu=o$GGkwi3 zGT`V=E+h8AAT-rG;ZO17Mbgc+6x-l0?a&%F4P&;a=IGH$ZL_6Hu}t!vxySDtP(8Rx zUje|Yl_P;#sC1+#E1pTOG%E2dkRF!2Yn}k9VKW;Pd5Z^v6acYtCD+_g+!i9Yrk`EM ze38(H*P#%es{?bS#~=UzU-c!V@Z*K!f`AZ=T|RaKrE8J=RRq`vobH?+mDyBAIQ>Cy zf9DptJa=mbvbg18Q;US50C%r|dQpJSb@QmvkDnfJb#x|?&hmfqZ?!yBL;duA6;g$w z3N5^{_b;B|*wjJoGLWwC7ZR?bB8D-PTi7pjuTPZ4>;zP<`$O56n1Wl_{dUAr9O}Yz zy+ zpsqY-WDTgW&a?2{ct&$AW-X?MT7l%z99oYatVuJwTXVXdO+B$fsaja7ZKI16o3gSo zGQ$p#-!yq>KJ|mg_~9mLX6DS{rj_WHjoy~+wXF*ex9m>1y~)@*rXMfL$$Pr3^YRI< z2@RCz_+mJanR%M~(g4r?s&q+r8(m0JU0@5>!KTc?1v3e!S_&UbqDk7HaaRqxQr`y_O>7V#Uq%Q9#&U)uSjpNi3%^gw)fa_ z@0Q<=Nm~8@cDJ<}@#y zj|Jy3!w?qd9U=4o;8vPFSY`nr8N=oOv^w-Ze{wNcOT$NRpdFujMEWIc1Yuj!Zl z7r*`^iInM*?)Hx)(tNgO{o;I%cenJn+`I4GzU2kZGmELg+lx$YC7a9wHJsOdp^$vE zVxcHbb!nlPVj{Cx65eQo3T5vzU3~ni+<+mS8wnFG10~5UF}al$OBI#%OG{7w$*rt= z=l=a^!+gbGZspSVYC4}?RQx;V-wcapCckA5F|+DwA8;E&KB?xAJG}&fj9{!S-KnB}8tO4(9Xx%dMH%8VqibWYld|sQQrhIaVT4ri1n{SxK)U7ewi(Z(re21qpWu-1p{VE@a=m^C+ zWqA2}D9r}?mk}$Uy5nw@_9trk{J-K>zBx94?~*&GnRRBIUy=poptN9}{vpwQTS9{KTzLLF;{ddcpc#@L!rnm*hr*O|^{lKJfvUMbM&? z8C^!C4q^u41DOBZpZypC&clPv_tp9Dw=c4r|2cnQ;s~CO6_;w~wWftiHsRQmOY}{=48-Z7d{$Ik2{worqJO&09{##N^hb(CrXf>Q!mq%Wn9Qmd0!zxkyX5@2JJ zO8{Y6Z23jL^rF-e;9IPuV*Dz#H?#rFNk(u8^sXk!OWg>HuM;@lRos!ENxQ3rI47|$ zWq{!CkEw(H6%K5Wk!OJ5DtO)Gols-M^c#0#9@ZG(v2=NgSA2Rv8xBXwQ$w5wB3M`1eLt zZ|`NOwG-uccdREs%wno%^zrax+SLJ+SYsPNra6e=5JMZe#LQf42SaEM+~I;EB77JY z0wMGj;T2Q^sQlXR^+T^P5eC*&E1xO9+^od?B$}voB^^KeJNDK}nb-NaruTl-Vwq{z zQ|gSjT@TpJj6u>pF}_AK6Q+v;qCaXq2E`=qQa%WMQFxa9RrbcXQQx6~7qgfOe0y#A zj5r{Ieh2X5GFkg)7A}R}h5r$JQ%5?J2S@z?Le}nQ8XOo^{9B60M#+W>UpQF`pFh>_fSwt@$5q^| zVgyEhzs)11T}+Lq{tl+-9*B(ueDX7Kd0@GUe1-M9aayeGEK0dS;4K9jEiOPp-+C{b z+UaXhg8qKbHab}W;Up#}rSi=2UFIPFJ|S_Wn9%7aD)45D=zmW|4MBk_%g) z?v#IJiB#z{t#t8h-&*cB?faVFp7{6yF0{wwfPSmoVeiqjs*C^a87AbZ+cXB}xzb?q zTZQXo(>n=P;?vIVrK_CH<2@GJwK>0+Ke|V0{0Q?O0jJkZV^2+L872UjHZl+}3csZL zYbbYa1&D>H&wlzfR8}m4u7GGU&}rT@!ygeZ&ba*&NG~-JIl0{%u zaLRJ;bPA#0HYo8vS=XQ2WC(~H4vaZYV-AHuglw8Z86qS`wPe=2|d3QYv0K0LU`uBZP) zOvN!*==bU`j$N$4!)DiKf4uY^JJt%)#nwL`_b1*z%;0UMvw=+cMEr;_vJiU%kzVHMa1pzov^8az6ma=01A1~B>wg3G>-AK8V2bc%c#R_x}Ko8~%-w zGqqf0=brqNEW*@sF@^W_E0g~Mk29m>|GrSmCfXebG(G*Af1<$Ritom)*%IY|f-#EV*{V<@>@n3N(6FxnfmkY`^3Mf{sctLP74(A(4QVwQl95T<4jPk7Md1N2=?> zkm@sJP=e-k?whlBzqM@i@rQb1hSk3;2juG>XFlL;=kLy)QClWLk~9P^Y_N+z5628^ zEv$;eq$VmiZWxO=G-`SwJT2%cxz?xUu&@f2D`wclARVB|QSzIacY2Ob zt{a*NAIeE|sjh^pQv>dD$*y&&7{4DDNXa@nY$hol3DVb zvkFrbStsHrdvnXj*R`#?RSU*ZgVK855@hZX&y82Ye7*UnMo>HsXeG`#Qhe9B_{G=omcHJfsRw;h6TIw6_ZWaf=YiwH z)Z#CAl}NJodg}T-1QMHeLTpr(u_@T|M$+dllNCZ zUtelXvAA*7>DELWr1d%EnTD^@(fEBu&Qr6dkqw#e>4)S_kr%$k;`nx?x%!Hbv0bD> zI3U(bXi(&IZ>REbJ3^e`=&|&yhrh%Msl`na{5d`{z24I)@?*tdfG~+a)b@$V43abY zip7cFLnkQZ%{hD!f5VA1O4whf-0%rIr8JCZQ}UeQ?*_c8Jis5(WnNY*0wZ(+M8IPywC2`_sicpb@!5R*TW(w-kC(#w|ZS4ItNiT0mfV-7N7Y-EGq5x zF*f4*VmO>M{2+x!i ziZaO}f7DM|4nqMasWS+V0|h--7*VwWod z0ZyrX@`+QH>=c|;h$>{Pagc)V;J++A(%yHK3vCFq$B2#SymdUJUN0{;klF7&T6|7q zJ&X46yNz(akf6PLIVS7vl1)QUurFxJ! z-$s*|WRY+Wx0K^Dske~aOtOeHuVAK4j-=}i&MOp)D0ADqaMv56*UPP9`^O$n7?sQW zRoIqRpvex3W?+qq3(|}DihEm+et1KSn9}q6F)EdZ2j8@3*DU=jorRZarwTGvF8Xbn z;g$m5Ui_sw7PR9h!e;hJn+25^I1Zw1Lh({7XwJZ1kjNUfTXh-uK{sAP;FD|Ajc=nI z{(=6&o2$!LK!n8h^{qOtv?%wB0}gHdogyraPcAP4KUg1@hdtd0>_HHcIQ?zQMMg5) zRh6FDGioL37O0TRlV|{)4PRLnU!`q7Fo7;#7d^mw>UQ-fgpAJ#9rpHU|FJH@(u+iw z$q=3O8U(jznCK=s>V{WPLf}DXdZ~Mq`=f!+S8OhdY*Kr)zc@bO2U8)P)29?~&_ewp zLSgcN4%PLVDC{5({H_5c`Ug#xE+hzt5<2xz?UDE7+B?o?GIi`|qCdh;gt1Z`xAyBZ zAgW&Ud@oSbA0O^lf=7)|h^iE;a6lyiISL@j#Q3my3hBcR=`37zNuhq13!#VVov2|S z7Q1jU@LPrfqD6lqaByc(+jGU?`x>V-e&$g06%;Qc;vFVP#9^CYc-|@$RIud)V1yXT z`=^jq+Nx35l48L89Dx0(IH3u$zD@!<3=kMr1C)}@R?|^cd1EO2yO#y?$2x|G+Zjx= zI;uxm4S(pO4==-!0-T9RX{;FFnw5c?4V6<0DhBYvvS?XR<8M~tL|$Px9t{aOTWICj zRUl~|JlU)$iWqAcuK_%t7V(gK23Eyp0FbMU;Ix|K5m+#Q#V91AzliaR^|HXiaS3Q| z34RGF`>>4PQ#beT+l}(B67{oK1;2=)x2dOe-j$Gp)r$qz2$9Nrqr(7~S)t$1NWlYC ze4r4B?-0c%+>L9wLJbpYI#lS zb?Fc3W8mtX==PDl@;^YkoetG`tG1MEQ4h{LWQoe_k06nmTAu+zzp9x3NAIlJC;RX5 ziVS|N*3J~%s()YJ#8PvrV_@%n)8X@1Jv_Z3Ir|p{_jPL66rWB)t{rQGb^Qp4^19ht z74Y(x&dViMZGEuiPXD=Mm6;>KfKUCq!_^YGb9TH#;Er8@f~;Qg^OmKLptnQ;7Xg-} zNW~NEWqVKmZ2x)|p|23R|7rivFM7a`bR74=?4%hFNI%3NS&U*R@XshYCME9c*~7i@ zk(b*qMt=Xef4D!**>`vTg7E$e-=z!{4ikZ3o{h5BDYy|Llyk{rNR= z_-Fs{5P&7Js1w0kuI4b*%uZ|y{OiXpw# zqwd;8`3FV?lDSheqJqbxLUy8vSaPU3IoysMiRCRu0XhT7JEgGLLn%~ZFF9E~I<+j+ z-zxeSAM$ajc&6P$o3ZG%_iQ;nuq0^Ahk{c~l|hrs%ns+|}bHnvthw$3iLJ}|Z+ zGq$NAwq-o_gH`;y!1#g8_G6MqH9?=>X89gkOD ziwCa4Su`kMdkR|+g^eFDiKT$n;-R|~6n_#YdxFqf99k@%g#>RUBvh}$>X`UpZ-lr; zvP2f*Xi)Movt-FEgv^KJ?$u-k{uCvRl#});-Hc@QLyhEa90IhHQd;SmZIt+g z#f;JNIFd$YhcpUqmX%hXXtS7vJ8VR}B_f@pk+1QH!SSRlGvqK1-f54fWaaQP>&;kz z924Q%m-k@-4OmngSXG+9K~U>9Du>Rm@D;sqA)0`o;@ z)ZX$T>QT7}e$3eqnNSBROJT`gBRX{&!ahn}U!-=r!E;t&4BY)yH;@Mkq0OF2DbJlO zD}G@Y-x!o291W*WXH78e^ODFO23*)IZM8gUfSjZqiWKF?3}vCZR!bi^Fz+dd6UC2> z+)IGO%(HHpafctu*hk9}WY84~rc%H%)=_vnE~;Nr1c(E>;NV^K%vK_tqc7*VYrGJ9 zK`RBppq+6xLk{2(Z%xx0`O`p-kGF#mQ?yd9_7Y7JggH>vQIXE~$`oc&B#!&s^3AV{)JTL>2y3B5`+Q-P!zlICE5sOSz0r(oK5a`W*O&Jxys0N{FxIV5yHIyd`;6Q=s9Rd;l z6%?ZnnQzQec_*T?8nf&^R7?<%3<^SU16DN+TQ;jIl}=p2KHs#p+|N0e1-WAd zxuXE_w}SXG9S98eERE7TO?5YN>fM{`?>MA=$xfJu!meF{_z@t!c=oq=_FD{ADh|cBMdJOztj+MKP`s^FJzUryH_1RfFzaWWac#Pk*Rb7LQF#xNMWM5 zSwp=c;!NrU=B6jjW7M>FtIc%5mX6aB@2rqZ zR?WkdmcHiZ!PCtHRM?q;I^n*$3Icq9klaH|9?xl=m~54cP8mOZqS&GEaxRwEF%2um z$CN6-ssKn55fVI&vgt$C3N$3SH!!2*F=mJiYQq^S>lGrK7ZCzJpdDmG0&&m^8Z$>u z=QyCFgxWcUT19r@`5uT6Dv*T&xJ7{kd*_*HQuKlfF@5B@e&k0y(j>OI@ig-IL5D(1 zvx0W#N$pN0o4U?RNX?c`tvKWW00E7q<=;m+GX|J zmr%Y%is4;!Z-WMZ-w)%&b3^`!^*Et9n^ zWBXRf@cilLcRe6QgU_$YLI|=DZ({!~O8=GEe&5x8n$UpbX~JzWUlK^Jicu3M7Eo`?{=&#jT^-3i(r`q9H4(yM_9*BEEjLS7UGF z*B(qRXJ}%u)|HC7V#EfdF(4#1E}ccZoiCTkG1jO$HuHFOc zF(f)FDD5yCY==XsGFV-UtAU5q?mrGFp1e2MA(ZCXQ5Py3OFIC_005^U{)~nIz@y)d zO^~%`kz{x^vANpnHE1nvpN#f(M-I@k(C9u^U?p2k10M-&ibq{XqF1#bU8^v$k2PHf zK4;>&r1Q$|e0=gC2JAurYY;(#@!c$I)dFIyXK>@;I^&V@I;G2)>d!;t%{qKOMm6BzJw#+J zE}qv7m5N07A1?GVR$<9msHQ8Z{e)f4tB!(kS3@2oN=-g#wrm*<|le9vNkDB|(rP z2#!C~VdSLOXU zd=y+;h%|+dujWgW;7u`E=b3Mqo+pE@@Ch2??D6-0txFbS%ThB-5w7sJI3)HKSL7Z% z>1u(k2>MY7SH0Dl`+K=9Kfd3*^}0P|$x?sW=hl~~h9m|7IUCQ_%IuRL=L-H!cC11V z-&&dO|6W|R^hp;r{gQiEmn-FLbS(`rL4R^YEWS&q?Dsgj4}f ze5Z%}ysNX)`SPcP<8pXIQdWNMv6`e5-LL)vD;VoyDaY3F2cOGgkqrFWv812a!-6&5 zp9{0YKY>T$J-IqiWk>W8?b8UY6SQ_J@-<`Ygb&R{5B1QTXIAT%tUkqVB+3K>;JDxn%w3pGDT!)KQX;RR! z>AvJ^TucC$co6fG#*@m#JmHWWI;hZT$lvIk2pb`a zZb}*CwW@BSvEQ>oW@-1-g9Ec|m)cc50ObbG-=>9B>uhUC%FmtowEgBi(^4*Y0W^Sh zF-Ta?kdVgh88*`*wz00}zhn_1yH!F*#2xeR^ROyK#{rf=rAo|25s%}@?c^h89rQb{ zTm#~uhqj+D*kOL%`qcX1FmiE;yGF&YtEmv7 zeM9h8J6YJ%EqSS={&zmYW&JQ-0(EYIkNub}O)orr_XyUpu6dvl+4pSq z__l#$jS=Saov_5~JKlzs8uO-XiK-LoiU5h%feK>sCj6}Mj(6UMaCvU0VpECJgZ)pn z*6E!mw05S$`UDJp7mFw+xk{(y4LysEDG3@-RDQ_JJQf`0R6ZzV8T=J{i}(Sh>0Y@T zVHl2Y{GJB5x?7|hu6sX%cX&?%Y58JXJL0hCrD~xO#pDIJT-@~7qmxHpPTgmfSU@Oo zh@re{jd{HiM(@ZBnh0-p5$Xz!-vC0}jRo92XP{zhT~5+jcx&x}Z{GtF_#==fkFUidHCU3qPPmIks?P$XtWU&y=@%tk z&6>i`ai9N!IwymlN3msS9rV^_Z=zJCP?yu!!mfwc)16Z@UQ5W7oYh=(!Q}9)cVXU# z`X|;oqQzH~WA>L`@mh}I4V}tM^Y0!a!^XzXYZMo+S0A%Xwm zmrB&UiZ)3&%IW?+CS}3PFeZh82Q9^-#lsL~qd4cIB>*^_;}wW95U=@TK~`RCRXx{z z;6%?&Ws_z(}$}Upfv{XAE3_27T!-IZwl_FQhmVyTuk@8h9QkX_1@#h8^fCwOciuI@g zhNb(&y&8=M+b(eg*a^iiRS%%WdjT^A4P$5+ZL_(X=lG34$^5S+9`Z_KG$(D41ISPvWu<8kCxE>22j=t_H zigamsYT|0wsrZF}54)?6Y8W@z0u)E8l#r0_JA%{i6x6fASrt5cL0^^?`ZdRATprGV zaJI}7>hNeFuZ#Me$SIJXtbQ7fzR{i|&$Z#%)ln6;K;)lMD^R=dtDp#!s+FClY zkUkO0yO$%a_ zU1|{S4a(A-G8kn;+hptA5nRL0)qOVQCc;rL_N9BdS-v3xj}>DN9X%K6yI`E(U~bd4 zU?ePa)4GUv%jn3=;#q~1LB^S{!HwL~(KN?6pAWOxiG?D9RI2SA8S)cRbeGX@->7Su z(j=X=Yeu$GamNJSKE0iH!ANsGR^HuN+hQd`CB0Dk>dRBu3A^t3&>F<8+^yp>`f`R` zmx?rk^?ACc3lA;r1c({)3=K$x#|;&aA~F7O512m4KA99T%oc(4GVPQ#A+hOYOK}bW zUP&W;A(nET9HC5~%H7z>$dfTnp@^i#gW1804IK?R#jzv zxCiXIL)?v`mp>&j4Qhh7f#)FW$rr`sn?i-(5mYcMK1kir(?MUKT;6;4UdIt7n$`-N7HcS?A8hJM!K59csraD#_m?gI0{wZ(`f;G8Y&nKTv6L>^xYNkY8d| zi_?En&T!&?M|OW0q91$thqA=2q6o)QW(4+X6jtfNh{YSe5Ba9Oxv6=KL=9~h@wxCs z%^+6Q^uwgtd{49>Ha^jq+H~}CLv)t|Qt8Fj_DEQot3k4PjDN759{bzs-kT=Mjtb|H zH_L2g&a+($C$Q*sNcHl{bNHq;w!75qFh&Tv(A3_rxz9WNZDzoT>vkQ#GogjltF{YI zDBXTl`D16B+)z4XL&1Q>s?MORN6+6V(@Lps>oXFbfR4y zBjV7SdSeoDO5N1vH8PCM)Av!`*v&H8t<%$qza#ULK7Iz~!F}UJ(|PhOL6x7|RK#`2 znqewKCryJQhBRI1NW$pe$$nxbC?vLdR@Epz`}~fCk|^T%qcz;a$KitEGZ$aWx*}$* zCv}W_{4Ehe2+Pcz`HOlD93;i&+|OXFH#se<^#Im-W2>Y~y(yc?Bsdf{a{gTYx!~#8 zR<3RMUAvzB!AnKRC#V^Cz>bS zKB*LZ-~4K`Y{t%}qAG#W1?VW`JZ3xT6pZRpD;?%GH+|X)`)(j{KFU7dJp4!L!qBfn z-J$T(?&RP1G4{-T@o|pP$12bE2B;r@29R0}T&fM5=Ge;RcQ0)DuvN-=$BjjFM;8*j#P{a zwV}Y9Z6i9mY(MrYO6Rg&o&6=gUY0l^_DrGB76^YHZa@7GE^^aMbfuX+u7Q>!PUo&X z@%tX@3AeTrEUZ0cN#8@+5;fw_(K#g3aph29^c@4Q(ay;Q6%Xj+h)Zndt5qE3 zqDZ;td%OA)sbtYQiUoy5L!EUT#UEz%$oinuW=t;7K_yQrLok;8e1oB2ZA7qUhox+W z3$3Y{ro-A-nBjEtS|26Zs^c@Xy{Eh_uZ-i7@++6SvX|+R&eYZ>IPsoll3lRU0EMpP zDA_hm$8|R9ZPbj!a=r$J+una>KB#cr=u}KCYb)3D0y?W(cr;iD;VzURycBt{EQ|n# z5hluUPgK$cgs)L6f8z4(K{!_amt13Qi<1?1@0wn$WgW$|Pzg0IfhLEMQf(b%<5g>@ z&ng&gj=Hi;zqT47m`zFcO@5 z_xg;A`AD^M1)sTBLk2m*QFTIN8bq#1z`k+FvaW~*E~P^$mJu8$Mu+U)O$ zd*V!woI3Z?e)QB=sw{UlnLP>bg$F$W$0UOzuaq&j;;dH~tXFpiM-YHfCTl1PIX zzfiY?8?M|AlI0feOdT53Z^;>G^>Y%%6h3hoS6+HTCX}%qYS9K27iCIH{ugui8P!y@ zHu`?05E2NGP(u$z2t5I$1_*>I9cd~m9aL1RBDO$65_;%SLFq+M0TBUFLlp!85fu@U zDxjz+MO2iNz4yD%J@=Gx-*d+qcieCJMnEY}Wz) z*QqlO{_)za%c|_L%wICal3kAAmplRegXg8(@OZeGm%!&`R}UjtRh>KI1p*=6!?XCD zfrgq#(p}CangBTX77ui*{N|*Um34V z*>>Md6wE7Y_*m6=RA-icW+;jrUx%#p=e6Pc?y{Y~__q-k)6nR|& z_&j_$HEqOm5W{oO$eZn}>a#tGLi8MR(AtwL|3m2jOZLsf9vr*u(e3YVT6og0O!=LA zN7HV-E426E?tvM|@pz($akA+5To){L|ER|MWb?NIr1uR}KD`Vddjn&={5QAso<4iW zW0riJE#~!NIq6BsM!2*0&an9$n{8O{vS`#rrO(TDk7U^-Ef z1JP%Lq@NzV8JD&73?$P4(kxM^UADX3e0U+15$ErJ-wMyi_b%7IT^n>K#bCLjUZv$u#jC1~KeVxth57e9no$vOB@6fvZwx++ramE=611RA=1E-uR zVeCrN_ej-JgCnWK4t(Ymm~G=|CJE!V!!PY0@Y9(oX*4Hn&J?eq>HxtUf1gyQgMXQ3 z-Mz_2t$~`S;CucC$fM>Izkt~n2fi$ObuTuY3+FvU;dS$#k1C^6L?pwPX>MMb)l5Du z7FewntkRII@1I0%1uFx|#8$PQDC&_@=%Z&KZMaJJ=rniT4?%L3=Hn?2Rly2^bHIdu zazo;=77(@OLv1Vc@&lT)|9*qYJ7?Go9=Q;b^;@#_tJ@EoKT=F+Zi}7E^l*Mk+6(&e zQFjhgWv*)}Tx$FmW<0sSzl1rOwFYrjS$w(}x~? zny4)%p7#i)_a|<}!JVKhbXIcc&^{>y-N(N=^;mMJqGPt6u#&kk?W1Y%gai#pD z3K>KAmpegHNYh$m_s6Ebx9nEvQMg6Q+R*d#;h++p5t?q^VMtnQ&)TQCTDXNg`M_cz zh-N=u;teNF&|SB^N-xO)xv&Fx-z%dEht`g)=By4Jp?BU}9Xvzl)hc5zgS{H)mn$Py zyH=m8e7^h{R^fH+si4Gpf%k>29k1!1C(KuKC!oku^N~D-0DQ7!>dD=LE@D7G#F)bT zg*MIooZ=B>JNWFxJbh26AVS|Z!k2GqlVDncC*08dG`Lnes01S(Xk&%vw(N)7s+_L- zBgRpLS=JPVl&Gg>zM7zaef=u4&yVTC#ut3&DVRk0Vn?&5)bnLzgKDTmOyfY@X<9tW z2-8EJC#5BrGB6B1gL&#QgI2S4C7id2n-^t%>G!>vaPnkJT5t13#MEd0P-J~u8$4_~ zAF|8brhj{V9pScJ@V2}ob@_A!^7YE^yFu|qTSr7vVfMc*74`d{zL8Ts=j(rhD`T#~ zd03!eO7h8mM*Q|Ms!<}a2BXd}jx!S#;1ua)UJ^V}k4@PHm@ujlU38hQCP29`@jam- zMHSCH*ATPE=eyvKv~@k$1HNw)<;g+5O=^uioE(c&d!uf|PbE)%vwiGWL}Kv{e6_!F zkcv}9>=g8E6-j8bFV%?mus=iNJw)qtI4%A-rww`G8Zod$(H}%fMQ+@r<^+(dGc|EEb^!p6@-(af$Hh`bkzrA*8 zhA}1t&_>p-8#47TZ2=82!%xNm`aE^5c7Ucg(%J{Ky038s4@QJBJNX(RWFoZ<<>cZUv0jiW?^y>0A zrGA#8U5@6l9OXU$y}v19<@=r?wr<#1{juCi%@c#c@A8hFcth}eoFJ@qd_zI&#PFnj z1&0M6J=I~uc)vuiBlB806&>(vG+UbugaHaH_pEXLy%8b=2^A9GdRb4sWu2x-~@Jp>G|BNwC zsqO+Co?AOskgqimzP^v;JUt=fJ1M3Bl?RQYZ2-rPxu+5L1LpbUJfH0wjI=tk8Fc2= z;mVtbdi)o~&Uy*tuR6cmlcLr9u8Eef^9U}on3o+ciBri9Z_|FTV&YDgNpAVQ=fRP{ zIr|57;RE62+evS5O6z<>x7%2AX?NP#<8AnE0n;6P589DP=oLG3p|N|lAmQeHS;oC0 zgO*@B&#V>Hts)F68Yd0N7 z%&Scp>YY&37qW+NV1L`n%@g-ZJ~jzcKthD*xL2QUmua_Wtr_1bKAh8*suXcI`t*Y> zKH|-i{NRg*)8{@tG<<*Y_aDQVM1FIlca<L|=_iO=c*q_6TddJQ;f0P|WQ}7S^_k<|ZM>9f7@=Ur? zk+MY5uk6G#1KPz;*MDxce{7Mp>&RW^50xo$8e^6+qvcg6&%D<9JF|H0viYx-x;q`) zm0KdDp?iZ_;wzIV$hn2x9-`>)9o=^-&on$6#r@MWFE2cQdYUs=|JPwr!b*gHj1^3R znTH9)81)kTI@7&~bElTdq+T_DfTE!s$YtPKNi+1J{Y;t|)mLIe#T~w7 z*N>3(Wo3kusG?xKKaUbtlA+yLmQB)xY8W+ktJTj59ZjV|L3m~GAk&D$6>xrimI z$p&oGqdOc9IJE>S`{%%qKZ09JU2jaSjT_ikhv~+6Th@pgbRj_gApT#Y3@dySD$BnY zBU3V>hE=*DxXi&{Eg9kI0ZF>DDG)F|S!EQEbYAWhH2&u1O^g-8k5(f#93bA?Xkiv} zk3Cu4gCllIOz51VVLpskePHgufr+x3 z`{#H(vZea2-o#iHwZav07x88Z5Y zVnpi%UEHQ#Q6`K%i#~JLQD2SO@{w?$1}p_s)P^5ZViFq?F=qg4IRncS;=;|K!ubBC z$i&I8>yvT*S2o2f2|PG5fYcth_8Uf|qR z3{{EOa>T2H1jATT!0M8?*0B=adTbALdIk_-`-3keCt3!K(s;0trj!!UB~XX&j){0v z6b6QrBH6qw&P zn(Vy;x}EOT1D(Sss&r)Bmc`c~po8#W+V_U(aBdNb07}UzxuHU-S2W6=u|av#Pj+Fh zuh%b`t+$Pc@sIZvSkB95EgRfc404W)I($=euh;!L0eKT{9}ONP`QWqoDCv1hsZrf? z8FAZB_3cA9VKW$^&YRwdXW|Ek<`gf!8-OPqV@+^hzJD}MIL&BCHJ3|ukCnTmnGR`aN-;Gv@58q>v`(TQz{kDM~ zrv4B(_;QgTX}DJS41fkn9{k28FoV+fQj(;tZZ&rl(u$9EBngkLG(XtmF}^a|^#Y@& z?tZI@Lu2qb97mAOFrGiqmJJk6$M&!l-BT>sg+RyFJ?r>CC{_RO4g1+vUws=#)$mCP z^(E8F!P7J~tgfKx*8rIad*+ST9ZR%jhy&!7SD<+YrsY(S?pXJ6rjyy|)gpXmD)Zej!9wl{ zT#;uFyP=plKH#gqbPaiEGAsBh)V2c^vT?N&3Bq#7yDGDz8IumewHFrZL)hyg<{pRd zYMZHeU0ENiD|~ua4zn7h^ZU(kGt6@SsfLJUeE=2+-$N7^mv zi4^%L&twBAV|M~9@tMAz-KpzOJ*7p~yW$e(YlAPcl3j(x(T*NRbf3=41l_})@tyIs zPf=P!zYBg=|IkmqCIwaOCf`qzamtu0O$oJ30^9ClMGQ(s%oRjG9?7}#ba}!*Y9h&{ zAMAC}(UaXjbxU^knqMUp8Ya$SEq8W#zYKmCU}AeG1d^r0UIp8zN^<%XBNBIlAWFrAtE+ zoXYskc~5)tcz5)xY3ritkwSBd&fmE! zo+(&CC4zW4K~70mrCe8ANzb5M&s<4gO6frZ!`etu^Lp<|H|pM^B*z9mLTkTlW>Q^$ z7h&j~OmF{&vz-nA!A>M<0uX~_*?a7F@8fn4;*Kbd!67(hs^LbtMHAJKMl}Q~EVh(P z>&d3@1tZLY3A};?Rwmu18roM_w@?jzm2Hny*oG?GovN@qqilbv!k(_|kXhkSpuF#T z#l9+K$J-T-p%r#pL1a1^Fv{M0q}`YUGP$Hgim z{P{=f=T*i#ag?jlDn;+Jd)>SQM`jkBmtFN2s8$mYe<;kK84_x5Yqm@_TO$*ZbeoPn zetngG!+Q?DsysZs=g5c3BVYC$-Ksn~9bz_0wZYg1^+PO(P{qg)-|$}7jV|Y#@KGZO z@zqnw6(>Ww``rqf*D*4nOogfJ4trP3Y9J-tQg1}|C^-@<11F(4BeHosImp*GA`}*+ zPd5y<0`N)ZL)|0~Sa4oQ#6H_Fq^cPQ62KSmh7L<&s^VTFLo#i%&AGu}3)sx4Z08r=e{8F|v-mN{DvKn*f?wRhd@4 z?}S*IiK4UFRrmOIYxAToT}ow8gl&jX-$9eaZ%_{RacMI*`ssaiD;$hl`V3?)2CYHP zn)d~4kdtj;%$9CTlC4!e)g*mST1!pZBV2l4P5Lk{<5f+@G%oW)cv=g@e~qdKfa3+j z7l=@7-r;g%a%RVF*?lI`eG|ELYocFM3=gMX*hihNO_e-zHT6KRt69~9H@?8Am9%$d zDz=E#)N_#N0Lb71?CC+Q@R0Fti`ExpB9)f9=&J%X)wCwokWEq6R`#~$95OL>_=I+k zQE-=mQ%z8FH%)PYh@zRdc3W(a%_)1r;^{<8U)90t>PzZ1^qV!ds%cvg{i0gWW{@0| zYLGtp;|h}ykHxE9{kvU|CB~zTBG+9%KDV%x`fX|Y`8$(?p>dk1{auO#OpSRsF6}1O zWTrOq6`3ds7GSvNdu7>+V4GjUW~i5E*4Kmcr4isIQXJeA{yC?W2>K=GIu{`mVXKk(nfe)t-m>^9kxM zPsXg%K@hEmn|jJOxS!XLi@nAk6Z8I1&-8b=@9%n2`X73I@GgpY`k|KC+KrpqwKVkC zFvY;k(y2Q<9DZepE;Q82?KrN8B2Yn5Y^LIRI7ql9akUfC1Mo$5S%i1;p+FE+x2%7s z1-whFgUlCBmG$hjpje^DsRH#RWHSd@!4X*_TkMbxD@ghgOOst%+w?ozQuSHGC*KM8 z&ig|2IZx*?5W1RtI9Sec%4Lt7jVzQ@@1d5{9`E31yJmM& z3+_>Zui-M)s=0C~fF@#;SUyHJt?9NH?L_T#%dh~$dX8LVH-cg%72ANufb@$v1hxi& zm5ACQV-`qe6&wQ!2)zTr4v_>d&m$tqYAlLj-Y2Ag=LzrKo^6#zVI4w7!qQK1o>QLP z8av?mqML4RqjP;d3y)L{-MSCToH$2ZjHD14pl88fM)LU(yB??yH&=bXcWX>^F4;Di z#dnh3ICmOJMw&F^oo*>nkcH<-JtvC50tva=B?WX^Gg@ z?*V%#e>&u03&b=6kKUl-(n)(u0L2Ooi|}1b^hUQF%2J=gA?%QmK(}-=$zlp5RNoB` zCv(4i3v3s%2g0}7Wt_*+Ba-<#ATmQF3%`mVk92Lrn%|m4{rKhq)Fd?*-Kov*CvXk} zB=WQPqh-!K`XVbTMM;p#P+w&?LlRZ9x%o^@XuQjl;E(z#5n!pAOnr@K&7!!cH&=;k z5dHo}v+x?LU@Mh)%imnQC(jK)k`*JZ%o`wPmpP~k5@vz?X__N2(Jjfn*4}e0f;+#u z0GhPOjcJm_1W9}x^0|+M;&dZ9U8X$%_kALZAm}2B(CX%yK1fJ-bD++d%!1SD#i|b< zGWA5RzadoJzI`lG|1RdmZmG&E=<3cLYm|T^#VY+-CwW6Ox>+9Cc%i$hk7}6SNsb2&xyJ$QLTh#+ zF`_|0ldQiHWbOpfBvMT&WJBLzqh;<5f~*zZZL$C{n(87@s5a(Qvkt1)=WhmBs38h! zm`66W@75)Dmnkm&&^1Vu*zTOhyc^R^DV?1-2H87Q-1D$SYZRR9)0&(%)b;R;k3BRK zVKqcaQXfA(_5AJpXp&~pHn|n76K9nvCUFwf<@f?z<|Akn%!2+g|Q<~b$J!xisAB&eDG2ZG&W^9fu z^p>P)w0J|SrHsl?G)G1^C%v`SiKLzj&99V(R2^!s%(ZiC>i^u{PSD76$ae@5wCN;PxqB?Y`Q>eO3CoEdG+7_?c zEfinwx}$NYPLFb|f^2;ASb{F8{>kN?C#KZ?EaHF;#MKJ&R5kaBDr8W#Tc^PiA1pRV zCAy||JgMs#$n6;ZbYY@uXLwz?|2>hgZJ9=j(Dm=GaW;q|nZ6*O_k%--b6pzgNonp@ z*lp0O^+frJiIY55^$>9MW;E6heB7?LH;$2-5%t32{It7En}vus9H;fk>A?eXy0Gn- zE?9M=+~&Aopb|ut2q}3@whE^w$(hfon$IZ_dkxKPACUVbk~3W&WgId}e%-pbwA+d= z0qucPHT~arisdgpDPH#ZyL|MLz$55A=(F4M5FC+4K!~_!JQ#~;`TYLUq#dI_mN$o# zf7&VDqqa+}qf4rybNoS)1~y-F8Qxfjo;=%Ya+Bwa>*LRdiVn^s;fuPY`mL5DLi$Yi zKR9iiz7J-xL$&!^UcBCY-BH6zxn}OM#f}CpK(k~1wS~wXjX>MKZ&K!V=Zr|eTP_Q0 z>G$xG*lK0N>#igr1zUaQptv@(Ra2_@USpY70M9XZ&2{H5|JR>yoe_`r#;NnPH)=?0m^tR%1U`wOZMmcG={!x&)+>^eE<}} z11t{7nVwyn8F19d(mHf@eY`Q(G3$tV!up3>FCJ(g>1g@9Fe^4y5E;{Y~p&j;eaOo&;J=f@scV$|(GhNzypk8(y5MSl zqgJ~;>n_Ag1qlC=k0hjfPgiQW&PyB+F==)}S2 zPvrTd!yf!%S~E(bhK!eFPG46Dr!a=qnC3fMN@Gto8izavwc1w426Z}-`-cbv8#!d5 zM5q1F^8D_qvkhm{*PU-LYhSpSW?cC;Y?i#TUh2;W_H?TO^5N_p!NYg=HW;)w)`;!* zyW87v#QIq|@ByXbVPkCbOfvpv^B7SXQp3Ok*pHz_QT1pf=DDoAdVBiZ!<)`2 zd;<5efx|ZUhhOs9yv`y%%XrI)IDU1w0W}ABusV`7a$i3%gnqGb^own={GP z`}a`Xv6;SeClTL!=F+r=v$Haczp&pVeJ2eF=1t&V`5GV#<`s-*Sml|(k<8@~BAC-1 zdiB@`QB)GJasagt3?$s!5C4@kTYkr*y2NW_UPbZJ9{~>WS5LN-Vl=!-XysO$Hf~nX zV)fu^qq9a~1lH8}&^`9cQxC9i#Z&i{qk5uLZvew;Iza2YFK@p-1_}AC)m@O9TI*Jr zD?FMKI&kjFXaRvyLPFh{`aVb)@mqgp?Bj4Ww`or}9p~Cmy8go5_3-A)1E(+cCB))W zm}Y;Y-fg{&8ae#qoq*v>-juS1!`rhdI@8-6uhokB-H}^k)(7 zY%8(btYod&S^fYFS#p>~-`hMZ5XC0Teqk}pHfDtqG1dx#*-RV#IdnGLdXIK?igWCo zNGZlf%_Te4t9eeWk!_=ODm(4)#+*ba#+HzoogSh;FZrBpyZ3f>#>v=u=~;}O@o;u# zT=Tr_H@2Nw*XjM|H|FK5MbeU5=fpsfHkwBi>`B@=+12j5$=zU5v#m=`PL;d03f!u3 z->IBjpA~OaOUb86+vL2;DP=Y1EBp3+A?M$U2sQvW2zgI;%m47N)QCFp&dCBbC71xVja&P?ESh4^~xg`qbmGJCcwnSfb z8_d{WT4QNL{`>>MEVIoK@p6!7NI;p*6zl-jepU0Sm=CmsrEt-CBM*T-CJe>gAYDmu z+K2K<*RR5*Jd4Aa5Yu5CiT2TCe7jm+lCrWp;m--O*%KtjfsUJQ()t`&of79=O6jcW9R*&4kJA(hKsParLw)WqmO6ZH5{}NR`jYThZ zq{{v`aZYaY<3BB`7*{_6R5VUZ4;}c_0aTiBMHQ3UcHqE;Jn2Blk(JjCL2nn%I?eFD z;fgAMx3gwaLKMz$n;#eEQs??}H4JNTq>jbW@~>5@|0xph@uNS#x7RQgBuOh;z0q z&!yq}aP#TKSSc>apRno?9iJlRYhk$u2h%M)j!r$6deCQL*hC5>P*x5Z{fi_)N!5Vs%y7f zvyKI6KL|S3ouLnYW0iKK6^cT(u3b;&e=Ity*ue2SmRqb<@H9GG3#r7tM=v z_h;-KhXMi*#U17ePc#+%j_sB33Thfq`3|xIkbWR0R`l)bWRwk*1d}^A+H`v88}|q% z7Su3n3nVQJu3tETjD7OlDXk#t#m1lSsd~y}*&EMY56Q~64u+e_YYoI}ZA}Chp4@s9 zUVUq8GUEQ{t+&WipdVAQ|5Flgxaq_Kb?n|2>pvaYsiLqcJOqIGf~xLgeA7J&|Jnd=Ju-PV(G{b%#z($&8DuYZ59 zJ<<6GiFbPU&-T)t-M>3OzH+ZXWC_4)&jCxhStiZch7XG~}+VP%=&`=^WzlQb4b=lsifSMqxk*il{6Pcw%femdd1xX;3qs zCf1&xD+TF7lWeFYE9Oa21*woG0VXK`tBhePV(=^rr#W;MW==f6D^-O}5rGHv%G2zv ztG{aGwfJCRH6cBqB8xWYp#5Q5~$J0sToqeu-jnwzo5Ml_0 z6#0Eg3Q=&9HX;dO2c2PXzj<6(5<-fv0?pnI1bj<}5{Dv%gEoQ{tPc#i6{IB6JF8CB zU;y<;(WnDMiptlIFv@4R_2FCmt znlVM|x+SzP9Gz6^e~b;&r-X*`Fi+@QYq{#pqV!EL-ixvDNy3U};1Ng6J@SfIwW%ylKj(hcQoXzCHhHsjeLuR_z3hXofIt4-)|@D9-AIa%TPKS*LPT;sqxKc7^j6N>f}kNmAAl= zX2r_G_L1kLk?<*n4bzh*@^!;ec1m}d5J zeD5jft!HNYjdf#`16qGP{PGzd&Z~RWv=kz%%LiSt)lL2T>&IiU&rEq>mI0P-<;X@+ zlO#H34EhlOAKK0r9BC=zT;KsA_4B+Au-cLemH~M?yj1sK+?MU`w%~7cr;}0u4uwXD zXQcY1LlT?gD_r||jY6kHK{ZAD3EMN?jfeHT`E8s%-a1keG&p^h1zXBdEBdfZF4BsG8 z|EnohAlj-&c~Ie2zOQ)Sy_;MVR-!{4xbHtqv0nAtB_sF#(<|Wr%oID; z_uYkSiv5bY2Yl{p;hJIwE8{KP>QzRr{9poTZgKtD18((7aeta{yb|Xz^E?t9trY2O zDGl;e;8w4GTb}{lgzoxE(E8h%PJF}CHOVv5{E)ZjZn!=+@6;IP?K+J)IU}wz1;q=A z{^a43))1|r_en^_*CW=PW7MNSAe;uaI0Vn@6Q0rMu7GbV8*D6WWR#Q9yp||{k0%ku z;RD6O=eR3ifxY==2bq<0Wb^DW$&Y8$78scba?%8ezUY$$#fuD)He-XFGCaKz2ah)) zHeAg?k&;4Y(0l78q)$AQYx&_-#s>?)#dbnwA(@P8#5MS`Xz?c^Pw2JdTPv#J{$2aS zEWh{bjS!Rn)-IP-iG5tYlFmh8LtVX0xGSIs-No4SWd8r@74ZKP6t<}`wne$dGDSss zc?dnb6W!t%van)3LwON%Cb*xY!~GC+b7y^+lc_gs`fH6aYP{6oKKOFErw!!_ z=Mx>CSR#zSGJ^E(Un&9lYYDnSvV%O{evL56HUV!MqKqQtci)XyIgyJ`>_4K=lX?1` z(?*tg5P1M)yx4!1wXhX&Ph@Hf9_wOsYQDD-SMn;Tyv%&s3@_Y8>KEUAyoqdUUML2-BDHWIT3$yZ~UWY+VMZESo&av znqkwg%xIVu9$GRp)zH1q&(amAI6?r02RVsbLET(XkdRrVrN+2W?=OMQt~4+OW})0; zQY2#cK|2zfG~|x}my+QaFt79uPHOxBd}Vnw30O$P3K{iDdggU(wC$6ANwDQJGKBb4 z*kP0RGew~}ZAq(HF(4Goiu>n9Vh0`D(`IS0dud|NX^K*$!@hp@BXQs%4^|WejF4Ig z4;v7{DJu11nXxF!0*HZaSr^E~+GCS~E%|!54|oo*WrbC6Vd+kRrO7oc95Y;asDhw0tK|oVT3TixKr6+N>u(g=}jpi^^-AcLD@r@}t-&i`je^~(w ze@9|L6aUteQo#-|^!?eISQ7+6(XihA~v?|1C ze(Xc?bY)#yhESljWXrz9UB#qkOH`Y57t##{)Be`2QOW`YVcd8W-vSl>ruQNk%K?H* zu^spU`4mx#S+fFc;!WtS)z0Ra3u;kcSavhG=Ylh}gtH$27t`a*0;gHsa@rS@t+w>9 zQy03Wzxa-v>u=0F7tw{){*&!9F`LmO87%i{CN;Ao(4;ChL^gz<*ELhk!{?nYFb6*f z#Ky8BJ8qG`&hWipR|(62%PxT(f-H$oUM9|rUh?aFOJdlx28N zshKZ;*L2doI)0b5zq#;YME!A*3TWY%lb?e_`u34yMf9S~!R?_tnBVO`l3u3ryqPE$b0kN#>5di&{r{ zlFu&V4a=M`M4(r4zqx%je^SVYv94XkCg$CuC8scB37UBP@ZIY_RxN8d3i)O#{h9nh zp^5mFe%;yYmXk7vw=J!uSl+RK;yY`-h96xdP`4vA1tV}yUVIOt(cZa?UyoZP9fNTjusM-R5iKvGpU`Dyx`og5?Qj$ zqF1cfR5ZShQ?SK*pUN$eC{};yzwsiZ()q(Xn=5Wn&7mKFpsmSH%%>IsBhy^iWTOw} zpq*pRog|ok{0FLUzgvQ(=HOkK`7iZNJYz3Te7(C~hu-Rmv?|7?mawu4gsR7=0(grD_~1GP%0e?SzUr8J}C!LzYQw)9Od0mSQa zlM{>Xmoi=B`(uqtEJ*CLjKTiP6q`VsMkc8<@jK#xal<|hU+FuPL_&>}hYz)KHr9~& zZ&S=(JIzol?z@8}_qTK}iWqXxE?lyX!&le92jcKKPe^hrA+W?`n?$aqgul^8$fbzX z&A>f;(U~(k7pwga_a|qLCW9!5bP_rMt~iCKF)Rh<#DO+dKQ1(uj{@o_h!7?!0|l_w z;Ndv|XN)i?9LjXp*UyiM^4n%WXX!CGRAH;mXe6-(K>m&qJ-@AU8IMxI!|F?tA=wBJ zK9y~s41Uf_8)blFkdq~5CL1ZX=v0Ir(~QHnAAsBrN73xR5Sdz-m4GsIl z^W6}+q|6;fq)9MR5H8w|(@C8Hga{e^SX2=f6@X>&qIuIus5u;J6OQksqz&XFR&gkv z0aO$vB^j0N#gsVgi;#YU%EO^Njd(zjENCbEls#PjiiGC`eqO;<5O}Q=sLy{^&EHxo)LgS@VhgUjZk?L@C*tfpMtPFhiWp)JDZs0drUI9gd3pF z_m?aPL`1)0s4%Qljsywi?JdY4>~F|6w(Y;bn|&zajl_K~bc0vnxu`;cS&v1Q(E=)A zDk-z!dlu4z3@>%&NpzkAxiEif1sFOsjD^xxWXmbAO)8YMCiO%K8BVc)HVXLTp}rOD zyrl~XzE`F#gCGRH;2f0q{WFD6g0qaIUT&dn*JQvTkhB-_pcN`k73F}@PQssQFAKS+ zAe40ly|3gNPiYR!(wj?U%_z9f2_wyD{3k-$2{pw+?$`9kBA@O~NS*%fgNc%R>qg!f z6?%b1eJK%|FX7K&SZz|ycn8z!=88oV`FjAQupNKY7N7AClu+pT<5k7*)Dma_zseIg z2#6AH#eZ`^vilr*9c%1wB@~f_ikq{)V}B)quK>A)h+M^U zNs&K+=ciWCGm^k#EL%q8;FiD8CRAGKMTl_e4N!^Mfv5PGBxzOu76tjYK=BoehuF>qEw zS%}wO00Ddip`Q(cA4+^Gx@!~NYvG;zXB#YXUK>_@l(>EsWfF;~@`rHtJKVX7F~LK@ z1fm~UsqHGJT%Yf@F=|Y*o{~iQ?u-F+ z04OB%e`6ApacHU-Nd7Q{P=3->=~w{vx?bdPx9Zt7qnM9V|J;itQFWaLboaPNt0k)+ ze%k!+y-2SG_wo;^PwTmPj@NhmySaOjTft+19V9m9Tuc4G_aeVMX$c>A^KS6|Kl{T= z^3B{lN1d@AOK%rdaX>CWPIOrN1MZBSoT;LckCH5GI@Q>drR>H}q7z>=M5ZfLTI zNgmE$z`D%cy{H|WWgxisykyFmLtk{>i|y%SVeZg#he%3Lk5S1IWOM!3LpYDoH7;35 z(Fal5P*~I(6y%4a}peFpkr zC_Hoq`WV%(zfV}u0im22ZfrlV->)O142ACMJ+rJ}@%SRG&$CTlTJAn&p^Rv5SR3Cy z1hGb_FOGV4dTrQ}26Xud^e{ma-3`z=`r96VY*7t;X_z2wAWGY(Pb?JYDH9Mt28)1d zcqQS1Lec`knLGrZ1@NeOyJSx~&l}ihuv;1x9thR;WKKc5(t&VGIA0rJ;Dkf@-~yqb z@a_O;8D`}j3LR)2BsF*sLgNG)fZeI2;f-EEIY?R$2S>0`6!m7TqB5Mroi%M>b$tO5@Sku(4j_9A<{Xs9;)S{T%Lf<&`u2d71a{H$-!7HAJ z(WWKpEc0G+#D@P(QcozV2?of8n|@Ny^4ycuK$ZIhKLJc%9dDo9ydD3n?#Pd)uOI!| zOOy~MQiNT3JldVQpMt!iV7W;kK%Zi&FHa68Az zv8!9nHO{xVy7T0#_N{vj8Mh+B9N$jvPHwfdKD%}5?BLt!U;npBth|@!ACuTZ$DG(x zFCV^Zj_-!Hti%@}EcKfj#mjv2dOwleL#zJOy^)3oS~<_pJyz`dngBZwxuPAm1JsnX zo_&aFv1{$FcA!qL<73J2;~Dpn{zg~=9=Qy6XwweSj(w6@ zzuf3HuR3yXuoyCmAci$OZ|k(NJr8CEp@MYA^ymcPjFl<3JF1tb9kU$YUDMc6?u3Ap z>kiK!nIyDopZGAK(cU1zyJU@e9HFa?ow^g!Vene%XYA%08L9IlQ~+_w1~_$VQXfj{ zS5@dMoqdtAZ$wJHx<7{Laj{6?M1a$K?ZRdVDb1_;_d6xBK}WC6>bb(S@vY(ekA6J+ zdg=G?_rOSoI^?#N={QIL>e|{RF}y}M-I+yYwf3m~dlEB>IH_=&@ac!xD4cUVhCoh6b``zXU@qfGkGvb}5j zn1=V)N(PSeD&|+(Rdf5=80I7l(fHD^XAvlxdwyt_CDe7j+&uTsYPjoz$=AbMEf4;f zS6_M%^vb!gYVhz!I$#;C0emCLz7c} z7boWB*X^rnFqO_1;~*H8#i=i;`ckJGmSv}n#&vT7BF3l*zJvxHP4Pm~ehv!(8xRiPN1=*eb(p^Ig*X1Jt~>pB zkn(5ufjSx>vyTdA!8uqM8u;$mg<{3`C`l!z*p6BN8I&FctR>6AsZ2PRbNQ@Yw;B_E%pghS-ulZ5Rr z{WV0a2J+Khi^hhDjFEy(^$>Ivpt6k;>W70k@Ju}XuOXZf$$fnpZKU(!UbK5+++K7v zcs9v6D3RMAM5B2@C2)&r|JbY0i+xmx9(VZXUpT5HOm!P~Cgx0xCxj{(AMjDWXNLf(805e;x^$U8Q6(jOfyVl43~iU=qWigY3LB47ZKuAwR2fFNKa^bP@$4u)O?4T6Xi3B5z8QZ*D20ezyPB7zLh z_nb3xelKRNc{~5Xy;idBeeb=meSQ2_Q0Yy9$u%xRen|qrtlwo=4rDy`B%DT>=~%U_j1=md#x~~$lv~5U6GT1$jVH&6YimF z*YXw_6NU665=x?wRk`oI@Dx2R4qtzcQ*h;QZrHkzMaeBeGDmtoVi1IZ-DLxxDM>;P z)NrG_L0AcExsg+F#c)kc{1jZt&y&^vzrmGP>^@?r;7U^VS({UE1*>-L{~zGW|61Dx z1~n9)W;s^9Y?`<=KpuT3!mwbgpchVy&r?+xc`AZXc45cx9D|T-fn9h`K=j`#6X(+% z#imtY3tj?tx$?(jAP0QXD?^8QZYKTWXRaiZH_S3?Bl4Zdg+}K+GACx(<=fhbT$d>q z41N4YdtUoH3s=bFOCY2rM7g$x2k&UQ^2-vgTzjNZxV7DHv}*xnpz& zcTs5wmB3ea2jDBnfjMJVwwHi3inTG9E+uk|D88YcWPNRQd}B9EyVVPSmBqPL$|OEW z)Hhe`Co-nKUtpsDYN4=j5QM%%;vrJz9Q*{URxV(wJcaIlNkJzrg;kM)EgQf@T_5?L zR=+X*3f*^5tYz$JQqXS5ejI%Xo$K!ole=j5?8ApX_7j=j$M&b$mRcYe)-8c&! zir+KRv}pXF5Wh!&B3~#8fGbq7hy_ve`aul%aGa;dlu_+~Aq^Gc##u~c+SN3DeMXGV zQQ(n?0*Db|zW5l9QWv9BA5|a;C~{^`|J%tG2ljY5pPQVD#vS!>C^<_1t>?&S^;vd6 zsJa2OGb#4$xAhJQ27Nw7$2>m49!?44BzDFm!=PreX6sQ8xBhm#=14a@)Z2jhIx_Zb zNRK3Lvmd?wheL{Xl_g3jkc0FcE;lroqXsQa-`vBJ(sAlw2F$4=-@6I~EPzNqMvZd)*tv_yCWuLI>{qa^)A zJox<Lu`MKXK6THCc-gnlVDm15? z7Q^oMP>;o?#sGChVK(nr58unS5$p`r>o?rwLi_-lFqA^wQ^f%c?lu-(l5F7?lHUI$ zbGS!GrPyPm*`hFOkNkbO3c(3{P(KSJ68>C7NP8UZRwS&dtNPVeUc(NdzYU-<#|J zQh)C?1~dipZ3=D$LWwed!T=5_8TTq5pC0-mF2bS*qWp7EMb!9i`Q^NvM)@YH5A(%s zcD9H61~)!SFW&rQ?bvf7dn0K#DKRiC#Yy_Y^O!M5uqT^1+wwDs8;ptxn0-Aq(uZut zXo9TIGG{tqC{=jGD_*t6!BrMv{^Y9gpgJP}5zJ!P%%m}>RrTlWZD}>YI#U8>{dBgU z__ia~4SDY^=k?$3LX`rJGem!~))J$+0igI<0LPv*NcrG&ZAXqhYq17(KIq|_AjhkX zts(9m^r8@ri6$279EAsc(pHVh_G9Zj?Faqn^v2Yi78?S~2LtL8jp<=y8zO%W1~G^i z!~}~?alzk1rdBUbo5f8jt>44g^l!0tUu|T*OLJeHcp-OO`a%BQ@6nh=W*v&ZxcsAh z!(V(uIujkG7n**vpEirirxVVbCq>Z{p*&U?!2g4HW&maZ6M)74qe?Q=$+)y4OaFIZ z9(;P~-zu4o(2X85Jsqk3TO~slMp4fmqdi87%#_zh3;rFcI%e`ro>oc52Qn!FDy626 zWG&6omZqz*<(kc*SN?@tntWF^mHGdBr20RBdH+)-|Gx+3G2C735jx1lOmcToByZT{ zVPht>^MF^K%~VB^;>x)2k0TO~MVQDivseCiOWw+J z47BKC)5URqVRSe)tEzM|P2()O90ZUkcT27*!`ynuZGonQnAU`~q)szE{Q0;#4PDn! zR#(^OyFt>@Bq8~dItSeM-hgigM&wDY8MziRf zHP70(H@qyYVK6zH8?yWPOrZ-0MJDRLplJoc|ApDv@-anb>Edwle-n?L6{JZuJthLr zQrG|aH}RO_-AB=vlvc7&@y;7z2CxgOq;bn-uXc&_<<-{jKbKb}W8f=+ zzfRKbEaUxH4pw7$t<=|6Lt@4i@q#+)niEKam#!eyUn7bu-sSM60>6ng<EC?T{;`i1;gxhN%>gC%47t(1T;exV z_x?sSJ3}-8aM9GeH{DVe1KPM?t*;UDASoRciDC zNFI^%nBKpr?rD z$%vj>d;Vu$@rva&p;w0e{6KtCN*PzRsgX=FP+-_}h2yeR7#;qaL4a*4CI&(4_&11&78T;W`9rkv zMjvA8h7zbWUbToF5u9h>;<5&{I}hW^4v$l<*Bi0P;t*^m#9yd$Gq;tE&7RIHRJr;Z z=}+nvm_7AB`@bUE#ann%U{z=>9@x$MV>gE^wk85|Qm>mzjK1)jNMYs z*HkLDhSs?lw$~PsL$AKq#w126i!+p3TLBN{Zq0jFYYjTKcu0Q5uOLkTE>kD0IFJFK zTkL4`NO_$#$Rk21KT*T31tsGWAB7B>;*iHxx_^ySZg&GdY4ftEFn!6sJwS`Wu?7zk`VtLx^F<@ZpA|;1W1+ym(}s?l>n;tR28$xzOg6Fk(I{^!Xv~~1?)QCbxKT4x>&Lt+5qaj`D}YMl zoMOj$9p160rg~|6KKSg{9pl6|XtAYK_8 zbFs}0=F|LHs03gnN2Nio(-;H;DDj%!nF+TkZv2H9Bei)7vtdUR$4BWxjR}T$d*ZCn zN;ok1Yy9Nb2*itrUNs3?7I3$UbU}uNzDUk0C zdBBGg2c^Ez5!MH5@QH0>!Prt4#G7(K94+qLH>Ar2b>K^g(b~_tsMq*Gt2>OF%39+* z0K1~rC$~njo#LBkZ2>VMeGAT86JH^Q{^bIzL?hugMX0KaJA6Pr0e?(M3*9b*S0nqp z)a=nax+7Ecm*5pt8;=ERr_E;*j{a+y)TNf0^bfld|noZ#apY{q;SN^VWMn?N1~=J z|LJh&qF`JVUO=sbNXiv8yI`$0>-5*Iw?t+aHnwyU-*%TNlz9HLvqjFFskwZy@y3JU zBHL*Wzw55H+H^arKh0_HSL^*-J1>rS`7DKCO~id(fG)$$=Y|1)|CtULlv{W{^! zbLzO>iOWpRbLi!l?jKG{w=Xf3$^O1h7hRflTde}}2q=Z#d^wl^_we2jdSlvuE?klI z+QB;Niaz8*UDSF(_zjIq!f|M&!w3d<`(HP06HdO}kJR_OKU=J6>AiE12g4_FbJv73 z?cB0Px`HU@&O~skK2)j|dU1t2?@?Hl6rz4ZbsJ^Ncwl>v*KS?Hjwi>BdjK{@4z9#P zQ?Sqq9F*Td43FYOHgmd{pDD*OTiRcIP>y)ZWX<#8!H<2n^{YlnU&5TtUT1Nqgp%C)~_xs@5Zf^nJ5Pd#%yM-}DmAFU2fR}k za9lIYO7kfA3y(ptx%al@euY?H-aHV0>w#cCj)scO3a_Xs^P4 zXQxM=f#37Q>?^CE0*zt4x4duy-);yv(Rmv6!Nnx##~Rl{TY^wFrXbAvU9Yv52mC{o z?|4(hiiAD`iK!UF>bK3=L1AT}LIS@U-KT(C0e4tF1gRMXca!bE)Pyk`J!Cb6onA+@ zQH8yXkgG#H&rVKF+bCAt*~`!&IGv_Sq24)HYp24cFV7!ZM`y~VvaUNIO_2aa3eRaA z3x%rCMTHB^m|Ntg7jkCbY*Meb%|0(}?UMHp1aYoIviQ)lWlWG}IA&jV$?G`Q=TwC( zPH)5`1^t&<-{?-KQE_zYRl<))6&}j5{K4WNnPwum5Fj=8il+wyen@9!@?tJOb?VX} zUtd7vUT5JxX{c@>k|F|02}YG4vc#BVS}+jII%jYcxZ5Mwi3F-9!P_aV@iNGQf3av#$>5TF_j8Hkxut4sR5r{JfRPQ|>uPPFt zK`X5Wl)e28xp^8@iDyFOpe5Rv%>ht%6u27gw?r-%zgs>5fbC90T9Xt=fY72`wGxw@ zDxT7(9I)FsVFD5qR0>q5mWm3L`4&KLQkh;7(1|E8mI5vZu-MQbt|wUV;R_}wJgkWX zUj4?DNMkM`NNCqpMQuUa7egjhO2oW^pT6MtLGx;ns~KpewIumxOL8^^AXloWGm7ap z0py2*THql~$t-3>@O2cp9K{rXXVxY&`=FQyF_33V^)FgrPk)jcUTUA)PPcybDCvT6 zP-C?^5vWQ5mD6Rr$THohIc8+$%cojNq)ZJF76AZP68YWm%mgwMg~FP9mDz_5#*&$D zA^}q*XcH>(sk^~n!)KdN>}mR?=N(v%&xH(WlT4LHu0q%ZfW-%JYUnfz*5K730#|*3 z=JbHHN9yD8Ebr)uB{F!Dig-m~oCn8B%C7{=3ZaJh7cz+|Jp|Vc2F^uQgQ{a9I(3}Kq zp(?n&b$iX3`S+aK3NfP4z_45^bNlM;&*!S&2c21d3e-XZ%+Sy~zeD*qqhb77z4@?L z68da&Zy5T*s-D`NQM;PT0~D8pu6ZJj|(#T%2%wIyNG>9&ihKx3T9DtjMyM_<>5-UpoW zn@0sgcFo-JS`1@Vs(TOElO1j)@fcvbF8YJO7o?wx_qnWeeIOvx)Gh{w4L-b|_p6t< z-u_BrY#{a=k3Io-_rwij()VZ)-(`S_sIA8Sbw2G;8lmw*G&VP++ChQ%*IH70UgptVQnL$ ze3^z7js^=nF18>Cn#aai4}-#=jb>K%vbN8+QVy>MSYM_NuK`SQv-fMVxZ96lGy3v_F0Aw6-?8h z$_8wF8z%ecZLf;O%pmgN@!LueX_^4HXn*2PT-scJkeN4h%oKFgvPw59y4>PIx&NPs`Qb8(e+ zhiCwwKWSS1vtiFIiGVm#^Mu|?t2|KttpB}(Qm%dLVb4rCm9<+=von-=g$}`?V$Q!b ziO+?-z@@&VK^Mq~c@%3q8Zk%2JbQ$hqeI&O5nIKhEebA#-H#C>c&du`FSkqlwHqC8IhQ z#}y4XM}bPa50=S1{o(5?9#f&;gx5vqot<&auBXwpWTrxj%=(!C?!m$C z5D+VP@HD__8NfVDgWg7~cq0j>*QnLg{gj1i!Iv7SPIjS^c@dotKRR!f;hCpSkcxd+ z;Y1WmH4TQRr-Tw=%Y>4C3}hXT2%xHj;$gR`aBveO8V~W-UTO5u;^_$cd1bTw_6*_g zJBa|XRHpUO`}dz?p{eHJmB)q^D zj*){+RUvryXJigkmjXXq=&0~=t2iX;e?QvsX>ed{yt0{2RXhO&3uPCKdcc3H>L+h@csMh_Z0xV8vwU4YN+GX@ajbzZgsIQe%F2S7lJK|DyNJ3O0h@k}jBbi@xW^Z>;R_T=Ur*e)2P( zJ?p_%j3&ZS#qpLk%~o~ZHcqDbhjg>sC7neF&<~b|1+5|*2F%%_*+-u&V0Ue|?@qwG zh|wwk97L{6$q1_qjsLPLaRBu!Tsaom;CAoi{b_Xlenr=W7Z9}&*y(Z zv*v+QLd@Twg+%Zj^n!56;LP2O`qA{}3tj$~utFqWPnamwa7yyu>JF-j;B! z>+bN~mrc2o^$usRN*G%gc2wHz9x}lm*Qq2&9rNtX`(3HVgnwg!qIP-7&5z}(;XM9c z=EYh}*DeT!h&OvVtvv=F+lOw~u4HMP>(G33**{ySnnfS>7+hE$%{2>V%m$k}YF(Cv|Kq&`dWC$N4{ zn>DlUv9XFj$_>VdmhEpVuk8PUjGabaRPU9p0$7bqv9m0*RhqE9gBjN|yOmsVS}3n+?-V zeXx>^6URC>^wR~GMKH#B7NjDjx-9g;IKAdv^@(86vrRB>G;v+YMw8oVi% z+HYm-Wk(Jvz8819`&&x3Hf|Jp8NLRxdlL$V1TH=89Wa@~efHMf*%vS`@Q5v{D+FLZ z1!5lSFsTq%01UBgI^XhoIel`1j0OA}UP|RDA7SG%F0n+%3;2`Gr1HI*&BT+YYo@@3 zzVG7R76g5)%)MqN*Ry4>$yR8p6VS#Wbv~O?2y^uOP61|Utt@yhd5yUu3sk>^4=j16 zLI^M=`JgI<(!w?)#NHo&hF=Y27SH!MP0`rP?OMFX)_%cW<&DByfl4=uW7v(oo;?Y>P9K{P=gD%I>kDh-vzy79}o!Gtb8lb%cgeZ>dSMpNWh28{{f)~ zD&5Sw^z3JIf9o~t%GRhFKVS|Xq-(-u*s}&s_t;cFBXlzwJ1Am*V?jU9Q)E1|cKc_M zG=I-w+;f@E6FBDaKLgXS?<&Rq*6M06H>I+*TfRaBuY7Z0E>z8N17_Yyo$403Gy7GN z85{lkvAvdw#YFzJRGh9vV9V|oNoP&Fzr!|Kf)n3ozZCQeA-~33YnQ_bgcwx4bpkq7 zAFel)aItkN&3+HZNiiLWoF8mYGVML#6JO#yPVKKa`gALD;`{q&&7~>Ud+XQdq~qjV zni6bh%XsXG2|D+CGH_fBTnw$N4XQN-n^!iZ|G0~)5i%wJL{-OLo)#*7SE1K;fBUTH z`hen3YzjWa06MuAuhGT;728~s<2MxlC;Z=;1l{UV{rkoezVa>h5%a}0;|uAHFu(I4 z)}w<2EowJN(xr#zoyObF)cs74eMOt^9%Vuw6G_rP|49!_9Z}LbAfDqZXT5VUIGEn3 zVGoLt@D+0BiG1}Yi4qk1D0b?vspFX+7mZX_@dKee;^_*wZcZ~QSS6PH+MXt!S-XN$ zx)wKbHCZlbq|l8bSnfA=%uo&5qrZ?Qn; zzJ+qBN@a0r^~3Zj3ALPZ&6e$Sxh+ZTjkb7!3m0H!F$O7*4ztx@a9KZrbsJ4#2|ynn z{Kdbm`h3t8S;m4oyA6JTj9pgFjbrbmX6v+~^b1K|t2C=ihr%s&b4oEwNd}X{aK8f+ zv{O{J>)bZ%Qumz9UCXB@*A*Du;T)Y!9~o)Z*XjxN&&THb=p(wnTG=N(*qd>?yow@dTnbIREGSNhs4SM@gs4a?!a{cwD%`h)NC z_^$swrQHr~V6o7r*5ez&mD+=p-8YW>602Y$gTBq>9Io`wEDt);AgP<^gT;o!U6 zuh;H;^2^+>tc&J_6^$3$3sy=Pi1ZLy0z@{15~psc<*+B>{Wq?!q6SaEMdEcVR&Q1? z=Yov1IVn{{ne}auc*luYs>*pFGQhOo(7T&i@4N)J6Q(cJxI5vpkmsQ8gm}nju1zFc zgr#Jlx7_9PP(2usD*!(rlibLB4gU{ck3+oNEIGx85Y09P07-8%zEgO$#rNFzA2-j@ z8KpvgDWf|zhL_&PskMs5T=$7Vm1I&p2on6a9EJoKgP=NN-J@flpG9*V^D1d+N_Csk3;KB0n z`B4r1#@(cjHTW<#rpmP&W`5u%5PxqNI24@7OPq}T4Rga=CSUD6UI-pwX)dUvoCjTn?RrgOWjpt>!!IWa2 zn^EBTWdB;mLCi$=^`BRZ5(UMYFD6`?^SP}Jn72}{($`5_2~Fz#6%6+$T)18MPhsEj zL+EQ-9Wk%HBaB1J`l;VUP?3k0EXb}&?xnb4?m5j|%Pza8DPJnYBUehUn}og(uwP4;DX1%OxSTo$AUpx;`I6(4d=Pzy9`Rd*lR`2V5I0TJCT99^YY` z+U*QrKmLq=G8K`~v!G|9^X-{l^E=MTFyB|9wvm$~B2A|UBnA?106qQNe#>Eh`SUel zZn^Q1Z~n;tKH0Hx<@mGAe{{9I$a^l9ciXk)UNvpkxkNf!3wzjfck|>9YM_R`^h@X7 z17|h)3&|>>P9yie{WH>$AC2_zK%W<^(;yq9ROdj1>v&%bp~3g=po+!qP#`Z|76nG-RE)E4}vwO-ECx`92YTDgv>{)C@x$yfKKkp)Kmm-!T%*`4wwiT$;8l#Qp(WSNeu(CZomwm~t z{)cSWCu}**@eL;zkG%uine&=-Kt|n6hZCeM0}sA|(KYeBxVp=s`mIrH5dl!)VW?1D zNq*x=i*Y*Obwh%#)G!HdJQvlgKgXD~qg8DH)H0Rj$)<=F#u)v8Krfia2B;@oJc#v0 zYT`(7H)&vR>BQS>;G1X`|JFD!Z1%>v{vOJ?d8F7M4dbP!RVNV%msw&02;d78FqR%0 z$O4jY0{SliU2$N!1ql~c=w)x9c6gi>Q$aF~x)Iedu~%@9oz&9<^Wt&H*z2~YJ?9b=-BsgN23~2EhRzBHsK>ig zqtW5uAQA|h7=M9=Y?}tF;(-2nF>;CEPC7`H26RN5=5|P>&b-m#&ueUl{PXnuGg+`d zA?C(r{1sCsylI>&IYw)nollz?I~3DH20IhLIhVBFGs>H|t7a+X)H!Jzbx0~mz}ROE{%E8u&ogUGA_j`e2H%9G#@uZ0*^HdWVd^R}y0?<_nU-+T0tONV;i(ieSx-+A1mL&r2^ z;!Kp4{k>0$o}U~k9E506 z{WL!sCjAI$cDQZ0XG;ybKUuS5^&=L`?)S7@;!OgrW3wJR&zJa>3w!?(xyyG^V_U-2F;v(pJk%Lda1pIO^(G){S0sDYfsbu-tG9$;Zlzm zuP)Vb%yQJEu-s*8OuEn~uq#W7qj#n=HLk!=84#P6bo>I0PwiEUn^AvY z>k@4Hr##-Cg_RLvwN?@5=*@WrFSQ=d)NjayMb8=-%^KRx8hOncht8VB%^EkDs`AAd z3&+`F;%uo`?DFEQ0y0N;M|r;5PG~UQ?TEEpU{oi?4!g}=4V|-(n{#+P=U6%CRBUHX z0m?bpIiz)40^+POarX4t%V|l3|Dsd=bMQwzWjKccEB~QWB9Eb%|1g|vKb?l~VtP1; zgn5x^V_AO+pR(_YgLTfo4Clja)29`~SuN`SEg$2m96mkx+pBxLy@B zZ?2gt|ZBwcFANkmS(<%R9I2F92gfGpXQ@zO>^w@PY$LnPae&dkq+^bWDGyMC` z{~Y|WideLg*LoBGi{acDBue}r3}@5FNs_^-e5|ecUxxEkz0!8daHfmJBL+0!>le5d z$q=%jY<`U|UX&{kn--Al{qXExqfs7nXPMG!7^#I+p9NGFxhF`QI~PsZS~zLDrUZ~{ z6gm5*OpE>Ez1U7hKvrelzw$A=*TI#(v(ip+5D!-Q>0-~U5Nf{Uyc7d6W=e4Z6~e67 zjFc9ZKb4P_#>yXb z0;uU-=qkI1C14_-iz3syu)S$=aVbkUR7|RQExv_i#u(7Nc(4)&x0K0?*A?)VB0L9p z4CXKpW~KCcHWSM;pBdV_>dlCSND)2`PqT_L?2FHr#O7?C)zj95;G%%*>r@;CG?Q}s zd8__%c8n-^vR`*A0-yAS@_1^!v5+dOmGB2wzJ~{7j>%@OwcerT1*um~g+*-u* zR2$Wm&?l>kE4Oa$eI3r)2x$4>*xR8rJe;~dMR<5-yI8j5yoknDP4%J@;=GB&FCD)o+IRQv{3^LdjR+f&&d&b)=i8WC*NeeR?guI8$YF*ALBIM& zqYJleza0IdJ+*pq)^&S6UXWpSDz~N_o06bfop352%Rf;z7nsn5vGfr(=U5Y4!u!91 zO0^F8=>%z3%-Q*w6dZO^FQV2u(wKoIuU z1TFm7h{LXPML#ks|7p_!DWONpUJ^sNs=nrqejcaL%$;?DzM}pbDRHK`X7=j=p{LF= zJ?OA?c{4{!qh3+o+xMRPuluc9s2(c!c+eI04SkqM+93B|xAjl;;V&Ke2pTCS#Y?o$MR z3^9U~q8dGffF2`%2Gtk7vV~C@AFe7VXxJzM17anFx&R6D<~}2%mBEjv`6XQT&Yn#NJjQg`2qWye~$P()`*&_`52`(BLi$95r^cQ10!I>b*3~6HCYs}?j$+4Ww zm`HRl*n$>y?ypCh}XB`v6nnQ}^=kKvE{!Ka2~fDWnN=C|%MM&(R(iWL0nsJT+v;JGc$ zzSOUg_Q99ooc#sF`|(>EeVz%TscIR&^&i*Z`_JF7=D^i3Ds-_p+*eCgVvDICi0F_` zh`QuHR;tEbdw`G&)MI6NcV=KCztQ%d|Fw)&aU@CFNcM_$ipqyGe0=H8?ekYW9(`hD zXOQj}H`jwI8Gs&yx?xlCQFXRh_mfeVhvdQ7%tS?I0$0@#E8;#S0TLbUl-p_`zcJ>S z@ktz6DQ#5pBP#~rvc~GX5X~dL$|Pm#F&z6vYM8N<2~BWQyG4j8S(8k~socrTzo9fd zj|J;(GGJeFf%5clygwRD2wQcyx_jDhQzKOg0?&CALGcI45D3ZSKZE*P43|6|^5Pk0Zs2KkPC7HvHb%X_Su!}zs zlW^~g8im~7_gS3DZGT<6=47cycz-lV_wI_FLYWbodK2`TMGRo!kod+Ys#EP&$A@nQ z|9t%-3H!0y&%&3*B#((=x-6}gK)jcq5S6Z(@kF18gf#&AY@bz`UE>ZU$KNS-7^!L6 z^R+BLTvgxJvjcck+-DG!rqZE$v{NblnSzV!70Djkjm19?29;F5vYGE+5It;d94h#! zEPT5oPWT8VXB7oT>@aavvrvRVVzGQkgLa*i)7c^Bt=jehr_n(IyEKD)&C`p)4Cs1P zk~OpW9uu2A3xMArN#MEvH`#jM=(2JP>^!D4s~o4V!~Qkn^j?~EFr>dy*DW=2wk+!b zNOM@ekx7-rh6u$yI=ObYJO0wF5VN9s74^y?o5!gf!VNH>;e>%`jS)mTFg>~zfaLql z07N#GahnEqC9<7EF`bZr;r7=s9~G;q;3yr_%aq& z3Si=s02O0khl8M;th;~0nCEbymjI9>7G{Ju(>4y3Ylh?~X+02QGQt5haKLT*2k1vC z|470Nh>9U}5T687G!k}rmg#*Ch|l1(rDHQdF(m<*?dYJ-&G_~$#a60b{Wo4M0?<1# zUXBo!3%YA92~(!Q-%;863BV;HOpXG7PP}VEVEKL%woGMgr?c6i8Q;+%qC}SE{kxeS z&eu;snh#2W8pL=%btNk1<&b))N3!pA3w~DU}ll^JLH@ zMKzV>;-^Ze_7LwQ^{X1Rh#Wq52M;!b54dBz*&&)Ox<65-Nl&;!)O}4ljFFcRjMPg6 zGLV7pgMX#aQ&x)lnb< z!FM+?wJXMalqEe)DcDae1AMxgwg%DC zj=n@Q18+D1*}=?`)N8jGpE*&U`J5^}yOGKG8pzbmIv5kM;+@rC>wGM&MLl7M-JxYd zx>>6L29g?&RDPSN{!ZIv5dO@>6M;cKq-1wsz4preeyeBeT+KfGDm>l&h=Ir)PG)*S zRygE&OrN>n>6jDnNY&gU$G0}er70)ywVE||M0+$xm>X+1E?{qic^=KSO+q~UeHvDs z7p;*;Sj>%$$V<%6OMab~3d#G9Vhxt@bX??NbVFJyX$}He<^gOUsCgy7^GW;#Wl4EI z0r>%E^LJHwh^E3I8;&GHy+WV7a*e`f$HJy0L!7Ojr?#5{*$8_q9YsxA7C4XaX8pA6!CbfS-Xy9K$AgD<=; z-Xj<9@fWoIhTf+_-epCE$dvHi2_WZ}e182TO{Q?@cS+l@Lb$b-+37qHUmX1!v5U<6 zyO=jP`~-P74{*0Y9a8MaF8XUxltjuutR;y+*>-V=j~K)j1+hjh`9jNO-9elyD2p6M zNY|0RpvzV25Yn3E>~%$BwS|v-cpH-PxnfBVewRM1HQ_5K?ND>kONiZC1Qc2>lU%V! zD~tSHp|FFnHLuiw<~fbzao)8v`7LoLs+1|&e_n<_|@S$@Y~Dv!j442rTc2W&W}V zD@`^!fb9zwv5#ciq5XS_>0O8Tl!TyDa_KlWI<8#hWU10ww&1#^+eKMk&*Xf;WRmO> z;yae@5DSwbK%+5?$t1R)Sok20Z4Y%C$p;@svwfq%qS_E&(ePm$+cyfl*bMQJ0{@9- z8zjMxXcZR@Ynqb^s~}ZMl2tn9GD#t|F*_BXsfZs~w$9VLncF}=I$Hn<=s1KJK!I$~ zz*A608xQ;oW>!UmOweqec;+lSrdkTzn3!BnWZOp9_h}YnCO;l=;?-TM7lP*bI-Ncb zOc4df;DD2Kr!f>Z0tb@;z~_mKxA0d2aPT*SY=%VUP8{$z8Kz7}*r8pk(ZCf##c!wj zRsQ^8-%>B@+5>*F-4fy-Ecx6C60Al59+R0BDIgO9@E)2~58a>!U_Bv%eMwL?s#ORk zS{V<+lb8kM&+i8>K`d7P_Xqm!z zM}*{2msC-OgbPCae2=7mH*ae9J4n^9lC_=iej+?Sk~fE`FEN16H1wxA6k9 zP0O{tT4TkE_1(t;yfWPm&p$EG(z+It`pjI42I|a3L4D!u#@g%9Vmz}m_Nn~+{u@VK zKWUIV^y2#*eYiDDCml+nFmH!koTk^`EE@cr6_LOU4Mt+B?xbVQHh2GA05s!w5fAsRhAW;-%Bqwh)6;g-GRjj)8 zcM9@RhAn=vrrBk*CAIuj(P&%8XvfOvoBGim99uIvwGPF@(9EmOImj3S8KuCNC~#^$ zoB=gHYr#HO51%|519ih00OPAG-FO+E)(zlC${fT>=aGB+Z$UJn%L}^plMHh zS%E*trf8X%`bY7Ax+h1;uwe{LDhxV^gU{lrEX7o4CzVwW4m+kIg{L?!PC)`VmD#6w zD;x-e=W9nvZV756kK!8hqo;3=hI<3x` zKA61*pW~3KwLF>{W`#!M=N#el*X7{Xj^`D}=bhx{tG>CXtPeQ3c``MkTXEXC*l7d3 zDL%P{Sl5O42MfqFxOG~+$SRM^>ugXIb2x>0Qk>a`%DOym50OdT15(=<#z!yAnR906IfEv*7kLG!eEV@o)%D`(pSDq?k+yJ1D{e2PZxf3T7dUt+xo zf7h^Bb^K1o5-ELgJeLZ7F2&N4E0;^)RZaDeqOAHK!{*WO6&$RTz;b#~J%iz#LBeP0 zu)qh@c_bVm|Cat>?RpvH$CUbJM^c(r+CrWjmkg;%V9xkc;HL=7gPB~i`7bSfjQqO&gV|Xed<>6>-i34h9dn{G22vTX z6X42dU@#i!jDyMHSyuqn%QRZq$?B>nV#e}#zUIM}XoxUx&wCMVOn?;^SootU1+<2_ zTqOXkp|EA6fiuMRBO+9hp6rT-%i*C*sM)>F?H7Su+7o@@a2|f&PlkcBa{%~95|ak? zQ;?2X6B%C64pRp}*U@IfRERzmtWBad>g>*5+frY>ll5@-dgiV^LM-sz?i?0&jt*vR zXCB01X?P}(2GEQOzfJ%GbwFJ0a4P!qoX&1dLx0P&&n}Hyd&=vOi=P)zP*p757!Rw& z(pB-$jD4Uc4wy`U|3d|zrNepwaD$+g@y@S8m#2~&{#l&($FbWv`<(nq@w?&&%a~x+ zcIqsspLLc5pF6>T5&^7J)Y(xS$bk%>z^w?Me8)^uMI#H&G|sqR5H6i*FaH*a>wYtP;(zJ-%|KRCAZ6mRRM>I!EV`p z^7Zcz$xr@B2OL&s97awawuv68bpC2z{ByPRP*0x4Sf5kx{n3Qz{#xe(=hjAW=C1eg zCU5cVbA_Y46WyOPw~pTY)BQKfH*{8gEAsD+x4}{aFJ{?z|LXkZHG4ej;an~A>4riJ z|Bk5ZOXKbLCxEHTG)&Y9OvEq`yQUux7uNAy_~(g&Ub$86-7_gUa?T9e4?+Ako2FT3 zEVKH&QgZ6;>x|PF`#y{6CSC}5*Ozbm(IA;e(YHBncN1G?lv3yUi6dJyUnNW@PQXsq zpx~myjTP@JyYmgE&go9Fw(D0Ck4G|%wCu{}o(O6M#|he3*jHNItV%nW%qQB0A8)xh zf0d=a3WoPqvgTwgbU}P3+Oj`R>qh(>P#s7`lP}i`u|=vbrARc`U+?|fUW9emeaIxJ zS$TMQ-cu?3q|c`**YQ>Nc+6@vIPgWT$>YjhrH2c5{dWp7Wcc^8qyS%5^Y6X-A>{IB zXlj64;-j1*r9j@VX!SUk?SlTDVMO|ew})TqKPorYuf@xS{pfnD#rsa40%%hXX#9bk zu72WfV=4*bs{8%1=nmq_*;nqtLnfV(3#Bq|ewWx@7L}t?!G#eA-$!+OKwS9Nb&IBR zFCXswHpvr(3Akrql3VqN52;h`ED||p5@0E=wU4Q&So()&gR1#HB@u^u<#1odyy**E z>l-SE=GiOR&zb!Tm>$jhI0BSTz#)`VA>@t`{G{9iHSgg{tX5|8xv z#z7Ik=~l)Q0dMlG|7dj^h<=G?c<*Z~@c-iNO~ax7|Gxh*n^`|INQ-sQA`-G>i?NGh zNC?%4WN(NfsKA*40!`_0EDjWyOc}a?6=0u+dGaF-#{+@G3h{X&}phQ#k6yCR-?j8l5 zhhWhwAA{iOuY(tZq#GG%b*77zlP^Iex?HL`EVaB*m}pWMy;rx`+92V&d$0`EHkNom zNYBIBDns4`nU`>9pazn0IWq|^8a(KmQu+}LQXgxkoIH8TBF+0jh9%9oD)|WBdcU4( zMX*e@YYTl^@;rleY1a&>75wxvqj1J~o_M?e{6{e7(^L<_`5ZSpTf7ca6|IwONV`L0 zw2E9=b*=MEvQNG_A9DY^Y~_HC+XFS?^qHStyv{!dt@-i%U6G)!vCc0QR?pKNI8_*8 z=ADvr@GpL4a53+KTWBv%O_aIkV)K^MQEFQj613d0qNOe0jg`;5U}~>|knmv$%(nDi zjaUurSJT5!-Cq3~bUnkX`j-6rGgpRhOiF?;6tXLGF6V!;+&a23Sx|j5AUNflc`7-A zZ)T6Pqn0u4L(!p&^~4J{t-0}TjkjerXHpFlKvUG_2iv2R$OlIWyRyQ*wGKzgdt~dl zRwVM!R4oT&r4YJPj8;(gnGu3_=D$H@ z4keu_X#}n@3?+6L`Z=p$hrTv}zkdmg^X>J!I0VcZ3KI!Y<-4zEAaro@QE zGZQ>3Kq7uLh@3l>-(^3aT3JzBLLeKZhkE#=03_{ilx}+K=5l(ct(9yl8+A6#kbkD8 z3IC1}tw534YoQS-`Hpvc^WI1|S<_h1hZC3cX{qp}ILk($wp;h;q5OSX?HEUP<+Uk- z1f>Rib$JO8onlJZ5W`JY^dDW`tIzMa3FDf6N1o2NT#-2}U!=C^NV~bpvz~HH^v0}V z{&NtdF%>NIu{Tj#X>W9hVz~^@xw-n8;)_#-UR)6dJ=c;RfHW{pKy{Ebc=II=c zB7r8XknZ*;tin6{BeeF|jdzykD)MEp?ReYL zgIjh2KtogWhco^wjy`RBZYZ~#ngl$2jIE!Fn2Ts9?kFqh@R*=dTTs})louMWA6(^| z`nMtcpOlw~w-W!YA^g9Tmt#`pWWL*v|GS*wpn)G>|2>HNzYXC(a)!YC63|3lw(Yr! zqMlg3V6A`U4DmG{3U9jBrWKvv=3VFMiG0qGtDf95^sMqVO=eP+gDiLrAuadkd~3)0 zmyx$r2pXWYCqA=}6cQatHYF=ISO{DE{E99%aZXin-Mx9^)ol4=%{vl*9zIcUEId__puLes?~f31kFV)>otDzkf6BdZS}P)v+wuVWmsm_E&uoj z3HtHvn~h)W=KEYpt9SKVE6x{lFZR6qW9r2cbG&ZV@b{+II!{k@)%*W1J<+FpxV|S; z>2k7R@sptors7fPC;G+qcrVLuE|ElL48}&UE`4 z?$pTp)z8{w_(tE3zh`T>J>&GN0aBT9^xg18=+&lO_6skWLg$998Uz%FeM%r__MW=) zR@Zjv6+Q#4(6;wt|FZGM!Cfi^QraHxJzt4UqskV8Y_3IBf%+`$-qe}CKbZb^gzZ_e z>-0C-1M*p9JYWB~i6~{Nx^uU;*`nHMk1&Pnr%Dn=+44FWrR%1o-um@n5oKTNZbe1g z<0BS1*KI$cm$)mXl|TKCloTMkLg6ARjvXH4h6_v)51xaeurBG@JA zi-rNEZ%3F%+q?~G!w7(s`81la*Y)=(M4b-fGdO8vs~q=DYQL~eO(bCmPnA}J2&>~` zv2o+5VJR?@kI5$qrpEqiJ+fDGE(S+5<E@8E{OAe1f}DwWF^6|QrKxXT(K zz>WIIYRVf*MKj!{d|)Q{3MOnEB+QkC1BHXa&d^K#=P)cxLrsb8-tlwW9DVU<0!#+v za-9#Mzt8b;q*~xO_8Xe23ns;j?YQpRhapPC!EeeokJ6y?(o)y}z=L^T^3z^Z(1Jgb zL_7xi(4D6SRqg^26+yo^mqB^sF&?|7{EU~3L6+ghwgUzB#j07a^P=BJncYux-x7O% zA?eVSPgiJ!#^=YgD_T7gRA{Wc@et|VvBpsPt~_eN;n>HO*Iu=U|Iml(SO{=IHgio+ z7nAyLUthAanG&SW^cw7$gJ>N+6+j4JLJYbg#Om4t>JEIbuayJ!9>V|)4z~KTcF3 zsp2&yLGks@mqfsPnTm}E%08SdN%xvgI${Tk2F1JFfgqyKgAtOUl#HA#e9_YOAgDVCzi!kPOHH=1l7blQIg3JUxf+=hW>!$r9}lR}$@1_~_Y zNUbRs`1+mp!_Sh8{R5RI2OQ^^@^pBij`%~&io}A&<_rr=> zO8&~ReT?2Y)8@(kLd(ix`w#PWZ?-@GD`)uNb;D=5k814?ig(1@7^V*}fhtDK=>^B( z$j%zS`}U(y#KnxdK~_Rl#r?$u*F#Q<-2hY8xs~60uvxqhsIF-r^>X^PI`n93y<%D_ z(e`!d=U)e_>o5Cy2YxXbolMv$TEpUQ_x%1=RHgQ6@oh@|X5%nBA?Qu^;#I1)*yqm@ z8jYRDD*lqr5@5ftH_4p9-RN%?n~62m9_sZAshR9r;uZ!qSuG}nK-v9=W7=Pj3s4{H z>5K?GtGQ4nLe2Sr9~Zq72%7M>3um~BuTpuCASryho}>60$&~k9)S!~wnIt>@4_~dX zrCa@)KECHhWl!nKD^6GeQLmCX*8A;4Y$U2$y&Syae0t28pu|n2ovJ;_mmO z{q}Ctkk?R8&BmZLmNOp<91{pvp~K9{5FU}XsQ&BTCc#lBZs4CB4<-a71$KkNNhTU3crFD# zNI)1fqSdL6Zks0O@o)t$0~2EFnpVwkL`2@Ep1ju%9QtwDGhMFGVL?hjHwVRw>|+_&btZb#2784A?NkcjWAM}MdG!Sfm9Ldnb8o>e z{3*hF@7_4SB~*M))H>CxTLZUD#_dqO{;+O#E#rc!AFMKQAt|`)S8&5kIDa#obq8?r zhTU+XS9eGJhdHkv!~;JUibbK93csJ#Y@%p;0O-31zB=G1+e6(xv0454ro$eU{&1B7 znxLll#vsja+y|+dBy!F#@k)}LzRK^KB+G`l2C zgW9aPz2YH!U=l@Z;_qjqriG*zrll9xrawaBGWW#|Zl>Ay9taUYU)C|qXMoGd@{lg)Ai0azRfsm}4ubCgWgg|ciwtyJ0 z3$~qmFKg=D)AX(M;Vq$Hj{6PPQ?QivH6pwlgsVda%!E8E{0>x5khDin)%XxpJm|u6 z*OkLS5;97%cU>t!trR>d+Y}#R9g_H63yO56Z*}Hudaw$PtmRX#SVfGXF9OdH1o zvt--|6Wz_mPAdVbLs%t|Tpqe}iV94UbEoNma9!@+d7z4Aqwgi8bNsN$yc{1b@4-F# zI0+Z31R*3thw#8U9k;~EUsA$tvj8>&;DCT*TDVJc&)!x9%_h4I;fJstz$<4y)@4zb}GA{1<`O3qk z%W^a?phT<4h63XI_-K$_M#y$DWFQ81k%l`rM7Kx1_;UC~h2sl# zzC#bT3-2QXoVALKN$@Q^Fv`N_1!1^kek~@Tz)O@(pj!lJ1PD;)+#e@D8#I49)LE)F zUK-u>+^;Kjjto30mgE5Xs zF@~PMXx9X$l!`vU(2Fc=J_&0?KyVo_V=f-2z=m_#aAPJ=EDX6vES+pSb^8dE!#k~FaR5SY#AN9$iy1rF^y#27uQdb;A0HzJR|?h&8p6=mtNjNeaPz5 z=-df9@S-|@n#sF62PT=-EiBv*Hm}5lt?vQYNZ`O*=%fyS5?7_%%T@{#~SO3I*VsW!Mhx@e-P^&QMo%qZ|b++FwsIy_tSUMbLSX& zXS&{ed{bj0`gXr^7L41SPC*5Hc=NUc`F3nruWfv=gr$? z?S^lnptaD3zrz`$FB-&p3;%dC2E5)d)_r;y zvBvg*o#qRe)K4GFc(7B1^!)ts*)82R9f8UW>-?6_$G-075 zM67eSvg-NigO7FE6-%(^ynqp6JL!GX2n+ixvpe6pt02BhytgaXr^!AH6H0{pG0?+I z%x92Tc09J5iI&+B?LO5+UufcEbYI|giS+`H!!V!Yv7aeGC%s`)I zfO)HyQ94Y61g#Eh7V| zN5l;&K?2FBSUTz>qxV33kL#@#;)4N%fPmNe{%>L*uhn7uSpy1ev>ynZa~Rc4gSau! z3RM1X3S6Czeoo3%Eg6h^I~c6fk?;qfwAg;2{(U|%mhFrUq(Uxnpe?*H4<1UQP(yhG z8wx;XKy;aKz4*a0h1Lh+!#DxN*g{jLPtW}@;Pw6P>Jsb(m(zTbuXTcnt=4HN{WGE> zHu~u;epKxJfNxV@{d?l6uDti}*B^|zl#Knz!prc4=h)`$x8IO1op>y|CH06;E`$L8pOA=rU zADuuo%JRC~vG)^XXY3r|SvM70M#Qv}Cl&s7T)|G}%%F0KJf&=#tPggc3jd>z(I+6@ zawhe4n@1?92*M*HKYWk@{w=TNVvAnVopG~lKWGUj@nQ5R$hTz7<-ao&iP-?lneH9b z<=4|NDH1pv{*evfZf1?LaK3l}ResEa$CyuCTI0j7xnU&dV|QoajfcbR1O}S;K@|^n zC>R?&W>6{ERr$O0*r^vV!Hi`7pk&-v58Qc*?k57UO>{SKQ2-F%;SiyL3I55?xK~uD z8xg|-Vf#tIA(J2O`Uk5dKw)IeC*q3~Dr|y{Vg1B><^;7|SP(oUH~>bO(fI8tm~9HI zhJfw$!}ecTyzIXy(})|N#h@>%4KXk*CU%+gXvR-??w#N^6*fc%P7<&zHfEIgYfV>} z67Z|{;ZeHfg$ydpmj&a#!wj+mAU(pK^Y|~j6!5Of$VkO)5UP_6d}3g_iP)#QOJ~P> z;EG4TA(U5Xm~S;l%Uu(~@MuDe+V67?kV1GN~ zLo4OE_TQv|PekkpD@y00uvYEodhlw@^-Ws3Z9lQg2ILxqp{G z{1V=TGzD2BYuiv^#snaP0ORApAKB_wM=3JdpDV8Jw!eelAz`#Akcwig1`~IVLwfCs zRr$?;jx(VOq*TZ_rZpd$LA>@sF@$ny!|aZt0Rs$ftX^SaHRv!G4iuIJnaF|3;?IEu zh%_-@KFnVp`~N=;Vbosh38T1w?$=YTCruK>PyDALy!V#!6-7kL9QT5M*MGf-oh573 z175vv$H{!1f&INEv(I*p*APCCFiyAq{wYEBtesIX$)%xi5BKcl^s_(g%Fe&N4YLsZ za`J(m5Lm4vQPT1CiRO2_hVZ9zT~NkQYli)=3-50I)>;#F;Es59{dl_RFCg}@Jvho zAD$`iVuY6m8#?_%{XV=b(@B%~zq)$6oy&}r_y47c`tbBWvfhG{93Ic~d{=)?#q)n; zy>Vw8)&94x{>A?Xo@tfEwO5xb^%Qx!`r2#8GUs*f|CE#Mnft#NBMjGWo~)Ob2iNS& z?fjrUDew5wc}>D^X^#@Q<FDC+E;qfb=u^k8&aS5@C6mY?W;PswCxkOV?9PR7j3tKgwmZ1GN1MqkH zKwwlDG+PC)8d@le&!}EEKA0^Wgz$acZ|A*OIq3dkv1;V{f1`f?tetz#qkb<`{WyB6 zPq2UdO_aFV%kvq|YWO=?IS+Zqj#1IB!ooS@&cnrGpZy3xj>D1vf8r6?B9&OFi zW6CyW2A>KN4+VQn*3OkwU(o#iCH*LEK20ySdNE}3=l0K#H{V}WmUUQ$&TVo0>e&oe zv^l8xN?Fem3-UCqs(CUYRA;T_(VNlMAGdF8jLhcttg!VY-_G?pX`@zN4Ew#)jXEgt z?!;C_wt9ys+4&? zf`#t~^Dp9`ooM@F(!OuW&dhmqV_qtIpO};fxYhuqn}kY!D`RcwD3L9)t3pK;aT$EC zA1~ioV=*R|P@O>n-E5Jx-PC_DT-bXcnS=8yT#~d0waE7ezsABq0zY~AwX~+5hzE3Fl0n3S*9n50szv*EV>mUN*bjx-`w?H+n(^x62O2}#B zZxRmmST&|rZY+JyntnU*>H}PW(8)!lO}cyXRnc2#__%h*Lpvhx+|J-9g%=yM29dhPF@#x?1`+f?Bv5udM!{!+Z>SV)5E?M(>ZUv>p z1=UiUX}RjMI@=oc%Hl&!#pe^_zMwuV78nZ`|4&8KZaaw`v-wJ5Ha4^dBJuw!qI!5% zEY$FB^&?LIrHJxevwr5w<-1gw^7vmx)aX<7%AqFTtN+M)Z?0EV;9IJ82+or{S?{}i z-)gxGr#YUiH`my&IxjnM-fR8U=QTg~QK`h`OB?ksPx#u`wvNs}sjgq8#^{Xre+{Wm zd6%l781miX!b;9YLsk&Ko@_6}_pIH!Y4IZ``u+8958jaAfD}WbMG}MGyNb_KVn}@N z$A2xmhE$zbh`1xyf4yZ=au#o*y3m_&ohc(RPc^+eEC2-Ya>*aG^1FYA$GK0{RlcI4 zC_*}kyDt`-o?@G5Z|d6wpAx*ig)p6<)Eh3X?|t)=#ZP&C;1aajRbq{0s(cAAdGmdQ zei^x0d2=b@^8RKnU{wrPUAX(el@TevN^5`I6YALMXwk7wWN14&Wmav5JWs3nNEKhpXJjLQOswWjnVYty(KlM@ce17_pw7d%~=bRH2&=jFmsyz*8lm>__>j`T_y8c!L!X z5x<3_0Je zc`UO4i1nq2kJl*c)P)0b?ad;6_1Bv2`;8pw27e!HQn-D(``fD?!)9CerL3iRa+%PL zX>!98wPe8Y@9paE9t}#`BmP&aZ`>SGDERH)ZMj+gGEzLvxc=LH^agYI7AIO!+r9nW zX2Wae$_N}~>bT-o*9);q|LTDe$(JD?uZ^w9eF>O*abP{)YHYQ@^u*P-?{0dj*{}Ou zt#5uYo)ED4cZ2z_taoQZl)Kqs^=>)wSAz6cJCS*O`*MNRpLr+lcH33mY7pP8@2=e6 zY}_60X602UFQbb)b5;%8_rL87eM8}AHvVqUTHWD1`Zm7wvf=NB-k?j2g^8lvUp%YXfXg6>~7Wl*;HP4JNOO1NTzJ2vm)NBfM zl9!^9aM=v-buv_e5WvIxEmDA?KI}XVM<+qI*w|lm+#C_N0s?r68o*7xyR#87FBEC% z0QheLYZRn0^PmcYpJWS-BjY|(V1`s)*1O+^hTy#rjLC6(s{o!(Z?zz*dLoQ>mSLp< zT#H4h(=f>la3LAfM?vSM!pUXP^$#zQehl#u8vSFx>=)aqZpRNGQv$yVh zCYzj09lVlS9g+H^HtlQslfj86nfuZkW74t=X!j1MXPiv`YIF}2o1RmY?rZjNtmY0M zJ3Zxl8t+|soAj_MExqRJ5#vi*pIPZ|Po_?QGBl<6Nfj_&syj`HV(rWNq?y%!E{m53 z5ArTX_GQhpvc}TFms#j6E=55onm_&tW}1nGRz98o`gCFI>Cb)7IQu}$=bmvwo~@@n z+pK-IUG#L6^9*E8;{AmxX6SZOv6v(}s*aA~JyN&nc#&*Dt!z{yHiZcv1WSZdFhjg4 zFejTJk|V8^v)?i2;LRM_^c=amoP%CikuONLOStGz_7TTi^_#gG>A4EU*fN^(*JCJ^ z`D`t%JR`?Eqxqa-b}nRJp2<+2<#yhIxIA;YTrs&k(#?Datvs7z1)^jAx$S&%SB}$m z?y2G&iDIm*SN;(ZkV{;?YhB(2tsH}5tVc0+gjgVHUJxAje2`QSR{Y#oq>wP5Q=pVT zf9ARL%>u#@wwFsq9W5@{?^r;Hdrp-rbTKcy>!@(vJXfk1%iGX4QJ=pj!D2zsZb||4 zEH+RJ8){Ap>dMaaD)Nmha*ivMbi}@{f(B+oc*z+FH6wz( zUW|5N!j)(>NxCY7PtV9l_z34S>OTQyPAc4P6M}-p+RK+!)$m2 z4bsEFj__<=9GnlHPlW(2;1vAc&KopW0M`~hj>FEsT7ug;ghl_jRM4EilSF zq6HJ$N&%D!&~?s%9#-}U1AU4LOo4EG6n=d+s)m6H^Qt!8uHY6|hZJKQ=%@#1>`MZ6 zl!2iz;FSbMJs#uw8x_`tZN!Uk$iOHQ7eR(1Ut{FEYt`baV^EBH#f8`97(+y0iiy2- zvtWRUeg8Y#_%}}N3N{E2eab<-V!vU&$ZdL2WHT$8gHkSxl*^mEPq(WpXS?J284yPh z>LndjMn;bezdgSF*4m=}bX~bU0dq)yGWp{e8Ec|!!O4ILg% zf$?rO%vtCHHmbq88Yx!)G^3RMBM*8OuqU8@(xEB%h6-v)#&Dzib|X^=luJN#vYH&U zu%kqzVGisfoA;}$T79AEa2K|a2S|hzNMZ8vM_>+0D3JwJJE28l;pLZ4;&c#VJ2ZcY zjbSpeO|-^h3i=bF^++)m_9&Z=(t56>^?fL&n2IVUqCeqV+>R8CFzvGb%lP##Eh3Re zi!kE*4=n<+vn@>j*Z3v9(8`c9jK=?WTEu_0U@~1IJU#TuhXS5O&Yj2dx>NpjnY?~( z;rWltBuypfHP2--B=!$2BG=5t&gmaLbpA=++uyuW?(7qX*Hux4LHVEm)kD82w>NNh z>nlFrJs>;8qeXQ6AD0PMoAHbJc8@qp;>cdcczpw0=zVNEJH6`d-}NTr+E>%vk3UF^ zVK!b88|Xqp!!}dqS+S>lU>G5d|QJFW-E?%_%u) z*zqIp?LU(&8SqqBUAd735uK3UO*f-z*#|(mtZY}E1dutH?RfjE-Ioo{_%O=-NU9u( z-hasc``=nFcfr_nlzJ8$W#M*D!2RnbzQJ%9ph>g85HjC;$-?c?SvdQym~P65{L9sV z>{$6Ak4sd3FB5j0$(mZ)^~Ld~Z}Rp~N_3!$>Vva;7N12uTvSPpTuSc zo*CG(x%i|ADji$4`n^EzCG}wx-ljt;8mmGm_CR0k2#AxTnaF+5OSbd+o}cPod^o?X zKF9Gg`0L?fQ>2}Vh0?KrTNkB@-^cz-Za+ zy-?nA337_|=)t^?$x(NYZux-@mBbUgw}0u0mBPN$nm=p$tE-iUZ`uSee+T3(Mgd> z918q$x>}1fSi0UiZq6;)_;za+Tcdq@L;Uq;F!#P1ZNJK(+LwU$Jg|dLU=l`W!mTVs z^X-^(g2s!uTuaTX&9{_}PlT0i&6nKo^O|{#wC0`HV(IM9I(4-lPwN(n?*q8c zkmg(~HG0jfd}`uxD~!^ypWTV?XP)GKtW>>rCSmybuLVGBg7Cq&Z=`8uYYlY#M1}UN z+y=k*-<-ILRhH<*k8{J5zNHO+=MAy`@vawEPMKgF>vODfS$B0u!fX73AQG^?u~~Ee zEV{I|Xwn@MpSG0Oi!_5NnM023 z6CGsSRS+|jXn;s?xc%c=XHU`spZD!s(1_8NLiJuNpLG6^X=W@nBY#2ANEH}uW*}+tsh7Z(4hwgiFegGF6nEI%_4)8=>0z9s1}g)-sYO(jI_zep;K)d z2fNI!)#Jqpm4%x1du?8amtEgNAJ)c$;dQXd_1jTsO%JKZe=zAMmZcJdsJXuMAM=_MjfrpI@!{@j+ys;!O~uf=TKb?T(p48467Jn+(|_K4F;htqFc&3D;q)mhE)18p zkzq{O@+EpCQ;_W&FXR1(f4px605PP@CSB%OAm$o zRYs!Zb^K!@oO8Y(IY#3hN<>oc(hxEtHiWio50{wqI|G{r~|7_-Q+fKfa1E#f)T^rOH7KFTa6Sq9c=3wM!2Kx z$PglrdaaR}tKQ#=8@r^Ek&h$5aL0w5I#>U>t`ABHTOjk!`t5`JaDy6l>qNUbCGx@< zGv#Y1xOAL~5N@L5;yMS{ISYI%lw&_MOH?)6P|=c&R@XMhc#!z7)A+;K{0(M=c0TE1 z3UZK%D-MiaCj)wqLY67kg+e<1vfBQ8l~zr0>bd6Su$#(mNxy|u{9}(7=Y`yp30&B( zx=K7N@%Y@|WYty3tykPg$7wJ&g>`t(GI}J5*4KFQCDkOCej4v-v7US-Tg7@wRq4;G z6VD2w4<`|6DW5MFr^*j?8j*rh$J!Vk5FVrTvNfvRo`r&lN zi2(z9eWNo>gaHkXW8KMASUBMz6^S3qf6mEm2s7fzeZZ$CX&z8>f`3Fh`Xl~0`(m{ zPt_ZxOC?)y_Nz3y>9B}MkF@i{u-xEY+`bulZZ0)l#sDqT5yJy7b(0FE)*wFQbm0{qFqC%VLk)RkLgU?yIt|D1=if#lCz+ zt5LZYP?Kti30Jd}aKLQgjP~!;(w)r{gF~4&4`!YDEbr)OmKMl=435gh$9I|UIXj=A z(j^C~vx%I#z>zC`y=f+=_R=WtM6*%pfden2515?_R0laZXiUG9d#uUP(psmYc}zz) zdVqFCSwMO54!f*2DnB;Q^5cP{g)7FEs(Cf@>m|uJhS*Zk7iv3P+{2->=;%pzCyW zW$b!WvdAsAQcbs4Pd~AG*iQgi_!oTZJhCG4o*sAk@vXXqB3B$YrEE~RK<&lu-9O5V z^00HZS!XB9Py8?<7+0M0wz`m!!WO#Z@c z_`$lc|M6LsPKDo>EtgrL^}0m2x6Z`< zd>$JDj6%n? z(P5X!(5p;bH-&zliQVQr7&vBQE|N|RRp_wDOAX2XZ~%8%6;%g5{Zk!vFs$KiMpNNy zE#B60hQ|q^A;y^6b0Dk%9y3CQzNBGJ(QwAGSW^mML*wT%Lp`YcBU~mV!5&&q!l*Mb zJ!JQbRQL`{o|k~iRGxS%Xhed(+R`-AFlUsTbscEcoL8dz@b~|$U9}Pod;=CBhQKgQ2D%6pU`on@JgV0u>#83u*JG*;~4r^s# zOnAm5g44yd2VQ-i@4uH0rI%jSI63X?5MvB~u>cRCh%j_^pV7wsAm+NLDc?I8`p(C0 zmV_ZPaeqK?Uk>UN3-AJ=#_3SrE}92+F~DPkDadXTbcchxf=6_-yBDdjHpXqCEaV?T zWS9K~i8w$;KIgK`@u|x6;U@R@YQxPt7_zxP) z6OS+jVIuI*&ny_7fi>k|sBB~b6FS1~+9JTbX#B=J*A59bM)};NgbL%J%t2^`9d3mM z+^Bq*3&~J8S0(A5P4>)HsVG#BDptSM_g1^x4vpi5Nqi8eH3sr39Wlhg{o){R)8t-( zQ0)}dM;6dd#5Ga*gK3yQO1$V4H$g;(a4=isD{GaQ+C7LMPQ(&*;F-Pp1SMn+ZO|dF z;xm885+z$LeL6&3SmVKKhk4)!v)ooCYSpZ9brUyA!=QM}IWq7El$dcgVT+O`{Py-3 z=j|G)uI~@7`Yi9WYw?5o`^6#cs@m-<6@O$0g+VJ1hwFF?`7U7h$WX)E?AoZFp@+D6 z3Z|Wg**uT^L2#;71>~IW_zOFY$=5|hK0dgwFkod!srhjk_W5)v>QuCtQ|{QA^5HNn z5YP%hE!mTFz0`XO_*%?n*0)X;_D_IS^4?EW;D@jYYok~qNb z$C&85@l{ZJ)HUZJFt&~QZTs}qgPIkX3l_DuM^7JBa;|+og?&vG-0zW8qQR54-_95L zJ1MRUG(`1WT)?!^zildD_f;e?K9BqToe{TuZ1CotwPnWgqsIagMB#VSX5oEP_cJH( zxCM%nSERBo; z5f-K7D9e{z4vfNrUnB8DJ^Ar>b{*I5&Tfu>^*~{Q{>|ta#^f1hh=^MUw8BLVoHI}9 zzsxhyTAOXkKG>Gt|88bq|D6T~j7}FEE_XcF9w>_sW+ebG_ zq_M4Jw3Xhq7KLPC#_oKg!<|6Stih479ITKO3+yLz{7M**`LZRlN#(_ zMdfXf)WESid-C=lGwb|kjwHD5NgOi?;cdZoGiq6=*yg>T%7bf=47ECwarqYr3FMRNP z*V)GfgHp#C0`dtjV$~Jeqh!zIR1{c>Iej9y4xQKTQ8wt8^Bxn+e`NO!RKrDmYs+%l z_(_jhJNq{MbJlRm^81iQ6Cg{odv|Nj2UA6@6QRh(^X*T?-?)YheU%V9+H=i25vg6g z8FXuK=x8Tj?Cxb_&RK*YDC2rhcJK1%SEVmtI& zi@+PtrIuxB!Cx(VT$7{Q#AfqeTjuf3LQUJ!15KZ)(>ZrDf?Mf^= zG8LWtdoLhL?ut_0x2T>u-6Pgh5vdDP>+c)XDYx<5Y z{_7<2>N*8-U%oJ{Ktzj*$Q8ZPwF$nj;75(vb4L9;JV7p%=(g9-r2hIDU*la@p3ay3 zIO6QzE{s#H9@%$%l=AgcLHg;{`2%}hF638V*a>^lr7Wl&AKMgA*LW6vlSa+SQ0!vF zAoV|H=RWZA2{sfZ#Z!$%l?F8UQ!m>d20!tA_2<}oW#fadr~Ft&m?MF9?zNXw&e>hr z-!)=gz;l@-gxCcwoOB2Dz}ap>RyyU?9=YiIXUiY?mhKb3-qN^+x=t^g=03Bo3cee2 zY>H-Z-z$}K_t|9z`Ovcy^K+)V6zXdDc3&L}G0l47uY1lf)3<8v^7CIaPCvUy?t#Y1 zXA%%I5mVnU-&Y@@H7EQpuHM3{$@dTZ9xRE$NI`0JcXy1I7^S2iQbNFyQsT$~(x8Mi zNF$AuIy%MCps0i(EujdC?%DVEJLh@MdH#dz?40}BeP7r6^?CsgG1p!bf)7OYI9Drb z_(IA3p_DeiuXIyAQ>AtaJZI`4DSnsA5US{Z1;9+7^j!fL+p}ar&U2MH|Elv2phnn6 zr`0lN?(3h-VFBA4(862R0ozQD(dGYcOg4{|2u-!q+mx#3mfqe7QJ9@U#gHkbinXJxxf|Y4BmQTWTtZv9Nq2;%=?i8BLaeBgd6kcW~i1X#E zQ{KizYW&VstF@xG!446bX1#E-J{xI4@fB1qwxg=k#Lamx1QLR{h9Epg8M98Lf>~5wc#Gr`WzMGLuEnL98|TvDgPNYtYRE zF=Nyg;7RtVMaJ~gs;qM_10CbQLcruO=flRWWWs!PZojb2qaVCTy*&|ani@TD#q_!u z4_zy$PQEYamNFq`%w%$eQ{3ep`6;=e;}03Y5}SwA-Va?n_!)1iG5?0UQGj(>=c2%Yj-ZYZPSPk z&?0f2YO$#alaRzJ{tioL&9|}{aqKPP9N`Q`!K!LE;L9!fJUbuD!^C;0h# zsFEh9mbzX&@&nMfXZl+!6me!fceJTqeP=)4UcEs&k_J%TsU2)qv1!u4s5)$ukygm+7y?S=~ zW|VBm@^Fz-5wI*9ylbV0^?4zy?-+b7eKRLzziUN9N2y8Qa*k^e5qCpf+iQ6yaf zsLD&_ZmWGeH11*lG$LurGg)G$(`~Kt#BTbZUV9N73LIZlWN z9g2XdyB7oJ<+Sl1fo(?~p`A@s`=7FfK7#$AnmVWPj|p2`%_Nd4MR!zwj&yXqKBW2K zG~nKYo!a4W;amUZGL&HHSw=BJEp`W(QY|t{VTG-mSKLgGpUi%NdR}S{vj7r#uN5sU zl;#!1Pe1;y+O%E@UDe@EjPk04+n4E%8*HSx`wr4LAoSI%(D8~G6qEhspx9-rwU04l zq2w#0*FSm8J0Vuztc+UCLkA$GEk8NFC8?-Veu0;9JwGLDF<@=Z*?jy5v|-&WG17BC zK)3|T`FG_~v!w;%gWRCs5z7z^+Jqfl{+3IRiTAQ~W6iIGnrQRRKAj}0ewQ2j zS%2|*)6L;XQ1*m^Jsu5`2Wj271xumF(*cw~Sg3~G&x1I7|cF&g_IC?(;K~-%b z)PLdH?S5aA^cQRo0}P*2Slh+`u#i$i1@vX|!+f&4EgGfBSU@eg3=C`09h3A#>7+sB zQy}%{de%@3RI(5nN>Gv(!Y%xPS`o-GX!4N!w~q-B0TvvobdphtvnG(sTr{4{UkFH)b{6G>VflpAqVrX5 zq&D5}lbvxBkepOv_>B`a1m3G9*JZ)+V4%7fl%Ep$10^s&4B{CE_6H>J)zS!6^&PLL zljkOifcu-3_&Jzz>uH(4pHg^nsk_A*&I9_MF^^Q=UvMh!Ha zH_h1gXd&aGPkO}=;0OTJ7!9?>Bt)%4bXOo@W$_AziK#C zgeRiZ{1M~|@qZ{dPADv306!R39zjXgFcZLHN=d0*QpSNz@7 z&>vT5*a^?RVFEWA6b<8j{D*mO92ejPl}mxv*@_b*GgGo#hE+c3`-|axzmE3<4Pf+R z8U|2OTs87BET8<-~ z%SzFMt!q;v2)Ouhj(smEhY!x-L(#js$xk20g>q|)_i7$ck5Q28X^B)~-Na>dy4SAZk0vG0pnDZ!aK`(v^l|kJgo)@!*=}TdGvh?d z@L=mTZ&z%q^OQt=3l!Q>Kix6CR5(3u-_)1dc9o(Hosx||Yi}lRVxWU%2Iq`+=(J8N z*8$(HHn#UOc7{D^$@EGc?s)Q8Mev~%p13@$gEJOit$Mc_Fa444orNlGOG-KuA>s>KLT? zy;0J?w!mo8H2r3BUjwhc?0d67(_f5riF1&NBJDt{JkP1HCD*$)vzX+- zD;h5En|8+U7?taPpc!Nm-bHLe9tq_k;}#5`E*QO7FfLw5M|LQ`uu?5X$Lr8#AUjYW zpZ9Bb6j2CK9SO$TzgtSR7@MAnm`m(wU-)0kq;t{mC<%a`^@+W6dWA?o zA-w;jy~F_5a&)z!2{O3}ueN=(;P7I}r*jE8Wuv^ksPc0W`Iov2nauaee69@rK(ChH zh6k6ubl+n+^!1W&NUGoVLOM0iV%TheM|~FhcDI*Fc9c2rsm(*Cm6#^$u)leCW4SGr+3~dYp0FHa_c#Po~P0nq-#o zrja8JiKY}=SB3|2_+6K|#EQh|{3Y9Vnly3FSnvlsemj3DJ5h1k>_6SbKbgsl^Y*3a zj>>QWr>kW@TW89I`z}X!ClnnsS0X4^o`fh?JAEkm^m^06zMjc8`-PPsl6^W1>e~&r z4@>ZXL8JE&0RUXm`VG6ukE8_DShsAyID3VNte&hRXYtcv8%M4Hil*0@0{9DTFZ7Hzc!H^ zG{n?Vo`LPpUr2vnR1z=*Y2p+4$_hQvU^gYOa2V9BB}TU_p1URPt`NB^8Y;j7cC{t< z#m7nD6D`&g9a5|$I3#0vk_&coo?|(qtazrI%4|O+#cNSoXX<}~V?FS|Qar>vzsp^# z(uUWC7|Zd&Cx5wiQ3a_5QZp{bUPZA?+V?8dRGMDjocrH6Mx$$K@ ze{F)pSMGeUO_o-U_)|x-uW0O}g|hWGfFvBC7Akd;%xXxwzKh|mePf#R-v1J3qHm15 zwH4#!CUP+K-s+1?JyZyr@EDWGBb4A%8|!8Z5gNw@jgxDc0ZGB8>#KMR+r+5+1bJI> zF9I|~$i#q|b__64@KN=@!MoK7YNbl#rCv}|4IB&Mix!L=H~$7t1sHkWRp+-I`e?f` za4UNJX%wJRwA;f~DK-cJVY5wi#m0sz;WYo@WG_MfQn4OMIFH>#Hv%NwFxKi4N5og% zt0L!F&Rpv++cduxjhJ*k4e9oraxVuYvIB6puQvf@(9&*D?ZL{!(B&|RckidTB46Uv z!XT29aUz*OTwS7y7w#bz=xg}g_7dmXO}@Jbu^1;8VgUwwK~r9Ok+lhty-vOmBlsQL z;@GkQQf|`!C}gC_qw~om*MOzivBv~hey9iGla0T#+xIhAnpS0;R;A%SF2c4cA_@A4 z0E!l5F^}I_Ubu(bzjcsgA0E~fO@I}Udxi*+|J6I@0en0CbUc4_{P@bhr;Dm{ zW%+&gZr#7sAl8gAe{*}-n-5+>kCMJ`?~Ma&af1sO^t^az|A7k?=6K2Gd;0yGadl13 zC+{x>ed?2~k}-~vixF)n=eyERYtv7i#7`Gtd4YK*R5Z4L0a)9_#MRK{b43cAmyEZlbbSzkiC^&Yz;AG@oOCbH@ z198vIpu)-@%;veRl#yO#GLph_ZvzUHrWIb@o=*=7iP)4hr^t0dnu$%UL-;iA+~5ZP zn438xmo&Yd^E^*J*u1GAdOYY(NUgxzlP9L%XVZTejhxX7o^-zqzJ064gq9*4jWd!6 z(!arP&@6Q(^b=VcZ1e35&~fk1m7zCOx=W zy1sayEDT7jkGCb+%qcuqKxzbX8+-yR+xI~|B=&Od3GOOC?}{`HU3f)tmnkcKtU35$ zRtCb#8EWPQ1KHKaNw$C~zS~FmT#4y97C!u4gNrEU?g$Y4g_ym%`zrVa{nZXdyhT`o z3L5Cr;ws=1j(hOC*5FS^X?Vyb#pCZ`j1L{9{us(vjr-z%V*pFmQ;`I zym38XzNVG)Jo?q|oMP`(IR)v>s}LWGrPTS6od_Gl%e#hgvV6k#k>>at)+6dvbzDiJ zg-=B-aUsa-g*%QzZ?A^)?#HhudSDggTIo|!@o`a(U!%DXY9Yt>>Kp3(OYkxKE3GKS z83A)Ean`_d{bSE zfqE1lYt)klw^j91v&%3)s!!{z8aP`23o#qWc_{Xtjp%vRy&Ay;E0$Ky!>>|7rr-02 zuOtSCgC%%(2^IYQhnJ^J;(7IV+WjBVSCd-QTP{@ViSOG(zkP0EtCzs`2JUz8i&Hu} zbyu3i-1R%YzFKT_=!=G{cD3|}o^FQRIy+=dS7^=#i(G8Kdn>PR>EfO9J%#H| zp3$_=4VV_v!L*ME5CN4VnogHzv}y;AVYObYC8I7lZk6A)#=JA}j7B=3llO)gm`j}o znIYXU-AromJvB0z%dpIOW87i}s`s~#wVoyJYY4-;Avpbt5^sXybyT39Sgh25Ia};? zP%7iv#K7>)E3MWk%_YMaICCI?S5IWckef!`GMF327K=Xz7n1pwXE5h!#0&MY2={VV zolgF-G~ug1H>)8NJ2#?y$!?V;=GpeJJ)f^#Y4E~M4Hu5&YMXfZylZ#1y4;Y&ye zv5J@X>6(9kBjg%LS|)jRHRHP4Jgpot!gW?pBQ*H5O63!ER*Hgg(s>4l$8{x*0@0Uj zQuDPVcL#Dae_mpq>GdCDT=%qUND}Xvdy!FezV5W)-bKzN;%`1`j+sw~IyMRsW&eQLlc{(f&x|w8%;z=cr{qU2T7uAzkre z!74%O;{gM$=5}Kat@^2y@IwtEV%gg3>Z052y`505N_7*-W9*(*wKmJf@Q6ff!VJ{) z1M?{`etbHZA(?wvm~Ry~pyDQ2#W%31Sn7SaK)mq}i36r6{) zxX?{*jnLsC+UeR7{lZ~X=t7Is>Qsu_F*K{K-w$hQwIEuyM3t2bVuAL%8qwS4tTGA4 z3Q(*V_6P7}<74=a42_4)YDa6T&|PHLL&~Y8+P(o$;QJH~87z^#e z0FWneAxZy`n>L_!i1Swv51;ffZMqlCrwgC3&{8`gwlpP-ipLR2@kh&5UaqUlQeIV( zRBRW;dAttIxwOb7%FhLg$QPuKtaT3>y6&P)M4*!4R}yxlEL0;eg%rMfVrgK ze09U5EWSmU@LWKlz3!b~VEgk|a@h)1ucin9>3sSEsOqGPAz9%$I>jfz03PLP_3cHI2bLWb%&&#?OT%vk z|Csl~$klqe#?t7;GFp6h+~o%n&?5T5cP|$NP0YvNJ1*5%RTda1uelgLzwMQO7VmZI z`|3nK{bIPRpMz;QWnq48P>nJ8ozWADg)+;d7kaPv8`6y%9&5DGy&~xN2vCXT zQ+rh1zK{omh_APObnv0gm9NUoyphF4#ONp@%f)!H+$X_WDk8wdH&?PUQC-ZHwt)$= zKUrzIaG)1Rx%%2n2H_zufU^00r(PMwCAz@tg%bTRo88q>tuF3k)nKna zo#x-4WwhES?jQ7V@P&?Ua-Vw5gGUFNAOmc!rqF0KFNOAzauUg@&1pKe~V(#QZ0mZjFt8>sq)RH5H$L{;mcni z@N@3N2lB0}MSr4~I&Kz}2SoO+B{Npt%mWyy1K@|!CzXT} z+oa3s9wrKCoZ@l@w!Praa#>LqP-IS>PU9%vRtnPoVT_b_)<)!Z5A&;(dwq1WyKDD3FmG9G z&&aBG?%74)^E+bHcWi;2tubsl^}ifm54!0`?zD5hPH`Zd46(+dM?^Q3H~zD2ojr|^ z%ad$6a5^uXD^M7%R!x&Wj4$M@e3MlB{f?R7PB15c>ArT+siFzDYg)!0=b^ z$It(W7tL`;-Yi?P41tjUUBTDmmsCxRvbT{ z8`~5tQLwj_%6PY83QYN*i5i?HWlrJ#`79<{7nhV4`H+vt{>44N9C%? z;P2erSSxKuzvaEwVT@;gt z)K*2W$>r*BN@+)ola?|_cRi#kHlXaQ&59k801U{Upj5AK*D+adK3$k+Vd$E5zO}Oc z%q|Y@tPM~@34yd^FoQDALvkP;KyIm&7El%j{Ow^YXNZ!I(kTj#+f6RPn{qeXaJLSi z)QjR6SF|}hhFBZ5S-t|1_!xCVZJFyhcDeDJ3o#0ez%q6qVyzn6K06XYk;kPfWtSA*MpsYgswxJ6Q|{RAFK0A{VrY{sJNm{z5_B}ht$NTm>tO!Sx{_M6F1Pw z(n15wVrCj^1A^B>5{&~2p#usDYmFJT>)zApmuAe1};ohR&DlFnL?q870K1O_{1~AG&Ja<}vVyqo$xlx7UHH zE>4$*o_dka{KP^y0H^@V4x-n4H;|<8H4epC^4EO~?u}EA&oT3(MMFGnU-0sar+8&o z`>Z&>v_SzD+*o{plEVO_RFwVPH_8>f#F`dm>Y%KsyR?_iBl{?4WM zT@fANqjZ2Q^^l=h+=7@k05EU_!qWDm=rZxvfkZp`q8R3Wa%rz2S+9b(OrG(^wJCI{ z7GXgu?i-1G?1`xv)Qedh$xEJpbKWt{T}UN!bbjRad0)GcYt~xhtvk!_U7A`rEb0qa z(<$D0O@3PjB~w%?4@2E7(-yNHlBv=Wvjs|~>MY5Z%VSV7>sV&y+FhHym!?AAjkUu) z&l4Cw`iJarw>j(fvrE0pv>aKF{OoP?)!RtPDc=GmuXQu3oGX%vJDq1=Zn{2ip!831 zELLhjh8-odCiKs9l~~^&VaC|(k5~Xzdz6PEwQt7A;B(9Cr+V%koh_e ziPXlsukLU+6bc`-{a&R88zfcxyf$hmwj?$j@9r&xJER!{6~+f|T%$B$v53@Ik<`uB ziiU!^gWhANR{4(xthx20La*&bo74US>>h{)Ynz{$Ac|r|`G&q}*A67I4ho3r@8+r^ z7OX~`0a{|6#)mJr8)jS@O-OHApvKcE-|>>wW;#^h64OLtE{6T%lhFqLkZ~`|1L0JV zbkdg{`KEadaXAyPEyrE&2UKGK%0oh^@s+oQS`!AFlNN{A#=5c-;54Qru0LwxF;0_>NdL zca6N)-uv4yv%P|!Oxqp*j*MV~LZ2h=ztVOBSRZK?iOYS(GGhmYv4cWoI*H2u1^h!# zDdR-)kIXU?K7E!r-tqs*S8=>Ap+?#i%XP*~^LG6GzbW{?h&dMX9gy~FQWuIrPR9z? zN(d2R53)(4DRE99HuZ($zzd1X#0Olnaq6i+m89lR|NKvAn$^m6wf=9t`~SH434jj( z5ZOEc03!na|89QV|KTyE0bB{MW&Y=4x&v@z6HQ?!@t6}iLRR$GKc#sM9l6*Bw z4@G)$JJYOxJ=Ugc?!0~T|GD|QIaT&+tW1vQxu5qwHt}-p}QM6 zWTMb!65lgJSDBZ{CF^)GW6-pu*56ph+a2S9#)`y~d2`L{A1hnwY8RCm>etu2d>Owl zYb&!=$S1z$p!J1cWUGl3e9g7h?{Ui@ipg?_8_zCm<}*;lF}T;Sub3xlk$ZoArgyK~ zJ;(Q@o#%7YuDWj}Q5QWgO0kgrn#B78LB?s$8iqR+v`#w7NOBjin&kh>V@BAz%TyAc zd0C_;PG++Ew{RommG9N>*EhD=3kiLgAkNvFRV<|tBsXFz?ltsZ>>uC~A}Ug9jFUYM zTCpH}o=6_X?Q1hZzfUBC$Ubl6-@$b2ptVAV4$E;LgimCiQ4>At*|jvL=AZKDV|=x? zLpI6(e1+S)_j0GtCHp>SJB5GEIDK{g$&yNncnx~dhzkT&y$g6`6&qU@sFeaqcv$i?f zTy#dseg_@+0H?m=Mw`V3VeQO_*r|0(ziPR1%M5r^V4kHG-L#SIa-L(Z@z>qdW4Zs| z<$GcGl>r?X{N_9>BoqXCJK5-BVh-p)YfP$Ij!!?;n-#l!&#(-93JzGZ{kqc*{uj zI`$zq^)lU@O7;5^C86WLuTiPUO6n)JfQZP?oBZhlYykFJnf`J{lp_z6o~3YVqtFmx z)we~8ox^EnK-f@q!IgDW%@+cY0#f-|NJ(mZBHJ)BA++&3gPvim^qEBhOS}u4 zN(7Y78J`^OJ^=YsIZQ`PMI?O~;7%M}A7f3y$Gi7?8@x6CtO+Vl05p=peKAAq@x77OO)@^c>4yoXHim)fBIJFd;S?iOcX>jrDB9R(p; z)1u_QGs$L-3f*%~HwA65K0UzEj3E-e-8U#)E)8TlEZ}TXZZ{NQV{)IRQ@9sUY}r1J z9pvTl@@O8t&hoSyWAV=cu!>Z-KL!AqtB&X*H;BV{9J6m`2G1o8lg%ZR9&<`-J`JG3 zjK{E*1OVZSTU-v#sKj_AwYS(tvWf|WvFapQD!!bnzc!ZH9-HJp4WMe-g~}#ng1>n9 z1rYX^Io2|X5Czz#oM zlPwxTJ670O+ZlnEDfn}ivTWgF?%1}x>u-(9n26mNk_rkqqi?stQ%os3HVivi0I4?#u{5DFMYN<>i% z#Yc>u+DztjU_To7?Ah>ICveKJa|g}i%8Z>+OY_^6FjD-?%Q0v_IT++zE7Iez&mHv_kb zJmGz$A6AS>(;s@yE-?M6oC9}8Vs9Z54%OYf5>WLf&c3f<$Gge(9pbH6EZPgEC>thWK zeuwuDlv_;1~Xp%^fdQNHG1%rZeZ?YiiH=g5b4j-mE4 zBoW1B?a>B*zHB}Fg{LSv;(Dtid^hych?+eh#{7CbloEoh=sQ~SQseg}k}I{U|2t)G zo?yvq>27okI?Jk31CU87wrGJiPj=e2c}3HPFFAg$P$-R8abU1uwz3Vb7&Pb(61?9MS~<$=3!=2gL+s?BVJ(jY zEkfzXG<$Q6ZdK4Kty2;+p*knDBtYcpGObe!bWsYpo5_9X3_NUs7@b5M;2}{Yae^}~ zN(!1G8&c6FP)Pv$wm|%lP^TYQgdttytKh;jT04vxdI+x60(WWyp5K5^JBQbw(|Ssg zI@i=k>%fl~aDgId0t@v&LF=Gtr^%CR6{R>P zk``>iJ_5YiNj-xA5s{FBT<&l@kTglWMF69T0Be#x>A}h4PwT*$GqgCGO7Cgh0uOb} ziCgQOdkBoq-N28*FvbUCV}b@9X;CO-LS&ItoJw3u=%fc_aN`!JNsEIb0shGuXpaEd zp3vSegAkE4Di|8ly}UCX*!3b5n(wzljw6>(fs+MPj|XzJQO6Q)vj$Q}q2Zkj@G}Ih zbR7IsCT;IJwAq<&21!fX34Pfj@L^r-s)hQ(nPj>?Z+BD`RdCNG}?xD~e@@)07(4A+#D>_+=URki1 ztR`r%^1W>GRYsSZZ0JBXY%g1h*d_2PG}|RRTh0!lkc?9@l2s|Np1Kg$>_KRUr=VD6 z?zc&NaG^@eQZ%Z|g+I;uyqtTL?Sau!{4qyy#q4C$lYM73+kQ{#U3;7#9)dwbWA8z~ zF##GBoczDN$K?+~D2@E1(y)jS+B&;l_ z5JFe*aIcV;S4%^IGRh4ql<-_@6&)&^+n=2Orhx4c19hHO(MVk&N!34Fk#p!O$6%*U z5JvQp)J&{;Q{Hmq#B<+|-kI4~#cwL|mJ7s-l%IW?$W4}g#HS+|FH@kmDv>-_V&u(- z3M~1nCvI--+H@u0Q2CVqf)?+b%dndBk=1C9qI4;qn?zS9G58vt(VU);O2&}4H)ze= z>`aCAfP6tW=F4b4JThRp^Eob#`W)Q0LKBLlVNA*s5>S_-ryf}MBV3i-tmA!wAw{IA zn@JA>Cb<~{_QUcHpHTWBC>0QoKb}yXlB`%5Fa{7F)+0bNhJ+(vxh)jWGb02hD?iup ziu?wPBd8qkcWMBMEqb=%Qj}wvKwC7`M`z$}K5VQEY@f*sRCxe?DC3KS2CY9MxuO2; zRVts*`VdK0V`mx#0?jQn_^lR&G#>6Ql}N;ZTM>W@9Q>~or5_S}u~p+IlRHduJ`ece zA}SKAZNd5O{5%7%77%dj*c^R1qSHDTgv5Ge5AuB zjw*7Gh=0*i>xD5}(=zeP1b4>4i2!hHCby*)E&Wl(NcFjNvWXq+J{mOe*y4Y81NbayjcdW}xc&Fg%bs2F64s|7zl zv`MhF)3H@B36@az7K~I<)^b%0W?;>m7&~s0NL;RW=xPn5v4KJ5<0^T5bLm z-l3v5YRJCzr@-NfuP0!ufQMHSfqx}kJI+b^+^8bE1UGOf-h_jz`gB+w4sxG8w@RC~xrbb^9kCR-0* zo4}@9_c3`WETE@=s`uYKFY2t@q@kC$;)RJbG$yO`*)6xE1A!J%SM@-zm!e&LR6H+6 zp(H|;VWPf96cL5(>1FG;V(?A>(=+p2NiUG}I57Gla8g}}vX=fj)z|SvdjG_WzC?;Q z@jBv_nWjNyV3T!d6fzzf&>hv#UGKm@sQ+e%N_k_ssFf?mZb?|17z#Y>6T2yyguy~67iLI@*snf<}8Oc=%@VP zQfOu)pO=`wk7G3%x+y7+SHA+z^)dARAY6AnUU?9niHj3BP>bq!HE%^!BF1~!R6#C4 za&D-e6li19BZ%bq$^;!E0FhWA3IN$WyPE)ke@6iHr4Y_R6BN|t3Cwr=JVAQvKxtlR z-#U%gPoVz)w0q=wNEiVPYTa)7K^1JiI=NO|+IBbqlpY`>(DWeypAfW40P4r5G>iCR z&?)sP5>bP^1B!tps=f_Blq!1iw8fsfEd^}rOxHOMdXA(OC8Xs85@ZIl*ua9*|F~H;#`Fh_nKDfJK0fM7)&hrPU z|BmR#-`zj}e&aoX<#2LsicT#8P#a1bb^mhx;=M}Xs^6@xu#HESDjpHq|%aRT~phRnx?1aKpNaAHCe{^2%vsrKhqd6@DtHR-9?;GRr5>5^E=rzK5VGXOB#Y zxc2};Bm3?BJ73;X(Rw|bas1a#ezi>zuw^}izm>Y#Jf$)7aeK>d3rq&Ly1StFeB@Ge z=O4q8Y`Qd6%+~t-w}C{OeysmDi_eHejn`C%Xx!;db}OR z`K3g0&rrs1U+UYF=ndzlFM)olv?P3;Wq>JQK+jH{er*R=62r|D1*4l!u#%VH-H0&)Y2yI7BZm2J zg=A=8q=)sfl>|`#uVWgdzANg{$)h}+wUHa!4tDIzZM`$ zNc$QB8o)iA4o5Eq7E!f$m|~-@*){%OH-BU8`_F0*_sKz-)yH29vx%2rp?kokh9D37 zq?i{e?_O}f`bV)bJDQlStY39~Ff#N$Tb7ub8SYl|i~3q4iKo6t2BNsSv2KI4bk&^gqeF`8lid7ViM0Wo zY8gm9jibC~7778Kl&3K~mtR_4Q7zYf<+WTzJY=8gTJKa%DOgK)!?lCu|C_JxB>H`M z^GN>SwoP;Y2OiPT2Y_}j-j_~&{93AAACi2BRQMdRKCa6?Wc)0rp~s)NL_%@LZicm4 zx0t*|cHr}}C=KB&YS7YKb*FzeyqoC;SXs}7h3C~Ntb_S!3TrgF2*pnwoBK@mc*^6- z4gJ$0rOrb;QLN`>ogg*{1K^kBJDc3%^x_C_madiky}M#^(;E6p(c}U)>cNJnzSW(+3!y$^H6DVxK?oQ6*(_m z3375hGZH9z9JsJqnRs#7ZhMSpXl7&OZucyz{xA^2=T#kZ!Ikl^pr%;lpeLo&?b$#J zr&}58#I)6WQ;ha!_G^(wN#5Y6Jde(dMY*ysvjnkT9SwrE56;L|Y-3){e={FL$YJUm z2p*S?A#7D6%ApMH(F;th1#m$ z${Q^B)O<|iJe@ivC;RZz!*7os-i(Bjcubt&o3JnPfvP_jojf(18Ud@5Om_VhpFI73 zw+cocz54bh^7~t;X4L7J;M=I9jhM0GbZcVL&z&zBK1~g&v-P){b!pAmqP}gseM}@m zodIAaEplc87OIOR5|-(J9h;dvX7nmYX#*aE6 z$KewuD`dA$jU$-RghfxpapU=_&4akrTh25g-6+lrOpJg#m)zQz4(#qWi~CBfNH1gS zK6pLxFM|u?3#E~hcW&`#=>LFLhPo1W`B|Q40$J~BcM15n;5>ERZoU_y6{|-*L4Do) z^NgNatDgt%3riHs_d-Qk%w|0PQOWdeKp#?{&PJwXz@EITr&Tn_ zQ3j=z_SOrpoz3y$a}SG!8R+%SJoy<3z9~UQZJ*ziecj^vYezfdN4VrOwpOUxzp>Zm z7umSt=?Wzc9^G*uINKT z#|m^K#w>t0T0e>6;^pHCLt{j?!GPPrAGuBWM%y*u(I*%{ z<5pX45Z;AWT5FIEecI-sFd=*{BIW`&mW-K8yZfVekSM%RXxix8Uf&irqC2HD6SlL< z@Z!o4c~Mqva*blMN02jAw(sJhOK(Zl z5-W#gZ|k!ypyPkm#!>4z56TXcK^0(Rv~N|0=u!bsqS;CG9YIHR7~s?aAg3|WB3JB~ zCFhJEV6!at@u;jZuyg)d@o~#XQ@^~~qOpv5f}k&EVg(WCaAW-r1JOk2;Y4y#2)*4e zIT+QA-umzHVV_*3|47H*x(0$BNQSXzvuSQCShi`y0pV)tIG^}f=v7&wQiU|RvGWk* z#jb(ObQUFhN8Alw!x7~-Sa8Ili>@MKP`QJMOo(P2AX#=rqWG85RQp-ko_!BIuV!y> zue{)@fZ>_QTT*|EeB*j)8=Dh|1}hbD1BTXp1%E1g zZ!LXny}_`UAH$42&2T?)77itl7uKT_n8UW1^qq}qULtYgE6yAyLVnUICmEutu5Htm zZ4VAd#~iwH9LQL7H1rp5_yz-^ePw1szGbkxQNx_N*f?pgjnoj3b7n!2Z1GWq3-sC8 zT^*^Pa4a7+o7WI0N(iEWJ^3ugx5@RLAdjqy0Y-MNGAohl6PT7X6R82T3L-()*#aI7 z*!W*RxLOFVR zbP?rIT`g@qm(kT}e}VtQr2wFpM$@D)@KxTFVzFVOFHf^xKv6oakHW|UQdt?dm{itB z*#r>jcK{nAeo})9B^xOMqU2xHF2|U2GgHISw^=?mw#`gmJONY*KQ8(NQ}51T}?ZhRHqgR?-e2dtKglMCQL6{Mu~$ zcj!*p?FuoKn+bdKmHU5^Qh2DEVnvVL-a^F6L_hT1yPscc*=X68w#$ZRo#Ta-7as-T zX- dHHdzTJcvn=S&TFRA%S~zS*j#Cw73PgFk#Tsjsb_J_@;FqgVpi&_}_e^`6-cPRgd@Bf_DHgnEcv({J=g~k$7RAZN|QHoGa+1Eyk zrKGV9vW+N28c|WIA<0&ab?ipTuEr9wH6=pIJ@5DDx{mMl{o%TQy8nPV4i4uy&e!Ah zd_Eu7lPzh=G~diPdzM9@guHI`O(!z!kRaT8FgA?`C;7DIi^4-LTSiv2ZY4FfCihu| z{j?;{B3!Um>dIF9DeI?&=5Ab>GZM%yVbFLDac2B>N@iP5(UHi@?6aHfw4bq2@@-Yx zt>SsjJBO7MBicL?+U}aQ7df`4_8rMzIKteY7;bDFbhqGyzi~OGtun{DaZmK}tmTtR_1d4uc2sq;Q=1T{1UmvWY>unTYS`Kg6)2Fht)Ass zJ}b4V*6YkEvSD6sFQGrmz?XX56!ufHX^kjV&9N2KQQcW&{ca(LFLrgaqBY2OX1gJM zd@Qr|tm`8>K6-RDE?A%6Wc#6x+^rTq*p{Rdo--!e(R^O!zDdJ@sYhEopA-mw?ThYm<XN|1X8cxA0wQ=#Qi%w^AT4l}LPH1B zPD@KhhQ)^wkh5f(CrLiy3U$K0R$RAiF1+G-HC;Ih1t6ZQuTdeM4e*{nNdI(+q0PV zbT?E1A8kf;Iv*AXq?~w>_i?F{b0<-3OO7C*NGS}u*gAKQ#q6h!bV zd78yBay(?9bo33Mn0u#b(t}VnXQ-x+h?Dav?L`5LuTc5f6F4hcJsK8SOj8UKkS9Xb z$k8g)RA`&AMUlhh6nf#qY|AkRAHg_)7^M@2bd-LXMks?LUIL5(fC!KJBjtdPmSRQW zsd1ior2in)l>@y}f!KQa%1Y$biLyFjLIS@}5hoo6ZFx4LFBlU^h?fCwJ$w?s8+g9A zIL57{viNtRTz1;Qwf8L_<9E&)v3JY9N|C>$;L_!Jd%~!@JkZiB8zM%Hd%uq)e-Mfz zLdyoD2B-s3aWsG)?T}47fwBwWK%X3k?h8Ylz#+K@M-mjy-1+`M1i#N`jk?0Z)W%8Z z^+NQkqPumWthkYMPP8H=Muv%5XQc5IqL<2}_RdD*Iq?O)rHro8f%(pbu(Ma2x{m{K zp(?ba1QMA5(~*t~8QtrHAB(zf>BB<$;AsLeUTRqMBIq}pdJ2QKa0!e$_&ZFC>k3L)(ZBS_mk@Si%Lc;%&u22L5u+f?n zmEC7Nk1n+e(Y~x5FZP~0tlp?la#3cOBDn52wc_bfR{Y}h(x_HyhdcI*`>ep_S(=G0 zRF5m{9qBcn_t6FI{%7aiimsW5qRjQwD&JulX2Z6;pwj8n@@!lB#ORbB8x)CFGL znf~tc{ZQ*-m?kmai2(Kg2|qd;>wrblmMq-`X|CCEOpmWjMOvVB$0`1`OBLeu;HbQ& zx5h!F4=+YV5UxH54PVxj5eLbJufj10nYHszEcwfNKMYmi!%KcD=(RhfVc z6pXf^S~(GXGq*1^y!CFeSnNBw_;Ff+OIwWzbt9+LHQ&3WW^p)OYp|AB z4H`ASz5txag)RtkEELDyMug@oC4`k(vcr^rNvM((4qTqoDcqBgBC8+8QQ1~k7moY- zkCO1vGy979fq#^Q*GX>FNXXx>{bLti2SsjB_G}KksNw;eSAWdg$yXDn-}04&OSzR- zQra$wjJ~<|yWs}x>F=!~`?p5x^RpkGp6z-2=JzjVhEO5u-P=F+BB(=edfpvo?}eWe zy?X;LMd;mmCBlmvjnY!Fiosf_an46r`6$MmcKh!boR*LoiXVgXnMhQ7R6KFB|N4X} z@JXIMk!X#4u`NJvP|Nq!7&NJS=VlA(78^S=Z+)^V$-CrupirXZa>tqc zok>j~!pY9qMz*QqhIv}zhXk?PN_07_C;HRJm;0O+bGS+xz3Nt072U?llPA0OBZi#y zhuk8QwENI0TLDM*ay974ynjW zzA)8gxK1taJ+RKZvvT@=sLVzvwAzOxSC%JA{VF#;J=PX>X}{!WVTH%ShgSTcy4~*FN}f)fj&+lzw|>WLw9~s^$*g%Dk_& zd5=Fed!_w#So|Fpd1pblZ-3J7#$%he8i;I9+PMnd1;$1I7lj?!sX!E{v24`9yB6n*85x|7_>(=I3AJR?7(OZ&o z(0f{UdlSt)6c0SAx~DO&1@Pa+^|QlT4j{iLX`+-@q<-Y+Y&`ZGqVsCV(06pQX zb4A6i`$A+!u5D0o#!U~#7x1FBB$6lrA)AB=UQ{24m*1&0a|gwT+8&+LP-M(LypUjd ze?kx@4-vFbfSaTNR;Jd_9Cx5bJH_MBcRJb4Bdg|Ena`n_wCY|HT2P}EVUU_0Ak*wE zJg|k(A4T4twpG;1t?s5OG~K(r8K08MqXB~nJHFwfiE0IfQAH*=3tsG)m@G-@2P{3$ z@o`pW0_iZQVyX{KLo?OsuhrEI5(Qam!xpWn!xV(0CzP?A$KgF__)*lv5&4(C01Mw+1c$5T80D?8qyLG(RrJH zMtAz7h{u<2nPS|H+;P)5vopUAdEWvAL97|3SWE>v?}P z;fki)VL8{)yN(9FZ#07*4xb#*N`776%m|E28uFw$z7~RLUV`0q)f_Zsezi>uAmET{@r#pJm#s3+!I3Od0)!2l4LbB4m1^5{zP!q_~Qu% ze+$xfLM(R(+B2iKb#jr0YxUSvexOd{9K0L0U06cEpa}9=^OdbN{Z;%yHQNcX+_fgP zGt4;g+0=`I&ayY718#cTPRc%ZZdxXnB^hX_9Y%#U>4W9;_)@ZbZDI4?la7a}!X8S7 z>uoz*f&qG``@Xm@xMMEm2?d>Bv9p?9T#8@{PlROzNk-g(; z%jNVH#fgZ~@b_&p-ye(EO_{n^$&U^4&ap!t+6ltmAI`6c&N1UI494_is(!iyBd5WX zo%;$^uh8ujyw-F!%q)*Isv&Bnt0(mURLK`b5|EhF!(8Rol84dJ3aIs}r90sq=x)d|{%k{RT zIYCiqNi?xYRO^hO%8moA(el90Z+f{#U)5AsQ{&!tmsIqykF$U76ge-<97alg5@Bsm zElctt%yfHOUd!xw^J8zbry@4%TF@bFc>M5eKJ z=tQponHbm*r^(!j4STuu7gUW{O+5T)YI18!=+TWLC$&`p>XyOPQ7&q8m+D_{>e?=< zP!;v;dn)L2U9gxMbxg6-DT*}{$(z}ASQY!lAX>#aS~VwHTswtVwo^(rR=u?b0bR!9t2~WQ@4xOVl$(u(C|a_dU8q z-}3m&oeeAj1~ax2(0a!cVF9RmVoZ7{3PRzBAC=uMT_rTA&_5tA;p6#+vM{`EKmi4U z7t8b3F;Wx>d@k;3!uGqk?b($}b~I zTlvNowHBP<786m(R~;}NUVgmjd@G5AS9(oQE;2_2q+?vj0;6Q~sFy)!l#+wDG}Iw+ zLmbHcg&ZSdelp<)h$809{jmDv+Yb^&-@_Xz$U)X6evmMTA85jYKLK>4C0GR*%SL&f zR|-cR6Sl>pTu7MrWDMVc=gff)0{WIjNn<9$w@TE6f!M2a%KkjufQY?ikh0l}8Dzou zk;6YM)Es~w!wD+m&>6be;w?t#&m#2}$}QoqJ30#Bgk{VG2VKa5TjOE+LWqz{2wQsk zCKFCq6t(%dvzAUf6n^XPIpu4d;1MRGm?vUOLg|vwE-d&62`#ol(!Zq!20Oa_Ky@%t zE;+Z=gmyIZAO<)=S2BEqi+rGhcBS4~p$ZVV$YVg3R21wyptedRJ4e$(a&G^MlKW0U z9S(s{{Iee}+(8k!>Z#0O#c6noj$sA0vUX-1$sx)B7nwp^I7BfS{egvE_uBom?e5w8`Lujt#-GB=dCKrZ!*vQqqoN=-4?s|{?v{_ zLCi1-J*G{ZT%^7H{H`%Ue9xIqLhxZ0UH5PK$6u=NfD~PS zugyz+rL7E8OZd*3im$Qv9PgdEzA^adc&U55ex+~b!bp1HFwUWLJU>vp4q{|Lm=g5vYgJ)iSDg>C7-!3u_MdqpZ6}*wnr|R(kze6 z-`0p4js4pg@%_8!+T5bSXO}lWSKLUO3t0@JmEh&=UUTTaqp{HHZJ(+B2&fehWR;Pr z3o(nyq2jSk7RC}M6BNm3@sK{x2XI!C_8$%H7-GE8Wm7;MS#Bl@{rEDT$ovUw!9t80 zdp!3)Z@ujY_8#XX!lE)_rJzU_8bq5<9sxcjL{B9^<9f~ZL1MMB27`hgnFspwj#~pi z$seW@P8|?Bb!gFJzk|s;I7i6L9R4y{G^}47NPytjg+y;SL(ssiDtjg*;j7T#b`y{F zRO19BU@Zla7Ig#m!->hpTNT?_vQWt_Q5&6tzh0(RLd{Y*)RF-UAX>eEjpv$)^Q%oKwTBO2|XfmBR1@hn)B zdo%n2+|^h`!T;7FI3!B`pr6LLl5snd5hw#;43UA@6Vms^Is~WGZd?mk?(r-_JGMwO z^TdfUTxV0#8?_M_w(^J9kCx!tS8L#S+@B?+q;ay@4yEdd#vM zKdF(Vp8d3F$qc=@=a;7DiuwKOA9|Wq@B=ITQaig=2C!Fxbp|~QVp}eHKE8+bb$qg@ zZ_E>qp`GrqM=_9}+*^x=uIRCtAMk`c=Rw6YQ_>r>mGcAj(u5m^AZLz`_D5Eq&s7S(v3?o1($u33btZc9ed!ek<0~EDb zlW<%05FBnId5@%qd@E}Uu5)kGM;+)GY>=X;WuB*e4L~O55-WK$w$=Fl1FTMUE(M_q zeR%Pde1d)?K2=Gh%%MZ9DKe8Pd|C)D3iq`HG-jJ`{VbH$7X)NDINbh|#<-7RoivXnK%cLo+9=x6}*#qm-eN;IGjV%dpJ;OASi0N|@of~|+$s`z~bf+bH=X${v& zPLH{L|fwGTpRlxSxz@PD#3#T=7$ z6WKv7($82|tqN#)@?0h}+~Hwl)p!>5&MvtZ&jM1p5?wONmvg4~U2wfTrE0#UXZaV- zLZaQB)piJMq0J#e2Guv&SQxf28fWZUc--!Q`OBxy=qVZDy0b>;Z7m}#cLC^rIl`ai zD#v{<6y7FwNfHZEqawz^RaX6>Bz=eES*|$r+(Tde^g2%=58GU4mpk^o$Ko}9>b<6H zM7_|%GKlP2*=>HY)`=k zg=2Kufu?lUljPf_Ne52t%j5|MP)wg#iux;bTs^>_D3u(YMV^WK(U1MH59o4jIa`)~ zv_yh`R`|kKQD?_G5ewx`J!^9p3LA_VG~Eu#j>F~|qk~aWyK+CCJrx-CE@&`HD4g1& zQ*_QHeCv^lOpglf0HZ9%-MLYQb>eBD!!fiU;v8OjH6l3$SzI+E%DhWXTQ zf5C$4-x*K#%Pf5M{)<%vhasz36qrh`rCgjsrh{usXl=w@&PtU+CV|RR+r5Va<^h6ZT9KPKVumV0fchI4@vGkO* zInn6;u^)n7%O$SH6UdaPgaurVN^lq|QNXiJTF*J*tH}&L=6GE;u55Bx^!&#-ZPeEm zY6<({hC`YRqr?avev*6a_QBbyl7lnZ5JRdsVAj$Z$Q3m`lDO~w9uYHv$`a7{2Nf>7 zT)MSg$6UvQsz=&x+eo>MBBDCDDf`=p_NGO#^${kZyRDR>6JBx1B&Y2G`Xup$>hOJm z%)K8xu6Sh7Vtgvt|8<>>@;?Y2pPj4PW)ofVBYvqjA3`-vu`(D|19|Y3h6yqmMQ9Lw4W)KYvsWBa0I<|G~ z^^KquKc2!!#6ZNSGR2J&r$&4Hui9D2yTH=p(Y%wF5?W8K>V(;=T@kL4Rv*v6<(l4G zz4I>O>9tQO_g`!unZj8bG(kZBZ>PTvCmj0vbUeIk`Hd{Ysk*Z4`qekbP38K-TDD#Z zb*p}T8M!=4Li;|?z}{`l^(_C(HZ%(su(s;izEO;e7LNt}lSd7{TZZoyj{vt_Y0kPj z@)*sgAkVUpeoRCt6+QMiv(HUlzz;yAg4J~y=j+_iz#blI&=S?gLyb^F zXX3AZ-L-p83V2tDeaY5*CIviXLL=yK2w);qg!wJ%QOC2qrHm_?^oChcS1m$9Utbjt zLwe((hdGD{3Rn~h_Oj7>^DY zW}w1RG0}#q>aH(E5ptL;77(y{*M1R z)x?GhAEYAqLgpqc=*dJFv0%+yEdqd;V8=iE6)htU90}D0O|A)gC>T)DC0N)i7QT{h zSucJdf$P98D4;)HyJeMV(~8+3Mhrg=9Hw3$c#q^i4wirj8!ys^=a+y`%>dM$C9;Qv zx<-ce;6z$@!jc?h9TxWOk#GlBK$D54QXr8`)G<1|pMf;Qg1S^##WDC873RuUObezA zoxD8ft$;o!w@+{f7XkBA!SYWUy<1q6J_Xr6vFEoo`~*pWt9bAhA#q_gAlo~{FI1Dl zLhF)5KC#ddc(^qY`j9TnZ!~?!!>{q^Hh}N~URalbUI&ooI7|Q@Zc2nQse*<)a2N}- zq9CoQP!0taO~*W7z!pgGa1QvC9j~FjTU0dT569?Ixnmt;=RDQHQUb^!qR>jX4kD_D zvkO`jW;qmaL?&(IBzmA+fG=v#p@0b-=sPlBRx4ZwzveRP;LK zABCPS6V<{?OQ67JSSVc%@-bDgl8QFRBUiA(2LRB3D!7i#)+A(qP`fr@bxrw_qf)tA z2Ug_f)(_;mwlEj3G6FcfVP7+Nozv5wqfr%_d?jy`1AT!7^EuEQroaxma2W^MNC8c; z$XcxMM;!bZR^Fc;a~}}Y#i7Umqz#WW!d`bF!kG-g2Q0J!57`qA`-DRr284Ub_ey8t zhjJ(*`!CW8H1>-rx>L+xA9mfxA#(UpdlK9VCy0tqSyI1nNBX`@F`7&g&NV}wFGlKf z5a+2PY%KD{5b`-z#FPp<#zQ^C!_JanK|H@x445|-*@hDdpyv-#kO#1EI~imd59HTL zM<}RM6hs?Kb@$h3&9=zhHI$^NUEd+T9?>#4HVP55sXVo!AtcS59eRFi5Z%pIO_FsU zX2snn!}w0}FY$5bi$h(ku1?@f`t@mJPM0Uhk3(-hjwXgt*CH)Wg+m2(Gef0OMc44A z#c_U^_>Buv@u80%qw9#soj$=I7}tpgS2WfxJ+8SGo%KY!_+EtHQ;uwrqrj!^tWquZ ztAwL%h-fLNu1F@m%5>IV=fi93Gsrp;2 zGw&EMn|3`H_haxZlZU+THO)Ze=Hl92oIz*Dr4 zjqDFUEKU*2kpw146&BYjta2-?Yb$I=D(rt(kmO#OC+!I28-{?pqx4rUwXfVpUY+^< ziY!-o-muccwep-Ct(+$-_zTNs?5)?$SR|kL`U|BxJGc67ZFSyAb^h;ahFr}9!HJMP%jR9>sC%B`*WUA;u*cYz31xZSU6Ynxo_TKwyH zM82p-_>%;ooauJuTHSlYH+}QfJd#XThe3}Gx_7>MnhX|h{eF|R=WU+N+k5_R?-)s}DRnfzy&=hXZzq>nv9;bp_dPK+L#7QzZM}8gZ54JghkM>|D z0dNxE$i+3njowah8gk~PxD0R{S6^#Wk9sPanv1fC@V4^6S|rOUbXFg<1!p*D9=0(s z3f(|zH1~h~h1D>F1HaQzO}Iv-rO`iG=V76gNMygko!59 z87wT31NyUenv&&C;Ne?La17^a%0#T=VOeIoAsi819(ZmHe9VFNaM9m*AeYP1M%Prj ziQjfWxKiLTYFJIAtnq2qGzIjt6R-t9R}NAikLsYpR*1->Jj~l@1d$9sMF!0Q%fuGU zbtz!KDq@`iOSTd?%E1J>qV-8|TL6A!0673L?5pgbNeF#dXYU)+{~~C01ZN z0O5gp5eEGobR5Oz_FNV1gC>JheA395uZDvq0Ge7NGQ~O#;k5BfX_;j70vXj0@LL$@ z3#0rHq;NMK#TTp%bHNTe%0ULjM~?5w0^v;5IInS6>IBcINhTQ8hMPq8R^l$AD9<}? zd>1CXWd)wYERfqj&>Bin7#sbqUWdxkXgY)>=SsVt^3EG$h z2INhLyqQ)=M+F7-gakDOX<0k=i3v)v_>2A7w*}Apy{F)aD$xfi|-FD_MKVmk6awgUmX7X<|oz> zLKQxotIuAlZ$Gn?n>!IPDfEGPa)jTW`Mbp1{taO}T0zl!V?>ziUi$I&8^1mC&Hmf! zbL@Y?ynm-~Mu1hI0P^~OgLx)XyZ%3zSIEx*nBJ66WbXK93g?MiTlvF|EXA$*|G+%L zCH@r7KN$c%%;RSOihKWsdF>S?A0Cqmt?&I$m^bi(-1r}u_tNLXlhYmid7*z{p3Q$v z;f!^>=EFQH?4Kzd=JOwYq6qm%`AnlulxU~X_m^L*B7Vq- z&L)1Ii!$iX%OA@+l|(`2U<2GKsl>>8z9N>c)98ASRVYNF}Gi?uht0tQmHx7+oF)8fo|q730pV_x!2&f=o~{4}TU;Y?B?VTUb`4#}{!AyxgDh9~p(;_b`3^zJY1Uazuhnb5kt_-1o;{@Xi1 zK!eAEZwuhn3+~eJ$`f|qBd&e>eDo3WmqGXM&C=eb-&^EE7rwJ`@fttaKYlLT;0hD= zC#YmtDU~(dIOm?SPp2nfxr;DUy4-E_Yhk&EDA09j-*A-}pms_2ed~LOo*1AK(U#oR z=jar;^3mD**-F1#=;F$No9l-zg^((p_B{~J`KcW=IQ|GAE;4nwPcJ6$*I3xhvtRuV zSGUA~?U1VI)qoo)$5zt}0{T+tm2Zn{lXTOd6#Ys#GcKUPj*Jz;G+*b8gd9;=pDoII zzA{ynhZf+M7L4RP;Mx;FtVjW!G#;85w6RoY)188YREYvo$9TcA=z}P|W@6r+rklj4 zC=bK2H%=G+jGbRDK*;)3K-j(`0K^o~V==6NV0pbmW*O8oSxaI5m;P*~9SySC<@@Wr zEK1MpC2egnRZ_?J#&sU5Fv(jdHi_&sB6t zE5*f8hg6(<<12;Wp|JfAphD0Cwi@&(nbP6?H+vD1=81A236^4WK&s%y7_X1K7_|DV zDGuo%_X0S>HPTHmhO<)buH9AG)2nY(vxvRu4_DnS`g%`ltkJ1pMg2#?siX?B^eC5x zX9j}-fU=DI14UGfb_|&^E7L@#ZRU?#pe@=YFQTX#M!K&bL>v{!xfrt>JQn*%?Y(SD zMZJD%6ilv@E50(@u#=$}tIWSa?(=CBy2zwC4*~*)gUtw=@HcG*akP{X|`O@ifAe8f=gAZg2*cKVh9xeK6eu!HR5a{+3B#A;_VZY*;lG+@OyyDz~x;2hgr$c0Q`A+&z^(l^>4AiIM zmMQz;+DvGG4FBT)kg6H|y3Ch5DFIOiQ=I67okXF9wJ7<8oa8`!fye~2K4z7Ibm-)w zKT&Zfo*p3Wzj*u%S&)VQo1S(x!35`~nRQHJf6CPb2(ppD-hPWo6Fk!(Su) z@VQy`5@N#bJLu`Z)9yt?Nl5#2&9A4EdEfdthMzaef4wd5dJ!p5H@pR1djs8$zwvJV z^ZxD5YEuf78v=fx1q60Bh}mC=8Sy`tf7!_g2bLvR+D_z4ro2)>TElA{Mx`2g&04A2 z$=({1vLDu3^t-iF`L4F@pR44{iNQB-yhmS_UT?LsFTa)5Ii+;E4RdqgMx76qg(t-EYsg9I1U{ z1XB76rPX-#XeJ)KI;gyT0e8YMAP^Ha+qj*(HMraG`MtadT!g|p*U}J`&!c${D^xMe zfCTC9cQ@CoBn?W@KeRE|=7%(7FmDKks9y(??9a!ZDQ# zA)9LULBPvKxv$GB_ZKMJVH1AU?G(4H-5>o4C9XChJ~-PT%-{-}U5>&Kh~@x=8l%-o z6ga*J0`wK&)cId661lOQSGt z;XhL_WcV6eCI}0p=1(F?VJ*8(;vDOCKOT775-|H%IBi}T;C2ip8Z{rvf~BZPVKBP z;t!$eoU?S;r2GmFah`)2=0LkS7#k8?{Nf>BhFmiim?6PWV}TV4$fs-TER;GAwL}c$ zZMzY3G6EVLae*ziVF0d>gw2_bD>&o@I_47~pi6=41Bi71{)&aU#=n;)p&=Y}Cy|eX zc6=ludL4Frpn*FCqoXRr;l|NBi^Ui;@EZr+Lk|A&=%3T!3K`YFLA!)S&GB5vDPTXp zVb25WNFt*o%tsQch6OGV18oO=l%)5*_#VF0?>Wf;7x1Cii^0m1;4%^86`H{12C!cR ze!+uMTQ3u~TY}r2NBITY{VyagnC>5t!mRMAE)9+-2 zJng1h!Oc=a(z)rI%vP}u%cL5DS7lhz?)0Qu>Etv0NpG{o%GHu9d~UvQPF4&~Zf(8E z?^>vgC-+$0JgMsYUQq1(%lMDQNzX!3va(ZlDC$?~drpU?&St01Re3zONO(g{nHUtE z@(JlanYJ31ww9f?QI)ninD%!q4e(8iA58sn^4$00lrd83d=(uvM4z{!=aR6bFuJUE z8W^4~os(|epZWuf5<8NfcU!BAD-sP^o$q%7cP}xicB!4 z!a?M(th!Zj27l+dSGaW;7_%NZ$GG!C74%|*a}+)!04uz}865u{9S|_&ainAygdrTX zYcDBWGQ>A~j)V^6AU%#F?~`+S`vaU`|8w%WGjyS@`ND6f5VqvaOWE`dDR7<7gD$ds<3jN2c4 zSKjaFKY#CGBG}aeUOEM5@GzGEqzQoHBf7)Jgh@f34q`V8OG#b7IDJn z6oeWH)k1-N;$duXf^0nO1W$OKB%;qjZ!wX!9LyCa+=dG6p$nR@FyHVneh|Zn1Lbdw zCh{;PJlHx5o5oL9db! z7kHSDSYZfWfK7&Ru}@t9VSN(16A$ZV2ogzA`b+^PU8tD{5~+e4+>%9NslZ&R)pT+1 zhSr|~$$^{T6c(e86`q0|e*wU1`8smFQ9{tcD#_5rjOr!a>ZR(^)^gv8I`~#~yj$(?{K3#qdr~jdi-vw@J}X3L zUaQv_ZO~e1n8jn>P=q>7Q2G&#guKQBb&W=&jfXZHiSkV*0VqKS^ePv$%4@Q&YqA|} zvfpeX$u}P}YIa;`;?ZmVFoj%k*ap)Ep>!04D-Y`xiayrt71838*Wwq@T+)Gg!jd~P zihZt(%_TSaN3g^4*jG!zRdPmf9k$!J2{ta|S<0qGv?gpet?~!BB6)0Vfqqn)?U zuugUrAebsInx4mYN^ZJ0+H~Kx?Ll2rMCsuilxVI|`;)qMTetSd$?cY#O$B*P8M!q! zqivm!0<7d~=2=Z8h8?AK>{W96i&1RJLR+_L&70DyVmaXAESNJC@SPjL$-Ccmr?aj! zz)1s>DU$OY=xSR4>qhhI-I|{-myNywAlv|iXL%3-35L6Q#GfdaHw+G9=+u;&XY%JKs5FWu|Y&{$P2BQ|4An}24 zFBTAQ2lE3u4vjU59_$lz=;OF)9it+YZXqE6{0l{3KNTKE*Ky(~2PO`-S+Yd zs5Z=pg<I0z8~VZyd}V8Tb_ z0UUN*54%VNAuJSxh}`7abtL9Lnx$x~tiD@pPY)5d(rhHO@d# zSdXCRFuwSx?qCFe-0s*Gar?b~yWm`G?Km{O-ANuJDJ{Z0j_LtaSX{7|-oMD<(_w)G>Yi*5Oj~&K3{|I>iCUne z6qL}?<~Z4gT{`z4H&|&b8)k+h;b6W-h<&t{DBgG1|WTtfQv1r~TyIk-E;p zL!Yysw?66|HSPNPbo>0X(ytcae0k*j$I-dVXJ)EC&D+_|%cbsFAb)K-^WRfAZx=d0 zEp&G;EYLA;aU;>MzlJQ$zXcc8QqVuS@fX(?x!ac}4lPZcS(=Vqn$2IDJF^rKAyR9P z9bHH_!U*plAs!SW zJ0E9Sieyj_{L{RfSk8mp(WohHRkj7NH* z*07ZOH|BDt^CMS>&g~l|EqmvlHi<#+2&5bAx)+c$RPaFk*d&TSL4PDg|D$6@0pBxa zI{UbfB#zz}X|J2Ik6pBtp1jXrr{-Z{CfS&Vb3ayd=b@}g;ch;a6h|9;v@)I3{Yc7a z*XfYZP1(cD7Vdi07j~;tH&O?N*6sFDP7rm$#-O8K4bK(r)B2%E+V%FY>_mDYm)wZ5 z)i6ct4;#Vk_URY#$F9f7iY@x=^D%ZhgoOuodJGd?wB8J$)2?kL?QW}6`ow=KH@bMj z8s||edclRYaSFXxg$_xqb{SKjBJWnf0swk_VO zB*!209%R^cKkVe7#a%O_q1xk=OSU3xH^nBS+9GIpW+D8L>0oGNFKjib4s#!-e;6Fo0d61j;iq_5VX z&*a6~FGR`Bv5IFbU;m6TS(Zn1I;Op^m=qt7*hYx_qgLm0TOLi z$lVW&lU#|WSnt-D5?o2jd5?0(mjvXFL-m+*^hq&wUgI8%dTS>Y(=^qI!W}T22oWi! z5rdM@uZhw)>{}>j5aawrCl>8*HJLTc6W3SuN(u6DmwnH$Fn~wF^=4U;n{<;_VtxDZ zDbYJSuO8olIM(4x+nE)$n?qxaC!1G)2#)mgX7W^yvUfIu^(2JU-*a06>a7oMH(6~X zn5%T3LbC2mFSO$hwxInTVM1+`cu}o_n+|$G47J^}>OP5_*dWh>x!rXAIY!(WI0P$s zrCA5Rd*_MdjKb|J!d5RTQJOyI#Gi1d)f4L9i%RMN&%@$0&OhPgTYLyuIR8a0K#^2< z(aM}~P)!SG<@l_#&%G@Jsa;ia^P`nAVE=`5lZ!|IoPESk{PA%vtVZ!)kE#BP^uqRb z8c=l(^gZG4R(J%>jK1=sy?pXUK)Tb@@{D^zHFwT$>lkb~uv$h>DfQT8Gt|DjUuKYL zy3Kz4<`2{>rjz2y{Y}Qh?{9@ve6f1w=hQLWU$gq^nWR8~x6R1#)^Pu;2?{$K{{0l^ z{La^Nlz2+K&FF;euc}tN=NGd&MyC%LRL?OjEuc}zjP=#mOQiUa*BxU^SAW%V(J#Vk z<*489{;Hc@e10$hBFIlR)i{X?7)Adc-57SNhE% zRaCVM2ZP-fwL)9w7-fcD$rIZLLTmRRwKdPm-wyJ~s`|6Ibl^^>hx`YFw&By3gj*VJ z8yjow`}&{9CrS5x6026XsMLuWDo8`t#AbF~|Hd$2s#p&hzYCiEf0Lq2EsOV20GU) zzPV)wH-2Ss*)Q|xg{pLnPqUw!$U%a5MO`V_M0_@wM!Bb3P8G2wA%Y*S-i1*RTs`l( z4h)iGV15V1zmek}&-85|;zWfC!aH7CI`f~O)to55vOSlPkMLV$@lZ3~O7_E1x{$&e z+7qqeM@-OJqzXl}w5q3kx|noFcen-}z28RlMk#N{((d8FrJc3tE`4{-$+1ZMPdv^O zvcgi*huiG3f=@ ziTCW!ZMUSAI zi+dsS7h!^Kt2Q_2ahJ|-hD@Dw*({>+qN&FZQ!gmXp@hS@&=JDL7x&333wTo{(jy3C zj$)<}5@`OPLXon?jt6Zc1-ByPwjxbO!x5&DN5}YN&{3KhPJ?PuYQp>)8BxdTBHOIE z)7PR%@sS)`;m)H`+OC&O(9z$xZg9BXYSEA8jNp!O#s2&iZ6Zs({X4WgA|{mp+7=7j zqX9>B%r1EIoUpjHFf4%-3nyai>SBE2qn28LB0BPv0o9_I&nq}i%NuATfW8D?b5k)K z5&j4tAIU~XZ89#v30(eE-k4zVGIE^vR=iwB+^U;as}hO~wKkZ@XLZ7f@9#=w#6?n2 zkos^GC9X#T13=gVns7<+JrQB2HmWszl{Y5drn;3|l>|;gZ=vDv7Vhpva0i63;0bId zz*0(ZPrm;h2COpv9enS^g|9O_hvQBJGh={TzZv!x8^-J9OOo> zaq%Tfu;7U;r@w;-K9DC7J7dpUeqp3SdMpG zS=f&o4$4sCCTM}FWVE|17(>T57$?A6fDfABINr}%isoJSFK}^#?)jBX1b$L*J5*Hq zDuk(Cgou*@CU%o?X`==5W7@l zBoix7 zas+US_~xXST!YloR49O3y}@=t?rI@gI8m;vfOZQqlfVNdNrvEI73*Z-Qw0Mfynpqh zx@Hs+_yp_>*ByOc7F;Gh7)KJNeIWp8nQnVfAjZOO5_xP|xaM4d3I^r}i+d7EDjB?N zBK8Uu4I#BQY%03)l((aH_S`?|1Nwz*N{MJhKILAlieUCP7a$*mj&dL*xa3+Eun7Zp zi5F9ZoY*X(^a)@{!_mpCKv`BIl!+bmF1&${pQyu$nE=H!o=y6#e|}%uv+*Ds7cftj zFq6v~?+I~;Bz|K8yRhA`b(8`69xcq2tOZE%HP+ zGDK^la1M+|K8`K-p7YC_S{Ul}>noV;JWo0<5gQBs$bNO;**hxbBMah09m{gw+4$HJaAI zhEV-b?Xy*4B`!12q6YV+wBC6c7r$Ol%#Sgge2KC1e%gjTm*)KobX=z1smcueWSfi= z@i66T6gX91?eI#^+_r9c-wm;u{acJ1Z%GdcSjE@vucd%_7k zJimns27pf>%#gul-hzZP5%<^x@C=yHP>O_8Q7#}%Srw6L2vC~Z1Iw##hISsxZyb~N zg0H^is6<&!U{y$9LNYf;e#Zy_G$D3)RSF>n~}0|7J!#U6;m*2q9(Z_n@L9%+0Bt*reA9lH$coMu92 z8?ZycbP;h=OkB%lV48vbN%o$n0l&x?XaEVP;2J2HFJ)cRP1Vhq{u#g8F&zjO1SZ}y z6_;_ZjDbyJ!?kYan#;g*odh%8*L$m;*BzNRAkpZ3reyvb6?w;p*^HEiyV-Sh*Kc`_ zYdT7?6$TGZS0Bdi`{FmGYx(kV&d`3T>Zr*f-R4?SA3nrl*v!99Gi+E4-feC<45?8> zrG~AhhjJVS&s*ZH!$#EgMjZM^B)^TI6b39MM%^q&4>Z^9QbxTM@Ly=989E;Woj%?S z`xyNA+Z(4#OkAHH+hvGmON>8xJW=XDUTW4{g#DP(Jn>R*GW2=r=iLdwYOK0> zvdQwJr;~LZ7XNs9vb}Gz)a*iduz5zeKtsZvb$V*{d(Q-?^rwHO6#sYv{?p^=&PTVW zacnFwy3$I?8Nm1ezip;&g-t~;)Gi1leD)RSdp^C`Shme#rcI_T>sDv<_N}c>?eE29 zd}D5~N-#d3=kB$el?SeoXlsO!(S%PArbk_ul4WK;W!Ve7O}Mi{8km4_QD|I2Eu3@) z>&ImPeHp;+d7Ay6dUn4Z_Gti?D`~zPwqAXo<%Sr6F+AQukEzUX6<2FgTVuTx4EZ>O2m;{kIPr6JP(9pY3`GUrI9E5GKkAh~b>6{-x9FV)@hn<_3LTbJ0iSTg>8r8#QN{h`KM1^bmrk}Sd%>i$g#gKTgni-z$|BQTx!m2=22fl zy|&!<_`jlD9?%@@dMm;36BB@B^&`7DGX^T`5my_nTTcU=V7%XnB96BmT}cEWD25d2RvkdbtN@f%Qn2;BIDnj-8tRD5zk#J2i_StmX&l$Dwt z1uA@>WBLG(#L^vVFN6J#SBtdz{r+o4A%J-d9Q_MG2|sjGxNv#yNggn?xYc!Rrswl6 zCVA$@%J}XJc0oct%<4m~isq+@)&iLik9C88iub3Q0G|wE1tgsPf~{ta6D9P*cNY^c zR*>Kpxkj01znY~fIK7S*IX4e&r}zKVo_TKJbm|w5_$scmvhRb}zU`%c?3ZeeHvHFS zEin5&1@64oo^@f_`h`<-cn8n+=l>a(6ga#+1DVpIPSR{-agh z6!LuFMeJUHs_z73v-WyXs11pbD#I@4IBjiGzI4>5_55+z{`vCz#!Tr__g3K2h}TW? z*N%U_m$a1M;oATAsakk>NS;Za^WLq^mFYKepFe%tEy!*E+<8XaVS8(DkIh9SZ7gOl z?EmMdAyI#DQ{@baYkxGcWqa-)8DZ41cA^sJ!8wK@z=bKzb5@qFG^$tMC7u-6|CD0H zcQHCZ#-4)|a8m4Q=o!iI@cN_1`|mv977G)N{*Zehz$iseA_V#Jl+1;nPmMt*6+rS} z5vDX>y4EPk;BX$2&(zL)?uTyS;$^Sbqu>5n=nYxqHS45%)>hN90|7B1dhx8$gp zOVQ)_1260(0%2C{?$No*xZEdyXJqn1x9~EVHysGMShD z&Kwr>|Epgjb|cZQ@Ui;~`^}tdH@7u1VO!&)Ic23DH!Kfy9$L*a82BozZ{Jh>DEB5} z%OpX*dP{~^vxeIx7e*nsCBXvGgm`x|yO~(n1OtB8NYV8GOtN&QGaeRsdX`6QbjwRb z>IK?>c4x4Clsy^{A{IECSSwgzd=9}H$%469ab!!lw7%oK{hlR7y~UyVY+8y#)~)yG zJ%)y4<^3%V7ySwUNnx=sa*>#DHzm2e?FZKsip%y?Q^?or3!5}K*K>YI%S~vx>q=-I zIyeSnpj*%i-;};QgjLft_CF*a_eqk0;i%c-Dbxdtu0JaUu7AD**{oSo$H>dwNiyGO z?|*ewr;3=Wm&AqBLxK|&EpEN;3+5;`5J;UsvvOchl;n6PK3qHu3%U2cVE_C`&eiG8 zN=2cNKXK=V?I#e6GJ8btA913d3)5^k|gW zE;W{BD|_#pEz9LlwlQM*eEHy#|DJ6(6O<0&P2y+ly&>9e|m zv8eqWk?57`jwHGf&w))M_lfon<6Ak&X982=mL)mg-0w?@wx4q&U<-=X`Vf*=m8B2Z z&4LF}9TIVYIi>dJ1dU%FP672V*@4`$@{zpv5Ak1;<+3Y0oi=#k7oW$Gl`kjH)tuG4 zbKc|VLYtY*=*xiOhaQT}PZHd?Kcv4wdJjpei-KYv8ih5 zYdw_p@nE~B`m1`&D>qfL3lH$CcGUCv+#1SRF!ItKv9qMK`Q|uqqyMkRVHWls_7CjM z|28)=jN6s`cW(55JP!YZerGax#ZvwY{XU!j5Jvx2{eRK#kjnl4qTg5ie*bWSDTGEJ zaq2$LO1Ojcdf;pJ>d5KvUlc#?RbO+Bi0Kqmy!WeeyX502L49SSCG3zFj33(ib3VZHeFFIYlH1O4} zC)cvEW@WPOdZ*;`#8HyXIvpx8L>_kyN0zB*Ul)PoC~-o-{}YG-?~iCL5+3CMWn zZVzE$;ct2;X>TI0yC>@G`$syg$HK#o#*N*cqZ+pz?AL8sBzMZaR1JBS zy6123)qtZd_(_Jyy;HeLXU7nL_S9n4185Fza6jAq9okazN=^yw(WZcn^Ie^@85U|^ zyE-w!v{ea0?L1=8DX86d zNWB*%?Q1(a+p9w3B;J#SpTB-m=!3L-f=WM(uSISE8a%1gNS=#1Vp_fihpC>3 z?5%K*-?#R;{;N?FsUvcM$reYQn%okOUTxv%Q-b>)=*ILQ$vrAiFRBI7p$XE+YMVJMqNysjPK7Xd3N|F3ud6;9I>7P1QQXQ%vja_) zXV8)Ub#9z5gJWNi88H^|rNYItx#6P5+>uQOe9RHnuvj6g7?LXNLvV(DTE%4aUKKSR zYeT)FAr8lX6%aZaS;x_Wlyf;Ks1l44Ok3Tj^T3U-fEbHpA2O2apW+P_`8KM0+%?7N zsG;b?u{PP<0E`iMP&oH}V&WzvMuW`5-%fkC^NEJ>g3fQQC(%k|sn}ypUxW^F#M;IR z=gV?Os|dBb)JhwRd%Hx5vPvY>k8_r7zVFl>+$wnbz$3v&`2N|Lz*x0%cmaBF;P?sU z1CrZm`i1baQ^0{l8NLhRXOt~1-W)iTr&ynd(K1YRoSBoflgqt0aLte;YAU&Zw98>< zpFu^F`_W%pJ#JTIGg!QNhZ4FhEK1#U;Eb4~Hsig%iJco^F@XWCOgGJgXA98y4aN%G6rz+3?u}sQ3 zAFTPS)V8nGAZ~&;`{u*aQzNCeojd1)d#lUNom@J--z=$SFzSi_1#ibLvyXRi7fLU_ zDmDD*YF&0fHUDSEW!*3N%wT4L#0sPI>~gnlyupS2&1i2e^b)hiSh{H4+r*QDiMz>g zXT+!-)my?Rg;%>vd`FXX`Nc-xrTnT)ZkF>9@@2xHG)(aiSl(!kA<^1PpAfQMvPq*UY<1;%OJ;IDYveW z3aha8=uYywB@mkG?G!+sIswGlEF?F zeAtXqSk(UMnuOJHklfUi)g_AhyPIfqCtKcB&RjVsGdVK3da~x_w(-Tl#>R553m+R& zjlTy?Iy`x9Ec$sV>_@mxb=R8U@2CFXeni&VOn3R!whD!>W`3_N81@K$^Xzu}Df1~7 zf8Ou6TVZQK=Nup7f7CUeIR2e>e`@+Wdn@j#Lio?{M#D}}Cb(w+n-u@eKjV-3cCU^9 zKQLSL7oFOm?xOQQ>2GwtvI8Ed|6}QMzk6!Y=2f*45>mN?QIycjw_JWS;%*{a=vO_j z*39T9`9^IN#J*C}(f$)ytTHUIyNDu~{kDkQMI4F3wVVj$Snu&}ehz1FotSV1UUwga zZNRv`tl*R8`)Bw6geLRaV!(qJ(<}Jr+sAkg+>Z{e)!FqtW@Q&7ZS|&LzdiU~du|{x zcx+ap2;Iq=Oa|Vb{`)-RPVu}=?s}}};r)HoR@-k830YnVVwZ-sYK9~bFC`awiMiH436o$^{EN^qaFz@4Bq@{lt z6sSggA%NGYxSd}YIa-6Cex+^{g0S|c4}n?~CwV~_gcFN*V2|Tv4M|`J2_j0JVt-M2pGER0 z;jSp14*4h|qHdFH0`Aawx=)^0MetmN^CFYchoVsTXm)GVVA+h@YC;YquHfgtFW!EO z3r@G%UJc%C!R@vHt89uB1|8zybrIN#Yw8T-eRauWfv1=j@3LTH_QRS{fA# zK)Q-8J?JJXv(-7M_L6@5y>h{zbf}nT?UeJ&3U-6+YkFV*SKNzDn~OpIE$`2_36t?& z{#$Bo7T5S4^sA$i)rshemSA{|G1j z_J%kyn)uDj(Kr0XIf0)=c7k_(%R6sPZCTr9J~}T;L&v0c#9*BY?bcT9%3}P7AK6~k zptX3W-MwM!<&%7MJ7wQpUQbOQvKDASK{zpS6C(h-1K|7x;MV{nd~nW5!PMUuk5}H@ z49<{0b+CnimhmC$&AV!moY^gyAu76pj4RH>>=AvtT(}x&fMCiURd=a9Ciav*W<(Hj z&^~W^Wz<$#8dmO>l;Q4Bd29z0SoUbw|Q8$tEPXTPyW})}tId9$hks z5#})=p!Q(M*H5Thav-$E)oE2=*(NgQ6kXOQtG7N2;mQwf7MurTF1R3(1Ds^y6N-}H z4;ODZRc()8FL@+&fBnOAAzpB4P+AsLXCQYT31SviXPF*wD)J1|!(){CLL*DVp1xj^ ziyrY=poVUe0j-SCU9x1~flE6i9E<3?(1NSo)<;wxe^?*B-{zge6o?C%v#r3vQMEM3-{iD=jZAP46y!?ps3OE-T8idUhl+_EcGJ zmOq`B@yS!byT=-Y8XDa0ne{jb{dH+s1SC@Z4$hnK$&mn6=+mYu+ajqlx zo`2eT4r~XX6ewreznB+&&L(*c-+J-w){AwzRZ2(sigv}=PVnm^vU6q?J3Hl@Ss-RC z@+Y)<;FpVs30c^q=yYZ%%E6z9Hx0XN-DQ)6(W!LqN>{6|a2YRKY6ItP#HPc`;pVh- zK`N)n%U>*O>V);}y5KG@`k_Te#L}&cos2!^b78gvZO<1!w(9=C3a5VGYPSV@8-#^Y zx%`PdnB}6>BEaY*uuXZ%zif?mxEXb*`1ZZjvBR%kEx0ubz7)P(apEq1+*EkGl)+Z3 z25fSSegTo`P6g_|e)lsAIDMTUyO;e``#I53}d z3BYtN$3k|du3vS3c3!*zYfup!uU#CLqntSMqdD+0@iSHEkjr~CUGmyK$mucVa!jYO z63)OpSw#%>V0&O35d{&93P1BuVVI#6D_ir~NA~;4| zj&To$IXmR;(qi_gh+bOI1?CewgfEA_N{I}pLlcSE2MZ^oR7$b0uN5NK1a8P6q20E` zv^P6hRX8i^WRZx618rZX?m-=`0V+<5*nA=l6%SFq&o1`6APP9S9F^Qmcih{b`7l<) z?=gW6msU7S9^%ahZ-a-V!6#*^L_AFO=;Mer0Vzk?*B(WLl9re}MztX5NJHhZe5@RW z>zoayfQ}dRs*IqR`w^nFXVO>XRTt@k-IMtGr4z_u(&j;?E;C0aJYHwA|w%1HECR<^hYwTE1!RTyXg0^ziAhA=Brl z&7FqMIE`5A4O&^AKKFdkW_rZ=@qiun`0LhT(Y}!*ebrCq2X<({E@S9`|ENUY$VG)g z*96cmRH}l>eJNoew0m@&GEndiV3Ujd!vXO`czjIcmgR^@-`FpT({ZV>c?PCnvnbN!yhT|MlYu#XyC`hs5p9Jza?2@MZ~T$} zxJh$Zz!G>WRQOWgsJ|Yle^~G|AJ+0+%^|cvw*-uL$vuNx;O0bpR81|MF?wAr*nc`c z>G7mEJ8XLV`MCbzxMSbwctVi34)PNNThxK$-V)IFjIU>cy@q&a(`GWBO5>EnEuH=n@vf zo*b^1#m%3Aq{G~~j@H8oZ(^ll3O9@VpO2w(2Xvf1a?i9NX2cM!oXSeg1Va_WW&Ke7 zPoYjTdyJ|v0!pF{tIyzddIuy{Y89*ksz<>=Rq%K|w(2rSFg)+Q3RGUG;y6977CxKt z7#t%Goi_nVEbR!_xxD6y{1zk%-<)aza_km(U(V+Zz@1VDz01cgD@>_5k8!bc$1%xN zID?mWq8X9zeW&tcf@ZA}&G8!tYK5h`M_cH8g%NauE-7+K|E;l=ffJ0%72qTISmem` zbX?-%%rxjw-d6KS_lF5sO2URqErcq7dOQOAU4o7&f+p&x%}xoLSi4+(@pY;UuqmQ? zlWxcP&!fU;Cw~uN*BUwrSA-reN9+GH=>$L`U#QbJ%>;f>Fgq^kQG39lgK=ya_RA`e z^S7GgDR#(3=H-Ih9u?O^37!JcMB~gm_a-Zy#|jD;(fDRJS4C8>@Rv{Vp(fLUdJ{o5 zWAF?hNT@#J)buT(X|>xyckX8AS@sB7dE{@oe$j4B*y%Yn zY%Jw*sJH)m>~xKG-p_`|i%Zh$MtK`Yu5K);u9>knQu;PXE92ygzpUP@!aJ~0{=Xb6 z#yH?z{Fcy*jWJ0~v*n@3&11fAHvK+tUSV%i_W!-&%l;MWcyXtOn;&%A6&pYGHU4(-e5EuScdIump6%zeuN*}`?LCcDe3Bo zZ#KKrBBMD3A0#t||71=P!SJDQfy2eWuIs(3z310Ih2Fj}B&j}O^#1dm9iR9<)gS)e zmTJRfgj=Y5N{7?+bh;H+An#}fO|VNBofkSry?$C_+ELv)PSpN=LbycYuinJXH4j&f zF{6V08Yb6d6V*RoFnn^yA$)A^S__JPkJOBIpUp)0EAiZp2&jwOXCIjI^oscLf@iU> z7uEVy+1ocVV|La;+(b1AUoNQKmVRle*86^q=ONYJ6l;4s1??6zQD@Las?PT*5U*R5 z-G5iRm-$Xed$A3xrRTej(fC4U-^FTZQNQ%5>bo7p*`BwrnzNbKt%CNcK2$~=x#d%3 z0h7gCKP}5m!k^YWe{+3Ar>bGX^7@OVk40A}a=ygL&>tul7I~RfI^Wi{zmAho@GHP+ zjgk=w{ObJ4z3M(W0SJKEq|AY{)jh|9R}USqJmx@H?2VtO4tR^D+Zq~SZ08CsmEhIH zcRJ?P%nnVDMHfS8XF_TRPWQn}OF<)8zG*G&`{&+0^eEjPWAw^1nu;8+-!PqdcPRgt-@!v9wnm?hk?ssuML?17 z?LH^z0RvTa=_el~4Tlf5AKI?QzZG%lrRQQN{njxm3oTk_G}O^4-5_hVTj_uv8s5oA z&N4rg0`8oq!ZCz2mj{RV^@R(zjMO}- z@mu)TKw}b0iEYn}y+n8-{3N55%^1d#ARV!~cdN>-3u2^20oEA&PWF>)v^?n`=M%64 z+2-;N%r8GL?;L(GEh6D~i&48!N+p%Klrf(lC6%))@QX1d2lGWW%@(gN}?WE|TIMZ=# z1!Y!z?EQt5HiLvFryP_3aCeI6{uonTyDnSHdwJ z+u4e|kK@nojVIqLSHkjkRGo;N;}oo31Dw#Ue07@df|Td-HqlG;)JP!D@u4`&?+bs$ zBLDHYgYoZC#m9yhIRzW?lVDA4T#pxHZoUp2?7egZM)#hQH#W;jxmT*Qc}h;OE+4qD z_*URVyqwZgtD%t=PeSRK+?hDU>%z?v(P?I+`qm6CU=bm7a;#l5%xB~+)r+q*e(8MN zbsmkU?@BjYm&hwKiPwq`iWrdJ%AXE+@X~YM^AwsYBU(E;;pe7DxpCIoK^X|5OQA1o zcE}me+`F_jqT|5}AkCFa2MNPE5o7Dm2k_Vt)v99$Vviv8Z9lNn zjA^PU-`Iw=80j&{6tk~QZZK=~Vmn{Wo8;0XM!pV>=)q$r2brhJq_9C_5l~}3(pmo& z#>c4k*Z@Sacbb3tnU;QR`29ly`se-m)3LVa?^T2@n19}x`2Biq#aKCom3Wa~O1Od% zqq1tw;t(5anGWu_HDYG+d$dDzni8jd*kXpqVXN(5ie1JLce@(SYhP@r9Iub@8oTjU z_H^YvjR%P#EVpJwEa`^0g%G+7A)(n{nHbbNEBR-uQ?o{1X6T;X<0)*wxp1Upmz^ z&1U5-ce-NbDq=^RBLr9;zC+ImzY+*@BqRN~8Gtme<%MYH8P@zuqS zLdX2YlNu9)TDgpeR~=o+Q4M|9MLOg(r~fHuZg)PNSI%N zMtxZk|DYqeMi8`F*Hz$_nH3j1$EBJ(lR!9@DLieZMZS1*Z9Gr{t~U({H+pkvFGUP_$A^u}_czU7c;Mq2*d|ax zOr5wrNC~7CNCv_Tj(@RA3hkZUr()WM@pT0xzdaGwvfUADkcyTTmI7yGBUQ?kkO#*| zm_1np?kOcoX0-ro=n~1#So=|#IxU$!X7JnibE;pssKjh>Cwt$~xZ@k+Fg%-z047?a z+|g0!Z7PTOJ*kd6#fD<)8Sg}Bt4ZE;l9(?PUBe)?CyoZ;c?2BXE9~Z|tGW=(AI3FR zyYEx2`wSRvw~E|`Nef>>+_J$y{?U_=6P1qGW}sYIST7>NyZv9f*08SY<=ef-pY^fzf1 zqqK+W$+#|0KA&U(Iac$} zf0ulWd!G_pD^N6gUXC(S$K&kM~D)3|>ofn>wl$n`TpP4hB zc{e1ng=Lgh0#Y;63q!JsGqXy$)1$bv3PLh>!Hit3>}tF0s*uFi)vTv-nKk3tueY<~ z|H*2&3uc65Y*TXH-_7Wh%jn_G=^xK-)5_tr%84G&8Oa15+|3y)0YB9bw^{di+Miw(nk(Rw^*m$6hI>%5TremrftD|eR! zq>5y7l;-}br$>wAo;~!qqvY|6o3z zbP@D*>0JD+oJ}V1421o(#V?uy0{CpTN>t7}To4m`FoOOP>TjB5Zrg#!d~D3ZI#km}DN%Ur zTM+P7ZfzILWg3A)if5|?RRQ^Ti?DDS1k<7}Yvy_GWG@H{oo9zUy_^MzuLC|oICU6~ z`wNd}6qd~5|E3=rn4b*ofBsS#1kAT`#@3=y&ZVS|U zhef(@ovubjG698O+z@N4O~*!31M{ee8D`GD?$Vl&#FddJ;E}TTas?dvoR^ru)&kat zj)V%}y-dIss;@)ZNf>U5ikK!yg2AObtQ$?-&tHq=!kI1&ryfsn=RuG$n}A+^bYT)I zK@gB)f^^1g{w>@s47d8>Xcm8!^t zYVsLukql?9f@6PPTKvg7C;!U0toS##s7hnC&E%_lJ{1xU)y_IKd3URWZJ!&O)%f=0 z*=1KdHr8C?tx;^qqd3&AWxev!$+>#D)<(YSig|5lSg+HIb?2%Q>b^SX-q+Boxy z@WxlMlXW7?X-!$xzM}Ohyw9&}1BxPLK9F9v=cVCRZ60sK-G=&5Y`d{VCmo_t69&@n^Vap0d(uskQubMvB}w_fS}X-3&_;4ZAOk#K$l8LpNg9f+`Aheol>K?1 zTlU!cH(=q*KmL{LuNZ8Y6tW27Lp`xqX+oD^qT8eb#AM?YtUb-|n-_0yO3VvGd zd&b+Jc(<8KR?OkZ-(%$N!d}67UafrVXUX*sG2_e~%s`ghz;IK?*Sp9qPnO40|DD^9-Oz6gEmEyArBhGsxE(s$NO4V(Q5sAqW*TMEHlITI*J_-y<9bBE=)f*L4(?uEE3riod>k&MJ~J*cEa=QbWa6GLy!ZyfJ`nLNQP@dm@E6l=-X8eYg5w+D zcuT6b&Yc-k_-HSQKgsCXV{m>|!Z+~4JP3TQ1n>g0jbi{sXWOIT1kORd1smrDFU#Ry z46LbDrGyfGfQg%B0yBg}4Qu?u81RmUSpo6yS}-D3UlW~29yiYzK3+-|nW)U2GF%=i zd4V@^Ta(0^iV>yewH~g$GyD4$x_4lQY+;95ROLi~5^@o4!`~I!F|JzN)m7(0` zfh#Lbr&p3+taRX3M!v6<^{))tVKo%LcSyoo30dQb--SP&EyymM|2zKu(}YBB^}6$q z>)}6CvVZIxpH=X{sL12~{{69~(DItN3Mq`*!V+oD-xvBw=kKWjM51dCUnKTU7_JM=bjhM)c6JC_vSklr-c_FBsL8b|W@ zhl##pK!M)v)~9{B>-Q%(9GknQs}7%7TROdtPVTiRS$7qOz0TsgLglF}c`8&n6nU!P zeE&vM?}ngaOH<#*>Ufof82%UerLoe2SOsKl>0T)R_%j%nAPOsH_88;wJ4}4J-%L|4 zUJwuarnR-#_4~u#Z$+gZLf*X;LVALsZ^(EGjJ5frM=F1 zeixM`fECQS$tH!Ik%kQBDh@2H2LXgya#TXZQAyYd;^IdCm~I%@NX8=cfl03vVc@5x zC`@CjBC_FV8=cid3*4D5Uf0bw}Jm%dy9AZ zkOrGYhVyHhxts_;Wcfc7yNnPgLS)??7x0||rv6K@=jw(1MP^lHHQYb4vL_}&wL6hB z%GySgEeU7u|2S^kBTVWSvV+%!^iV+ID}IL2^Xn{;yIp{3enA}_=rSqqZot(mHT4yM!^wU zy4%TJvuQAXZmc0(n*H_DJExzr7P-4OC)|(PZc)DM=dIce>dg4!pMpS#@V&}jC-on= zjAQt{&pr?$EVf-|!Mv1US~ww)A@kWr^^4y^Eb#jfAz3R*s55UrJ7A9ebMN3k$5ZY# zpyfLL!aYl2zJ~r!?_jFXa^aH0T(8*1_l~`-1m4qgw-uM>W&do`TZNSDf~0BLr0ZQ9rAz5t0$Egog(ujP4$S$ zk&52uowBua%CNS=c4Z4CwVVobm6+W@#vw29s=mo?U6p?DZeZ1E9m~P9r}cg#)=!^U zj=p|IKW2ITjN#ikCc8^t=vR+~8W2-$dV51_NyzvZ)-2#jEvOU#Etmy*+raGxARE%P#=R` za*eX}IiX!+ce$ct)BZCh%X;E;X`i}dKxgxXu`5NWbjKSX{jHT;cQw<;0>_`#Iy+A% z*nC2*e69WLu-5l`B;@vE8te9+hY%|_LtmDq!1dzQ{#saIfc~&z?kiRa3@OmUwVnBB zcETG=(~rLKysy^!jjAK657USynT#=qHPwW2`nM*N}yk&jnOuyP! znDuB$MiOP>a*;>MT~YRY%OxBvExd5jJi95wyHl$YLHvzn@jFtypDJegwmdae7y0MT zDf@;ZVdMeNW5;#7N_@*u*+Fed!CI|}Fe9l0d9GVNGPyoa@bA;EalFSIxUp#GDH@&= zaY+2-=j4T|s?DDYl1@#y`g8RQ*5fkn9MDqLOp;bp*_#;N-Mq6%w^^Qu(BGc=!HBx{ zM+6RZ+YfaLv4St|xB-iZdD!P;<3h7En>%Em!s}*m=|dcp*iG0yTSGc= zld}DFG9t^Svf?$Q-;}D`Gf7B_H#LGSxg;O@W}pG}H) zNee$O3#&l4h#>bRMWT%kkU;eA6N4Jq*fSDEER*xCN$uKNv;#*(0g0|04HJKR6;A0; zsi{ki;9f@Z^0XXW2yQ0M73{w`1{Y&cB^}XEW6$3e6fxLJzT@JK-qqy9y=TU#QT>ua zh6}b<2l-x$NW%_dNJ?juC7h4$BP##l(t9w2eHuEy|CjB%6V*zh9i+EF0n7yI0%%=^ zqEUF|R=a#%M8X|icZu%dcPHlH2_eDU2hI+=4{mJ@z#6qKeDub=QlcKeH-De|`(bOcqh3J1 zr?0HZNniP-@Q3D75mdBUcO(9ni)jFwVr|1(|FM*NqlSBU)A#RN^Uj-AbU|F2H{zgMb5E+(aOOH{OI> zg5ZZTTd{5)Qt$Z7|J13Qk7iDK3_5!}HvdQ`diP8%{fADSRrh%5NN(9Zd*`>bgXXyw zA`DfV`zk-4^25@rJ0BTBOug2zDVto?GGh_Uv45bI>TD;^K3wKV-6_sLM;mK@3{dpH zO8#9tug0WB{l(o2J@#|{&7NYJpec53S@cf*&F{DDUblvF}Bcy^so_AzMge-x*S*Xc*ba8d);-eN95rSc)Q9N|Ks0 z-{12)=Q+=F&bhAh-~8d9aecq#zl^FaK?QcK<~ zOP_fg>ZoOy!Bx6#h<&$H#;}`T~DsjfMFc#bm*6l&lYbHT_1i( zMEbZP1BUfkErc!_>m=Uh@P+a!Rztf}JVPRj^KXurH;xDZp}Q%zKGEp8{#ZI+769AQ_V1s9=x-d#u@Q}9150O_K&G2>D8ws!JREA*_eLjCC^eL-41EjTH zTd2C6!jRBCT6?{`njnVDh%|7P7^_$aEds05dRXgf~k~i}(W7%9eL3fh1&>XaFE>WGuNt24| zAvrQxITw6zFb($T>&7}vp>LEGw?hXiBZR@uq zzBl4Bmy`5W6&?W zIgNM1Q|b)?YY3|tsYVc>Pd;LsGpVOdF*;RD7PK6oye*Eda0Ncn z;n44*lWiB)wSOO^-GcqV07@C*_g z$WCe9^i6X*&?+nba=6Lq)kkS6rLL(;WhR0)P7vibU7lw1Nr4#}T17BG|Mi5Sj>AB_ z*1{w*qDL3{G{FED1j#ONp$bl`T~OwBN6NYB3EtZj@oX4)biA1|6s7p=+cF!eajh)$5!5i8s`#6VtWGSSv%;LHHRJQ0?N zuGj{J0HrBLJpur&O)1%kjq@ryaj~bISlE{VacG;2VXG%Bd;v}+E>ZOi^zp48uII!! z;@Mr;OAy66#V_UTPhA6F4{HSzA^Ocs;FeqGLJ z<#qAjb|KBIqI)5gSH)WArgHZio;+aFI@n1jNb{;L+fg;Io4p%nbgjH-94}&g{9jZQH5O!>cwp?p9_#*?g9)R`lDke?Pe4?++i+Z8-gx;B3>6uLco{ zD~p?uX4}9{pOx4UW0E;3i;P zW$cZS`?kOJ{6<|l0rm|$VO*2JJarf2)*?e*|ZLI<^pNa zB0IFNnHw3)L8Y_9Lr5l0-TZpscJw9n89%>Un(2Y-(G0N#K)-gvljXn>e}Qjm{rKf2 zM5M9p&=)m`+C1Jdh<{!<|D*rocS~1KbLEbZ)0B$7Vp5dGdj*$gYkl5kpj<0uppF9# zXAYS??`b_~{{*jg@!RR}2|Zz8Lfo18PE^>mq-gUCW`BJ1le%WE$cqOJHSrdXVf3!4 z+k@YUXIj$$+@}FwD7H#}Yc+jBvb|V5nU-G+z^{3kciF{gc2kGrvaqDs=6YQIwa*-j zc~OFw7xBS~7T@siqWK5LlIrdt(gRB+#aJ+d`WmjR$GDTlO3y+thnP6^6l#PK8e|Ms zBI8m{0&JO=h<|}>DOVzeQd9zbH!OBna|H^1F=p6{6Nlg53zHZ7V%e{`XoU`2pleRf zvoP|1tUhy#_7{Z%RA;uM?brY!y0hcjBTF9xL9MHns#}BB5f5fH?!Lx~B&ZJ*phCeU z33X^ZIz}bt5|_S+8m+Guq!4qN24u2_4I5Z+KczJDdacHPdw&%sO2b(P&IF;5Z2tZU9qkurQusfE+cr>*h&|Q)R1z>tp3^SRVD%1vFW9&euj+fo zzg@5W<@g^>x-t@F%|=)0gA@KrYs2ntW8Y{D^z$y_8gE1Bkg1$FLI?mH86LSdi`DD9 zgS{!%`uA|u`Prs5XGlb=q$qO=WZ-pt)7_@U1s0Y2%3?axt_h#v38P%Bf0vMYMoWM` zK`~O_ZbuN%T<>Z70dH+@Eqru(*MB$nk|X1Kh;$zZcckw&-D{VO+Q!=N60I4;Yt=JO zacdl#So^2X41ZZ#?_;mAsF6VH_WOY(>7~mda&0l#(F(2NbS0%T6{pWq0&rzgq<^f07at2 zixhA$0TpT)2}#WfDYFT3jK~D8CFg#_1feAk20bAsCowlC@eeW4NheX*FY&QjQjuK} ze#!X(BuT(Ev3NGAx;e2_EulOCQ+SZXq^PU<`PAoN8WWOV9VE+R0AXS zQcnn`eSq`N1d4i)G7yr|C7nFHjvk%mB&%VVrb66O>S7K`7N1H>NU9D@o#p3JeZckb zC+B!6ieEZy)i~89Aq|<4%4LO`1*ATZO8c9G+Q+5=DX3ff96L1kwOv$8F*Bb?e_oox zq^_R^5`k!0Fp$i;lnBDZSu)t@1T>>2mBTaXDSrkcBQ@I=rZs^Yq`?IQ0P-&(X4eqU zNnxf~=sN}-zJuimB7(gs90zKdx$Dl5YniafOm1;>6LYhk@PmHTqI6b`M;7O2&g`aBz#7O|cP0mc!_X33PZXQ40rN_sOVNODI8d=F zOoWe^E%mU-_@R_~2Dbpf)iPU`=Hp0U51|R14G6hNkTrOX%%W%Y-v}X@B-KjiKr>Ro zkq~0G-PamOez!WaryID3Vy+awY-b3r>507M5NCh*s4TH-;8C7>hU!P9EE1GSOIbn# z0+`DiTegO-Ofw>Qb^^Ryqj`4EeL_05@pA$?@i90ueWID1pyoBM#mz9=172267ra#j_#AD zK!-S+KIcCX$YR&X`)f}TU{=;mDV#}_z3)VfQB% z;B$*C1)p7zdB&X)2R2(>($cqjB}ysfpe!Q&Xl;dR%c)I0Mf zHxH>1E+rW& zc1oB`QW30#TL+=jQh4hyMbZwTI>8awkNi2v++}dM{6a0bV3-`MzC+Y6fPcKvd z+Fy#5ax)*YE9ufb18bO+@*raZ+SDCnNNdxH*fY@Zy8g}e) zzGqa9-d)tWJ=D&28Fi@I?U4Fy=+TZ~9*a(euC=Tg81}7(b<_|NLP6=(Xu^V76LC?u zuGhFH)daOv?Ul2#WE^kRtK@8D?feD45sP^rRUpr{hs#J2yF zwD8Bzd}NDuJWE+Jn#sfIgrw^!!}ZxRr5TSav=5seJbsxko7y$-^3~zXqSlwzW-X5% zXR*uXz~4P9H7ifnY*F>9Dm`p@CWDA1ysWDz0^e-)FK>~2SJtK3_KzDetZm?N+fZxU z;Jeh2-+JO+AtOvTqGS6^SbN{&DyGT0Qnr2ecRQUS^ost@hPAWZea?6J@vASbulmeh z0g13rH?!70ExCb+d%lTfrot*(^;Y{vGK2n3xcI z*m<43JlnWyBh0!xp{wg%;uQx7Y9aBC5OGVkYE=^>n9}|8X1Ufv87l?^DnQPza6I0I z-0efX1|TB{2nGoj9b!G}!WPE|_(WhYJNXZL{e&QZudRgJN>1J$!c6Cv8X(!sv#nzw zkrI%?Ydj1B6$%6qquIos^qHmHI@dzWX4vJJS;Ag(5&H?xSqh*);<=~UC_+85cw0_` zz%F4m5SP+^5LTQNZrw{`4H5zv!HEV~n32o#xF)vqxKJRCLl+Bnsd@N%LMNMVXr;B! zyK=zf4r}^`-g)ME&IJD9TsBJq>H@Z(MF;gA8z5bStbq-^LeOXneeqIg0-*fr1yzu1 z9dIHXynK0`F1U1P#s@i^d!_u0WKEEcTmRv9mf~XB* z!Z$(&9p9&CKK|pV&_b>axHdlJ*faIGGhLPwkvGmU+D3gc@YS*H#eCwdcSUki>EzsG zAz~6;IVJzTTkZ_)^qJRKh8$vMc1r2%lvwJx`kyIHk;yX_mv-VLFi#Hf^OmNB-`6_^c9OP)gRAhUfNinnPEe;m`MM# z%Q^}vsChVZ>rV$o7TuCO9eAoU`0i_qs#3{6*Fl4&v*u5aooPFfH#=@uaV7rgaOl$$ zXU5|YEtVG3$>oy*>QlSw&7}4;%0}Dm&`No8%%pwOtMIp+8gD^zJuOXakpSpzVxjVn zvhVg4xyUhU(jx$0rdVa;&y(r#e5gMZo~=!g4e1k z{pP#r)c1lTv#DqLDj8=cJyYhfUwgRkf^x*6z9i5v8d`pV(8>ica0&T=Lr-JT8-Z*r z84v<1ylpS{D;i=zlw+Www<#b~w4oy52|cxY*_kqA(H1X_j*ens*~y?&PCexVB-Kcd zass9SH(6>mpV6Jakzh~OGHbUv#&4j!sDZB}IG1bQEu}83yzk~#mj-3PwiZ|}Mh~&z zEkT{E+*WJ@!T`?uXHu%b7N&hb(&~-{{z32?i1}PZ)!QC3%+4uJ-i)AzFQcp((A$n> zR=&)V6#VQ2GV#YEO9AUW$3ntueCnAwKZ~JWGtAkV$yewAo!3i(iz+FZOdgVwl4spP zJMyn2`ZuG~2W#>?>!*8x`CI_UQcEzxVG$LAJ{4^FVfkpB1*r6uj?f^iDhmO^wpW*k zy%u1l_E51kGQ=G>arr%se0hamt1k(b8T5FF?-U~V>?HQlWKPw`7Wt1vk(r0@yPHDi z-fs4h1pzYz^D@D&Von3nr{<2eSEip`YdHH#F}E`;l{UXc4{&amd@}W6an8j4Bg|}5 z^nGgH-L3Vlr+3=7zEqTK|1G`b{7ohF+d;(hcYoXWIldvcX5I>IubtgEG4w4+BvIz@ zDU8w4FxW%W+Tj+9>9gIT9MJgBCkS@zh%$DtV!IMz<|2$t$>;GocXwqvcI7_o$}@Ix zVtWdl+I#m(GL+5-R)p<6?0fi&7yTc|c6I;|AXfmG1GE4~{v#%AgAr;dozYM(8K;4o z0%lAo`QOnSZ1*Dn9TWa1vVG`3(Hs9*7a#XW{Qp`PE6&#b8Tz+%(Pgwi3tz)6m0V)Dk3Um2qjmBP5%SE zF;T*r;xHN}_ejHg1~jWMH23ix6WMP2sxt7~nwybN3pe4?=EvFkn@r-V`uA^+u_6pD z9?IJvU)NttX+x?w4t`!T81jFAoFJpqJXY~x{9eG%bKBr%9_b0;>?aX_j;}vejDSkf zqc6_Yr9?imNSMQS*~Qs=Lk}-LihS$W>>A5==~KZK!4q7hIPr(2*c<(7Tm(V%jPymE zNItU)KVri=8%MHN5m%}WWLr&;2;~P{f6d>&q%;jMw1~VbaHrtGY2WoHsZJ_^iAvmF zFU$dEAUa#T9IwDMo_gRf8g!g8Z|j z*vH`5?v$Vw1qgxhpxSTKJ)-d1Nu?|?$6oU4so?}pJ&D#Mh5?%W z38=;hV5`MNyOJeuZILo^Oc7a}-I8!Qm~yOq)2cUCz(!}5W zG?&bUWUz9%Q*94Nm-#wE0Cdr8f~Qf9)dFCXgJ%A$PUI*rC=h6Y2Q6WZ0T)Mz-TY>| z{folGDq7s$xJz6BE+F)(d8w}4omh^E%I)q`YWzB6ULYl^OK2I4h3Qmbx>H1eq+PJi zNf62S)ZmB^Q#p~P+tZ^$OA<0>vLircpYOS zm;<76m>9%)I;~$FScxWa1EqmUt%LmCBb*lk?x&P^vJsO4!8;5xUT2nWAETqyChiB& zOW8?@TD178cJ898Ol`?)^Jt5CFQ~+TbRP%+RaG+Gj8}IlebRq|hNzT~`zhZU^Ipwc z4~=4F)tit9>Z1|8FTO>7;{pPN0cg-92Effc+1ylUJ+q}{fxc~M2?tub8DZK$^lsU# z?OJnqaDa7-G7#!FD2vYm4hxl`R}pf_w$Vm_@S0P$I$1?^yC-X${O|O>XnDZzR0~-; zDdA-_5m|j$pJMI3d}q9s#T>fIyu=p=Xs&lP5b3O{F0z<6{5f}_nJMSdOAuXR?@3a; zzzuI1uMjwC3|&{IRI@}ht$CyqI;j=4YOIM@5Ck!v8bNHEV|Y`hQm#F5O}(ZcEg12r zub7g7;G0T3^QM_wi6Wgk``sXM0z1XCi9rQ{2=aQfJty4?lxa44m$MxV`4U$VVwjUU zc+QyUIJL$rQkPBT}0Cn0M1={?zs>aH|ofR8#!+W%O<0+67D9_*Io*^VVAJpmc1ub zCfSuGGP4Ulb4cAB2Qf|%>H$FSZx!1#)K1RkK*PnsEN7r*vLSpgclet?(agTKG z&`mPIoRUM!d|%wzh0nPP`(HP_JWpf6LZ=vz&mk=QC+nn`ZE?1MFRPr>WoeqU*NNBJ zzw1pHdkAK2Cs`cr6;Ki}vdGZ;SH83GH4|gia&@zFj%7U2_J{Q5(AX>yuX)~vdjy9L zOy*AL^43vK1~lw+%dyAtmy`Nr<(CrUIH@Hl9~X<8EXI*q(gHm-DK;ghZ^|8*=#9qm zD=DtYpPg8^I|i8O4bz#*6IZ#j?8+@f_b9`zD^%;Kk_cWCT@`G<4V1zwmD*M$)@96;Tlr zPv$?PZ64o_On*#YlWDI1h{JjQo=o?ptfY|hj5LYA8-fYUcNBWdV<{tr*w)l766Xz= z_&poc#@8o#!cW`$jvIH!zE~fB7rn)WBW!y`Opk+r>H2|E1<}Pu{upVG)W+PHFc{fc z|EB#nW3hpLi6L)dD1SR|&V5WFr(tg(zGoYa^4Zq0T?pw_IkZBFAH_m{k)6->=_I?v zbc@co7-=up$|9dqMW4B!)}~a^D5gPjynLGo%Ep6gXN0R5M0cFUs|Zsz#p>8U<`nR zn%8N~fJRkbhnZ{)?fclU%^H;u>AXO@BiKNS6Uz~3AQ%N{U${=?0l;F#)0tmJ<)c)j`;`d~Q|5rks@;U~t+0ZB2Plz9L&Ok+IQ3Vf4 z{rE3Hq|Skk&>x)tJo9wB-Ot1pq!X`>=t5f25ZUjb@oFc|-D-O}Pv;)n%+{=23P0)= z{X?tjyqJdy&1&fGv{l|_zi>49ZC`A8(vvi@e(lz5H1-E}pl95&IEpm0^&-8Np|vVL ze`kP|wr-^9F)ns>GOeQl5Ye&sRO~L)Vg);8l+gM09GQEZ!FUC}+p>dQy^jw@1J3K= z19U9le(Wa51p8QkVqLwyfT9$swN_9E&rgC%A1oanK5BbqTHnm#dc=T?UI=>;S2uc z`dJfr>_0If4Vv89lpH>t+!>NGV3#asn9`7wGIo&iv@|)tJ0<;U%0x)&tX<-;aq9Th z)NKCnvK-#Bglj7yiB~Qq%BZG&%t>YDSqtlGi>0ZMY+eW^IlB3JnH}2gdcr0&<=sKr zc1YTX^;_i|6A6C~lDD8_4z6@&RNG5p{ceXoB5MD7 zi2h1rTOy*_Ofq;9lNkva0w>82>@KL*$o{#2E~bFJ7yu4gPIy?M-g0fI-2|kuI8*jf za`$@X>BL02nGA5}B?|T?*wu|~M|+IO1V`{KAH*BnN#;w;N-WHXy$DlxL8pH=Hl@LT z^4x}4q0SP}s~AB0{xwqb149$E_u2#J!VEKk?5De|beghPh~Z%==qnX{+BhpU7ZK=D`PIgO5|$ z?^BG^O%t!}O6QH*XM?SBCj_v90;vTr6PFl|@}8F_x6b9U=;nVJOneuTzs@fD;bs2D zT;{iv*qxJ4SLgD7cs`v?eEOyA>2G$ipP!#Lvr~XDG0>N%pYBk;;VJB<*^nX1haJkU z$x}{^0&a%_z9fo3OTN%hfk^ICF_@_M;ZqP^TXIO~`23TThoZ7ck58Evp3cp|ClwT^ z<*&~^RcuLQKJLmef!v(5nMc&$M&v2uG|exGo}KR6xqLb@mBMlQ|@wDek(HZ zqDB(9;9-z|CK&htwp39KtL*ejV{_I2$pe@r-rcQ{0Ezo+tibjLD(BZL$4%2D22I6I zUT2GZ#*Qgl^s1)M^Q!0a_Ttd1&HlO?NwV1wQd+7%XasyM=RIh?-VLic9LfY?pu;oI zT{99J)r(j+lA!PsSZfV(BPs8&#-)=ADocN?QOm0C$oshFJgnx|Q0=5$jTpQRlU!73 zT6cW-xzukSEtxdnaNVijb$kr7`cC6?Lu!GJTM z`kOa{8J37>2lSN+e|zqxqZ`HbXaGl-23rO`udK;+0Dg`50J5VhVAgC<(#(#JN^uO} zy^dyVgKk;YDzZ0an0Yw|p)XiAfiN(T74jk>>~V#2Oi<>{84jr5-79wJrESy?mzEO8 z))&8pbHiF&T3g%RwZ8h@N)u}PZ!zJ>yEeRFLnqmC%+XP2xajped!3E^w-uM>TH7sl z>R&P(FAN)}WmRzLY_y+=tj1W?=G&u(bJ9V6e4lPs&nLf<$7|~ztB1H2XFV>4cXrra zFMb=Wz9z&4_U=%`D1-b+{28rS)yyAiq|IT@_sO)goq3T$fYm*8oj?=_7&$q`Qg6z| zD;a*KY*3IfCA=-M(fCG_7{pt)ao`fd@ zs;-H4lkFB81E+z5$wE9~=7XU}MLFgjxmq2VcY{H{29tz`EGGwwHoJ?DxF0z} z{^nV=oU)jGM}7Ek??!QR+i=^$@T;R?n(#=M6IJNWU^hZk!UVld@%<=-xnADUkKk2U zw*Bhp4_$%`dXG$M@k&y9wpuy9Z!2MH;ipTPH%?{mj(Ea~z_23}iNtD3zT`8AE(3ZC zwW%=aD<@7Mb;x5*lYw=Lou9o>3lq1pD!|g&x6H^Df4zD1M$UIZFoieK1eyj@V;r$C z;pBSVEeYK-r`j8hepxi>tiuV8;g!q5OlbSczEOjSv$zC35u3hQ>SC#4?t=)gkNdCc-mReW*0|eM$R;m6M zo^*o=1Zev9|I*sExBS>(W+WfR+FO5qqjx7W#IzgU5iUlLl%aT8gqyAIT7K6UIdn69H$M>V^vT z^gXMT=ho9PJYrzUVxC^BmjMPZ%5NHs@GBk98}q=>as*5yEjhBGS%U;g&hPqwS`fLr zdRp|hw9*@9?32?d8ohXbUNkoYo!!hyYGe}-qE!J)&AvVxY%86}>Tk2VX-FB^-Fk(1 zFLeL(5yXky#=_^l&Ad0Re9{3^-Q4bWjbz#B5yjk=>W$7X+vyVy-rVWO@_ql9ZI+SZ z7qWHqdR$wsX>)fN*Dtp>qPTZeaa3)sQgQ4Lh%hopFY8V}!}j^=_eo=^s_#?gLOy%1 zkFY-VXMsvSKi=5g@EO_~gl@_ih>eoQ+l8I#{_5=N`#TywRk#>I?rKa5g9SZv#Qw z*7wf)@RGX$XP;2VP-_)Nqvrwn{bMSV`3d>XvnlsQXj+aPe*?C1*~sZbzd#WIfXFo} z>dTO|v-0#W=<~MCSgyQ^uWy#lscZm`ZgcM5jTR%E`O)Axs?vq3O4mAl;uh*lmk_db zbW%}U`$yEq%9;JQu|7fHLBClvFFiaP1_cT(!w8}*^rm|`t7Z|@{xug>m2ZEj5#`+< z784%I{I%-8_c+;M{5qK}jL3?<@+FS&*A->RvnsYZ0md_H9XXjJL-<5#ys`IMCb`}Ejx&Zl|8SyEtoCRSRA0Mz@j=PP8P~q61yF8pRkHU z`+e67tQ1;)e-zY%g2=~2!1cJk>NIf8=|CCiC`AfBCL+M~f})+c8p{My8K;9ih3+TR zU;xa5i!MT+D!6B;l-P*Zm@#(S*zD}NH?4EN(4|oKlNrlvC-v~(5m4lPsZf3B4#}o;P zmtR9Si<56R(43wOJD+}6tlb0LQ}1f9|9Li$3W(9;X8lYSH8?>&wkZ#o#Xdqa&8%_f z!6dc?1VJ!rqMexb+V>DHa&-hx_Df+EPP>qx&L29KL#pwfgagD_0BH|Ix^?873{5gS z(>*=9McW3tW!16~!OV~KBYMAfrEBWFkrk6Sl$f{jvl^F0m3-oFB2*h)Edtx3g_qIs z>Mc5nCP;mu#dV0f4D5b@uP>Hw#N&|sR`F4vKej?|aVDrtJ740~J*_`wr^T*v=p)=k zS?&9=jrcN2w0?z6VB*DlMn-)<0&_@#f+Ammv!#=MUJ=TbXL`zJUMOFWjFf<$V%?5o z!XZW0Juh8$tb5xR`tZqFYlL#970A1-06y#G23VL#3qyvEuzRqftKglm$0$i6G48oEp zc}#CqI66hH!|~40NkdjTMe2brbOv$DqR(vc-Lf>mhk!W8g1b0d&@Et#Hdb5J{P1}u zyJbvo%ca?vNpHML3z4V^L591$yD%!6_Fd3TS_U1jYfIzg9U3ziteGG`!U-@F?09AJ#y0(sc*?P zm(sXmSn18u%`EMFb!!o`CQoHYYInW z>6^+`E6LKn{_y&;KhZ0?lF!3fK7T0(PLD;?1807EvRwjq8QTS~)rMJ0lzl0)O<>d5@7@e`K1=&SKz+Kv1JjpL(R zK}@aPc3M;0n#H%!cfS`8#+qLJ9Q_vY`}YR`s+q=iZaYfohz^xf%i?;K7pr)*1bi;i z^SnDbIBN-8pA!<0WQj<%UAtc=)7W3IcQH=dbyb=nrotteyZf;9=p!!u<;ab5d%5q9 zKBqJ7PK}5hL?uHhWA?9;}shxL6!FS+nKgpz4Fi`mZg#< z(lAH(LUJG*;XCU~<=^jFOf2VU`3O8L&xI-FaWRuP@#)1qPw~)Cmmv-0(X|!{oyQU4AKnjvr=M|qohtRz_Fn6HhH(IBo zZgk#&V(gJSsJ$BsKS44Vnj)zGbC>n6IV}q?2+#qp{?|DTK5zPe+hx&feU_O2C_SvY+>`cWcd()Cb&2K0eT5`57o6Mk zsG=Hia8^y}Kj0?#k4&2Fa}ccVT9sfa8_RNWjdi2UTx-bQm&TkRml~Hbw_R7XZGV|n z=e`VcPV;k%nrf&L_Xf?^xu-J0O`A&R0j5{j?vjt!;a z-P!i8#ZjS61*N=)B4%;wgn>ooF3ZRRF1OcVO{sAp_0* z4@TKse{Fm0z9EcP>B$}1OfoRK0R=q-!_6D?$a72EdT^EoN(@?K zldK2Ou(T78;=i6S#i53N5rxJ=3RpSRol3<`X+@aQ{M4J8v)cgHlSkMd z4q-3XnMCR8(q;Yd^^bFe4(!R5O!JnUIS$|fSr3liq{VQ1KrdYMAozaIzIY|-*R@Qj zpR^^09dmUg*ZaliVmy#v(plgCRUsG#s=^P+z5vx{5iB4>?f`d{{b;1|fJ6$e^T^FM zTj-fIIvLV_P(qjy?*ZY{mi;|XH^<0)DJ=?h_)=E7%sFCI4ZQ(27hgl)d>dSmIyQmAf@ER{Flua3qc!Sn?Atw zhpjqhb%(1;AuiJ`n=k{J=L#$i9@obuk~5NUUS^igv#=Pjr~{qEs`DBm=>=#$QHiV8 zeI!I{{%Ytge~R1I+pjgh>+$J=J+Gk3b`1Mm@-z0~s91~xbI_%+Tns7b)H}tT)Aa1U z_eNEQ3-`vfY&W;6B-1yK^<#yaEALazjqFXmc+#bhv7N@$AZ@Hqp#|I9>b}o71%LhV zwvKXqf0j9?1#eH~K#0gU_f!)GVWR@HC|XxJdUcEl5(H zI+p))Ipv=@jcgPVyqv`x%$CQ{it<$!EqVDxF|Zi;sbP<+ho4IykEJTbFV!J%*-mwX zoAvNageu;Tn!45YZ7b{>jUgYt-GjOn{;f>v`O((YfbQ^obZD9gPVbxGp6nPcCe*y7 ze-$B}*OrMm6$O$Q__em?m$E?O_T|DCG(e&}kGFz0%4AF-Mm=@vBLvm>xu{}k`E*bL3(s9`%MJzKK`)ZFsZe6t@1WNfBb}7 zQzGF=S8yz0Nx@AT>0wzd*tf0E+AjqqfR^Jw?Xlt+l|ZD><*fvjA_!8}2ppS00A^ddoO){^20ObBvs{ft zEeZ9C^mX^E&qku6n4Bm!lL6hdWzJw|k2HtgK==9t7kM*AN~M!c+na?upM30?>Pr)o zpu$^`6XFNV{gfVzlbgZ>4@KagkOw~VyUM~|x=d>;6vp#+ZGVtWz~^4xR{)fR^x_|i zCu?p4xu5gLinK|_UvG(&FXxZNa6d14-3RfO5#6T)-CrR_b^?ay%vEo;ph12F| zNk+=LaVQ>kK4ecF@TY{3fEl%gvKDgw8SqG3N-~&tJNEa<>(ib~h8O9(Jk1jhRs^u* z#79N-3kOjmka&n`iuD7+#g9T~{MdC?J5inH9*U3I*)*T9q(xFKeby4!`w!sKjG%Fv*#^8phGIt_R zGH*UW|Dc$qHt@lVdmWTsX;AG&dj{g8w?=oY%zi?gI<)XfbHn0O!%uG)OAFzJ*RJ9U zxu#a0EOVsZ?LD~-n0wYzU@Y1RRtNh(`IH9YFLi<%q7*XM`1M*uMT)f>=Nit`LZ6&W z<#MpmVOK3$f`=0j_$LplmiPO(+=;PrhCsx(B>nUVkCl_Vl!J zegmZ@Ak7v2V%hDO^qB$UD@*4>Ol|TT4q|TvYQ`&1ccNmD1nS|&mA9plNCy`dfvv;W z<>eR1kprw)?veO`did$}4x_d|Ed8wq& z`ABn>(7E9~8w06`0fPUl9Yz_|qg(ikC7b2~5EV&hP0N@7M-t2Wa&^oA0iTjCZx_JB zBn)x9z3T>G)^mf~`V#L-VLCarj{=F&*fdwWp1;Qp$^oFrF!72GVZFRqaGXZ4--D|Q zZd}HvF5yNV;5QyTbZRDokE<*twdE$u6!`O1=_tEs9ej6cSL+q~1<>D{42sRNv=;=7 zKI%E@y_eM0Ett@`kRTy<_YN8)tW(>s7_r9r+}m11PZyyRcS56;=Mz2&pX7{|dL*_3 zJ`u?>@q?qNmHTc9f&TjziBpf4SQKO@P`tf_SR;#H9wK(PbAcv)P{FmLsL%HOta;ih7Hs z-|`dw{7K_KPe!b3jJx}5f1T8rjI&_2{_w_m<$E>rux~yUthv3T1QLU+{j9fvBeF!h+B-ynh$LrdVA#5fICJKw>+- z8p#>Gz{2?Y3=ps4B2F$N8c4TH#A>xgA{W^+x54fJm?IhX zyat?2V7~)E)^CF&>1_52Fn<7YG6T_6<1#5QK+uu-inKd@;-efM_G!V45kr zC=eeyd#5Ga1sbH9jPP1^_TI&GQeciMuGF`&^dB&XPdi?d5h3##Ba{m1Wph zHkwV=A~?WSgEfffXy~aRw%d&mf5Ii>kFY2JY?uV|$H9gf32X^2h~8~jwzzOtq%ntn z^4SBJzdIsZ2T`&eceV&tgGOXwFAZ+PB4}*OEAY1gnYWiQ3vZlhWb^78nVoBhZ~Ag| z%s#)0a0fbVs1t&mg!o|5Om-8HAjaw{##sOXi;IPvMBm-d22Ow-CvN=JMc-4;NifOr ztbwrBLcA!D6i;;Mo$TG(tIpeC2cji)!mvP@^vyl|4gl7Sh1b&zT~*GnWWh=S(Efec z=WO0f%IB*+qb|%CMxg-|GVI$btc(UPB@^2$;V)0Xn~3n@lW+>jsFA6YJ*iUq+0exh zeyoozn@l{ixnTr`M$q-NK~Pe_<3T^}Vn(KXkRPrKE7n1if?ElJ@bWCKNR|S{G7NJc z%d;>gucn7LuoC-y|EX7W9ApR9z71ye6M}?NZWWv6Vc|u=JnnIJt=mrh+}E>a3?b$4 z>D$B(FrrsIzfhN_g#vFRIF#4Hfi>*ybg5Q1IVR1z>yx~Lt$ZHQvQ`(*d6ipB?|jcX zTNV*Eb?1hL$JwVqsQwqWwfn*Y5P4nKn>Ta#eX$6m$kU*VW4$aQsygUEqG-FC46Ez; zc22}!^6?J^+XEWA?!IfV3;0UZ7tlZgU-lf_fiQ915-MICvq#p(mCD0d>8C$*~=-8y@hVi`$GqqB6_!*FQ;%e zJ2#Cmi1kOZO@+uVx|Yq7#ViT88I|$(4i#4}<6mP6-@zZn;!1SUm3}uj3!l1D$$&;F zKiv!AxPlv>3`1a+ePmNhz6*nZcnZx7^f{>=eOavF+^yZJo6DvhHSF#*wi3FO0mhrU zr!~-dit2V|L!G-z7v4i=J0Gg3TYzM1La(q?;C|qM*JQUmD>$k0dKg3mk-gSHk*X`l zG=euB7JTAVaW!=LY!lm$J}X`T6N@*$@sMbOv2qv?d@X3TQvYa9qpF?cO608O;l1G9 z6_`bXcv!Mg80d^|xf!Xo;7j6HZT*5CW-2i}sWj%FnF*ZARqn%bn5Sf34+&WlmDWsW z_uYo0K0j>~l+B`9j(6jlIT8K@_TL|?pT(xR_W9g1wdg0f4A(gRx_14>3?B%?ISf$i zAP^_;rJ)r~{kXufNoW6@I{#8`L<9Qxuy5=>j6{YIC)kVEBZD!xIZOOt0jS*p$_ARN$k$*}rQpuk5*X#| z(ko44Mn7aypHw={9s+=I%c{6`pUXlcR^x1l8`oGg@GAF}Q+rS9N=lpgmtA(1>#($o zXFRii{LDW82kfM=-OFP)nb@+VK$9>|FK+@Q7$EEVLa6>WdySc?LnAxKDq@0JIYHc3 z1esN?n?Xj9Gg!T07lEk>WONJSV}L-IW+%6t)D`tedTyt0Cim1wDFwHiN$;qC-`1s-YZbPTEKcaBOl9Y8pQh4vXTw5OxX-iC^s$zzdfD-MiVUul?S7Xzw*# zdFkwoB}aATnOmD2_?^D73An@e;a9?aH1e4uVeNO_XJ)qHjBxD)N#yO@!|x<5<8sjx zl%cI?O?bg1tV#=Nt+BZ``OI5m0;k}hHL`GD`=b;0n4YX|tw+AoO?!qazO{(yx)M}F zPF{B6`XSl38=lE(G4W~y$%OT2T1@}!Mt0+;a8?EgbFO_Zz@FY4!5vtp@8IG;dTs`k8P zQ$OuY$HMHwo<qN4NBv3N2y_ zE1!h_qPitNv>%*6Chx}G916{U<01HJNr*!&skq&|>r~(Jg**rOI)LnrK{`qmw)8q_ zeYFnqDH^|q=%@3rc+=Fj%zy}*N&upq0RIcW4bu|T^3^j4ST&ANT?4PasX@rDzPj>& z0whjG@>&LcF(d|>SnDH8$cQ&M1Lf5Y&Og0yVcHu@4rLo;4*-FSS=Gy5A)dWmbaiCL zX)RP%xDMMHr4iXh;$F9jj+t*7SalBdT{|)Cn$MUpjSpMr{s_AyJ(#H#sn<#Hrb7(O z)gE$WFVzaHz+ZZ=za8vGP8Mhmwhw*8attDe%N5OEom%`dI=zK_KQa1lhBB#Gpg(0f z`@Bta+R|#5_rkozRM8mnxi#|DpT+mAW?-8y1Lt&~Z-cYRg$}k}xxF7!@%hR=+96(k#@|~ae^_&UA!vU}olhH`-r$;V3Lom+o>toV_;3j^ZHdf2HGV9{WO3Sw zetAkle|qN>+_>EU-2S#*Yd#;mb+|Yep2v0-3cJy)f~VFe0hQ#J3wsY?YNN=C!mV8` zuFK|IH1CBO`rECv;ljnOllO+bITq5L_27&r8^6wJH+K`n_Ro{X`cPjrQ5KU7#6o4( zZ1d(>S|w6AZkkuw`cgzKWeLhRIKtP4}ew^F8##P-Vuv5%m%CaccwecB&)ks#pTKFi>>f)eKex;b_p!Iw)8nE@wDfM zm)(6OwEw}^dHz%3$Nm3o$3Dj4aL|!;jFV$;ony}sS)p_6Jt83$=WvpFjO={vkjko% z$_^n3os6(57C+OL~fhM61-c(y!@!P844Yj`ezQU+Qhgwe#w zu`0tULU;xbr203Jh*TubvD!I1|8bfq&ZIxTxk}yd#2_-1<(yUapVXw4I&+Sn398Zs zvOAhumwUI*O3tZ_2+M^G95CyDj3OTgmNSEuV@BTHwV$oM-ST}?NTYBnPHIK?vZPUq z&)E4Sf2({Iir9ihp8CkNyh}?k6#OK>8g1JP`g;OyVv>53IZsJ%-{Rmx2Z12$CRPk@ zGClD}i`173k6IWWF7E~(Fp7-k${$2T+RioyEHnhnMK__%y*!T}-&TQbbJTeaXBz9E z-C~Sdo_q9(d=&Cx(z{E^ma=0-DuId;mvvw)b4o_#>C^T0@?$j~K?&ziJNgNWxKHF5 zm+*x+l=;LX$b2gc87j8%wW8NDG(!@!V3JwmaY3g;s*9`|pPEp7`7e0HCJVR*_ZSy? z?0b6g_v=HH`n&fqyIg#`2Wd)be?ic^a~|;#xz>bT?_5jWY-!UV%3-pwf5Q?qQzPGQ zAVa%)*N0Pg*4dYz_{0T<@Q;ZwMCfET(~7UO*RQ90m)1*gYmk<5B=W|MRIKwj3~~!U zPbEc;Wfe-)3vR?m`3h|{*00ylTS^8|HYTjF4A)Aa@p0x}!tClD^|npPEc?cybuRw{ z0Ik$(hwjVeH(KFc;I+l5?q19khpFDqr>2zO%8^Jb@p-}aVA|FFxmsJGThCg{r4-gh z6uH1$8lYulr2e62o21T71OXv<^bnvXLuVVWbkTRo--}au9zjEShHDuYUP|Dh@oE5o z{anN$1dNlIpKX}o&{-#i(5ZfVn(oR-sA>sKF*i=NpAV;^&OVt)H@J0*c0hIw?->xd z7^mfv=OOo`-78CHutqTZ+F^}%uC;(mp`8bCP=M`1HuPSOcp66m&Mjb%-+j_nO4wo% z;G1EGo;E1(iD@>>aGyFz⁡8`f$DsH6J|YG%A-}&rvkdl6H$2&>KWvfbahf@=WJZ z5AmAuefIT9veY2og_OjL&TUx{=n%L01g}i3La0c%ex8)b2VG|QYTjNnVVRw{Ga;UU z%LKv-UrFb3D3We84UdWD8j1K4yWx+_#hxklkN z!DFqfRZ;>qiILiK^T`+^NV{FNoKyPe$szD_PceXCqs(@ii#Rb+2qF=9ULex5?Sj3| zj;6yRfY}~aV9EJoGpGAGJuD&BEZh%PXlg$bQbI;o1h2r2#H{v=LztfQi6QW*Ekt@K z=GGmS7Lx{}obu0laP(xi@ejwz9R0(3%p1*H_;7Ltpph!JU&x|4lK_#562DrJ4O0@E z6bOx?R#m+-0dy|eofS1h>)G8odm%167gc5Yr{By?T9Tdp5K)XY%vYqR@C_aG3f=*y zEBdQD3?XQo2?!dVXrC!B@~)8eWJfjr_q*(nZGpGCP<(qfN5*(_9KHvp%H^2>((9L+ z!?HM~FQwnE>k}SagcENV3a~uLt3iklMmRQLoXsJqSoh(w)uhsZDFgHZ=9OlDw)2&k z)3?k?pkr+D({xg`65zVq3U%Ui_FD7wL%FdO_435Dqn;?Dd{zB`dUQ+V(XwH~f#sTl zV4>@VD*h=WSuxr!ZDC#gsWwy&1*%QcxNsT98ZO5vM8_9bqCF7cS*e^WJe$*d( z$GNj2^S!R5Br}1gv?Y|Yed8yNkq5If^+c=PNUE8PNmi+jc)rCUpgn80Md)vKj?C*5 zZ8xLv7M4R4y0dc!@vPTA!)MfIA~GlGQ0LL0_Y{#T!6yFO>J1gC9aak7r@cakL70~A z6dwFzz@QDTVD1ug=4k;Z0T-jQvd{|}c)4M$l$i+AM6Dnnt>*gM(*di}S78s!T@-H| zH?X_UFAKEB7|SV3lJiHJM_`*UZIjd7pOT*R@cGKJOtU*)i}w9bNC1Yf&F1j6suG^q ztWrA}`3YsdfB72G#9N&JQL{}#2L)M*D9w4?Y_M}Xf_zVGAg7Zy)Fj(V>9@?Il@ZVK z`;$5bF2yDGSN!u4e3r7S;@QPsnco?B&3RDKvxf)?ltA&CJya5B!o29hK5yEL6+D+x z?OJjkdOWPwHd)T}s@8aW?dxLU!n2X3DWvct__nHrg}|qT+Nx!|>CNN}=n$JT+oMIA zBuiWRy4Iu7kpM-b6FvEy*u~bC%4EDOD4i?LPtV?M?vfH?>$ zKSV;|+Se5oE(`w+U9ZU4RND0tFOGm)zAyi%v1q&ixJcud;L(MLs!?|327RR&;|EYx zj~9EH;cKXNX0V#J$2a;?dxPZ1Hgdvm_VaKmzn`hjtYCKZlU6;R8-#1J2y$wxD7cLO zY9L4&k!-wwv>hZfF#Bg5dInDwn#0F0KPDdx$oylDrg#xsf<;rKsGHJiX-4s!*@1N; zZ9~~wtAaL&w}u~gt2JpW){1eRh7!UHqMK&PWrjeB3iesLR&XJa?b7Sxmb}xqEW3ED zuM}!l2|nJns{VRC>^;p)xq1S+Z*IrF`Gq0`toyfb9>IQof^t#_>)N-pgV}GK9`keq zg3Ep<@U#I~aErYvnM5{EvrB)g7eTU!Pn^E#c?zvsUD*a*k%-Jt(k%yNctkmE%&U7G zL5sBKD#XCEwrI;AVE>+Vw-9vu=k)sKy8AA6MPQ)chB_i!!Lq0(NllPaOxICR*8r6` z7(_%sdRm)m73JZi1PPyuT36T$SSt`5hn)?-*;6YDdxfC3g~@>%Nxj`r-3dy!Ce+p+ zc&Z&F+fGrnrOFp3A}4^d49Xc>sv;eP-k`W>LY=~)?sJci?KP8~Cs>^lh{5!eXLR3H z^##x+^{V+p7SE_ErCi=PtrnY>Gkf1tLe;4COv=W~ft8o2)w6vnP@&bAA2b#0v0#E( zl9QPpqy_dX9I8eK;Yd`S_N+|p#=hC-Y*r_C$t@G_{^fukXFI7+UuZr6n%nMk_bFqC zz&lP1O5)Ct8mTUQq@Kg& zHb*N@LHLqslJ^iz7wyyp?HWdVX_h?ELLZM1^sbK%9eTl94e`?7lU^{*T1#Gf*+Ov> zDmVmH%^BYgNfNMnI!;Co7TT{>y?U&0N~o?L~II0n+{e*fN=znIF|Af zPP@$`B+;KtVkRke7dkQIA)6eb;Vi50+Zy-p`IhjBiLiSHbUUzRIG>hkiGc;A&sn;beg<7z4 zQ_^UuquIwmFQTA28~=Gth$QZ_mtswRh@>aBihQtWuBn0uUryx30`UwGj!u!pQqXJ^ zA$Yz;-{a#;w$yW&0w-H~u8Lxa^F$Vw9*Q?w{sIpmykNC_nwgS0?#8b9C*_^^TU{@Z zEC8Y|k!*L6^u`6h%?s1qf+;N0ZsJWvE)rnu58h0|M$GFkZ1%L5(*ZRnxK(gYeIb2Q zTh5qcEF1S9+g9H-+Bq{YFHRe@0=C!GA>xy@0`Yn9Auqx$d3b$%JLODa zy7k?eOOdpLVr{R5E;{ByXF1ffDOrnAJSr*VWSssVWqJgtNs3ACmQQ?a1U%vZ9raU= zu^fO`-N_gKKuJ;1F=rw8k16c|xC{0c%k(?QZAVt?wm?pWpr+){Bv~@kLJMWjhtt*p zBG6**mBCnB{7Gx6cl-CEK#- z>V1GH!MxZ{I>@k~E3lvq)(vK5pEm6rLdujlj3a?9m=cRkt#|RJ- z1c-~^@%9!lE9;A+DX(yrZy6Iy-{1LcH00iW+Q+Hz&0H;g1FBz`ZC5w+c~mN}kT!}` zjcSEOOn_)DEHTb7WdexMl-xLCe{}`sUk<%|(fw)4>@j4J&iw`H$w*R7SnOriOH(;6 zOTp~TR2=*@kt6v4l!(Uwh*QbH6Or`fF}uqFMF;`1fJ4Ie2Q3p^RHNCmFFf@*n8Q0Z ziABLYHNC!jx}5m^!QosjaF_+$T>1&R%LwV&PW*SV#_Aja$50GvVv(g&kT--#2$Ir6 z*u@EK8*>R9;C`w>F13C^Q<~#aJJh{g|2!j^{|~!Pip)tUoc4#ESeraz4t8P`I!%Dk zO^K&T-eDXNlT`aZ&ux454O>y=FWoa;A?sq*G!~Id8yHX98!CPi4Rkn6qddtrb^Ngs z+83iYr~(z8o=dBvU8aNV6hK$QlP{K~9cQ*C@3XCI9Zg+n`1E|s2`SKPVejEBoz5@u z_$Fu9E5fFpSw$a0D2;~}2&0jYdfdh zg|LWl&a!CODZ|O{1Mp=qZJTr6CSOs13o1IGDAhz&?ZR{|mHVJ9GPbbivB^%7umHMV z7R4_j2CB12JJSxiP5?=F(n(FvzE;qv41fHeDNva<8+u(0w%NoNuG%ID97Uhx9yw0nO)ba&sRLk;G%2qrMWsA%u7F5QMN(xN!GJa}kJhR(_Yz`Eh!;sFpbuUB5E(Wz+jvOP~k~r{r6j z&*H8wg6e~(sZBtq5D*Q2uuD7WEHg=MqreEGYXP^HE!^`9SUq6s=5FLeI~t=s)N%d%*qYjRrSIA8iqF31S3KvLPe^%9CCKpgh@Wz*A6( zCZK3{VjPQ~MEfT4Ta*AdL=6k#kD|&mDApSwu}c(P!Yd5|NGAcNkO02(7j&$j3)ZaL zL;j+saeL^diUplwz5cUh8kw1@Ie%y|pM{6z(?Ms$e|RHkYH*q|1LDgD^BDSJV@8!f zfLNqZj1VC<1h6zA>HUp}H|N6i31DTyZ=HkS%7SE92dR~a-*s2x>MnMRTbE5V!QN~_ zOED%%`)N9+>jEqgO*rK5ca!c#Dz^ZSem4c@OvS+WtpK|5eD z8~7m3ELj~+)rFgc0#F17MTG=b4X4@__S%A8+n$GVgKZ@o9{6o(uYY;dNSRDhP`lWW z-db<=^sx9f%JCw$ByANbWqWvrM03Yb&wEhq5+q&dAmT>Wu^j!Qgc(F%lcJ98MEn}8 zxfwxN1gjrV6fsoorpxkS5&DHCEfLGyE&sk8@_H=_FLYVxz2y_Xmt>ugP3N~1-bHwq zrMvgOxNEFua#7rO|GOytc&zp++KlSldFR{+m2DeF1fCmnXDr)uVG7)+=kpAJcU0XB{E@(!knb1Iy z4w~CX&3g@|ynPU~9Xj6?xAJk|TH||c$Kd|5Xz=Td6Moy3ZS0ekgXX({Y(bW~;6vs0 z(PH^8lRxAc3Xjr)zp^pq0Zn5Kxclb3q+48~I^h$8Z;kVxTale_TabAgsd2cgV;bCF=Q9ug_t!K}vw&z>kFIXCt0Dk{ ze$U)%tyu54^5t&xoUvel!^Z@a&=99;yMKR1qNwN)h6**%6i?<1O?s=;ONv}d5Q(rK zlYKNnVL$U6z{i1?{kdluc)#Po)2G+j#LBO8`*PJ8;K4F`dhuElnBMY%WGMKkYtlXR z9sTK?>MPs6G1YNWq`k?o|2u27`S#^>_0e#Nb798|x3#2;Iz?B~V=;HkYt1x>x#=qS z+fkEBCF#qoxUhlgJf+vA-qvc*uP56@|4Y`A)_DE*WDrZb<7!TEP@JGgSnrSCwdk$@ z@EF!)#Gn!?IpbKFF%h-LxleGnND1 zPPKhmgyrre`6rn8)L}at_w!mPHn*JCtCksRN;kgfo+(`ql}VGSntCeeHnAAL5o-1Q zeg^(klzhyX$dR#FwF_Fy^R`sw7=AXeYzGJTnjGx@dNk@6%-?suwxL8kVh z_v;xYzWtsv>^O1PERDxcyyrgs`Md1N$vn1aw+Vd{8E5)>H>pCm9sej+?zLN3V`3U; zM)A_e>_NrGHuTQh-fPuc!mwA4FF0%2SW~_JQ%IM5_Uld+dJ+H&LpeN$8Kg=b=Fa{b zS!?~sSdN+VoL55mcO%sw2)9j$vtKPN@qlZ6-^uS zpt{@Tf&qHufAD<&r!6Pr(&VU^7dH$-}eLvf6&79oL6C2M>J0FaOwfo;+(X;pM;q9Vg7 zD(&p+ztw69b~a|Ib~*G)TKsy)Tbs*XXV&9Cg<>a@?f)7Ge2}ao7HL8V07Jp2Ok)MV zfa=QzQ^ITAw6)89r>+}}2oU&1mUP)<$q-nE;E(0d1Rkr(=y7Dph5?4Md;U>Irl-=v zqBJNx&4UgPX=i%CFJ-4X869(ZXtmO`nxoMq+i65D>A_c6?8V|wSR^m`9` z-W7iD_9P{PAI=xn-$xx+tb`GcbaXyHzCuKfq-et+7?6v9*L!6f5H+#vV+T@dLG3F| zQe^eBG3v5z^+ITA{rtDeDN-%Rp!_7BrR~G%5Xm#mH-;@{+O!=8#@L-+&gP7EA-sg< zH3w~~v;S*t>KJp5fR(N&eAYDV6T$@yTQglbOBmj7EX7zanSbFZD4apP?JiP}=W&(3 zw>^~kPdN#B!PbT}KKsNZp&|2QRG)~@i}S_7@hc%dB9b>KQPu6w z-bb$aa`zWvPhk^lok(lv;^A)Sc>tS#wZSJxkYY~U=()1)54i2a0r{!Fd>3C0j2Zfs z;wcqTHGEZqK?eqCMgmHs8^{$}XDC{TDN+ZN23NA*b@`L#@;RbUFjSK!!@zR}K#Yaw z%~;hSgPbl3V6o@sCZI2el94*0J#YEgriwqOzp!lR`P@qrU7w`+1ov{y#|$a;W73_5 zi0C{9MD^H%%o4;=GyR_)w}#yN2yT~7!!r+UlbeWX9_c6QG^>f|!NiZ0qiBa*dzeK;d~*vRoq%oVZ#c@GD(f zwRTo_oZEh4U^GK?LO(Us*^6ruo`g@zzV(j*tgf2y6kW7=KsUUAeu*fIn|@Q9K#|kT zv%HJE-S{z}yk~pbLaySxkNeC`9wEgP;OQhHsSPMaqRP(`RofGlqQD|erJ|Bx#ciOb zW*^#?ddhZ6Q~`{IfYhfbXk98DDWJXx!iplPLLaY@3`G_CuoweP+ddHoFeb`X%>UR> zbqc7SK#@-ZKSmgew)g(K&TGc#tt`sLlgF?kqu1Q&?@L|5TY^5fQyE7EFZ{uZ-92aE z6cKoz*eXzpV5+*B_yY>Ui}Xo}^kL(BHFZ6dr$BuRiR#-uq8JJWL*axuAMI1XLg3G< zZ^oHfSASUk#(_oJK^Oo?g9*gL!D43iqRxHtUBo-?=f#|ts;+y0Zs&Z;zAYG+nnGN> zb7v{7R9twytmg=$!R!@H=~E^3oQXf_CxbPbQbo#H#r{r9A^KP!8Y*`YRjsI^^F&-J z6^rRL)}=};my-f`bD9=%j?AfdAtr6WHWXN@&L9i{RxtyQI`k>hk8k1jQ{~(!zjjYK zd`-h`pI7x6>uGu;Y^H8gF(-vrko%O#{-W90k@gnwR9VGFdf^?)QAr zJs_d>#)c_jEj=w2nq_t46ZOLT;lGl0;`86=QaaZw?8?qFZfBnFO*unJwLeE15uqxg z1Zxr?8bfv(Rw5dChW|K*q*-5G8D4Hh7-|jn4-wfi#Tg6p$M(t_C=Y$Q2iw#yxZv%- zYiW3?9dk_ObJ2Spv(*dsRzGPv!9#P#Bi#TOun$Ca+j?KKFJ?5;*Yz|#u?GCWei51T zuG}_EpoVY<8Thd>u#D4QxjHp~O@lD;>H%x7dx83VEnBQ~wRfK8h^N}V`Ot-BRJPxG zbrLSX(x;L?O3deyBS+W;KVQhY3v>$Ej5Hnc!k2#j0a)xO7F_%HCU)4f5DxvvG>OQ! zy!eoH(#pBIG5_hli6TJ8X!;)Xu5;kl=fH%K+pJEh!{c+ThGiTzCnBjTqc$<4c5!~1 z5+|ds2`)}%y(V{o;>+gj2rh^sb6ws@kK6baf445>c*B>z@pTD=o1kRZot$8Omq_bw zZ`0MQ?Zf&}l%E@|3UjOBVoGM_W)9$U-K-Vlx@(sqcl5FOo>YOH8bK~e_1$|pJNHQE z^G|XMwd}H`yRL&_7hr*u)Z1MYnV}xRyh_)&&kw);r=8O0@~~dzZ|{S3kt8xz zwR=E$Dk*8tmtvA>qiOTbimrgb+U5J+-SVuj47?3+Qe^tz0kl)?L^Lx|W+>}ZIQUga z{piq!-+4oQvg|wfXE8CbY8RyDp{%I`*zMq0l%kvKAClU71KXA#I9td$TRkKnY#`dy zBO23tPh^x5kXAb**YVprl*3=)e4jFcs<3#WO-;B;?RS^Cv>aG~n9ADdyu$Bb%e`zC$=M>9V6dZBM_%oHKt`cV{uOui^G z4D{E5UH}kq*`VcuExe;Kg0n{T2PL{4{O9fVR5%!)u(?neVAB?KgD~K`tMJ}HSpDyM z;o#On!k3Sw4t2%rZ}S^44B|g%cWs6^?^@Yw-@?YhkeJYrtT+~jE`@R?hg!Ok8i%N( znPH6y_aMbB)GXLm0UXcEVYD#q5OI8BRQuMiC!VtH#X=I&9priS>TkZF$PbM_PBC{3 zCC7MF)XY4r1@Kk92yHKvJx0v_r~1%#(X^aY*d7p?vp$&uO z+LY17f08Y!kPhasZTVO3TE!%v`nU0~f3AM1J3n*R)7VGB&}Yh}^sX_Dkk-U+3FT&Q zc1v30uuK=SXr>J-Hf`uX5BoR1*8Vok@xbU}xA8@*ZQJ&NG7hM!8F;o9mq5%=XkS>( zlmN{I)X#!&g>s0qo4@%>C~xm3DP9<7-xA@&@BPVxNAmPY;=yZ05n;g1m121AARQe#TW zO##&yLPs!)NPCa8LSOfKqVNUiWe*jpRG-wo%s1 zGMqdtmfm|t1S|&!X+{|;$5Ujwdd^6K#Y(AdWU%IHkFu=+`#2Cyp!R<4H7*zP`LkMc zr)BES1<=ei(>Ut)#|pNdPJCsr2PSR|Hl|fu!6(5Y!uNc z9*Aw~@yhBI1oR0@8YsjQaod!$D(Q7y5x5ml!Ih%OXAYl!;z0VCzH|`JU9+FQSN~qH zp1k7f4(~g=(ks7caBnQxqpl}k6MRB+QmRXof%FMSv7to_m70in5ku5G1bJPk}iTd$_#*~IsR;4hRSkC1U;RUx|^z5 zFCVjQ8g7V5=vCJRYjpL=!+VY4y|S2I`9it~#^`hx=(Gbm5guODq-H*0P`wvQ<<>gd zJ9cwag-UZm?YciGwqrpqJJA;aTI}c5U#ODnZHj^G7B|DkRe+jcz0gJHWsm ziZ_4y!5{Brr?4uv0gF{{`1@4)XJ0c}RAWGL+XiZtbTy`d$yBdORG-qpFL^k4S!CF|%42i7a3`mL_kP(5 z!`gyCy;*R+068y@Z>cX6-yzoDTuYPh|0sf?s0V{a&Qp|5mgzCQ=$KQQw#U8b;J#8u zgqw&Mc6DPLELE!)URoF*az$zjG9*y=7tn7dFDQkvWk$N9aiWk1--S&#a(rKGg@ z`o!u8{5Tg!6YxLmm#H>TRiJiV1fTMzbUkg6*P%vkWvRjMN`AXS(mv@s!d@^sA>$ zI5%edW8_hEsnDM|7PWRz+4uby`PWHh*A;88huhZAIkkNi6vh-v9eXj~v zpwYXd4S7lZ4MybwzU9OBy_H9|!#5fhEiE<@ambPY$HnKxo|!6ue_tL6ehwU2%GJMA zjFf9`9=Jz#d!77QW1=YJ=;B*_$7)%XA2a}Ycjr&tR)l4kL*K?b&pWtP=Jzk5HIujN z|Jkc&D9s1|sFKPa|F`gGhfB~=E&lrNEY_qxZ&_oRoEyh?mp_ARg$azxA6wJ)PP0u? z4()Vt^^hlx;=!8Pp2lf{xWISPIFw21OoMsklTnw)fit?bjdf!TrQ34k!LAhB619ty z?L?IW3jy54C*eQXX4CxN0!*`|FLdSw*x$1$SY}H|3!E-*zrm#tV|!flBv90chSX`6 zK9iyRz=h8|XLh*R{r-nI9j9#*QlL%!@+M#1h5NQZ76FlVe{!WWlvmZv-plJ%hNyPr zCNsk4b%B!KOt298%&j~PONcC|uz4<4kmmT6A>KTEpZv=4tF3U8PwcOMs%|miVV_jMX|@RMPmid2CQ_^JIpNVD;y&v#*EXu++K1%1_A6_)yhFI=so$r?^EdA~z1i2D zZcOc{jpACkc0`-al(H9#>D|AXIwl?Lvb@%~t#gLfhJO%SQl}9bB5Bfr3{q8r(?O?&0ZYX3_5;2Clr-+Dj2j;w z8GmbwprHg5Ez(qvAEGBKyfUMBpJh0ZtGG!16+Wi>m$&z1S-I~wwV&$9-d2z;dPfr` z)7$D^`ZTIE5Ab&wMn23iiAYY@NvPnlflzro>sT3j~F z(Q$az0qNo`?v+al=Gjs_V~)(5u)jGlSWLn|pPV5(W<;60mN=x8gti~%m$YJZ>?;hb zR(y*{XX06vgY4(_`JKYGYSQfKcj-@kO|PpfvFpj@xW{}to|G;!KC};-akaM`6eK5| zq;ucc8k)By1-mPWCs|Dm3SO$oFw;tF&i3`9?9SH<+Ro6Sg%#<`PcPxwp@rhby-=qT zpY&nm`-rPjnvbs}Th*TpU7H$2TC6&Q5w>kYg7e{OBOP0H_qm+38lFXLT=b(9X@806 zFkjCJl}r^dCbM34p)2|qg=35S@|#XNrqS?XOY8@uv*ZSzoUKQbXI#H(-Q9%xht%Ik zJ{}y6Sj!Ei*csEkZ7YoEKJ7|_NFzjq3EBfxkyIFHYc551?R2TlC749i<=Y{Op!`HE z&w_vx$j-RLZmPZCFj8e8w@V=zXvFEATa&tDXMKDm_$}kX(t5sH=5A7kp9$-rQ%1Tu z3{76eOACiKDoKZrBz(_iTV}bI8LHkx^T~TC9BwwKlpm3< z(gi}1!)dCiKu&!TZ_bp2L79F+hMjG%aL|U4@+^VFqq`?w-|NoqWiNKmgC5TQiSxEM zcq=}yVdL~HN@%+IEV2Gn&Nh0V)ER9m!wE_1ADQWqOd>~0 zd6H-)`Ib*1mABP-P%O&iA(j`OyjF3{rZkUX5$yD%c{Eg1oHyhn)%74_hYXdYvN^O( zsGP$SLrQyyY~A$btBEA5Ka~O;Z+na!9k=t1+8CVr+n(s|I%>~)Ij2oJNaXRNVS6U| zmZc<^YZiX%RO&9PZ627v;ADODAOY^AAR#={ZK&KyWc82)XMY1ZN(4=%k=n!&xsn!A z0Sqz!y9y!Q;f4y)6`T&$Wd0kPz6v|xx2Ow5*Kj8FlxanCA5RLpx3DJ4K>4hK=ZeUG zOhb*WZcDFivS0xQtbrg}xiKq*|I-|l#x|#`B%DTuk_Kf!z;wxFyR&UgRCTXi4lRWh zksAbKpiOg~8!k#~<1g!lStD+8g}SIR;DZ{{lv4|C|C&JLqYNV zrW}E~o4k=5MZcM?Sg-WnJn3M5Hsn-+$KPe-C1$@vd8gPu#MA}UOb%>;r|V8s^Ib0Q z7li;h&$=yhu^f6S=0vc_i1n9Zsj%AFPJwEvu^VuygpzI6^ke^?5C+Eg&T?t zce743rKwk_O=jb_ljWxnvoU3UW$l&et|I3-FA-Ky0l+s(M!_4h)6IIxaCXmkzvrrkL^@Jf>c#;U?&qVkp9oqKems)LhV z_H}lB`&>I(H`Y{j!1xX~^?TeWaiJ?j0*^(}&F@~5A47&Tu3d7y_50IL9<8&+mb`cW zl+<=cnG7^VF>O@Ske`9tdV*)75_qj&dV0m!S-LN;M*n?{_;#6fWE`II z(~@rUEC+n7Jv%*?4GVXoC_Q!EJqvizsOE3Ssi(p_Q}k1%^@Mirdh@pL8fUhW*lbYI z6a>{7H)>Elk9!=wVOSF?S({cF0N1-Ro3N|e>2HS%(O^0K)su6uk(l9-cJ0Gei|iJ` z*p*%HXyOInS3AnvoqL6Hmb6Z*xFs3%Z5v&6&ZCdM_}XvUt%b|YN{@O{mi*6LbyIH> z(#-ID-dF{fT4KAD`ZBJKqo}ob`gL9Gnr~=i@wd{?dcO|eB#K2<9LEch@(zlmUl~)z`|af`D&(S|zv!>N8#06Kdgw{%SU$XdlW)*I1RGZT^LEJ9KXXfB zS3BO^J>GeBLV_65|5eKZMj6B!D_4dFtKKzt=lOQExR_JrLF5VkS~`>QO6;)tex+c} z)4yv<|HY1lm3=Sz2KBk9{PU@XJF4ekARX`~>`zX-y35XVnu|?D?w2)Wq5hkhd%dB9 zmKTto+|O4pg4kB0$_@rJ{_SP~Il91~zFN!BHtkLw7=KH*rYL$W&-EP;wWjf;W2bM! zp@;bpF#nS2zr(j-fAbMu{0|S0)-s5{UmUytZknPsaAh4NQV;8X&ldbF0=}%azOiXzMU1Kwk--%*BZh#5 zrp3BS>`i?%TqCG;xc=V8HCJ0{A^QqCl$Rza*kS(pF%oRR8~y|DHMR3q-@(Ay4Y=0AEz2>!rdz?M4V2ZbK8nWvinxTz=Hb^R^A$D=DU$hIn~~XX`Hpj%g|nJb z%}VIUc4$s{)bnOOY!7-MLd0|lW&f5BOGK83wNA;RxNHTJmXLwsLi2Bt>WN?XR(>sq z6(X>kT(zp+<3herVR#P4d<9cqvA35YjA{|T7d+yqK&ngBO_9RhSmOE~&h3L(ay_@i zdk&?U^NrGTXz^`7oG6c16iNs3b8V1ZJva8MK1YpzRu4l|^m2=vz!J$a-w=Z8L{v_o zDF+=B$ITyZxyQB6KeCw6iMiuI=Ja3UH3JEoc;19_2pf^P)*~djeAgk8816x#93sk% zI<1WVr;HFJkYyBeWO6NBq7(%Aj1(ah=M*W+zm2#LIb6v-k;fAWoU`4WivX^zZmt~? z2hTgMOb|DUj~lee)jqyBIi|R^2l##(vGRyhT^x|vBLDyjfV2pK2-gNHBsRy08R}_)0@PFwg`w$aU=qW_U<7>M+hZ}^J5c**fzL|clfbDR8&Pu zD$)HskRKr~WRl38M0Wcfz}McVl%D=$zCWV-on&2)a3&E^u7tj)Bn)0e-VdLVZpG6K z1rWB#i9KjCS?CGjCJ2L=Aqd(M3G=%s5I`~`Q6(!;0V*lR~srbmw20&cqhA240)kcAXj6e z;1mIcAae%xAa86&mnZTPD&|!UgsnJU8c>BfK%?sH5{W>WY>+4F+g+>dE?zJFFYgXr zdpRdCfb>KT0-1mR7VlK|iSNhFb)P*ZQE;9>0AWzYFoeevR(Oi|HjJO6`P_o)KUkE^ zCim$#M1Eefwhd8WhoGFviijqP>I1o~$o%sdVUE`#>OlVSiieOTzFCq`d?IgeVrl!5 z5R)XdoxrQ^|M*;Wq-#dD{_gak7ys`0cc^N%+~rq!#-S|+`rl7m+DA&gAqWI6v1cx2 zQI=cJn_^e&OHD+ zdWrMnqUO&8^k0%-Kaii9aMP_)wN=t3ZOX$9B0rSrZj z+Fg|&n|4-PB)MF|<;ro&k>5UqTRUyqBM$QfJjvXDG2Gh;LPlh6H!}OgG^Ys=xtPEW z5$9e7@RSi%3&a5&SJ;`|=VF@(rb^%9n+WpzHYL?c4NL4h7@1B0PbU#IqlTbVbgp;v z$1m}>Eun^cJO+TmKQTy?C64?Gfv8;6JeFQ3j%0R=j!}kPDetTM<=qm0da8K_Ja+VX zEcX#?d5Lc0-h+&(U_b8cMwW^rei8(`%LOWzP{A(G%ci9HY~p!p630&>oDM|DN1 zJ^FEZ?V-wb?j4g>8!h=C{Wx*oME5qb*i)deEgn@#lo(y-jat&oF+}ZG1snAsqll6z z73k6)!D=X~d{m&^E`G;Q2b7uJu!NkSk%^WJU5gG~Sh2Wz!OMMxKUiF72Gf;K_AW}~ z9RhGM2*~^jPIWcz-ZYg@dAx2!g8Wsr2!TUa1C$BT#`uk2E}MUdR5)T;NW`$C#msGJ z@P+i-Am^3#ZYbY7E5iBkxdRI%TeFEpcI*1$V8z16piUlem2xxEY^<_c*&p@Y(Zox$)bnRw4#|LK`V(0hLH z-ntV?y~0%xFC3*z25)~*22YaSrk5cIuQm6g&o zJa2sx2wjObjbGlK5w!4EH+mg8-jO_`>#rwU^~v@fxFMw;eo`w*pK1+soQz`ru~IQDN}Ym(x^ zXGuIF98T@)|4JUisUe(i$qRAWWXDSVoRQYdt2)4zFhDvC>oJ=fc87mmmv>5?_YGQ8 z-P;+*Z6U1RxJR~E)5Bt8m0}C1?FHoA&2v3R@!_chhlOt+N!{pClgdhEIV{SZ&}mdq z;CGY?D*UkSqZoIPGiP6N|MU<|83hRlPrX9yL-wNEh3lbxBP(hbcWxZ z+92WB*!zK{;#w%4pdnhD^|Lm+KW!Iu9=lw7?EdVrrB2|B<#x|MAFIhi<>FCUvo&v^ z!bY4mC9}o$X1o8mbH50OF(p>Tip?5&RA#ksbrq@!70KkHm=BtDpK4>G<-sH;aXo=-bb_*I|at7{K8iwjoX0c?8I&H98)fKS<#`;FuK zkIlRKt^fAh=?>VqNpiduGH??%qsl?gD|?fL?!N7b(0z3!{#C4Qj|Q229w2fpeuzax zm?*BeIGecJ!FIi3`0n4~D@y_`-U7bjUkT#9M+7!iQ-O}I*U$gH?$I3`h#wt}A62Yi zpG@Ed0Y`VA4L#T$Thbk0iyz6pEr{F!gLh8B^x<0oaGPu>>c9|Cadw)GTc3-?8#iF#AU*Qd;%PnjOcej(@%Mohar zpXOvoQ+XcRovV#3ie)*PiEtmeSBkYG>rN$bnkl)idGrA5dhhSW3!skPyzAyh*e<-&TLj)%guYmOaCiPK0eM~=)qH(nZeih?;reX?x^n4%SnAvD1#2fPbw3mAeZhxa zS+Z$jV^7;Wy6X~;KMe7@{$th}<8e?R=} z7eOC*d7DvT_+(h|NlDPB%s-(%ZtV&Z$ER%KI%4n4InA-zN)pO&lRV#=c)A%OI|uJf z9dY`qhsVIxD<2cChX{%&J#r)W3&aO2iC)n%^Xn7t-_QA!{OtC+OAI|=ed$&)w241a zGBn9G91D}-P?8_1H0E`O8w_$2A-hy=)%C?erN)|#l`H~GXf?H;-=!Mg3;8bSFw6S1 z_-f@HY>jdK(P_!t{<_OhUZqO$B!t=wHi;{i8M9X8&lOOeZ6;mhn|gz2{vj{Qg8y^K zec9O4se`4LlX<<}as~^?FmVW1qKMa8iQYekfA|fkP<>XeL9uU69$EVTQFPaTO}!5r zz}FkF!RXPWM-K#~)QxWGj?tqOkP=a08y(Uujz&Zo5+Z_(ZUsR~R7yoezkr4Dk%#9W zIKSNIKCe5@^}c*>S7~+z=8v5koz8SharPa{W@3gQE%hoHJDGT*v)6n_)HSquWTWDq zYS)*k(6)hpI!9ul;Y}=WpH11HXJfO$~x&*QZsD zT3~O6w}@l=BZyg_L*dxnwOh zuAlg{_;B;Xhtr6Wd#d)gM?a}1LiDrG6k)}oLdiWokR0FNC!`U%cxJMNT3CL{Cxy5k z)hX4kqG_w&ZV+v%yQ3mG9bjC@}5R>DXLwqafhaiaqYRqY*`Y9b!Gb_$<(qSO-o-vg5 za+5tVX_&8`kgCB<=7^hEVSUHc=QtWoOwP^tzwY#;kjYY~&t;F3m_5bDJ$L z`Z`1!ayV(b<%8P12Icz%X>m?G-LEFFw6FLVOL=T&$J$T?M?1lC5UN!l$Y?zMu+N+L zKZOSj10lj-|9E+dllQL_>;W^)zIhb$UEI?pX_H0RZi{yu?diHwq(JKPs-kS3{zMc%Z3jc(ePSS)PdoHTw5dG6excYc1tE9xnAO&aSbnYOs8oiRWo81b;biMw39cSv%1)b z>XT+KCpABn+e~9=l@nWGKs6S{(eXWC(Sy9SMxEljupO${Q-Xo!1`v&N2oWuray%dJ zh<-b?BfN%25RV5rk^m#F%kui?lZsK!JrvA(7%fh$%8+ z`8;|#f~cQ&2t;4OfuK}6RYmWzRjs@ofCB6&E$XzgndDV{@uc>=BZ_B}=W_T|P|w%z zWj_eIu$Q4fG z<6GUs)RlonTUI1ry2zQ`;8ZCnsL9l99pomp=iRSeo@ew)Tuw9<&5~-F;Fg7#I^_gJF@{IqqtBcLw6ocn4vU18 z7*-EvFX`>9iu`3jmBMP+Bw9b(X#_HJJnH__5BQqfWnvtW&Y}>jNvXAkZE8cIuu*lcO(p4^O zN_q@Oi)CRLja?Ao;wbP^bvWN#YuZCkso@9@%6LA__fQKe-D!ngb#2rdVvY)mKD~UJ zeZw@JsgHPT(XBEm}9YXljytwT1iAp@!0J82q`Ln3%%A`J8=z-RzCdgm!KE&3YobP_^N zI$PY+9YN*mpDPR?{VeYX*IkStQI+C(jIvbyY3rV#;oPh-m$lv^bsw6lr zZ5ZVLH}vzrm>cJGY^902NKT;kP9|_yKR8c4uf1X+r2BJ0=JLTtOR-LRkxU1YL(oZT@6_V(Ch{W& zuo0O2BUtaFYnRi4<0GK6jjG}Al2m?1S-*4Gy8`vkyXw;IfIsUI%!^2-J0$^}g6WVD zJp2ZMCCG?^*P=)woT{bF8;i~2u?T4#B5A`hnZX?$Yn0Y4_s5US`Qt{iG}>fLU@{4% z!LQqiMUFM_n8*9q^8?aKQVeixF^ws1=_zJqXccipPlRhAIW@MCwG&{7IHQt?g<2+^ z<=b`iN>%EPU~xesyrcqKUZ$1Duy`|I%ST2{0M_Srrl);#)g+}#v|-cYLfEXqFf()ZGSN%3#sa^3cimM{ugfCHw#SN(Sfiw+x~-4blC1nn(39V~o(uBbg$K zzj>7OwvpTj;JTv;`bK_c0jFG75b~Us*GM$Wy1vtuGB|}`XBvfk$beO%6)tEdh91R@ z^_=Fa6*{&Q>b~-}*l1))CT_k{c55&P zx*Mv(lXMg?N&r;DY91-vSECCOM?Mmldt9R%LEeV=nv7 z8M#kg!HT}(7Ev;-L}VwH)XB8vi&6x<6f#m{RbFE8u93AovGYx`HTu&mRk;C+H;AH} zaF<2;bNFTc;RbZP5C4bI_1V4E-XRM5C@?CHW&%X9YNAt65nhUTJ{KT3NfGNSoX3e7 z7%}~x4>vy`Tse-q5-Twj0T0c)pgJj}XND|gQhKTUdKrZ`SPIWf!c^Y#UOj93xY;K1 z$ayG|HI@$hvLdJiyv8CerLbkr^$4EBAO;%&kr;mb9 zK2qqQReTtR-`=>i*~3?Ug|AB$9y16xk%Wr{CqH$xP5r8cYG7@r@Xf+2O`^^XG2x+f zzr`l64=W0rkn3RpKVU@8r|)tuX^PJb*eFRi@h8b}Aj84D+!=dZxopJZNrzDgX#*Kf z$qZy2z##Z#Y&8QJXX8@u)T$Bn{Sn9BdM?5B<)mT@fOcd8@sSp*lA=urNK(~>=lPG+c zaor6l;z}n=H{Q4@51;VEnKTmE77=*i6t(b4PmNAbG0d=pvBnW#bf&-4lz;vr%d-gU z=MPy@cUWI+z(-%QRIZrml{t|!8-cxzrv|QhLjcau%6-()BPBrK*dd;w4=dB?DlrUa zXejeGQ`TTASDBlyc^AG z08NLv%(-hhgvG`XlqJuUX%aN&FWZ<%J-UhvBUPmsAlCq>ksYn+In*+hFAlGja;7za zQ{e^{Nh?H7^|sEeolEIJcAsvZdXbB6_m_H+Q!VK1GpsIH!zY?)6+G5qHGHL5cr>5l z3auj4PE5#%O%Gyi6{ORXFLBUlH%2I&hG=d?>T-_7*_Nk}R=E0^7pfx#~~L}cZn%~cDPHCPYE z@`Us?Wj+>R+r=O3V*IGZSEKmHlHfONDtJ=79BFJEf4YWy z;3PW8U5wr*?cRA17kYCX=`mintrv{EY6C}s<#fxlIDW;Y7s4JeHOCbm-?SCDSgSh% zU{(B@+i-G~{E%DpuTO#`u-Cyoeq@7{jBdNm65Hy-cK?%1TqN=}K=^YZ?0>k2$Z6cz z91Ar|7GWZ~#ra59_95Y+&>)Fz@E&wTm-UaSs0<%+^H)2cT}i)cb`elG{xK|(WK(}E zRsiI^ofQ1%k5JBG#~V(rk$l>gf<#56*oXt1&eU|u@*RklVkV*H=Ddbpp!y1=g3;Ih zjcUy%jF=`Or<2&OY+N$^J7QCXoMW&gGLXhqBf}Mmo&d>7&9r!cb%z_@qjCksMy)Yg z&M=%WX%5x|;Ok1uIse|zP}uiNkC)z9p~NN(h&}@nhhLisapj)Sb09p+fVw*x5>p75 zPOuRXB>U4)xKaT-ao-4AwBq^m!!mq`f(CX60e(Yslw@BErTo-)gQ&4+l}HyAUfw3$sUR$5w?t? zf;JOdvWL-W;oq2<)O?4G^8GFo3E|sJ*d+j~SBJGuH-L&Mt4}M~B64=ud~0 zl7tW}o%d?=qLSd)MPcY(cfbUu`+sDe6q>*lo6L5*==*k z#;oz^Bsi6E^?St15h}4kEt`=S$VUB9G7wdNT@C74nT2Q4^RW z!!PAssQTQkT^ZMghldhYFjb->k+)itxg-nZEVKAW=vpWBvT?v0Ib2aMZBU%|Y!KF# z|C3uwk=q>bXN$$Y>vOr6a=Wls+%w)xO{+6>Z`+}Wam69{%|ph84rV#0Z12~8!4W_Z zWC_EXy_rn3bNw9FLx@{%?{xo(|CGY@BmNeLADdw)Ji)8P^<-SE*@tbBgt}VL{jnDr zvH@>05GGwI>s1)RRLV@DSKetld_kgcZ3{nmn9i%(3?FVe-shFdV&zgO=sjX#H;Bi>*QJLBj35i_jnLWyX; zlm~ZdICIGvUPM4XVY0PH6nAd0xn5&?8o{>7scSJUUQpxFvjK}cxF~ZsW-Nbj{LmtM z)wN-@bLx$F&8Mp-0$ll8N?9v2SHH1_Zomi?%5n)N8z-Aq! zHB@eDM0#m`^If9m@tbF93ef3H#BxE^9Tr)n1CXjkk&nS;4(gaCNd z#Hp&1IRuSj)jPeacLWhvAaGQCa-Zx=Onejmgr5@2gjAZdl>9eer1L^hl1uu#R+mKk z7$IltM-B`0^6K5;msnJafX~PxYI=jEltcmm6QBt!+S)h zM*D{X2A?Z(F6wWJg@2pZfMvD%Dw{LIHZ&=NNAA;0%LYWVKy#x8RON z8zKB7ZEq3h_`u_?4zJ_hqCLIUYm{|rq1o1Lueo<`a<9?CU*)z@rIXT{H60Q@UyxSt zoRFNz%DR*G-0NxL{~!Qimk5#u6(y8vW_RdYHl$o5u4(hozZidWl{MI+Ln&x642t0E z;C~e0opaaWu0ZM7AUiuIsL-Y8!90=*Z*1K(ept!NY)tS{=PD-@2uUZf`6K|}7ih4LNRPrUxS^$GFM=BD zNdOVoFq1~XYO?F_&dlqa*Q zr6K*XLD_#5C*cDB9Uu^nra53DjUR89k)k?&xGg7%Tk~#+N>6C`#+DdKVcn2a_GYuNmk57ed&j+W`|1FW5|1ZWr+s{;m$yOQHaS0r;Fd!x71jWZ^O zErWPgUENAzN(RoxY??}K0mM^H&-r{ddbQjOq;Xg{tN&d0JK7z=q&fD**I^{HcwTtE zxjli=!(HXaBx=7%ISKHj2{fSCZY4KX*xvt`%H?3si%oInQx9yL>j{s$c=z6e1PO16 ziedJQqQ9mV{T))fJlZSqP-k~@wO}c&Lxf^^(XT(F1IdcQDX6tYYV+%fhu6YQE5~mm zFg`t-2E6q#pB{I)s&E?aa&yo+Uz@(ZK8oT|2@vtDCJS5=2ySUNHgUyZwH(zZ{*Gd_ zahzwpIL8C3>7EqVgdaU^Z>;9@UeKlMvc4|4Tja2)9dWUp^N6VT`fVXo=FArtTk09I z8i2A%&xihtdp$1p`>*GMN9EqVmoT9~hh8+NAJ3(^>hN5?Z1-JX{-^QSryH6?&trW| zV$ZNj2$7hph&o}9ix^d;CIlzJup`bQ*T>ZUN;Z>whm@I}Y>`a%^M>(rs zF`7MDd}gTbYy9f8%;yRddbZreoRGhTnY5HqHLbCZeXvl~U~0&p|Is=yiO8B50qx>@ zC`z5d0{yv}i1m!|_`P{LJRnugVk;|`CKY(8XZV=aqz=$9QvCWALTrhUArRbnp$R>M z21uq19jgJ_(o+;72H|H{BpM#18!3A1y(l{x;>*aFQzDDARllgUUCT@PmF|zSw*6Mi z_u1}ewG>jfic#Yc;Q>p3je_*r1FU-$+KjiqJ&1toV^5?l1DP~Y95v64ddp4vzO=?3bugf(MA*889NVtF~zs?aM88emc!a&zJL20FT=$#Qr@4 zs+%nVs5V{Vx6BmVs()5nsRO(IC2(<6u|!CY1!m^aj^v;9kB~eJw(>YRWOZ+@mAROD zq~MV7#@V5PyP6s0UQfxiix#ME){1muL~Y?KyVxigs08Scv=5VjLjKrR5hEZMPrJ5? zm|*fIzZR!{0b0djsS@L20t3?Nn*Q-APBC=B5mq{K02e{&2^$GLkmK+*6E)3>_b)` zEkFA++v^%~aL#eB512Z{i2ZXv(R&4OiDjo-u~-S5;fA=tg65c7Z(hsIT$JNkEto{C zJ4`NKLI5f^VUU}wlQI%?XTz8ywpZtKx?=s}?vQXt<>#4`0`+ukOAl4pQZQASaZ!3O z;v!kTuKa?MoNWgv7M&xWPSUFLvRreVx8Biq-bgO}An|UWRIEa(-{dh!2r$BJN=Ct- z!xCK#c^GsE{(zF}4AwEoIUHQzS(gHy8uoW+$~n0i5r%fXg@h=XGxv8gkMCCaV9>Nt z4Qtn=W&>NZTEXWmk>u{d_%oc**&4Vg`%B1q6^|F8J(t@gs>^2O+l{iVqz3cl{gY6g zXsEKVIBRoH#Ron3h=sVJOOtEBm=wpfmoS*e|G>~#;=)zeyAbJ2+d?y=sq?PUo4n4w zxn_*V53+=)LbE)as*8l20GH-3gW_X?)<1M2f1I>R8b%HObrAFSg-EbClYy%fuTN#m zq=SYeAvxYVSV&hgSJP(Vk8<@IuX-YSYpw5x_SRJ^>0skCKi+xueXJqTbLFhPj#lTb zvzJW*o!XkInjtr@t-l5O|226GZAYBN7FulP=n+7Q%~WM_GTbz&n+qgK0%@7z?6uIv z9ZyJ%6m|4@nN{h-VNA|$ijGZd8F29JlVCSE3+&{=Pg(K$Xa?h+CpOsd^;Psf4D$pt4>8|3A$M0BZwi zF8HR8oTtu`F8o)43i|eeZY{Te!AT$&L?b>W+r{9SkU&8>r-%N)XmUlw9#nk=c&dI0 zGl3##kQkN<&L3FYg^6>ec5Z@SF#7W>M)E7qUhcriEMj~QAllf%NLTQwEhXPawJBu4 zxFH0s6gL}L5)M}4^Ehj@V9OTzTBzW#kXv(~w^IPB-b16}v_5lZ6k!FO3^+`6|!Zl&WhZeRvPI zs5RhgS&oxCN0>=IAw-Xf;6a3m_OK55XDmDd+Ig2qnl-kHmm*R#ZEoF2zSZw5a`tzD zHcmI%(j-R<3i-{g9X}pFLWO^tqz!`!Yfp-hWQLP17$YU% z-drtWZ}7PT?aKt8B_Pr)i5wZG8J2vfW3F^ce?^RCEhb;6n!;Vll&)iW9IfU!2XilD zaZRtXXQT$up&pDB+YPG997V;3YPBL0sh95+K{c+KjOHO|tVaH#M;zN!$=>VJ-s!t(h#=z7v)g?n#S6Yt)1x(mU40Y6 z&BPONwDl&EvV{a~saum3K|o%1N$JkKPUz>6d>i#i2+3>3kPh#)|zRg*7>r5b3F zkVK5Kc&a^#8o5aoGX+V{f%NDPY_2f?8_L>A_tiE)%BB!y7wVEPb#3j87DMUPl!_X9 z?p!EX$>rH@5lD-HmYBp$ES3emYNj%baT$+wk?3|0;>n8Dzk}Jg5W_Dc&&2Ta+~;h? zZ031i19@L2JDY;Iz5~S>Ks_5{v18!2l(o2NL$3k9E&#f;eL+Tz#g{>~&`KpBK+-l8 zB__SPQ<>Qe7M}nLO(bI@o{E!!A_zm`w-+kk?ZkHNRHSXU{~9RGrMIqYoR|q*P>TfX zk!xkI_7)|veAQ+-Ny^|jmn{s)4h$RXrajx_StLp?>N}(;Xgw2Fq6qI!3F90#g;RDu zYOF`J21>Ari#(nzTqr=N+H<8^p+V9l%3-ZCd|O!$LDRv5HhC5>cs>63MSaxbrn-e=+%(1&YdZoCw?u9t4J^DY{OzRizrsJ3Qkw4Qu&NwuddQa75expUOl zpqK7)th+c3ZY&VifkLLIY34R{benR-suFEgc}2gp*j0&1QJ4eCk+tRKKr#f75}sm( zpvm`9YIz;y6)iPvs2ZfTM$fg?ko(QWZg*qA>T{G2Lv9}^7yq}l_Mjhpb_Jxl;w*yz zT-eCC`I?Pk0Fop>k6#2iXMu!p6ba@tnvu1L#xsHM$twTN2J(z3t*m{W0{4|MhBQ2C zwAgHVs0tHQTO1qbwRMhRH5&}HovGFifHGGy^HE3<1YiS#oWM;UlV)Eiy-vkhNkCHl z4;ZH~@FhlS{IqHglO26EW47n6?|u8zX{(txeS!mfIilZeO265>orz~-bIhZvkU%m< z)N4CgmTa_E1YrDo9RZi3@Db}mnM zgBT{*!*;1P8w-{rduia_T5o6RmCfvv8{-OPuS}^Xp1Bod4_>v}@O?cHm862Vm?b#_&OdpkTH^8-`hrlZnQq{L7x(O+YyK)~ zCZ2vut6r(9LxlS(mFE%Wh%%=`1>QXANBdxk1h20m>`ifZt_dZY)gIOH0$Cq6FTNgG zaa8=L$Ds-{CsS<^YA7q@*F&5K0;%WWBt~{pcaRE7f(5xq*(Ae)nLCzC{^X4v>o5Mn z5%BP&R6jcHHBmD7c$Dg~uzZ~2&jb@q#VnD;=QSw`8zcvvS5MJCH>HM!3Z%f0$E$bs z&Yx~OOnV)i-W{EOSy&-8kqtbF@5OF#|2GPhBjgTV4Wt2zzLhPqMW$Y*f~ja2IpXza zv%t>EM}aaIUGn?>eFoW%zEh9IU!)`Q4pMv{i(fQX^P)LvCX#-K=6LGatZzfEl5FaTHlW-5}F+k9+6p4r9{9!C=W%_4(OgbA( z^kW+|`UzLq17);RZ)?F2R`2&E3rHJObwrhWLhtB-4U@DJkV1Y*KruUmJGYCya2s>l z2tQM^(VYvlP49{@9QAL%vR3f!%K&ij$6HCkhukntMtkMb`5Zj#A`WfA(n4$GtY`Cm z7U296!%~0V)T4*&RyLKBv_bEIQtgw#0@|r-xH_d*gRp91z}dwFhbAM z3GU#POZggFPl5K^PXUniXP;edp=wyo{^@YTzRFJsh*|`c+fsf=^$W8H>P5!-b$#R> zfwtv?r99EWyPx;i2e-DV74P++8O0h^B7S756q8cz5DW)HT=PQCR`5!&Hu+9|USl|T zW$()g?#-qOd6(6`9~=Ewa;ocdXC|crWg}$NQmsgs0oW%sB!Q8e@9IN^Br?P}dJ+$Dy@0G_csjbl~g%Gh}0bU6hHv8$yEpB&0#J#e=P#zy>&cQ zQ%`hFUG*5@7Z~Q!1C@RUV9@@q_-Cj;1a_9WJ(zJc+Zg3VhsvKlZ0?IfFA~DAr;Fqw zFKo>i_=?vrnRW56-s(XPwmn`uhz{kp`we zjh;KPG4djEzMUh&iSBc$7G-yG4rYv>mw9W!&K?i!{Sak{ru_MR=<$YaeKW$!B%Kri z-f1sekDt-uFPFNzACXb;`)S_)5eU$z4`703j97|2h{sN{lO$UE|P zyvnpJ82FdsoHSKHhXzN$N>8}SST4~&38R4Dmp@d3S;^@qaaQMA`iQ6IpfDy8-8X{N z_!f#&{oo?dt+6raFB!{m6LqcW$6(K`01f$@X*LVmzO%>OU*}xHG3>q@{rc#<0%9UE{d z%xMR3x*)VdxuH*|fOLH$!s&t&7)<++_K!d>@}FQ>*qkoK6wT*ud>(+9uh6Ey(-gob z)1M&^@F!nQZg#X}@SpCpvMid)Sel;*(sblo{cZq0HBvM6kI_+r0r9 z!TXl;wM0sre`I6BfwPJ$s3EH4`(E)qXA|faNJiDAnlNHH?bfUs9qfuY^N&kr!rHU@ zs$Bj@u5=aezH6^RN85jYeQgWBJ#e3$eA%lv`s=rBrEj{&^!`M_`j&%4haBGE|9ZFg z%J6xI87$Xg(gcvoZj~MnGjiz+;ux+nI%-my zVgoXlrEKKGr44m{N#%R_j5~W?Y6Zf@;wFG5fT)>v%BC8gG=$Rc*ZMl8PutoO zaOzIalxY=P;Kn(>{@`H(R8j&jb`!2eUHtFIbffXf0LE`z1ao zHk{?vM~XOhFhOvGEWtLe?TiM-i;2j2fgk#oT(5WiayUG(tAfU&Ca=HG2Z#A)H(KA! zSq(}t=3BMdu1QquT9habRvAOojs+As^2{iNOVwHFKf`R}jZt?{hk}9s3%3w`5S;^;-%W8JMD$ys)94-o6Jkj4M-s@?QW zR#o6lv8amT`}@B;jGnIW!{JU!V&zWtVh>NkLGcK>+jY9p@BkKx1fr|z{{YO_K7OQ-Db7gPAK;={liWYYx_Y>(*ww3j84_0M8Jv1M0BN13T&Gf=~~2n zDzbt_Z66u6m;e|bRf-ChOKq>91jY#Rr>6~h>@)K zAMrlxK0Me>m};}FQQ6qZbU>`usKr%#&Wk%W+>eTE30XlrPAovdSoDz0F#utFBL~wK zpY5W+g;n<$Dy{WfsAx=id5`s-9^B{R^?gFB-p|oNPLi^K#|#h z$&y3Z#t-j224UkeFC`|0QpAonSbot zJ8l23N1S7wTQFhgxKp4TPdS?9eLnV(KiP*u&U5`Gx3?3@%p@*zQ|{QZjY9h9`s2)-1ye>#Evy(fo<~HL~UZCieJU0<&b5&sJPo zUO*+1RQm#vq{O-mxm|8fyRFw<`XYYpR(|PPCHZG*)1R!67dzJ^hB-+qTfC*@W~`1X ztK;tbsKd?U1H4xl2kQ2Dy|Fz9lAYeFvZ8N@4+F zO#+ROXOGu3`gg}dPI5l~wmG_%rE}X5Cc);IRBL(zK{FsmW{y6g)KcvbRY1oxr$jtY z5ym3yM01l>ZOS8!^OunzA^8Z|?=gFv3fr^4l@QeYM&OwX?33$2!t&)uKNuHMu_P4~ zSrL3+>dv-5dGOS6cCdYW-H3=ilUK|3o6D1hCbqW4oA!Rt6d7*ezV)Qv{#)?!Z4REW*iRIPg>nPwDS%p)1Md`&xi=gSV5NK%~d*+|1&hNoGJMuUNs%BzomC8fmHD) z>4e^qV*4ApX+LsNrDsqs(IOPPOhDGKd0B^LzgYz=#6hj}O`(qJMyxMcusy`%=G^R7 ztMLu77?ELVso7;$Lx*|H({iLe4r-rmDb|?dZ&=f`F_a}|n4mXGPv;Say}In-;x5Pj z3E(iY>yWTneBa7fg^{d4D_{P5hi%G~?J@VqhVrQU0vB=Vtq^7_Hr*UDXM&*0Pb3=> zQZGwibg)V9XNrvX-&P*-JW6y|IlYRcjfkwQg2K(Gi)Qalh-AeLs8eJpo+o(nnE zX?WGKRE!E6x*4x;PN~);rbtR>Z%ap0w2w?>lPEd~poI+tZev1joha1r*PwXf1%V}P z8Id5>unR|i!BW0ruzFVc+FG*D^_gUc9ydH}Zp>=JWPetK0TDX*b5YD1=`8H6J!AG|C#bf5AqWl9E{)Dw-5!Jflh$|PRj3m6;pX48blV8 zU6uxgiyB;?4VE!2Nr16}^%VDB=_tz#k16Sfm}D$&+~bIdjZV?Zt@CCb$~{OYvA>s@ z^J@^6@jXvJuiPl#Ly^xLlmQF}eydZc9}8~1^Sd}(u3ADKGY($Wxu z_mT7&$Fx)8kgtab$exUD3~*Zl&bTzW{Y!~`AnpD_D*nZe2)QXH_XA(pph)^V;dmAs zHDkLLVi`UFki;^r?K9&kIsX`_?@%u5E2&xGK2ERCMuSCp@@Ny852O%ebAPg%)M+`O z)ruiN*g!3NNW^gEVZ1+$Z@Nv`fZ7eQD58Zt7}1BJKhg(rh+*lwq_ApZz{F4%h2GhD z2Rk;U&^q}1y081ke5^xy?d(SLb$$&&v6~eeLHiEaXD6PS)z;ZOQ)3&lmZ~FRt;ub7 zb2K9hYw$IQrCkmY&)hw7OE~DiNr90W>;p4Yxu?B8C0IBYB;cP#oSW2);Xz!ID{V>p z+c`L@SR3d0Oipq2fA3zxIH|M0aFt`5GB#YHW#T3=+}xTznEa1PwaxsZd-oPiL`?T2 zE3kKRpUL$Avts1Wy+mPWfUBeejM-A1&gSj+FBCQgKe)>CP69oC-Qfdyn>k~)&&e@i^(knK68D`| zsHimx`kYs2?Q*$q=-}h)hd+!}@`!$$*oo}4r!dSw@2!DqKEb3+ru?kjB5|-=@JU6< zw4y^wbZhD&Jg<2-Bl@1>%av?9Hj{Ix#+FZg1?;&6!cDb;&q~;)0!Q?-hxiv={T*8y zSMSz)vEx==Ja>BrtA3@J6ZS-YeR8$6RWJn~JtQEO5^+(7bB6s^+seQZ=AlkZYlD-{L6N7mhd|981s4l zhTT0c!_VKyTMr#CpQd(>-_~-DIR4#S7ap-oN)5u&(*1oZFxX;W=r!8d1lkbiqdY`O zt?D*bp#w#mA9P$-_?8-q5d{mYFTL3c77BB`2Yq0i*CwF@RYHq^+AOk#M-3NAjt4oS zgULrw^D3^};ST@nZMp0~<}O21W!|+lKEA}YM!_?ZWpQ`(`LIz&FMfvm^c>t7)K@ZQ zz#-sar5Q8*T~K$=bgyAb&|d~2duHD91ePf}yB!eWfZwOpTns47mhD+O+7x;rv#El= z6@tuh5Z)lFzm|@~kN8X7o80&*a%hVmQNq&{Nm(4aDLjv-?eGW0Z|)8&RzjFzc#ych zdVA}6cNQr1iev609ThFl!|=Zp&hsyNafacBBSg|P=t^5_FA{45S_|<&2BDWty@0-K z30Ou|cA=xcIDUpFv=#N=QClwP;Z?-2+&9{}oP($OmsgG~@E-aH4=4XTFc#b%Qgktv z78;hB0e(1t54Dhvw>EEH;a(Av2FngJ}P%JF-`UICDd$?mrCvXlwEIVRB}L<)?=&Rfi~j)=Oy) z`P_c)hAY5d>57^^?}qje7d%J`g%Ub-2Ulvuh|V;lJ2(_Se zqib*aaPm{J(T=!LLMsrv7=%grbdjx6%)_P7Zp57WQQ@VH%mpjGi!Szlsj4%{7kIxf zn`-QsD_?xo)aCH3eq)g5gbd)Qb1v#y#AY(TxMHz>QvADax=6K zlDPgkhPYhd-So;%tnDP~q>`DM{o7JesTA)S3W>Zs$h3_;H#y`J_rOXr>^g&(SE1lB z-j$uJ`Ic`o0FGCddd4p}Rg+sTLORl^TMPSik8sm=MyFfrr@mU>y^h-M(DlJP?cMG{ zujZQv%l|t}->A`_iE;WLJsSZQ-dX6U#SB-BRzKq+xwrf!-Q)Ovr$Oe&uXf>jogddP zA>J+y2Bl+f{(N-v}(J0 zNxgiWy38VtSGgJV{iB1LD&dam$d4MnN6W@7iGJZvG*nt-_|u+i4L1RKAjx#zn zhs!8K>&+Z5HycQ3p=mIHOuWm_UfS`sUpyjP7A! zuyom8#Bh;jkX!rSub^#x*W%|baGkE8_#HY!b^@3kdYoICW4}^pdY!SxjDT>AJc$-n zN9nY-0*?-~+$T@sEHZ$nvE8_{)avvZbW{Dy&yX~5Vz9mh*fhrMi@*2iaF?@Eq5SMY@Y zmcqbuM#!4TH$zVd)BE(Qz~9>g5GWf>yfEopMBmOs1j-`JA{y&-B;J3Ml<`vw3<$jW zV>s|q#293ZeI|!H#7Aw^@ceoWO}>_9@?apXnueb-41SUJYBg(p{^k)gk|Io%FM?jD z%Mj3Pnt3EVX&~v;=sazJC-r0h={KWGmE3#ey=Vwkg2^p0Vk*zC$OY-bA_xmBA;S)P z;RfI_goiutj;`B2U}{*Fqgpp&XE7g~hO;>vvLxj>oN6Vc>HpL)$2?WOLfx!fZM35J zL}5WQ>OGBDsN34LBW9o8<@bU8m4?;_`nk|0c3bVZ!#640sW|U}*aHY(;<)S`!WpoL zwPJJqq(!CRWspYs(T;7C_1zbJzlszzC}I6v=YAI}xi#6|`4VFzF|@?yb4Kcz%}*tR zMVg(b``S;_w*$JYXAqVc)no+qv#8eTsjp*5HjCuHEWSwJp_s3idR`sJY>zRivLy_k zC{mB6zTvH`Z)Dd_ug7b8-e&@5TJ-X5H9{N$PI5%9wH8|0m`@Uj0Bsv0k-c(~I3k>A zHdJviF+9Zf>)>N9N;_Sc2v6x=4YI8uCI~a!!kGTTo}WPC!|$ z5BCvtlZ_;vyZpECL%X%#74>IJym5~W$`<^u8kMYB){WN6+fN^LDm>nQF)cCJs?@I< z9{O1$1<5+br;Xg2wR+PlDU+m?qdoRacR0)b`MK|j3(t4fk#xPZ+?vf`JRu-g6Ps7|AngaZ5g%InHmc&QsMfx|*EEb@3YJORG2gp*^c!xhIo;+?bZ!{b&6U>yadZmYPrg9KHX5&|GaOb)P z25}|?pj^fDf7{aHsUsOV>~L zZ>qj$C+4oY1yU0(3BIgNd$8gWS16TwOZWe{y6d+l-}rC*>kT$=bi?SD(J5|pNh1xT zq!Ex*#LSAM4@K?;Qs9dlqaG*^4(4mL`}*PNj3=Mu$gtm4KPn zr)^=g+kAgVL{K?xn=G&=n8W{+TLEkB@nn@TZadaozqXtt>99?t8@UezqS`Pk*xdG$ zzlx#{5*R^4_)>FKP|0Xp!T;#aU}s1-60OBb=mdRjla#wypgZI0#OaUTT(NkxYCx3k z$2xW`uK3B+XZX6eJ!~k46+A2I)h26gW4{%JKXu|8Yhc-!cul4l=qGA z^dCCCx(LC_CGTX?PM;%WO*@l45DeLcCaG8#{*?3U>7I5i5vYT_F!{e?8C=>QrQP?v0;1i zf7l-$n#a?HB<#uWHW>5MT*`^8(UG}fXdIHAU$JX4Bbi#8jBq$GsykU#+>D-~jm@Mh z_2+KhnrwIjH7m#XKIrhlqZBgh*p93lR2j<5Z@tT4Bu8B;cHx+{-_5UMu3VJ4oC~{a z6K30)ZhQ6b!R64Thja}gqWTsuES3~#DxPZX9w`)AmVWb#tTGpD<-O-6 z#Dzg=?w$jyJg_)d{heXa1Z3ZJc(dyM_|@#SrR(A!AzaIf(}W*kPG+OJxbNn0cXpOX zUP<0E)_9m(xI)~Y#Y0CXc3DExCL=;>;a!u2R(r%!{pxzOG<$;`u!d;^hU5#2TOV1{b)9bDkb${>HH9wXIDy~E*4uzIF z8Pxza$Q~t5u$}TqHso;W&WUZu13xg5cOaz0tqzzunCI?kTyt41=0b(>NV&uvkoi|_ z`bqbPm&plGCMAar+p@vm%`R=f+wG|&50BG<(hc#k>`9Y{7wbJsee8A|ujzl?KJ(N> zI^puN$KRKuyo{?|PND;MfqJs|g(Su@Ou?2A{dp9Os=orJnyVkLIG ze}4A;<8!mY=jYWU5HXDG7}|3|%m{;rVSFL;ZxVK#6Dxhev|@bt`cZv1z{rT`v@KI8 zJ4Q?7u7O+1gs}da&-0CMwyr?HkN24h={u8I$`OndabOd*UNTxJPKPt5i9v^c;51nq z&;tP&Mbztv?-s1a)urR=o9faff#j`iaRP0aQ9%b;?qLDpVdK$_=%{^0J|v%=Nm-dT7R(~%6=0N@PI!@Rwegg?O@s}$bg49@XaPkMJ7Kp^w#3M zVg5gQJIwPr6_07L_(lBJMQa()aUP&gh%Td1&rk}N?&2xoiT`v+3Xi2v+!#+VnSY%7 z=1cy*^-xO4IFB>?*JiHB#q+NbfLKR~D4s}iEtCoPU}$VLcw#fT0XQu^&T}hgD3RH< z2AINgi@X`#HQvszzx2Rtph2>!adtO*H82js6uJXcqTjMfPGA7VxqAT|A#-UGkS_+L z0{76>QI_xr;^v~|3h!yYmq&qKh?nQ!C51tsxB%JDZZ2H(rJL8mSUp#2w}s;&j0V5s z2>0(E99v1R$&62I`U9dV488QKE7{~Y;7TI*<-A63eh9mWY7*CSjbNfQ9g&O};i+-2 zp{4QhEuR?X289R**oy%;)2k7GzgNvnKcLgYRlu@{;CDG6%xB!PL*2(jlAr`BFNPVq zgxoHVOo1DfXHeO5VlHRG+_(;PKaq1SIL)61!p>pIfGE^PIY6|+iff=C{DkyK=5a=X zg*HHm4S+BG8W=~Vemqu&3-#p43CM$X4>5gebDi{224GeYmZGk66m(;NYZ*j@YliXD zINBxf^t4_3l_h6wwYTpBE-9Nnqa3q@=fYFu3ERR~0?XB5@O&MrQGhU)x7Sl%9Z?*)!OWAC8EaV=vvd1VLDz z5#VN-)Y2;UiSIRiG;gD~7y~zE#jOlYA9L4h3#;Y&5a*#6R83F}Q5*2ipz89XsIHQ> zMX-kVc}8*CKE|4Rf^(6S2J%8wvT<9ucUegoAq0KFX|JcUJs2GezSqU2m9Xu8ujO~= zr*SwIgj0J6(IX1r-@X(&SZc>F1!Bxl-ex^J_x5a%Vz&@q1J=q z#f=>{;AoR&TUSzQ+*X;{Otv*N9wLPkzSMm&ptZs*Ds$>ne1*}Yn=`b*id_oeJQt4( z2w9FVJYWgdt(0(an^#2{>mwzt02?oC?FY12fg~~fMU|TUgwLbYthDJKOp21{i_UWQ z1g;elkMz#aeMnjfj$3^dKpyH2+OKHP__?Y!G0h*(HNn$Ef=c;p`h`Z7^JM6a*PXA{ zh9tHOlR&{qO6zStJy7d6??lYvn-l@;#;u_jXNV%1>I#js#XcZH;s`}LLquDm!S}+> z;EAXFw-J{i(CzS80s3=6sHfqn3GPZ zP5%TTicyuAdt>ed_8XFsFe8iuX+}ovjcU0Z^!v~u=*s9)2 z=nUh8{Sp&@^$I`Bqb4u-CYUK{^JToXSR$&;H_gZreN}W%@+&PHpXq$9Xc?Of(dB#S z=n8|P*ySDviq=~Vc#0|ngZDiK^Io6vyI!B$7l}KaZ#Zw!`Fi`7uq!59EA2UkH13qjrCfK>I|PO`!VWAl5LDQ zAksjKG1b%m`Uf}T8x12Y{aNT6rU#FjYera2ThKwb?_-M3KuicO+=nYN`sHMZFsnyZN7H1*N?{17-h0)(Rg@r3XE(h%36XD?VX#s zpY&9t2N9$3`@3lsrD^W0KBTOlVFy4{d9g)evT+Q8{pab_-4E@2T@z2@blK7i*g{d8 zJx!QxIslo&J>ot_5g^@&U|zzd0p9W_1^E1I{(?b#4@Ii`kbJ_(yA`jAIgA-#RG*O4 z=FiKHh|Hil$h_>K{GxPJ8KCS2=Cj{x zEio~RI{irgAQfG?qnryrO7Y`L#(`}tJ2Bkiqoj)HvvWgUgG}`tJd2^cUYdzzjNl%< z{h#!1`k@x?-PBz%j^}@klBLj1M_l*d%Pb=i3>Q_h`>ZA$@_`jffi$(6^k+mO8c;x@ zImwe{aSLR!jfPkRa@z&chR}qQSp0Id>ODe5*$|Zg+8K}Fw>xml3-qBz-PBUJ-zq`L zCt)>2*cqco`7V6R5={sfxm5^vsDTz>knLz;TdHs%)b`hs;P0P|66D|l45FL>cb=oM zwo5|(42~zEnlXq=AA*aqw6nnsaTNH)Rvm;vP>Rq)tSO=Far=!Aq${W zNA-q+ShtOS4^;VXH*}fFlGD>M!c(6puVyj9WYi6-4>ld?QD=;U~AGXKm4czh%C(LtEyfJ_?}c*t2MX&bCB|r8ykA9JI8EF4%yvhI4K; znj=r$gA(|`A>2PVZ>yfN0lOl6NHkq+cD>lB?g^%$4FNI^6%T-q5Rkt^JPdPD4m}*( z;ixtA9qI;cF#68156^5TmP&!u10tI(a=1(RyztSZKe=h*_|oJhgqDJ$(b;tKH0-xH zWyg43$HUD$Q5tgaSve-A^Cz4$aoWnu{N)&fC}26`D>>G|H@&^f$GSCQRm%9L)c^aB^=%S1;X7pQ`oQN z!A0hyr$W%Nn<0A*+>gErXu#Mbyd%Lt+7hap?kbb?f*FxfP-QdsE*`mtw$oiQ%UnfL z0f=~l`Sg4)_pj`8AI^KZMR(k^93K%zHUz$q`FO@S@5LdbZ$a&J{aawg%=YMr4HyMe za4%Y0Sx3h?8QqMz(L5K62C`S5^0P&jNZ@sbf@z(xtS!HaVdBW#N4lO2QR@UdG8*N1 zEHuq<=N4Pl*12J%h6swD3DuKxUwo*Phoh>42x}X!A}Lq>e2netVu@0U7J^2e*jJ0s z3y5#ReX+EL5qyeq1)arcBN0?V4lEjQgHs9ptCs0Nm-&DNcb~~*r=dau&nFCo^RsHp zM4J!R(9II9-!yQq2XkLwBkH-_kh<6p2!)?{sE!TThs8{Kpo~WU#ZSQ}k1uPeJxIEN z{=$fIAVM681W{#tBt=+WP5#i9@gK7c#|Ix8S=Pg1xI}|o?2m?Twc3)Fw?VlYV-vN4 zvhWBZ%oZ)yq2kyHRSqUdfQDefOpZavtl=cpAdFv@l>!Lw5U+O8C+1fGO^r85P490? zJSVf%pEV)e^e-R{STaFiSN|9iSVkL2>D6?$ORAy3O#twVUT?=UP536wn?;)XV^)k3 z?aQ4jZ^8u4ScJhACQt^1!!gunjj^!?T7FFHS0`dor(RE@nZlr!ty^o3X_sr%o9FDt zJrgAD+Lmv(EvLf@j;}SYwY@V+V%*oXOV#8i2Xn2&aT^4#bn`e<9`ueG(Bx_k!2*hU z0*Dtl3lYw#!eAZ(FM0s8B|X?@^<+-8iO)j^r@;naFvb(%<5*UyTig<%Wk3v_Kz#OO zE-H#7W3h8f{&w~S%hHF4ef5n$@R*itfH5s#pJclTe0anLKPquB7->Sgo^$G2-=^^+ zU?*46w*_>b6Ji^KQEE%&A3X&w7h8kz707Z1uU~}PM@0vC(8(ybdARu{QMIIrvbLTCdt{)#4(OmFFIuDWg z`ns&tnz+~gw=2B|y2~LORKpe+v1!Pi#)0)2kuBaHeKHU0LAzYxB5)l@i2&jMu`;kI zx!tb20%IOTGoS(hv|h>NPj;+oUdTlZ-3Ppm_$}=*Y@pV!zHP@`{-3m=IaUWxdG&3o z{DWy}y9W?)`KV?wmei|}^5}TX9qmN{!#<7+Euz*fm zpG$iu+HSoihSHL*&*zJ!sBYG>gLHXcNH1cdJQ+O7R$oh~soVlIMcAz{lHA@t)7r0P7ff3Ex)q3;=~imeRYgZ5Xp ze)5J}ur7m7RhBk%xL0V^)qWc7OX)$?!UA#<`~1*1mV})JTBiVXLsnRmP?`X9k#>Mx z(5NlMc@B2XwF~1KfurfgxPCvKyL5NNVBk9A-I2jynjm5oec)&lK5rj3@i+2$t4K{1 zp`q&o@-KVnBUI%TmQXmJ&rX{hxgO4To{>!plqn{`=!NSA>*_yBp--+eq^~H&e^*Wr zmLJNK8Zbgq@?b-ZfH`%z1CuD+6a`VS0~cFrTL!10i8YEYg5{m1)p^S3 z7_9NlT8JG1?we{~a`K8d1a%^(zIB@y0^yC6z<1ko3cHmtLiTRKeu z{7f#pg&ahHuL-;H-pS5-C}2G7yAuD7rjv4MNHF#Z=hk|0tglyV=40O*7Y7n;%j%Oa zGr9kyD=9V9E@FgBWdH4unU`^%jTD%M$fQiNsA~;WUI{IZL8FLJm0}fhot)QF)pQn2 zSz5@y6Yu|isy-j={bXY$(T)zZq3G%C=*F`9CT~Qq(sh}`FV|T?=*OXxWz5sUL+e%q z?-}QR$k#FZ&(3R*RC9P%O4&nYW@!=RWm>v9EP4e)za$I*VgN>H8R!D+cIb@$Gqx0$ zD0NStcX7m;sSmsdBiL{nAFS#A6?*Pk?VeiB+p-^8H}6DX!{?)^%%yT?SHkU|gpuF5 zJ>95%TC>njggyDR7d)r)%LKh&Ln`A1&>X`&GvLk@9~{RxZpboiWf!i8&J0D;dLFYX z!;V_x`q^Gj`oBZZ${j8^eW4Kd7o7M&519`6>F>XdY?=Mcb-=d!A%bUhcaXSq*X_m6 zXGiq+n4h703x6V?q5=Jc&#W@&CK7BG;})&v>B3JZ9+%@&`UA94TEL@x|f zQsz`t&f~(2)A|*-i{ybH7`VSMTQEKxSa9xP^O!A(!Se~UVEO)|f~tA7bZBC5N3CC} zb+hGH&2-rAo&MxSwVTIXzWWs&K`0A<*pUM$clqIr=BBpCJq%#==L?m%#zd(>E)BT3 z$1RKz6*aYUuvCWlnl_EA439Br7Cu0n+1caZv$*r21KAIE+)7iu_qHYb_4%Kc^5;Uu ze|C%`yEg=$q0jozfIbScM&@^4FtT10-G@U~cOajd&jb+Qwq5RXgw7Q-;F9@|GEFdt z44Oc^a!ueT>jm`q{?}aQS>in$X5fl1fL1>xj5iLMeDagI6Y&5ISad}%%AnY;RwK{1 zWj@q?p_!09rcdCBSTvKcyqh;G259}sAlI*>~@X~zLDfULJQ zzsBq5@0Cy^e`!- zL_&d>IQXE%>Vs(&^PRtPtT?)tE?2U6b<3;|EFWI0)C{Cu5S+*n0Hcw6AK9=3#}HxU zv1AF>ZHNprUuuyg5dz;nQ~ZN`z3dwP>D{2@G%L4*vuH%y)Z=y;S3zwfx<{6~?Kuxj zu1&M65{=TMtp~s9O6`vjq%pkE9>k%J<+Q=fx6wS3j8pGPduc+8_;eNaJaF5c3ozsJ zZt(6ojJLwQbrYCsmRaZ&O|z?^#^zVTM%UxG4cjc!s+{tX7#2|4QfKZjX3>>a>ztBR7hL8kdXXkJ9 z2-|X(a7$H98=h48ohq1_swz_Ntg(|eV!T}A)iVQHIlAhRD*myARrI!n3Qy!tr~ZQl zb1N%?R1F9ZA>F` z{2bL>{278kFVb`JElcSI$s$tBh z>6AOVEa9(hb_=YWLXw=L!9?YEfPhYIdRrLCi}~I~D_vpSe^hXLwv`h$S56njX{zcQ`p^AZ#JA>H+Z?-hg-edglma@R z(xzV~1Y3xgcm>OTZ0&5MyCFw@SBL8Qr?EL);@VzkarN)oH}&A5B)7CYwIaMM(IYhk zCIIBUz0S{_YWTny3o_Wzx}<2OLB#!MfY9^M>+3x^7g5_QnYa3{LyA3ZUOuQ&MaW<3 zDO~he3dH2~-S7RqFAPrA1OE>E2eR*_u?NP2`q*^QrSq?&MX7)MNs7WS@HA{$LCSr#t9DZk~M~+j-%GzByxv>P_E2L zjCwVQ9gIK{KnD*8sz5y)v`U;wBmNWvFyG1Ra(YfIz;%DbHPc<|slr^E88bcBXPjST zt$~et@uA#>TKHDTBf$nz&ytXvY)cl(^e!;YhfzyiFF4;AEQraSAUiPwh-ETN#QJS! zkVuKL6tNfAiTt?t2EjK~s8CLj8%mHdDa}05Q>c1@yN9eLebsG?u2A0I{P< zXH3dPXF2y(`NzZ-2`?*7UOs?b+2oH7ea3y|q`>H!k2M!Lf#(bZ*Tua*H%ZUG`;SVG zri$GTmR;_2$*Xtx%O{JIg}XCfYP*@_W0yD&Gb4Kns9@t6ADF`{iBgwRwch?WpjQIu zK{xw=n*v`%Qx5SqqFpO9=ccLNS1M1;nv1;%3_gW?e>%zXl?427}fpZ3S>7mFjhhD`l6(dKHZ+uf_@+Erq z!uesAy3^NRr}@+*No?83L@Y_V?8w>T=R-?Pb$+mST-?;+LQEcuklN_8Q5Y*@*~6|piH3~34Hq)gwp;9XL?Pdz!3(n1PG;% zz{1^9*|W%4JxLcT7?DCbIE3J*Jw#%^M=z*E9X6iP(8BPasBI0MJWL(``5 zj9lxKL>ZMwbU}8*O)%q`Skt3-aCs+j3lQq#s3Ku!=5_MgSusyitB!#Ca| zeF}V8Ix6u4Nbkg-!~?;@cYE=?Ys4cq@A5HC19n-^Ex+4lEtjb^iI^bwDqq$wPj==F zvDUK8=SC19jp0hX$)6W+Rc5z0YG-lCR7w)y2m{#r9M<@J#`orzjX7&N5Pc6Z|68k0 z{GPop&oZX`FU!)J%)Mp$+tLALOk4}f&sB4h0u$m72NvYX!<;wJfb#7acnk#^R*>!T z#b@TgEakS0+9vF8ZAGi?&37Ddh#!74cmZ+lUv#bp=jUE)&U)68^XPWaeNna1^yQ&C z_4X~kof>52tzb*NzMo6tQOxWk=?A9pTh#kEYSo6AIr~Y_vGeJ#z%z~=;d@Dv25#0N z9#obBG*J=*WR96@VSYeKOlY}47jfE$Hr2lsgv4h$Y%TL9h)HS_K>EJ%yPv}^rO2P2 zKl>R9`X`2D2Jj03X=pl7yq2TEg3LpR>({9)$>^ku5g3G*Oqh*g`xaSwaeNro%ep7j zSYnyz)2Vf@HGmcIm;2h?-KcrS$NZ3dQ^7E{(^xyWc zuUKI{-Y-&&V*B*19g#_~0+i5RXwN=H`E_{!bCBd8kgY`_;7rnXk|q5Z;)PF4+W=Vs zl7u9Reo3;XV_07r7L=xyl!kEBeFam>5YLP>bAej9hJ`kUEW59m)Xl*n6maS7vOl+| z8#zeF4Nmb9wXWO!Kt|YwLqdpx`r4(2Zas2wr^VBj9}Pj(&7stg`%m14&xaT)?$sgO z5a}}JAR#PB4p;cxvam4?-+E91z|!4UK{NoMs4jH++4Cw4&&5dFv+eS>ZLsngloUlZ z`Y-D!PV&thjD&%q7-0@M$p->;=QPP3ek~?Cqk97PJ1=s@Xwbs&u)w-D=;LtpTE9+f zRs{*_UXyr{{yu+1C0LIFa_I2v>CN3Eo-wpO!O1tm#=H~tyc1#Jl;k1+#JeV$H>Asj zl;lAIYpNuh=XV^$(|pQ_7cv0Jt>CX*Jn?oKIj!7z13{%B(zWPUu8eBTF*Z_kQu~qh z=1G@&q`ibDDoOfEIum_oNegR?z~7>H%if1)SixJo_>F{f0proW-=qperfW@-bg-gA zj(7w&N!>u8lBC;!;M$Z({{|*EoM9Oyv`MvyRRB!Y?s5F0;bOa|!PjCcVcZv!2G@;f-Sex~OwrVu><*`1WzW?j!LgPp15j6jmHDIA5J~eb<&Qv^0}i|#YSi-$yOoQS z#$D(o2{{Z}yHnr`E#jVBRkuQ|r5rE89E@WZ$kuo=_M3P7TgEj?frkOE-$btnIkw!Y z6;g_@Ka1buhtV-gHll>(^4dOpd)R*l5+Z=kRnP@3)|wfdNj_`WZZ04d2>17lW<`ul z1UYGQEoYVnj9-tK2KzGju%~wOOE{ogjz*@ov@j&=47H7^?l3uRwR%aT1QkYntJLhp zqFTOfDl1nU51jcRHC(Mye#bB`wRN^wGQCP;n)Oj~LE1xBSy+~u37NBnumQd+XiPF` zew&y^z<~ujNzyr;qMJ|`GexF}{Fz=@#a9lv+j(UmrT14f_3XWVI{t|F3H0HcC2BAU|~~E?NA!D`G#9?je?5gfNXNj zcJsyWzIgQ%0P{c$Szf7^YD2oR%-KlG8n#ufFbfd&$L^?3>+!TWTPL8QY&TDr2}H2d z>f*Isu)}eg@?CSUPw5x506#TL^V7JAhE3;JPFJY4pK#~(zcxGkhyZk=>54Keqs?5+ z#1WgU1c2hUs&62R9kZ;@-Bgk;2QNGj*TSsZWa$`-FqRjcC5;EnbqZ)(#V<28bKPT6 z@E@#VeUi9sjr7^D2t8ePt}vH(wl1HUtpmWWP9%JnFSE0!+OF8Up*jVio!vS%#e@qF zs@f{t7V`TQ$a$)bV9)3=!*NYbv>WP2g4y-TdCycP*$NOSkn78UBiZreTD&s@0j zn!Dv=#r)Q!+H~UU&iM=(cIaTKp@PvW(~C9y8;93n(7r53dt$N|)?t0FhVVd(95~|& zNK!l-=@V}Gq~g%+#e3@;|F+-av5@map4!r=sjKCzGb1C)Gp{Ma>%P+Ko)Rt9tsXAax{dI582~j&bQuMQ#^Dl__-AfpjM&PC`7ECqx?YlOKj_-NVw+>3`Xf23C8F|3l+mk zbdk$yB7k)R$hv{jNVgyqTScvX&118{Of}ZeH~3fa@0Pj7zmpi4Z97;^3(TS)Gwvuw zZl7kP*@0h2-KT`mKJy=`Sy8WALDhu6|2a5Sg1-NS{q_I0gi=e=$Q-q9;ER0`PXU{e zAv%UvPmDR!4PJ){U)2b4*9b|FPe_nFyI{<^mF&QB`;hw;>%GuRGt!rL@-|w!8wYEJ z_UuN_PsnNw9`s$AjzLcS<85zC0Li!}a4yHJIwEoO4PI1H3sW#H$hzaiK|SeyFJ3xL z%GgZoa?mY&S9e@=r$3!81ghRN){>L_1JHJ@z0b70@23Hb2j)cCpmiWa#0TgOHK18^9J7AKF ze2oTB05cV?7c9JAI>%i{yg!dV=%n7?3D2O5OHdbMpvSws+2qnQsnDs&9ZJYWeS3cH zXDV_i?HC*)_yHNWxy{GsL5o_dLQ7w9@3;8A7c+NS2Kb!F}H zSeD{3*nOjjwn{7FatjT;-cg{c^8+7GtxNJfS4O)vB%>{=br z!4UKI&8E7syN8Z?ss!PS1!8GkW%p5B@`Z$Po!Fs4x|jS8r(5v+6Uv)bBvFx^)9VZq zdAeUJV(n-ER*t>qKu)mQcY3ZDPz6o4#a+B#8Te2BZUO$&YKO(_l2PvxFYhnD!Fe_4 zfW0ZOuVSx8KF{OTlJ4-D5mb^?_cMw`0`->O#m?Ta$AE1Ru)Zrtc$@c=&sxu4#HKlO zL*-U%rf$3;kS2fvul{uHc3eE-nS>k3ivUQ{XnNOkluHU=QpQ`tS z@cST}xr2}^{tekf0YChX{_*vu6~fxQ2rH0%-}>Djhd&~2ia!pz{*Oh06wnO&GWFXR z*9>NQ>?W%V-q=t247an=9=TZEy&LD0=Nt}0O1FkYx}vPVip&rE_5 z+e^9^yLKGV$2rK&uQWcz7Hu>z96Qwc%RKq(o3f-&u|_{dUlg4mR-Ur@o(gQ|B-TV) zjk^II!tMoS6|+M%0f|<@^@HNu1~X9$58rixV0g^Of)6gG$BCE41WU#@`tP3k@Ykf( z?3Gn)7~IUgsQ`;A@+p5GymTF${65@noX+t~L&HGe+us}ecOzoj!@mV&jrM{yHuUrY zmF|2?RKQtB$Q)Gkm6@WStsV24-uu$om5>lw56FR~dfn<_W!v=pBV_imOF}MXG69E) zep<&MQDCQZ?@hZwtufiVam2^{!ZWh_*{<}*=MlKc`=iasu8em;Z*}TS`=4Jo^4m;x zi|&`35}se9KsCJNC-fn0cMOv5Vp={?* zn!c*T>`pKZrV(E+gY!rl z4}z6+N8jCJE!wyBJ&lCF{ab=gHYOW%S*BVuo>`^v+yx_?KyXGWAGB?U>mX=@7F}c8 z;o*SuotlT5)!5S96Hkmf7Bq;Xi31LYALj9Blm|mUdLi99a^#Tz-1Ae|sikyKwWI&h zWwcTlrTtFC79JQC!$^f;o7$z^@%RU-a>2iguL>#Nq}yK-4msAAd3>>6+Qak_?w!MBg)%cp{XK zb4FxhOaFozunEvPJ-|CvYesic_zy4db8zP-?M-Z4+H!L7e^#c-pQV@}oN;0C88@!3 zYGr7*?@YotH4iw5Qc_+Vtcj{=VIn1Jw6|Vxb`*H-*D)ME&NX-}v0HQImeWq!t}u;~YOaCN_Y7{3@{T*YftwH>Li@*vK0_PgqSS=|1^aD{VJ%WgbB{s5pN{=uYOPJe?sx9RweOnzwcFcx&F$P zugHE$ZMDMA9`5brOAcqjX_|&HKm%Sm%TObNC5IzgwxH%eMuQJ(|5SD|pQZ%y1ak+W z7fb!0S&QyiD7%N(gl*A?U2&r+m<48b{T6S7Z_plfPJMnM*|id@{&{oI^3LbJS9RZT zeUG+a+w@h}ly6MlyP~+{azAfc%y5OtfT4K(BTc{c9evc#v8b0<&Zy*&blDMR8_lzW zmY08*KQakE_V_yW#cs9TZ8t^sJgj-<``+I_GR(Z6gR1~*L-gTI3Bd29B$Hn^SHU#wXDn^| zDT92hhLFG?pYjR&2GOT?F7WF4#@COwn48I-!j6rG%I!f}RVNR!H2czw1KgQi#kANW zh{*~h#!K~IKB@VtCJujsX#_O55tu)T8UFn|1kvR=RzdPY-JNSu9B=h@Zm}d`Q}}l`n(@&Y(;-_1C99oKS)jh z(p@Lq)z|-P8p$~+-+bUExuYRI`V5vzD9Lxvmi&+?5rOhpiI-D)IwGkVF6taT64HZ! zab5Rnf6q|Jn%TNiX?I<&a$uB|5(VY7{#sH(>}g(>U~mfNN4+pnw0GIfyxx(R-+A`1 z;opLIugLTjq=-EW(&xp;fm9B6T?gq;z`XX%^^iWso@ zXi%=m$BmBFi9u1hZ%d1HHLmFXi}?0d^rOzIBy(5s&SVOGZx55CH&#IcRnQfI4X(+@ zZ>-f9hmDv&51EwF>x31(Snh?_O8GP7VKpa)Vjf=koEIj?u0AJ9-Z4RN>&-KM`2EAq z`&ZlbwZwSU7@@FipnTSTOV9~g(RJ5kz(8$(FOm}oK4(>;ld&Um9Dq#4>l!k(kjlusp4bi?#}>QJbbz%nq&Tcx61Ol-joQ} z=V%)*uu2OUD-A^)gN+C8Y->;Ek6-6aH}I0oS4s^Z;PJNC_(a{wVoCP5-OE z9!Baq@%QKbpBH*%C|(F8zR?qde5kK)=C-QoLue_k++W@AWU2!{$QrP_YaZPGzD8ky z1+HzcPtiSiuEF0oW&8|X$sg_`^1*Oi^Pg+1hXf#e#n$?$^0<{zo4zIVY)&`E-$}@H z-~(%+LmqE<<-L**Jdy{F{6XQ5{0lF|+evq)^oDm@LGA2mZC)M;h7Vi3eXemcHBznN zCfTR*;|TfUWAoeQEWRk8OL(^Q+u5s+*?K?iyzR%J~Q5l2SP1?); zho@(i3D$S-zfU6JB~v(GKMuV2XFEHfC6fK|ac%;Oh5q@D?YHIomVbSAW$ux(1Yx}2 zaIX$KTK7>R=Qq=<8s7Qbn_2(z%!Z5Y;2Jmg-xd))%s2CUf0V1&PQP4ft>yjCW~qII zbri>XKB=RLMB{^FnmvS@!)$vY{5Q|hEt&gTE_?1dJkqDA=nw5xDjAM zOa@|^PgU0t@l2dytBB=7>~tIkk@=;TK>PcCUE#DWY3TLj2Dk`%{Ae8&1hd82WG$V$ zjD4zswO1uxTZ7Z`{W%?J;o%=eYxArR*~!+@tMM-aD)9SN+{cTDt9<4NhTUtMQ@?oO z&p_)@o3(M9=LPFHsSQpD(c*3ia<+E-jJN-6=o*Rt&Ru>U%`A3KUEo3)kINgMIV}=< z?M06?|39%6r#b+l`|uX2aPt?l2~@a43|9h6q^r@I@hy0}jR zZP$5!(IjBVLklK#d{lu&Ql%L}D`dA~HpE@jNS71BxA|*p??3ht*+uRslb0t>jjIk1 zGz71Ex$M!fCyFIfcPgC?-^$B*>?!c;EaDFyylX8j+C6bMSJ)bEeaF$u{iNqy|H>yT zfD*rIa_y&i5J%11lqdMt7^ntkX6MOke6o|N5W6tZgD-+j__N1|%C^}KzY=vs#k77Q zYg_mN&u~jCXGv15(|xNd_$JrWa7@>2H&J7CEN{qB&&cy}!TOWC*LYi5BL~*`{_$UF z_L#z>`h$7#vw}}#XI^m_PTw6NLCh{74Ni30L)`}^dYMJcsoLCNtV%M;$4kJsfq&-G zh*Y9%D_+#P!9oRkaW-0M%tqm}l^MM7V|M1zgy9ieyc3()0-d6%*IvOqE5bt4LhE*z zshBDxx?*0mG}Wwi*5W~S-VRXeK>wH6;?Mu`Q=ovK*u_PktjH++>tp9HZB1$1dh}$_ z!{Q|T^@n?E_ACC_5n~RAfG3bC?l-M%g06a*nB^fB2ytct!MB1399xq86+CCf7&irvbpF7tz$E|chV*J41|kw=2@+4U{18Uvs%+$Xq*XB& zFF^*0*enPhWPfH~GEU>ATB8gzZ}_i^ECLdI^M+(qU_TYc%u04O+#a(08}T~yHu$E` z6&N2XH!8N7$p*YoZGg!ajhdkNWWW8SH4|ptc^)5cIU7+0=qv6ML$22S@OC_H$Q(Qi zO%sm4r6dY(7~U2U&D zbDe@h>Pvn%n8uJ*AOo1Y!nNeTBI!i^FDvvyL$hY&S+OSi96i*l(-De7;xof~gC8#| z$wSp*y2m>7kD?*iiW|;6g_fsAcI#dy53&kPtP^@4Jtjdo&|?*|wd#lSK|V}Y6rGc6 zqt$QY2=2{^Ii*hm^bTd4UrG5{m>iz3<1tQ$=zgtg^wv#PR2TP)=U%jrG_NT*aJ&L) zk)=mbezi$muMHLrJJ*{ZC(;H#<47m@fi!J6nKN&Ff_2t4cV4E!uE&X%NJI-Ke_k5O zlh{K2K=V=90GxE6_&pzAM+Q1^=m<&RU8+88mR;>Vch68PDqZpGcPUhG-!wT(?ES5C zfhSXm}ePxowB}Km^^Np9!{3lOExk* zLc9cxO9p-NMTzsK)~t>#p9P~Ra@V->To>!6-olFCTz?@fmA5_8Vygigl_ zslE=^ZXeR#FJpH1Y^wAZjLQJaIL&*VY1M<{PY9 zl>Gf4e|$|6kI%mL^oJ#Z90z3@Q)kD%p(K2n=4mD0+?>dNdO~;f`U~J?p>cJrWy#q7 zVz=?zo<~fPUx0c;=WVTnF^g*ZuU=YA7iInWdA(eV1;)J7u?+PZdjGte?cHw>l=_}n zFFs_!19_r6#~q5^$Cxx$)V)Y#HWgbE=2kt~NY=McS@w(%7OOL<`0Kuv)}7Vl9uNe{ zd6$7WR9s0{xUrL-)DEdh$En6zY~Rlv0_I|ip_oxmf#{L~qA4D}lTWLNu*d~sR?Fx#TK_715+gp8KWy^*O2N-)WX>ElNtoG|ztY=K8K7Tp~E|oTSosqOj zWBo`svrZ~cGHp-n)~JSWD$}^ipWGZCjh{!~UtS%a-(m@!_LbCX>=)9{=r>J5a!giXwSO6(vC$mNbNYsT%g74|x}oTpve)+W z-R(E$j^;8ka9;Ag2*}o^%%D*F*_Mp&KJ!~<=r*>Oi{WV+?$5uwmm?ylPMpFj?(FpG zWfTY9J^*I&;+}}TV7AlwkCyqV{=7>v`KbBQj_(JtP4AQ=qt443AK8*-+i^n#=|4vZ zSto{#r%JtzZJ3&SGq5x<%=Zwy$?#Box$uvt?8KhOMP$Z@9T8lW*Laf-5wwg`CFcHmGNQu1? ziB1t;s1nqNbmY7&7r};0#yPY&Qnhwz1q1|N%W*34v6(tJ zFDyE&{bC>9;+dD_XNwYHQ_xqZz;GRDjLL+&Ixq4XV+ zdL%-vdN=Kkd|FxJ3Axc+su}ZooKi*7aho#I$7<L||?3--rji}i$W(eJ_a97~_ zl?d?UDCS+3`E}7)!@f7@RMe;5G$$K*BsD9*^`yD<$vcLhuwK?jodDjv8d=&Fy);o! zE8TP3=E`cW+4oN_ZB2cKT|l12%-+4PGCuGQ({)QGsih#bH>z*EH0e!^GVVGyJ;R}0 zd+V{RL%uJo!3(y!f5b4akfHKmS*M^JA8+Z-wNo(nV(N0&{jT-G;H!Y1nO+}ym$*Q# z83Sr2>B{`$ZKks^33nrE0m+$XWd*!$TK(D$(8lAj0WrcnHHBFS(YUAjA>nBxd9Q?+ zMh+h52bDpE6t?1Wq$ec=6z;YsuZbtfDh**OdP;y z4@5S8n04+*a{xBf=8V>>d4x95TeFgMcYE`y&B>q$U{7Tk$%iEh$fcDT&Qn0W@zJ0l ztjKp^DHWT?w@djlU)?`3q_`$+^v)7c%NPyYfj#R?>#ma}Bk0~?@^oKkZeibOcDU~~ z2SSr(Zbl;l>}Gx1w~D((P)SO1Dst-K8*UpEBXf?{AAM6?Zt?8vl*Outy0vbrAP zM^=Y`!<+PUftjCi_Va#4aL@4#N$*k&qye&j%Yo&A@UvLl`)@NIxY zy%eNp*ocmDy>_kDWK1UrE^wYKMNl)VgSR~bOPy^)NG1WXY{VCm!RIggK5^p;W&22N zgnd2l13zXLzcB&}*^+?uyUgh2$zAIXyA#TEdOs+fJnyD$lM=%{V6tD*Uy|jj$*oXAj+b*{_=Q35YnRW(UR9 zk_OjG4rcb&F1dMZ6}_zcN5ZN;HQMHBaC)_d`cgwv+{>%&7w#-sQzYKf#9Yjj-g=W0 zgTGge^qu~(`=x4=+LP`Co4LTp?>9~ys%y@Xy+xd#+MtA%E}!lA^(Hqi@N&lU<9#OA zo;iOrIXpZscXt;@bz)5Xw3DtjJ9s8uY9p-)v%#jWBA%N0YTf7cDmf4NrCE^8h}*6wtmmT(ZlEHhV_8v zxKKfcO$%8Lz?HGK588+|$==D*Jzq|@w+9Y$;Tc@GO@7>7^IQmcOUXcvsa3c-9u!~% z=!ZFEauZ-|YgRlwdo3?e%h?i^=e9(yrsrsmE3l1o06NB1l#jTRwB0vRs!yYND^Nv8 zfBfXKyyjBB0nby_qICFV;2JYmzq|2M4J+0olN>V377BQqA)-W1(@I3GZ{d2la!bdd zRv-BWbK;qZW9_mA#u3=_zJBG2T0$%a4m);n#WU{{he$5oWd$3^DHLB(x$|xNq0RFR z58~AtJTJc(&eZ*LK@zZ>-7OJx7*-gVimRgW^_1Drx9Q8WqtxhUz+7mMe^Qb~yV zjd;|L9JK1d_QCVzd+3iJg^?#X&u|P$!{OmK${QP|qKS*gOZUDmdj%PsyQU)}a!P4D^## zFp_VV?uS1*YDM>H+{0p;S-R|aRDLS9W~gC)7JZI} z%p@V2-2#YZVLAo87ZI44#rgzyxq(H^J|hSGPeL4USR8!e^N zn~c`dj2`NZ@r&(7{9EkOTLNcY9i}yRCt?hvxX%7E z0-=1Lpviq&Ma&wblivDPGrW7eH5t*?1!)W!)@=7{Qw+fbbJ})&YKe(br~=EyeQrzg zZ%;{YPdn9~KHQ%1uzhX(P^Km6P<$I(N2ytuk{hKw%4#gwK&f0gNpQT^@vFDByi1X|4UEklxJ1`Z1jHERkL~hYjpzV-gP5F z`dk-&=g;kM(bm82Jl@~|d?QIeBsn-fRc^Fvo3x^!(r(~dvqC3K*Usj8ljm51Z_Ai>v87LPeUZUBn)(GfhqM z+2hd@Hl?H^eOk4BIwO60kNOOL^>wW99cJZUL=m>w9;w-SrX(oAv$U^P^I>VM@SNLH z!nx(R=XZLY*AvEh%^4JjdmgNl?Tpv|cd~qT6*q-AE#|8ysh-oGLDXm zFLGZ!PhEbV_m7}Wp#+;WaMQA3;*&UMRxyRo7RMp@Bmoko!Fwj&>&kkwRN>o*FxD$v&!Zt{c&_FC+4Q*rQfon(gisoQmzgiq%%M9z$-GZ@TLZ^>P!n z1sGiHdGHBcAvQ~KF?^-dj=i+&GJ1aGZ6ErH$AqsfrcQo~y33(EKNNTg6Z;Ot*iL}Y z@L9p6MpDrsJ_k!I?inuQN~ccbSwAR{cQ+oG6v67{OUhyL_0Z4HTc8ih)fpwj1&y>( z&{x25-TQT(;=ttLvOTpeWZw?3@R6Kj)bH2(izng_xD9?QHG4d=OPmYm>=b3q6ai&w z#YXk`ZGc-_*>2$0L6KEa<{{wuKyiNkzItKY+x3zPc8<5d#5L}DKUeMXBLO>|P zLUIfiM>p+OYbD}=>IJ2O!_ZOEGgRUL$Y_t#{W%9Ca~m!%$H*X3Aa3O4qw~?mRn|}b z{@_HLL9$Ydgz}xqb{hG7?NqKr8W7aEVUtzF5Qa#gf9H+>ty?sv2RHCp7gGWoQtaclnu4<^=zeTf?s)5?>P|hE*f9<_ z>L{H+Tt-kQ%m#~=sRrYNIf@x$H;TV3aXovRoH7Qm%)y(K61B;DA*!+sr&m=kbHh9w zjO}Zn#@g|WS<>A;fq37zkG@6j{D2iYFn*;%+Yx&pqZb<}e^48&rJ^vjq(+di0g&^Y zX;UI-f2P`ACGA%G+iLK;gX5A5m#nGkkiHX(WT^{%);MJkK@ZKr;VKJ=8C#lp)^baF zwODhz`&@@JJ`6u%i6DI&+91#`EfMZ6PB@26T6Ik}*2T{*Isrr$gFCJFIL+xc&Sd5@ zM?R)i-GHLp-W!>hRl-Nx|TsIV53H*NkX6qf1Y)N*w(9F*c- zMVU~HMiqkM7&N}pnEL=WmvmEcMgVLu};bqV@nJbGC^sWmF@S#@>!1(sc^d*ssXz1gQv-V<4{pLO@wqv9cJDny!Bq*Q^gr)8Fsdh#S}V z7Jz5B`P!VUKEE*<(mzbHjZ2+*7^l{9Hjw0?4fVJ`OtFE>xomQA@4XUXThKpjFWbk$ zd&g@iSZuGgjupKAt(&8@*O_1FlY({empH7QpCPTrJ_De~!_SitGx6Nj^ej+4;@o ztdkHPY)d5>qzgDepa4rBVFOgsj3OXBF&QZvBPdfvK3+Y*XiJAgoxh{PW8iW@KT_i$ zkMI-d3j*7KC})3{D~y5QTlHKe^>h;L!t_Fm0+(jK**JL}7fCm;$RLOVjV^ydT@@p~ zQ3I#K6vqOw>$2mwmF04E7;@OX!Y0YvNd-h`8N%|An$%%og$l^@wn6mxG0@G5Gs8Gc zYQigGdUzK-J!XNO2Du@_ri3IgnH=HEPWXcd&aQjKs0VSLCHxz0O^$c2IR zkie|@QzTme@`Zxy_q>iQ zlw7X8T)KHl09D($izQvbbK>|(Th*3STz{^Og-ka#cd#G-mOLCUPEDbA*2*lOA<#eA zlzo;RC)w;7S-2kmBuTD403DATHL=fgl~L?Ap|qI8OltZn>TZb7N>hj6WaCQEI)jpW z@H;Joo2{bv)_`{0LGJcxgu(B0yQvILPI*}nd%GPe`8z@~54S$R2k3+Za7ieyV)skf zZEF7Sr|*@2a2`J)Wo}L17sx)7pH@dQ=ZpeP07!YcrA7PoMc)r;T*aJvRWm+a(x0|8 zyg&!`ot~7;FoKG`1;JCd8o3mMFJ&o;-AA63Jm9 zt!E)7sL5vRh^nnX#eS?z8sH{FjAEEK+(FNI?>i`_GC;!Ma}?=J3@lChZa!9%u2gSB zY`yPxm2qH@6jf}ZJxIcY@lYM!a>ml2=mRLa1M#%G$Ifc}Ig-R2NMeo#2p2J%Z9jWu zLAL=+hFh+WmV)M}XRR&DIxQ!JePq7~HMM9;o;UgG4TRk>*|(BA67L~!!-P$$tEK|Z z5di3$%%$-_5`mLt&dKrRY&)q$Q)SVTy?WKszy38 zxz%gIYQI(rp*&wU0oC zSOY(2Wov5`PRfGR95`m#1y^eJtdX;JXBTAm7L_BEDGR}3*rKMI*&>6DR6da=-Nh|bPHJFnl|-;t5s$EkZ_hBT~lVBrqxz?_=5Crd24-miZ)ANXda#*A!#9aKc_} zjGI0$AD>36#L|x^uvMiHa(y6FG9Om_Rqptpl`j+XK0>;l4>Mf%FtIU_N#?duQEUO_ z>mjQU&lBRz17X@SXK4!W7EbIoQQS7AJ85SH7M2{W@a=ZrHDII^avtywt+I~<90%pK z%guDGkfSui%UYH8b0!cn_0S^R%j00hko+||x{ohrwt3Dv7QAz;pgtbS=7n3B8~$Dg zT*l?MJ77Gx7%M)k(g>c#M|yZT++C`EOfYUB<6^gHlbLz#WV3M=^bJG8mIcdN-2A@_ zeWs<}&ycSiuWs1TGFb^R?Cq^_;7R;m#8?W&H&ME86*bX|eDGrjVk-AF6-bzrUzw74 zVb*0NZpr1V9hpN6pop;iFq}qhCQ_Km-nUWX8VLZle2S6i*;=w{#+aQ}D(oyo&@_H>(yBc1(8h)5Bc3S{9Bf+Csuy~OEDE{P? zGIQlG=o_ozRy^ot4+)Ee(2K;>z3DodU?Dk+t_NY-1#pBJN}{*IZoKWvDL3#cs#374 zl7|v6z{W7P8d*|r2s1Owy5FBiMut|%t*JjgzzGJSF3Zb2CR;v8=UxRlOE6ot%CdEk zcE_!7)cI~K9h0DQE=>)CNR|FOT`&$pSo9Ml8qX0zB2bU`lE3(XLN9JxFFv4`IHR7z zJt4DsR+R%g$31Csq1V9Olx_%TznR)~R9g8@hzCqQl21S`Y zlB1NxZrl9i5VYsc?s`O2^6z)3?ROgKcX`zB`m5h zf!hi#ZV)HeFMJy`i%zhxbRK|=b~78TNM?MgnE~dgTKq5m!aVUbQ_c5RzfCP6;`~6A z!r+Jlj;=A77ri&X!`a6DB7HNH&6>nHhd$D#K#+wL$BTQBNtG9+aUURi?}D)*gYZ^(8eznI8D<3D(aw@Gl%u28iU~t?ji^44i;V~w(?|u-_X{H?Rwgfov0a}p zg{+~^0sPbE=kxck~31p4IiH${SN zy(cgk#L>djQW-?t_R+9j!L4c7mFQ81=t9=YsG{PSFu~E|zv%nlHN1S#1<(P=`v35C zbpj{(jo1F4eOx>zu*1{IR0Vt#q*kb>dmrIN>2aj>u%QYcHa5_ zU%L$V-o%J-!;5E>mudd!~L)CbaJ?J5yS$k{bJ0tK)Hu`GO86Oa141$omeaRwl5h7>a;QFWAl%3fX z{p`aQxluUe+@TGXJv-k}**?=}g8#X4`PcW==Q9m^u3q``YqN&;**{mWZft;HT8k_w zF=CO8(CApq!kDcrW&?Iwq8z+;geX^be}^bfF=a)RPb#!?0jU;NK29LF$==si9kOyO z(3wah%IWlAK?>kW^7GQLIvLjS=Hf8L<2FC{=3DI~cB=UtN^5yu?pE4bs6&sNFVN(9 z9R}3FARLR7g|L}YcR%rCzJMxcjVazg5Q&$s1wAj^udn^1Q99)k<%^;$X2v|6<;ZQEqYoR>5q*>s6Bnqi5p6_-1|DFzd5 zT#UNPHwIsKqZ_B)>PF|ai#x$#>8DR4L_eQ5L9V9IN=@_Tw1I-@FfnTKg#+D&)~XWV)6v*tU3LebFab*SSxKz*S?Jl?azGv~&$;E0y%-@izi>U=hl z`(9+Ue6~09Ph6SOq2dG5yipYE2i4cm#+z`Lpf8(r1}Oq26+VZL%U)ho@=Aku2R$y$ zf-MEVrch{SD}fx;r&6~M8kPGR0V@vxp2fa+)mbB;VM!7LX z1(x6~ujgbK@^w`81k%z`aT;0YU|R}Y%Q8%Oc(2X(`h+6N9FsK3?XSif>f06>6+A&m zETJGNRAb9iJZm#*KGxQ~P+8RE6w-c!ozr>z;C75c{Y9<^0a{}H15eQmv8hcnIK~bu zdH`{Q`6gLqNcGNoP9_&@@g6sibtt`@)#s4)m|C8PwWg>+3@(GZkK%{K9%-E@t8YxC zn$a*M{XV3Z`7*wy2&wf`gX{gIPtTS&sV)?bHv|7r`Y|j8{iUg_(;X*ON0+EGpIqFh z!jDl3_8K`2-J0D*T**-t`xM8@tF6#F%uuMTtw(z>)Vl5k22Do)*uc6eYBzwo_xrg1 zD5qh)C{qbydf-B0s+|pF7fN8TY(lA^&g(tMIshu~Ee5$Y(}f;0e-D<%xvf&e+W zPgiD#sI@|vk^X@?a~-5&yedSDJ{ftH&9#zg0btrLbZ!G|vE6~7<5pcrsrS!mgC)GN z(s+0)=W&yk09l0)_rKFwNpYz8HEJCrY-j7~5W(@bhM(N>$&FRyzKAD#HRM6T2y2;p zm0GsLMpFgrOR{{2+lO<&=;Iwa-kkSQdqcE<-I8kHO{N6BlmR)hI!QZ)R==Shc_5zX zJa{2S-fKUwCCLo55jw5-_cf6ER3riE%vO53C@k10W}Nd7ToXWqYK9V2(2>RL$0&~- zBIUvwF?t*o%-s1xho~C@a6l-J4sYTp{Cd#?YT_2Wv89cDyKHXi0Z4t&(E_Oup&Bsq zWsf>ybMd~TzWVoK{;sbVoFUZb^uJ+t+BpSRK$&sAO+c>d1rIV`ce0;DxtmS8p|#a~ zHct0~hRSuPT!;mXx*7?D>PwNw7UE-GcTz)kZit0g+I?a@vz4} ze9x$dK{393@hRxBjB#hU!)7Di%_noOH>Sip6KlR&c?nrVM92`ernTvX#XrlEV^xU0 zL|*p&E#uBCfi>4*6ywQ|CMRY(&Kj@0s+p|W?D)V?w@(5)y*?5q5HRi1#-e@8=E*Kp z$yVKc!U8Sl(!2+;^Xcvf@JzL7!>1-^o;%*p{w~7Q>)D*q;)axd z()#0ZrJDA)C%V(`mjyWV>1I7C6`m2o9mf(8<*)k`y9Vm^jS~e%{9{x6GRSMIQ)0r{ zW`XP@iJ>)m<|9BgbvbTac~VJWyTX1)TR0%f-gc-UK4as$Z0ky-tsV8_@qPn@`0Rqz z=A@3&I#1*|o7|X6i;;;ZgSKugf^Te-OgzuJEeb#hbg*=dP^X+DyURAal$mH>pH>ka zk=8a^asn6nNGgz)Q)9feP{xXO!!RK}(>J+c6!zv8E*%dWOK8dtzhsoUx7#wWEV13j zwc2!&s+YQrcQ;x)*a2cQak0Qg>oSS6kaO$W*%LwV#h%Rj)6WOWp=yCPvMNtsdGi9_ z8)@FaYksQQ3Zjcv-dyCF8tx!}I%9W(QVH8UTkae^J5#O?&D45pb6wW` zd2N=%Y;cmp;KFr-^j>t+1-lQKpl?>DmbV8MuACX9$zK@!j1FGt*17Qf2w^D7={5Sp z@#g-Wh(?nm?^Ut)pKb(ge809wm*Lj%du7kA+}r2=ejC~NbFtEPOVn8Ax(bIlH+kjH z_kT9N={=(yw>xHt9X`@Df~+tIkbSY{HQ9GX z2E*RR6xms{$&CHBgje*O{bbCQ#GHNZn!2)tzBZW{MvmJGe)bDc_zLIQK@9ww>*q@d zG|oK3M*EuQF_?<`2eB?S1m!f~`fOfQgfzi{@bW%3m4n~qo8M5DhXgCtiz!<7g=TiB z4GIp;7-x&6alUPUF`MeZ(?-rh2q&`Ar0NCdb0cbkvDrR~L2GH|Afy{TG^^VRJ~H9$ z0;mf~e8&MaZy}pN))bS*^l=J%$rw)xbcTf3#GyJKY8?mKriCl|gtE&oy30h*@Sp>$ zQYl7ao0Vxif$4M&rH_yC05IPeQmIB_5keR(3|%%5dSV4AODp-j*++}O{3Ju4I6~0W#t*D=^9dW-iBiKA+X@d znv7oYT7rjSuYY$kkjjn85WvhB(1=y>eXLV)tJ~ra6^`Y@S$w~?*D7^Do?B7_`nZkxZ$-b(M8bjs9 zvS7s>Tb+=cIytiD%}U~q>I_43{Q`4TI|+R!%fKHgeSIBkq}4zkJs9h*DCbqM&8%91 z%1d`Jkc{GCz;&{=#$Y3T{`nI}w1@-d9K1a4sfkRqqa{+lsdBV2V?HOvEkP?vPFja> z|4Wl>)@JXpL9=5smYipoP*v%+1N1s+4?W+~5)k~r7Y*T6LmF-UiQ{uEM5`9vM%dp1 zxrfMB)M#@tw#9c?1@W*oxYr=CP^LMok}-{Mb;JYy_?}LDbb8z7EH*1m7EWxoGPZi> z*HX!Ce=BlaL$>>oTXmUj_sk45P#r;KEfq|~jE%xgN0(9hkPydhE_W2x3F;a)FEM^-+>C%#sV?CSMqTTc<` znIOdNDx9Pr_Df=S!kf^!B!`SfUi^j=(tI0`{`s`7F79bFj8=q2o4{=X`p?(`0cmP> zZx0&IB7K&Sa=$`;cJf0zbf-k7V`I2Ft8@6W6qkfTdV;nIw2kh`k+0$S(J!b{_t>ws z)O8s~IrlXr)a2f2OmtTEJaRGZOopfKIVWmg`VoS(SJQ#AeD)Dyw!+cyMpb_Lpet5q zqH*vh-EetsaPk!64wW*<7%B}Q1S${`9t}BY5dC$A_xGj-uc0^N;tvycBW8yE*M@hO zWk6>8_-{`#*TOS(@vD6!Q}UQAy7;aoL5>(jj~H=WwWy~@B|b{3(Bxq_ejRUek1WIM-A>} zk9sBSz35DQ<3#ki+xAKBKfUjN(>DS%1#*Ba{~zc(`hTRV6&?FprYf`)G!!Db!>6l_ zLjOhI|MtGGjPK_@qBU6lH+|dnhwBP-{dZUWSE{g|Dtcxo1vpF z|Dx}&*DMmD|0Fz-*;BtgBjW8-397`wYZ3Q;E4yAY57wBd&<(zQY3NY*wtD9VSEcsS zHw)*ZpVcp@f8X@JgE!vg`d#|*c`+f+4KDMq`5PG&neW&lo12$npPlYe0*o9;8N2{-$-3Nq zzb$|lW2IyYo=mJ#8MC?TrmWqGm9Io8Wur;)>r8EWX}GLFF-7f^rj^iqLt3DfsfY@z zJANux)g|>rcnFDh%639Y?ACtI7!HLF#6<1Lu|E&48H@o%>GbEtLtELofFq+eI`Oub zv$tUeBYUPZj0tuqwR&UPOzS}#kveV@=#K-}{rlo=xy@nk zb&7AQcW#bVh=&9ufMf#jn%2eQ(n&LEchhmzv1ImyFuG?pZ;-y$dlnm_lc8n(G#!ae zj9bt9vOuEmK6wxP*w)QZQP=bweJ2qgqud33Dl zruQ-TfdY)HS#68D)<^AgGlt(SmpW?^JFPRGWF4hb&%Fv!is+-7r7H-8S1Y%Yrca;U zDP;8=j2k&HJyGiR81f(%koV_GVtxFfwDZ=zWxYtxbMsoNw-G(|=;4b#|Hvx@NryF! ziC<&o8jmPKEz&F#sOw}kS+k#k5PMnTO&1}#*Sd0U zrz|#<)j>YxSaPv=v`y;4stnll-kXBEz8fB)WH*;(N%avP&D9(``{%kd zINRZx`PZ%-BX^GPrRgf(^|A-NTja@ExrbLG09WMFG5Fdw6u~M_Erwl;p!yPD$;zn) zjkC^z#7pg{g_qfC@kyALs31|Tj=x%=559#mbS-Zo5NhR9IBS@(04O&0stN&BA;EIX0`0S81R20CT``(%LoAqfY|~ znXrhQD;nZ?oL+T77z81RQh7NE@C3Ypp4Z0Jw4a`2eAMEB$27w{JVIu<_tmZ^)$*T}OdTXpE=9XibM*Y`&sl=LgEKG0rLTH*$NwB(^+zuvb?m z(W5TVDy?#1(r~oTv&Ps#mR9vxTMRVY_4`GYykp2#DPyl%sI_d9jZPM9&b1*+GrLL8 z!SIb>TjK&mW}F+E2t@6@_jrl;^tS_UOO{;jhl$eg*wO%tCE@0rdy2){_2{Kxeg{7E ztazukJJHK)kee^d&ejR;^zY*5Ox zCl~A}xz15jS|M8|{i~&IS5Y~AVzXJ)6f!nGU9H`#6A^f*k8w(H|7!CnCd)b`_`12B zwMWnKWECsqn{e6ss~rpZ1=J~y@5=eSx+;cyH{c{2Zy>AxWYeIRw?eiIVcCm$DlgEN zcaGn{vW3HxCiKjS57s4PZr+A-cw)O+w(HKxa&%MQJVYYGcVA`M?sC%W{p!8c6hv;Z zy7PCiIpqoiqbRFdlF#VaxFJ~SJ-u&oft|IibXsdT393B@drhb?Z|RV`WU{pG-4u)zX`Q zd|L&TPFth&7{DLSxN~8BU~p6k6e1UTCnd0;RRQ;bol~n@Z)9id`nxFd>hjH`9@`PI zcy!Q8)3c4gUmQ{}Wyqy5**_Ojyu0dvneq@Um}F~5axF{-XAhvt)@jOd-27-o^{tmg z4;>&06&=MS+{Pe6&+PIiQ1|aD^z^y0&QI>gYanEi-Pk;#C zMMV>#y|W~VN&53@SM|QiRu^tj>m7Q*mu?O6 zST6j;W>7 zN_m6c4}))Cr)R2<+){?dD&#y1Q`BS&Y>M2P2dWIDZxjaRL&Nxq zM+VSO?SL_%mKfX3WWaBuDt8)dTC0(*EDgde67-khiHm8Kq96&XnEM6;NDnvtb}zoi z({=Pk{!K9F`f99z6o31Lyf`GnL}+1?m3KbWFF(Ivd^C1vD%Ei-;0)TCR`6{t72`Lu<)SNZ}yp?O`t@~2XgUHakXHNc+dT1)NncFW!kp%fD<)F}V3B(-?V zxA;~<0BBcRvEv+zi?HpAZ(D-CY6FD2?g#wc>KL;Zn zaCfHCJnXA!V*rEiCT$rJ_yVc4`&5o5>CLuC&a1?$FveX{PtLz6lq9TiLtAdnX1W}Cl<2Ac4(i7 zA<&)JVi532yE5$;c?Ze)`9})~aRI zKARip!f;tr|7L9CK~bKZNUQD<7*lux*n9Wbup8zRM;d#w1UA~(GD{o7s|+1hwzdSk z+gogATNmkDY);{Cgki6+tc$|6g45d`kj->0RAR;3KlPTMY%&QsrSx|+KP4T%OM3Ii zX?204467u$)7y^eNK0(=2OkDgkO!2BpW2GLlzQ&8JnU_+>XQEDBfG<TOD?w(eeU#u;b2W8Tb^aAYmNmpcUs}i$f z$X~v15!33glzv#+x28Lv-8oU_W;?4j!PlMOb5FCEvRRh?ib%PrNo$0-*{4A7lUQOw`1s->=EK)yS{D?eru8P zXE$Is4N;5^s`(03{UUVc0j~=2647d(g+mG9=-Oz4X~4im=@DO%HRM+?$9W{a5IqVa zyD-s4N2EumNB+)RHpe5u;UhSAuQM|$+ns^6)xn8v(lb2qR$GfNzU`*ek!KXCyBiA9 z<4w@ZEb&MXrWr)=7ng>6ToUQJo^yj<=1Ds8#5d=R&XLYj6G(qWmp7P_V6N21UpN9; ze2^#gm;`m;!n53VNi1KL6lG+4g2dUF&{fP+BY_qjowX$S7=T)l;BkwF{d}#@9f0wf zt5Vd9=xmU<2n-_ug=a<$-6dZLBy4$57D&IEVLyK;O}uYc#jq;d6ay`j`a`>>)hKmT zS8{~~^`#-Jd8#SUnxPTEIqTee&qR;^4XL@WOc9adn4c-33xA*`azRQ-f+Q9380x=n4M6fodm6R zQ_m20_Wb-vMth#Co4oXgN10E?E#n6Stg? zZ$n~gsBk(L8c9RGO+@w?(LK{|SwZV5?(h^+2ZX7Yx~aj&!y{h%~NPpazmU&S&Y_{!A*lZmKe8=(@N$knaW3bU( zyH$+q@B?=9wmk|yzZDYW;gv)4!A$;#W^J_YU6=QFY!mA2M3&yn!Q_nHo{d`X#75G6 zZ`#xEj)?C1N|>58&F>+C!g#Kydb1rzZ+nvOc_hrc7Qq?2r6q6PSD<6m?%bPeB-Tda zcfZf}Nr2`VJ}@IMSUD+IE(@u>bNwafeg5blINC~jORoF#P?P?^FTM4l%i{(zMkC~L zL+>MH@RR8ttUz$*i2g&*-nl!w6<2)-gbnMEM-uJf#HU{){TZXMPU_?3Kg1DT>AtR~ z+Ot7#W4Co~)+6<2`ya*Qw>`VE8-4RAa+DkJKgIFTtJs7uvj%1k4wBUUuz(WrR4r1Xo(1NjewJV42mJ-MBbQ}W1BB+#sv4Sb@^|F!gZ zP}H1`KB=Hg*eP8z$^p-GjSG1f;=Pk6mHsqO_319|?rk-_0`$kDtzDO2HlpGfwT|@x z_O1;Ktb$%(gUJ$lb6&|jXnB#0*|yU)Lly(AB~UX7K#+=s=F6QYp4)wRX_M>re)rSt zRBtfw;*|(_d-vIsdzB659z_!7w`}@S^ zn*|BY{@Dz@r}B9Tl=h1Pd0)crGP^#gX7k zJ3o-0>REchZ)w5-iCOZ~<-2A3;N(YgY|)AGC2=t7+tLT_nUBApe*F9QBS>Wxa@9dL zaZ&7?;#;=J0}SV8t|D6GTy7J$zF&1Hdu2JhY68}m-LqCp{^-Dlnf0wH9;zB@SWMXj=}xk zPjlcPAxIW-^Zy`E{#WTk2UYIh8{PksCmqXg!(bNw-sr~0j{c`S315P2+V!_LH@b=M z?!J|wGOa2$H@fi$rrX?_Gm~1UtGa_c{_8Xc*unmPFMS}6m#OAIy$Te8{wo~R{AVpR zf9YT0pde22r(hp(akyLfzc#wl68=E`6%OjR+4JAwp!(e-1MeRV9(w!q*2u+=&jeDR zG0MMucSnsoQ^Mu+SVkc9qZo4a!Q_r7lnOtf$wmqi46A zG$^@n+&n*0!A$IGhNFX>#ONFJ(O#HM-A$iUrjO@yE4PHog$BA#bWm>4Kk4^7g0y!G z3KiK<{!N=(a+7!SjrMxpPYV^dDo(c zM9vZmt(h7f~bw`sNp<=ITt_@8|3zZLSL!`mo}(*M|TZ1P4BXo_}#n+Ls{0N;$D+rRc$ zt?Q4l8V7lbXu?0n53NQ6Cns{NAAa?Uj#7McLSbjrMvlF8rrL5i-62WTpmN?d3Q$Q~ zbdLskv_!p2iZc$&aZFY2Z?H;jN`KeCJKS=i&x8=wL2vMQt6#Q|srzAY7jv5~eII6C zZ|L0sy6gn*1+``5%e^CjQB+5{hE>4L=#N)H($MB)bnX#1Ww2&9pNro5ZuJ^queZ6; z?Gv+hUG_lt+Js{2yR{p~lhL0hbHIHCzH04{6_n#U-hG-usiQyN>>YCYeCwrvzY1 zW4}F!2-cZYkG%NgE?;T?mc~a(_hYxl`ajbrv`Bs5m^1jzoLD50Kz+w~X2FFZ&>)RIo<3(Kb$?qIZTuia2v(!vR9$aGO|g z(}FL=Ny;~RYdC`X^!G~~W}jX@zMqt9VCsNsL2$D#2}s&;v!ib=gk|4eYjBL(+BIvw zs{2X%3G{!l_Fhp3JIwYdg!4_?&_k7?7@AZu z6fr1j2)zeHj95O31r!tz6|v;7|8d6I=W1W=F>G)Y+k$P3WnpMdlSXpAVuxJn6u2t7Facjr~}sp9pn)&ouhc1GefojC~rW>3_x zryGfWTt9 zKC}1eB|yJC2xxa>XR+i#XRV*(bL8&~jf7@<8oyOl(!;1p{pM_)XVAMW0PM?=VmX?= zb6^&L@m2jX0QyTy#pd`ERTt|`C*wz575r@4 z`d}^y;-e}TV42Wqj_{5uRSn^Y9oTU)F0{8ww%n%fqTKe^Nmm<6)*^`R&tZqo3FyHL z0KI@glT~Rz0ml)WnylfdVkw&b#2D~Tdw@W`(DHXfNenbS@bl1NF_ZW^8t93A2ZEI+ ziEB&cjw-X#b|fXZ7EuhZ7|XSO!81sWZW?sFlvz37DpwRo55( zK$q$b;;XnzR{7zZKOVfZFH=l85Rz)$%o>IqJa@wiLo&MY;K`NNgnHQ{DhA=5nhyIe zoHu%$-;L;cbpft$bda~vF0OgnwNH(l@A0iN05{+le7^J3Ti$%vlfreqYr4{J{))mo z|2^MlSdJxvUxIor{i4b-j}ZS`3DgJw_M!yOXPxv4GW`44Qy-qTfP6LJ%?6gFi!IwO z+>GhZ>xF0?e|A_r8HzPeoiIER8!q)~XAnQxmV0S@S>gB25J9M&p57CpE&4K=ts$pp zbS1K;&DHY2>Gs*m*UyitzAS$jWK>w^VT=uTl4{j((hRA}3OiLc=KifuBT6LOZ%v6W z9ZhLQE{!8~?eIrS`jelB^z#Px3|R zZ3mBYU}^fvgwdWOhj=88kOS zRPs;nUU?X`ZIZl+2#f_`gAYvGIZtJmrzpXJ(5uBj1pnNdHA!^MR;*ly0m&;sTAU&75F|m6yfu z{=@2)oTUf>5olo9#CC&Dt0hCXr2)*j)88|vX_D>>c*|MCbZOUcbPTai z=2J(;lQZ@YKq9H#uk_l8;_}GOCuF==)dd193{#Xi;9Cj4<)JA4B2^fxo4uHZ+f#$w zC`}i6f`j>2tVuu>%^5=zyW`%m``AHgI65PbKzch{gWbsrQ?>Sb^e_By?n4YIB}Z-{ zMfe&3vRVE2H|-@Eds@R@l!<{Q!8sBSPuuo0m2FG~NyS$d`W}^6+`XE6Fb&(A2vOtc z|J%w#y{ZqY*t+!fS{~X%vJ;E_ma&aopW`dfcU&*>3*)~q91I|dojnUj{v$wCMM;zyl%2v1a6zfSx9`GaC)xo zwuauPgZ+jR^82JnM;gqNdVmM4-x1Y9%%9UDgmsJ95uWCY0)X6$)DDD-r z2Ca5-r)|RGV`;JQC5<}`OPM-dER4x(W<+jyoUW>zd5zCG1b(eCB3pxoS5Z7qAZ5Uv+1>E5^2(3ZlYw8@#&nZ64U|ZG-$sgxMr&+`m&JFvZ*Yyt&b}~<=kg}c z56;AQOdiZfmlPCuDEK?s@&)KqMsc(G{c@ky_~CtGnLFfRLq~(Nf@-wk2w@FICpg#Y zEBBkXsY8^*iTym(X14h<KhY%L!$`j zaB`Qu%zq50P|X(;3a1o;N!GbdKv=>0sLq46t;)sFb8t0ah%)9$x_WAEbz^LM1b)Tw z(-$L$!B-ed9xP%^f5hivsoh|)Wh#yatDZ3Q=&6~Ktg-HM#Q(v~K=udr9GkKV?(sv4 ztuwv}SuQby`#To6l+o8;i*~l&UiryiH$Sl$2Wr_@35(3BN^(C~Q~mKFNXa7qT6+fl zMpM!G*rfyq50f`^a7E9MVYi3m`k!asfL_;4FPl)+EfnVMcE^a+A6MT4wy~9M1L}Wh z-@E|d#r>&f`{w(yM5g|n7rLIoU;p!s>*5`-z`)pY7jGyA>S{svw4{6vqQtj#-ag;lcn> z_Q4Ypi!`GHry+88KW`_p8Jj&qA!QMm#g9RLvBP0xuuY!7Ka0pVvk|} z8@^+Nw-Zc$+l#iO1JQ?fAZC0(iqPIyQory6lE>__J-HFm$KxqxyH!-<&OX^E%`RG# zq%>WYom|@rN9G|L8n^v{66H}N^TL(R9*MySrRY;d|nXT4`Syf_Vg(PwGCNw427?a_XVz$x+JVc2~_`mZ~nta^?c^A+y|6P zTC7K%R^W(HhijiSm*l($dqtl$bTWINm~PgoRJEvqkmZpuhoD<7MGT6ZC$RSH31uNs zrw?&SeTd`3zJ1d{6rr-x^n=i6<0EAQ_xSXe^`0k3pH=S8 zCTX_$#9nist(N)T;Og1rcSEM=hH@rjz#8pe@BX~$hk!!Rgw`RXQC@;*Wb+oYfbcrQ zOQ+6Te%Z$*by9|Oe|%C!EZ4P`L8GnQ-N~klU$eGV3&# zqaS_q&O6q~U%8d8{un5HkxP*W(p;?Ef973(2UggEks?34&(D^{9NC_#7tbtzcGr5YTkrbT z1q|%rA<6}nH|K?}ZBsmr7X*)fKKsTPrldHat7Ek_Eqo^7MF!uWy8`)O~DcB*V z-5xO{6$`VI-Ch{l-$kPQ7_D*tozs?meEvVqoC+iv4~1dEGbL_1AdLw_Fz0+YCVm-Z z2qQ?I*vJ*fB|>_F97MM5KtbDJNGrP!(LYU=O;CXx-*JiYXCP9>DGFPd+3XkNA5v#j z_<#y(9Fn*xtgEw#k__UY4ij^*33%uLs}~ExAY^ZXAtO=idan)MOGc6vb!iYq8iu6z zM-q8(N6_pLCT*g9xu7bpqrt^yGO52?;rzdJOgkV=GL|B{$aO~H^YgHBH839-N#g|f zu;mmE8ymzaHr^DL?FV6s2FaLzXCaz@z=A}B&|_)`giQ-~=XpOEjjw>OBzPpa3O;R5 zXC33+69HjvIHRukW{bFnPXQY^h)E3KFiBZpp38x8xul@%aOn78@BT~%HA0nuaEJB9 zZdR09rQ*a5>E`?Yd?Z{7?*D8^iP%iBO&ST(ClLNOGd@twYh?|vSnb^1=cNv)kv4(*M{@W&EO8(qb`7j zs?g+qu)@l=iOnA2KPmO1!WwMoKXl%YL8~X;1<#wU)D<=CQp}XjJc*4$>o=IohP9`C z{QU906>q5G-?rY&sY6oLZ+biWnopfhUv#*NS#Og6&YF6BadPyx@sn>qzgpMY&A8JO zehltB^nS8+#AN97&H(N;o$i_2IrIJqe^;|f>Bobqt0rIW{9X`#%HJ9C{T*@&D~iJ^i;A_Wt*KFLs6{f$)3l{v>E3306u%?9JzRB%vJ= z2Ad*^PZ1AFkxWd%mZr$C_UOYY3Ogw{ELj;(Rt+Mn|6iTY9cEEOc+{{RDiND@44)Pm zly)L9Evhu_6e}&3m$nzNipQp(!>1<%rC&@;Pb^Kp%u2t)OTV_0PQw20sx_^YmdT=J z^JuyJ9U2{*QGm}V3d$%+%qT6*C}(BdV1*xH zg|;JwR;z_9F4C@>Zu6_qwXBHHUHFt+ zIa`$4OBWfe=DP)#W=9vfX%^GrWllg;I~%>hK#wp{<=tgBUzSz=Dr2nfJ$TU7@B?iL z<+Z`(cQVRbUY581DzA4#zbB#R+32od^yD6Km{8Q^Q}CFXd+}vnQX}T7n}~T?p}a+r zePfZ8MbT5hP21HX768?|fn;sm{Jev7@4huHUH0~6(PK=pGd~46AFn^Rkq^(fX|Z~9 zI-}CzSH41HP#e%@XzEzC5bm^y;rI?Xh zscuD%7Nz3Bm^pZ*0I&*nnDJjU!&@4VA1(eGcca%4)yWp|3dV3U^1yA?p3*4xMwQ$& za?qd})JE?G9NP`9_!o^HBccp4kxw#iaJsAEmob7PjO)<_sLMr(nj)yx0$~e`kme1j zQk7y`6-eaP;>$X3E%C)hG>4=x#zv13ke<<1Kk&uSd66&pJejtNAvRi6x(3KFY1%;C zBe{$a%Kwa@{{^F8&*bSP-7-WJ<17nFNjHc2Zgparxgv{nHWx0ii4e}uwN1LQKS^W~ zUL!1x>h)oixr;x>pyn}6-K`=8E+T3khm70ZBhMK_tDv4`x&3t1?-BHy z_+r2*6q{av(yV!frMp|+R`^A?>aMHV#T<2qvrb{!#Q|5?VsGt@feQ#A15r=9;~FjA zAK!$V&wETn2ddB+S{TM|>qZkMI`f7HNdTfme`JAarK8l&qW;WdEPMo_ee&iliW<(N zIs+Y=0*3?Ba}eZ0}E};TO*8zEDNs0f=zc`GnId^g0Fe$jP5zNA~xXIBoW;eUBP3bfV*`g!!0M8 z=?bg0=C2-GzeINOF)*hr!Sh*yA7TV+e7ZX6H5LY-miYqdUtL>crG`m}<(MZsF`Y*Z z5SO~!?KhF8r|O_eNZx|{bTS)ulMQb{zagO=%eu#K2r_6l#cI?12Fs*?<5Spo&L2L7Q!R3`jDg{@R}*lH4#^Zn)KFm>Pn) zw}2?&&p#Lf!1iE^C=7svfmw_WmZ0u&Gw6>=WdljsJml?(;39(c=n4!~!yWjLyr&V~ zyRHPu@tlSO@EFoVV-@3uM{wqqv4=flJ+H@D+5PV-o_?sfdqH;a_#d$y>8pYwdu1Z@ zEG}On{Kgd@0Z0{8RTgmJRa>$Srh*GEk^!WOO)gnaz6+V8o*xrfoVdlEFfY$dBmqHt zQ=A3CB<{#t*}Ja^DDIyutJj79{#4e=aX&_l1|50w>p*9EjNnBd!9DK9CB_~uK@fhI zD;_#6d372aCkP7Xa&$037#M!-sa^g!tap5}XG#JH!z{LakOjD0>2H>MW@Pisgm3dq zz^>isF2)`Ma3?^)i!AZYimCeSt-U`pZLTZ2x}MPKBsc!T1DcQxJ-hbIHV$*p6B9{) ze)#e8U>i(`JRr)4`_t-)j7?simALBT@lGG~40l8&e*zRP7)^o_Z$U3!eUW(eg@hp! z$bJE<~PG>Ra_S#(rS=Xe*Nh~_TL5!=9s zP4I`fw|4Zmt5-!2HlmlV@{owvY#WidW=v_*tca3;)m^X|8-q8%SkS?E%mUtL0eWqL zuZxMp0Me}|H&x;;Ii@CiyIrFzu#~N7a6hrYs2V1@`Ik(-@A|+Vg9x+nYG9^FCj)&lvkU1iim>>6 zOsS|h_m;l5=l}x!JpRkuw~B*=*P{9B`|ZA68hJB!;8xc^WN{MeKwq}!0o35e1NHo# zkTcT6uit@yAM^ug9tPzdgLxB=(i9enXj-_t=ad7r z{Q_b-L1z&|ICR5)k$bl>MW=7P&up4-h3?e?8JOQnixZVTHbrNo_8q_+N`|NI$B;>5 znTq14xyV*F^gI!Bo+LOHFF1WqJeIkDoQ5RuLooZ}1@|t^s6rV$PZwA_XQl1G}Z|?J01ieL(mG2r9O-HxLW6BY2fhQGl4j)Eg+q?2J#)^&wU*jk{U;z3u;Nqg zl%wEO99qg2NgIDEEnSkPh&zqY=k6uONv`N~;OI+L)r>vO3oKU7k;lMY> zUE-U|e~%q8nNSZ0BcaGc9XP|&LpuTs-`trl`%fR+wSmP3-w%Ae6*hP?_}hueTQ=8E z?A9U6^rPn9c`gs01?V#JIl+bf6F14{_#b#>DuO1GKCQ3EP4GjWl@U*)1=Y@*JUE>e zx*#y@`I~jXd`M&UiRc2d*9vjrSs2<6-P-}tx2XAXpgQKq`kSZeibt=#jU1b6w>g2N z%ldrV--KR}3W=?vV$B6aoLg>P&L5B*v+g)v!VfbYnD>65i>&a!7hn)*#&6TdY1zoS$1hvQXYOl3+p4IM!X)&UUd z;&S`TveR?^4JzZcjxe`jGo=wm#6$RkvT06!mhR~=c%G}p$J!1rE1MWF z{U7htL~)?k$SJS3SUB6B$X#*dV-H6unE;N&r-;u?#ZG_74P^a+l!nC{I?EpEv5vCN z(fK`KWR~XM=Rns}rlG{ZxZ={&4JHL+cL;a0>Z~rkzaMz?`uCM?E7IC2WEpQ^vpY2B zv2uo97YT7V;sIUK#3Vb#ArlYx>l2QciBhSWBQ!bmSB)YO7%NclV6N5M2_)WH;Ow9f z@#}#3(W}w@by7sa@unK0dS`sCDnT4~lE9{bQ_i_&0FYKX<4OkkuhQzIEU z-;2|n_gHyS8P=u+u=e@|sVG9uKhyNl+guipCeE9mymjfrFRjD7YMs7!Vw1L~fmHRE zgSF4KP1%6!DG#HkNYl>z@;(&EnSGpTn9!h`8K09Kcp}HIBZ4sv9j|9AFW_S1)K#L_B`i`%+lqgWzorAqlmOX*|K`FBNu$9l$v&EB!V``G^tTA!cT zi~|edzid!+_d6@T!P$-%7m7aDgp)3i4+Z}1@T|4_HA~Sj9F%t7O%86*-7wGyiPG=r zmdY~z9Em*WEYjaQaXa01SJoxpN8-iHhpNAMS067kt)EP(05%rCXYXbDc9u-GK!lns zuP{T&oOfwPpepNOVfK$Z?}8}Hs|I}&`k(0Xs}fw2V8TR!bv`uV!az7m#dXENuRaCi zfE#2J0R}X?6w)2O?2JaCF^Y_il~a+HNg0Pr`8}n)112Ui!Rf8`*xPBcdtrmpSbhTMAwoZ6!7r9r-;BsiN=m4;k zsBJ1BPq&v*)cS5vGCYdnX_p!y_kO1^Fk96?=t_a1*CI4o4V<1}Uv0qn(AjW&)bzE% zpp?85I(nfxLvZzliZF+hny^owMX2TKMMxhb_W4SdM`$=%j7nUnF7onyt}%^R9y8_KtAbi^>I2YXt46Wthbyh z-)@G4lvR*)$z63atyL}$sUFd$jD7D-ZUO$xnv zRvlB+kR~8}E?wIvLj29~vCQ)7Oly|CL?wOk`0I**R#kNO&w;NeqRs{ewy9~i?p>c3 z2P}C5LKn#-xszWOvXd_g3I(pD;$~kITWzdp#T#UZw^O*Sor|ImN6*llvZXCHhHgAK zRvMF$kgv9W_w<#CaU*UmCRm3eGX&VY)iCEYv9P2*PaC6Att0DFKTC0fV(sXB*C0=) zi-Cua#}<8Ek{-h@Hv%);3u_G#W2385)V8JL*X)od1N!nEozIu2FEOrLG~z1d5wj&I z*VNZ)?bL*=6C3AHaSNcS6LnD8wU~O{HmB1e_tT6sn@>2Kmn;1>(ylB!H*fG_CBt2B z`1U61kVUn@-%#Jh5rPkO8l(6P0ZnR_^~V?DxPW-&{iOE z=yu80F~Kb9yIb9M<#OCcLC<>G>dP;k!#~_%on1N{C_5o)>D1+Yw(Q=p{R=jjl*}LJr1JF=^{zx& z@u3bejY!*X|JK|-+^$Mhj9o+#=r={l8v>?gy^;si6P1?MGfa-!p)Qqe?pr*+>+;$S z8a|uSr#WPKF3;JdRV;4W89rzT*n}MHd9`0OpGHJnis`EOtu=&8GwJMYlJb8y>a{v4 z&$(1b15r{D=acPmO=rm1KFKu2#5svGul;nBMpBKEeXfP4n{w^3Q$K|3D7PYml-kAu zfrFFXP;HNUol{AR6dhas=WD;-N!@cb(Z!<++>HgMxtRW?3*LvV4)Duy?XVYqf8w(> zKm{e`lbv79#V$vUOT-IvAh!+UJo`ziG0jrey396|z88O=XN67mjr@N0!LvU<9*w$l zMGNJp4{1zlou*vA7frRS(#`?TJ4C; zksxT?3iW%bjkG4+)*q|pfmqzNG&FIM_Y`ZN6L=zYG6*`_O?PbrxcBG`l{K*Uj25jV2?@=bAKLrm}`IH_5MRaZ!9s2PZN z#Hnk_bI>@xZc*k*A zS}+s(1qrRwp&g;8ogxgBl#a9#RALxu+?nh!4b(U|#{zQ~fFIFow7)Cv;Qx8F8qmvK z9-SnYhc-aQ`p3t5AY_9BC01+(D5F2XRz)@KK-Ab6AnkTY+P_zD=V~gE2jO{)19*~o zym2xY(((F0?;~p0VUHR%mH))fNJctOQ8m*{B#Ra??yzm0znu}f0y#>u7h2Ofx+C?_ znijf2J=_3U6$hg~Wk|wE$FSb3vG7m;Gz*m>v1_iLl-v)nXuG7OUm+m6Un@o9m>6Gs*xp~Zife2C?kGfX;!0)%mAKk{ZuaR&gV0TZlL-(l_G zE3;9>Vy13)s~a*VO{iX`5YIP<{BUEjHisxU$T1Cw!Agb(4i*FhgmMEeh6aWWOk9$H zo~a9L7l+EpH2-yQOSsDNlluylr_8;Z0x;>PeP2DqvTmu3DN?kcjO#ZGjU1UUyCfgNGq z(9fhYU19QC(o7ufULqtS2rOX7Efugj8l_DR#fBOLh4N&R|H2EJrl<`NmKD?wU*#9{ z0zjgc@64ZF54fmywDzgmJ5Z89Y z0+;5<$kG4qXO&3#k_fJ~Lg0PS79{YZuQYX-()Pg$X?NcXKa;46NQd#O`Rx25h`u8#TARg-6gR*6KzqNl0QWy16(HU@Ww*x~D zNBQLJu-G?^hLxcQEz>Gf_o$xDRlA-!c+*0i2Ty&p$U$MZhuc#3MrVO+j?LRy&njO* zZp=DuWM>rBYE95lr+0$DAHuad+$2K~!$!@aBY{9TDNMj&YPgm%?C&@_vCj(uWCHbY zG;Qv_W5b@4<4dh-;kV-nEZ#&l6LJ$bu3)x2wR3}Sb7kC3cBw`Kq{KCLTP`xiQ?I{A z^SQ!O=UHI9o~{xbzauIJA5(6qxU%KG2-w; zCFPQU9y-lpp;z8E)8=NET?bV+<@jw3S(ym-wwbNjG4lTh--yeoU9vqgcf#atUzlz6 zBUaT>Nal}65&11(v!sO{gA=vxw8%N}dQzqp%pVkYoTGH2Io~I@fLO6;=|PsD`WJ>MvfGpfXo3z zT9~U))UA9CtB$PKMOLQ=PB*|+$TFvyE0qfdemv?e(M+qNC&_Q`54n%!N}f7cL!Bjx zy8O$?+P(4b6T%*zW=fn@>i{wx#)ajuCZ*G6lJE=a*^50IDtq0NY|qh%=66STF~4LQkzVUY-Cq#PRAi^51WSM>q4Lc5>}9baIAh(1H;j9z9+ z{7{~z%dgUPA$`~js5E(HL%t#Ix58Pmr)M}uG})Q7OKGa!&!W5VAPQ-n!2`--QuRwy zK10pEhS8FnIs$pNpGr2A^=bZXIe^6638zc~fmwJ}cvJEWx%88kFkrJQMeFt_^6-}4 z1E3slOaH%fbp$i*W*2_5hkD=u>YW!tE*_%827WsM%eRlFu2e*B6s($VDgT%17MV!^ zq!JqD0UHB9OC`yBY2kdb)5!!faofq9ws$J(#7qSxni)0@X-os{6T_WEs`+F}CqmSD zo8zohUE?~NzzaDIvR&*t^wVr{!A$fhE*}dYgah`=z(u#ubs`?JYVgPReFJKwi|>=VHpV`fse zX|h9P0zg~myHwgQ_T8tpyV?>(Ov+$Zr~NUuigH?R?8m!{aJASkH2|m|Zt7)1k(c`~ z>Fm=za=R;M1sS(hR6$*5as#H46ZPJEHHg>;HD*L_!R3dA63li4S1;fD&rQ_`I#(70 zsW&;ydG~SB#QNRSDgOnH^OL13uy7oFG&9g4HYO4n~4c zyb=5)mrvS7m#7VDliHc18{YTK{~Z-m%%;t*ieIY-$Q3>v+t>3YZXe8jeh`1qJ?lrp zxDTXGd20pO8j%i7ru}7Lfn)-Z%ubWQ!LU1mWRgYN2K3_aRSJRpY9CF)$BV+m?y=A= zg9M=(Q5!f;DniOAc4b4UpC-D`KEYvAc`#c>W$Dw(*$9U`dAm~q$FpiVVNWkZ8pH^t z?#0mSRXsadC+vxxwZR?KXW{o4b`n}}`aXa{rrq_q*xmRn)03>5es|qP>zRNt3`aXk zm+&GHXe3>ff;(11F6)P^oMg&BCZF80{?^4k{s^$XCf(z|aTMSSdA6b1(ENtQCqkd% z5JQ2LJ&BtFhwsMzG8!cK8=n7Q{k`U3euc}$!R!MKclGMQFx{)Z^(LpfNO84s{ia`N z^|`)ACBH94Cv7~`vL+Cew9|iWO=s2T-rH-Of9$>rb2O;Ez0o9zv56`}N1$LM!IkLY(|YbIpCT0zgOLrs0T6xfCH zK9_(5F_QV8RIw>*D7DWkY9%!%dE z80#&a+7q_RsV`l& zy2SRaAamQx>UX3X+uZJ0XF`v9?pzqnPa0wYhm*giJS6G|+N+Ft8~N5c+g;o-)pC8x zYe$)VT(k_!pCmz~+XhCT30cv$+`O%ZWduSyQiU>gj{iuA@(v?&Of?e)zyDgZo|^~D zXTEx3I(5m)`IOG1^@qRpdNxO`^dEnpkI@MfjQbUH&C#z|^(p4o98wM_U>u)s6Sg|8 z&3>IA=G+M-y0B%ZK{=+KEr-uWYm0#00e@J}a5X8=hZ;6(4datJd}43SmgQPY#MY>0 z2kK?~x7qGoD_~29P`ftr)`t;wBdrh$aiC=@zOQ@P%Zi|Xck7wA*yDzg;F!mzFG7?5 zn)1T4Y|LIB)z^}n+}McV=F4UMY|OV$`S8P@^=B!QWRlZ)_GuTf1EmXy2uKxAh;T%f zFlBO&==Vp}O<8?!Ft&JK-0`hyRFMpxO#hTk@xm|ukrT39Yxt)0>C>N(UzSBR-z?WE zE1o?3)Le6ZcXcJZWrSI%#~_-($SLwkID)-uJNKf9MID{PMmiBG=;2 z(4(`dU*y&rhOA&Li%G+HIe^>{NQx%J|227ifwTZoq1i#x^yDz8p%1o0kIvC*QbkZo z(BB`QO0+YndRLTC5gL8cGt4xz9woG*D_ba255QX%|Ld+&uD=RE8CbjZ(qzWu2X}t*HYX}j@HL`DpYXsr2hhksOkom?#@Z^tHyhUa~Nsp?!afTaU z3zPa{OhMX81)t4)m&|tMi3T3aHqBPX>Ll?BEbX26KdCcDdo>_)T3a~;nGZjK66;cP|~AP zWDgcZvy=4}_m|VP-pBV!6uRos3xJ$WGoRcP;=6UoJpjwE;G%L(s^jH8;$4g?d;2D& zDYDD2<>2NI&}Zqb&$aTY|f=DCkk4R6Tl(@3v?;d zMr-a_q4Rq}r}dSz4W6OUS%SeiV^>G39+BL*mOdFn{GcTxY3N+6amP*VO3O5@`RM}5 z!Wi)J!!hmmD)1h*LKkM#=J!a=7X(@Y(S$=_cahdz?V?8=yn+8ai$xLUxKd^jRZt9w^3Q>uf8Xq8=y+6n`fnbYjCfp+XaGoQmyt zO~VP~qr!uDXLDsSq-(wC2<{e+FWxG9#roKh-QGL<5uUVT;y39FOG~0L@o84?+@EGnv2~?PtU<8IFRT;Fhc0kY;26ZP)Xr#UI!(++3BVk7klI}o z)QyjT%wbX`ck^Ltvo$ac8c-;fPBu#H%h&F2Ncq z0bnMt7e&bof!aRo*wLsyY?o8#ZRum#M52R?;c42Lu5;<$V~HC5A$mxMM{q)XM7p}C zkp0bgp|=;76%$JBY&z-WxE7Mo8?2pjC+V}Sft`$!2E^+}h$viSEbe(HQVThlRBc0yDyN+}C4T>WO<_NOB#g=)Q%BK)K4Ql8nS zO30+-TkJ@mdq(SD%jsB3I;Px9v)<1L$OKN1fLTz4dJj~*uMKmh*_6HN~ARs z2Q7#1Zr25Fb^cSIvVUndT5tYNA{M7-K(6{u>|q^seK*+KU@Kz1&?{ZRa_E(v@wqWv zijKixWVnDFxd&YN&UmniT-fmCl|H1YE3AX{D(4zKT#(-|0ME?_x%WI!2*z{va~CL~ z0svWlREjpg-+*#0I~+ET1)9%eDA#dI^BVL4t3xla%&W@rD#BW4 zzt5)ge!Cp~do|Beg!D4O!Ej&eU%TAtoJhboED)fcC29Yu=3(-iE}lS$;uoQl!*()X z;v?`qBH71w{^As11iZLmPTvQLkfH_$#-QgJ-(CY$F3O94C)o2wsb0%v=@S3KbABb+eC6`F+LN?#f{P zS{SC=4mU0-0?8mpPQ9Q`37Yi>U6^w7IcUG*o&lGV6e+as#8}3I&1yv~Zi0=n?d<;W zLxJLsVxt7R1d?=*!~WV{6oagj2*xwP2Jcd|6Z%XHz*bQd<7@{T21j9*W7ZEghH*4~ z`Yb&hbeVl7J|GQ8FkT02-qUAh+=4>x-)Qk6Q14sy@&< zA0aibQwvs{8i$+E9qayeO`gp7+~t*s#9^RbLf=EBh${rRl}Mx zIL6iRH${Zu-uT3r7*zdq^C$AA6w%cDNY z?I$lkJb8svpEUaM$`ktK%6-V^Clz(Mk=+p7xO$v&KO08TX7Dc8;tF6ddS_MgN?nX} zz;Yq)k9WD(>F)D8$1!u{XtjXU6B^PluB4MSXzliDsT!GS8tN??S?vv(Pgc?g8}>fg za~jzkjhxAqoVlpn)|K3*sJ!_GI>v{G@QD8OZo8#9)MW;V_MhwYa#RIAsfybx5kcA>_G(zNDweFY4XlyjRDRN|a&EePsHyIU=IyYiJEyhk zFE-U*(`ra-YRJ`UEICyt15#-Lkxpx-fGE0*-fv2dN!y12tf>+Wm~c>6akGD2iyPy1|Y;;0kD;HCV|N)ae}4*%g)buU9;gB-YuW>IhPIBr~pQ?`drq zqMsgsw5kd|Gb)=O3VmW_etw_;>KWATdB|^Oj5hbo#4zS#dX_$`u6*uUYJU2!`4MzY z2@uPcX?c3cUQOUs`VWdRjO^QXDhbdhv5W%0`rC|3)#WX?T9O)85tB?4P70F!T6S^_YwD2)NeiM*Rbx> z!jqrr#XW+an(`t~*oOl!?8zGjmRqWFPZJ+uk9Q~tnO1G{Y}Yxn+p0{>i4!p?{SRQv_gbO6;fq)AoOf+ z|J}G#-=873)ZM&kmL%O0rF1jyiS33s%s`20FV_!DH?o(D zG}JZ$X{&OSb=cTH`m5(a`|u=XagfsR>GjFe>hYW6D6lq{jWq!Zu=E%u1~|cXoN)Ui zGyM-urvNZ=$+7oppOEP5Ej-gYx;X9EhYfr2`lLhwk>2>jWiIEobcwrUjo%;65n^`}U+M5(&k@BJ7ofds}A&^QO|b~_x^Cq@9kb=dMh*#dL| z*uze28=yT)5biuHXPpAaIqXTo4N6I14-%L`0(044jqC-aI7%kEO7$I<_l&n>+SBLO zl{@%NZ#16QZ^z%6mQ?-e+Dz#CW!o>GK-L~Nwmkz~(#ti&I0(Dn(RlRSnAM`hjGApH zD`x|hh-4*k(1Y@n50U~%Cj0jXLlm(C9M2I*1@0rTv0S!kA3-pZBhcTg#cFd`p}6~h z^Ds{V;~WIEK?2--@U~r3TF3vx-Frnf8LsWRUwS2c^sb?I4blZQp@WDt1re2|6aj;D zMNL94VrT*a8j5sjA|kd>q>F&4hz$^>iU9#ZQC4)$Io2Hi*#E!R9D5z@(;RS+G06Kq z_j^Crb-m^5U6pFP?b`N=ckFj+JLukV*r)Aie#i0P9S2^OcM7|3`;Vpft1J(}Z(ZwA z^*?D8?|WsVRjI#o4_}DOhKZ7lLPL6kVq^7P`*}I*l`nI%@sDU~*|E?P)x`#ewrsnM z9$Qq8hM|5FG^C)2?E-AFfEu9M(I_)Ww$Pat6AleWexd#eiu+cDX@!t&lB_21`C@v{5wT znQA_wdjkacS^!C@~>LU9JzwdW1;TjCeNQY09epBwq>{oHp94L>v!`x)3 zIevEbzG;swv-_o^RDBf8;8T}_>14Y7*rBUwQWLBgBrv)_v}RnlX%+N&OHm>ND-@oE z1>t=Z7@G}G2o}>~yVpWbp3&I_K;Zo}XfPC$v&DwH-iBER@08Hd?}BI>lN4F(G*yx+ zp0W8`_p0~C@^xxux@6_}7e~hz?_K2hP5Y0P{~M=m*G>(km;aEqDYDj6`bUHG7bUAN36r=ffokQEy28ErqD(LIfBOA(Go1e<{$~l+h(GwaeCAJf4^R z8iqxS=Ns+26+`Kyo*O+cWSLW5u6$~p0=%_~VxIXqc>l&MV~1#m61$C564-v*N7}me z^GhJez#w*hgSPr8QuqP?4u)vc4ztw6+C1r9BRq* zeO}VcoJ?1_Q=y@qokIDwirW&cJ7E{}`WiM%?RBkffx?qSE#S@ZfV?sO&xt(s$B*9) zjO}~rbKvl_2qY(f0$9b)+ua@>&HA|_5SJl0ifpfgy-gzr3+%Bq@+qn>Jo zX^J#k%ST*Y>406lqOekVndEMmQv6h|Z_Vq^c|ik5rVAn$Ur*nl6U1i>D0f6YTuCF4 z3A*DxW3y!ihh0)DCPsTM18=)s=5N*7cy^Q7grf_2JCxrn+};V12W&^yW;5-~FvLX% z8#~jil!ZZ%_#DQDg%*$be4Nu6O(@`LeU}4MG=SC_e}DI-xjp1O8MQMJM|L(!+wBT6mRe-S zFMo7C7^8i48(~PXojA#tmSZyWuJZ7fy$o*`A1y$M2%ynq9wr|x+%PTq*owzV9d}A` zqm}cCw-b30%Y>}lw95e@#p+&Z0{5*ul>>r2aqsNd1*EU37gj#<1wc|f;bbrhM4k}+ zwrzP+WADS}Ete@mmxZN`eZ0N28L{GH*T$_ST%RBOGz1puK<&qpo|;QeS&;H`Cl3qGE@y60*vl z6r1kas&T^yJ!q5i%4wC~B=6p5J1MkBUB$Ng+@V{6clMjVFygOqi}ti=M}-6M*>w=@ zv>9I&5ITP}BM#@54<$UN8jCE@5z78Dl@Ciyr^+!-tppvGJ)alJRT>^BCyS0sP*EDS zYOdzL+K_cqeuq~OUYR*TFlaVDanjx90>U%ws`eM(j16J86d8;utK-N9kl|!m)-J0sCqjGz$d$8 z-+%YeuXgwBv87Zl^hWk;!kfcJ=y2$K)>c^xIjuZloM>rDcg(?@HlZd?tVX^&&zYQdsWnbKMbd-sN=}Eo z&QhXXzK2k4&J*>prDS(WPqAk?o!U)HTrT#BvCqv7{|=f70`!6FP||+@ntAIS_{VGV z?^e;oVX2lpt>C%0{{qbjxh$W$S8V(T9QY5bsDh!@osy9%=fB`URfiA=^W1+A4xD?} zcenQc#VUF?w(Ji$@JjuyV$>h2=*8LB$=*VLtfE7oac(=w4@bG+z|OgpmBkP2XxJyk z2hB?#ySZMIZCRq^qfap-?fEZmlyrm0@e9{3+A%uQ~sReb=CKC zu1{&j=WG5=v!C;*oyybsAuoNW3nD&O`~}TS-=HB?W>_)8elvv$3Y9ZODLQjA#Y{7m z*^KFsmxb5zVw^F)%>|~ zzUIN&+E z15a;IJGQSe`Z@&9&-d?o=~K+3D|S91PQ9s{5!5YKw3I|b6?4IXq%O5@{aUa5zdhBP zuKqS)_UyU>-}s1KbuX<(Cv~s>ve2B zqCqY2`WxR5^XuVT*9{{pB3<`hCqg1_-Lq)T48!WYbpBDRj+mb95pT$6C=Y*mqW=2v z#qPZolM7POU0%nx3y^L$oOVA#+-tWhTsuSi;;hII_j=6Ijq^@*!(Ja33s&Klm-mxK z%GEc*u6mb7tq|Q04t~FK`9{-*(#c<18*gT%XgZzj4+X(%-il~qvs%Wbu+^V8!k9>& z)0;N51k49Zro!c6X_5xh0keQDV|T$hbW!V(`-9o71ZZ#AHv9z3P_d2w8Yf1{x)7Tv z+$zunYV)3-z#fxr7i%eHY?q!G0n+kxnhOcrh9o4n7RjJYm<`b+KaXd&C`n!>qPpG0Z$3tjb8ZNILP}MPx{5{xlS#ye}2Um_Gue-^)Dut?*ADzz~NQ1_77!iBc zGmpRSxOc8`y!QH-$)n-17ab$KmwvYsf*RQ=0vs~&lQX3p`nj{q=gNg=Lr(%8DS_T8 zNzo^FtK^a2CFsa@_(EtoPVD%KV8MH6?plic4GDf_p4f-F*FOL-#bD$H5R z&J$DfN^bClrVFiKZGN9T)HoZmvzg^2y|wxwYsSf}dM28T9;ffE8@J1ia#FZNIk8LM zqZJ9FRaHzU3~%WIHtd)L%y5F~6I-R;7kps|`vfz=B5>k>Z>!G{x1}b82;%v5b%{g3`%K+tgTOqd+Lp=w2bu-pz(w z@p&*fro3|~vSB_%3s66b+m_P`B6HnC2!R?|71qd72m*3S52o0$z9RQ3sjhUoAd}9pd7#x(_V-Yrc(y<4hX+%jJF=Yzslp7o6 zK>FL__%_jUC)Lh(P}9k(f+4-xQER!5LhvWlS0vO^jtx-Pp>LaC2PZ|7^(9N5VqCCt zS8n8-Iwzokh`s$(=PhyWGDREdW=+{*vOq!TEIW?8Fu2wJ>E^YUeyWyMqVOcL|C|T@ zCh7$gi!S6}i6cADfHXeXr?HQ>2F-pB)vF0hQWSbE^C;ZD_^ChBssCk@s*ENu5~U%s7Mgi`nUX!K*o!1m5Jg=!9E@`2M}HSFoP zY9`cjp_sf~SZ*nrTZZ}2MvV6d4dIY-@PSNOb;EvKlf%SCrCRQh39In@_Eg7nb0Yrt z>wd|n|2#4SR)#DT|2Jz_eRagqDPZ-5v-hplm#*PoR$sZrtFMiEW&dIA{y8%J?|xZ( zL+w)k{+7$y{r)au`quZqY_{(oXs8|Q<1r$E>k|ozHS3cpx{K={ndUn-xEqIo8=rE# zYc@XThc9kSv*LIBm?_B){4rZzR`X-7`tIV7`MRzhKNlKb1^)cfJYDm1@xk}SpI_Oi zotxZ^wlkYc-HNrF%l*1v|FGG1{#qGvI`eCF)VucA+S~B2zrK&h@BFDsxqx$^4F*01&H+O6N4-@kIHKzJ5_vS35SIW)923o6phM(*a&!4wu; z(V`XW!eNN^vyi%f*le6=BEAr9Zoxe=Nl}k2EU*WaG+hUch|M&2fXde{HrXc3Ul^YN}@^))S|hO zPrAdR7*iFJVMvuvrC0N8;}AhBGyXkodYuHQZTJ4TexX{f&eG6QQ#*o@snrf^w(aRX zoD`3-cVnn}&uUAK6Zhyee>j zy+T=)3}NnVhj_~GV0N2hcmUPd=Ph`!r2l3moKLyTOdO~_8(Xf?Gp($o@!&#SC&665 zQ;HvoJrYIXIbj#A?z1$Q-7O6S6XT>xh~TBQn$qj;0*Byl!0SfxVtVjuYgcLT#*Z2v zI#7A4vfQDj8ccp~VzrCGm(qK!mIuj)G|;|n+H>|vqm49j2OBF8;5a0l`=UTmhw=v4 zTBz4lz$P3y~EE+C_L1FKJoPPxhI|ZBTPQ2y|12lk+b5_$d3LZ z94v7+5dK}hm?*Q#S3P@#UT+Y9BR-Jd~ENNV?#wY)|(S)O7@+Gzx!$D4KwuKYczSJX{0T+ zm3pYZHsxp`#i8VWMbB>DMs{hIrq@BlnTS3SD3VaG;YAX#=s!gud-KG6&NU3*iV-}f zK>c2|OAgFPk5Y0MI`AoJy|O<)VBGk6vVoBY)%ld*$uh@pu08zXqCOqnu-izP8G-cB zQ{hjdC7HIMdFjUUp8L>3%H``S{IdIH6|^Jk$~_LfnzpP-y;B`2I&}mVpK=5bqy~JE zF#XLaI$)w+OE*sT5HSE6M_0{_4E+Zzgl5%{yqJ+0Gr5HwS3Yk`DtZA$ykJY1afL$Day&q#iwWdEH2) zWpH)p1B;I?yskR&JCrGMKR8K8Hz!4(HFw6AEnNQoWCDIpbDzQQw8OU*c&~3EeRcx) zjNrS-Ptbeqyui7XmZk*WjE<@<-d$L_oHn4BFye1`tGYmhyEOg2Wa#{D^P3_iz58z* z5YM!gEi}KN%iUe7tKBQH*S|n3MJIAZ_9m8Ig%tGo5HW<1Nsi5sjOw$X=t@H2$_Su+ zWNoZJcRcBMe&cv~Pub`$VOk8#T6)b^FneUY#$^g7dE&$vAv3hk4i0NN?7BT3%3{g9 zXea9BK&p^NMfLCOF=b#}`YYWWjOh|_U95k%ut`Mi&FjK6r|sElSs*?4lbLW{e1~=8 z`I=y}ZQV}jJu#PLKR7L{c78}PFq}%AJNm(k?^{|2^Gei$`3Wt(z9U-$ga$$=t9>6o zW^4U%ZFZ1e3h{unMKGE_bz}dOcT3;H_Z`xyv-p@T1!)2dLKtW9ElzJkuV1XceJ-My zFixcPNN)!Vg@)T{k)E2LZ3&YsNomJ8NI>{#K$yovWuxsVrdNYST)4lEoJe&t=uQ*rg~h}e!;!7g2Q5$#TRAu% z4yFN-lBIP;pC_8@Ugsdlpd7xHN0r87s|yB&;Ga`t`rFT5Y*+iP4en3`iv@uME;NM! zD*G66!Cbv2dSUS(1qAjIK_^=tc~-~_4GO0?FKm^G&BO~oumv**gF{*gFQ~pRjX;Dm zxCgRLve_W8TX&A5u`h!cXHPTb=XEKMy^iMPUrz|qP>EsSZz_UoR06*{p~V@T0)Z(i zVUn2AkRbX7Abg|=7dV4h=ag~^4FV7pf|YyX;0Ssh|mcex&U1Ft~(QVoXQC#Jbi9UE41cY+IOUz99#PpoOG^7Rw zyODJ@$24T?JqB5irIB%&-K9l(~Nmff~w>G`728j4!s$Hm}GR z+_D76#Q3^)fk9-L0u4;G1-q2N`HgH?p-OTcz)8&fG@GIC&MjD?)sJ9e2lK7<`GUxK zv9<;9LNts5!;w@tKGzVCtgk(JU%L}T^qJ^f-9EUJ@VefaMr`|FZi*P-NkT8KXNjc6 zK|O8`qL&sm~tA!6%AMEz^0AEiIfEJEK}Cd( z)UzAR?fSWEqiI=eZ0dOG`6SGR-5J$`=(8BTV-b2VJQ z>p6B5Tnok$TXHb&l>|sWtfxeTk98vV1})fL{%|=%69)~lZFkEe4l%jPHwle`M9q>k zPkiw>K6^4rmVQaRK0a=DP+l;hu-TAZcPgahMrFMsq)xG{PVw{SnlkA_fy6@>Pt|UY zac_vVfJ7bCpbl;T{ytQfpBAYaTbH-w(wB)U?yh4}7>*_W!aN3^H?s298LW=*a1gy%&Or$1=q!b>$6c^TTFkgQ>d$Db)-DeU8;yqCOnvk zFXLd_Xeb)XC0Dy)&wb$?A$Us`&s$sg2>_cnh@-Jl9h~rkBX`_Ot{pfkw5tj}%;tRw z!d>bxT>DlSHFB?(F;$}JqDIq*t@JR+rM_Vpb;yC0hO<>7A*XrY*%Aggu%mUDql4iW z_A^@6?$QiykGS!2omd$XaGyHF#lf(>D@~~qw>4FHmRa;MD#m9&GLVGT&1|q4xp$=s z{+7c#$s)MWVE$x`7Y#`Ru&%hKY6GEN$?)ttgf)whNrM*vXx};n9YCw)RXwZ{X(HoK zyTPN};I%XYWt?k*L%EPK1!T{ArM>r`{S>^Yi0`b!qt|#tneaR}lnV)~*LUxugviBk z`z9j1kA>ACV>iijT|g)6XC;d-8I!3rQuWtU?b{~b=shHa@&cC@a8hC7ZI3+*0pYMQ<;M`7E{2kr@rrps+P?Mt~T4_5> zpjqgcb4@kx?*AFx=dhbZs&@las zWt_b2>DeQL)GcU;^wX9~maE#0{bp4Zdn|_jII&R{%Y;wKV66GjSqCwNy zA%D_t*-!em25W53&tkeGr+D|QbliS@CgD%oEf;AFY6S?Um3cvrnA(E*f70$u!Hy}V zT+uBp?tc;5%L*`s(~N*SJRvqli7VLY$_`X?7V+8sk`7tgezckt91pkaJ??S0hwt&Kg5XC9FK@otkDaH?D(HYcfz^XrDZke%=cG4U!SY%T4WlYd8N)B-DTl-Us0#I zqdV-W@!ev!$XA1R_IEt*FZCzySUuEs@ZIK0vH6GU(Gl<3NENv0&IfDbmliMdmB*j? zJvEHqfV{*ScVsk=?Mg%e9kDa3nQw2O~%;`I6p3E|!C+kSB3$@n60E8e0*Mtmv3 z!n%k*ySqbS_fn#5N)cC+^F+mEDapCNNce8|lO5-llHKsdqFol9yRI#z{Kcwwcj~k( zU8bfKOHNyK?H*f7jp#4l_Px7n?~kP`G<*pWW!Y^czRXOpF8Np5%}ntsZ4##Kv$T(S z(j&J=;YrVdz~yun{-%<-Wv~6U<;?QGSoPk+Ez4PTDL2);E&E)?majJVf8v9c?uYjp z5syt^ofu-)^r6X|Zo^YMr9G29hB5krt#Mjq`cF^pEzON@u-a99Pug{*jXdxm;XRad zAkeQ&WJU|rX!Es!W!)|)i<4jEjyEI>98R1}avPWS{@|$8A+GF@#dgPeB5rJ7ml18;El7ZrpLP|B z&spqdWE*(C(m{zI`b{Y=OjRzkx}$`T9W$+fkm5WKB5j9eLSk3&Y(35S{EL&&I@~TZ z;3Wxscx_6kNQ%cR*U!jJDWqYH5>3vx7arVt`GmJZyT=vLaG+afSJ69P<3m>_lcFPx zc2=SRt>X-Cr-O0(e5lP)9_YKW50UD@9c=_xe|5Q63aDp zmd0?cDKXm{tkVewU}( zD`}5+Vga~-0e!E`FK!}9`mIlwyqtNh&d?mPf zQFSE7TbiCik4DY~Fh{n-u{fvl)u-U8Y-?8;U+?ayE?+;^vtI_0*_PTJztegZCZ>zp1wpcv7D=QP39DwmoZ z&B(@z{L+_hPXS7*;yi*VrtQfw+D3c*?Z9A$!|KopVUW2#@eZRu#H696gxT7JEIf@jDJ59 z**eg>s5az!VMKxMM0L9eA^CW`43@i%iXyv5j@$o0ML?G{)FD{Ga{dS~6v>CS5&_ho z(BZ8f5E_=ZS?b3p{+@BcBKZrF()eBGV8QgEG$CMzE`xBDzhxZPWscVsz4*k5zo(P| zvtwvQ$o>e8>S9Jd8pjz~@YmcqkK@C)f)|ZPb!_xvpH3Vt@s7Q!>ESXO`$g{Hk(t;d z463vaSUSw`@Yyy~#&;wrRJkzld6wv}M!K&B|2LsH$$CU1^O8c4eW(Ss$u{-_Jx)1@ z9j|WVB8Rv!DNN4+zdbVD&1iS1EkOxK7)S$K)$StjLz8OR2!>6~ZiYn0HNfO8!5-Tj2#HrQ zS3tMNB0+iIIGM+TALu6$0@E??$h?C@^wZF&3T5ycQUNNRhQ62gKsnR6f{0^71?Vl z3t!@b8{r*^&`m-@3uWzm`FHY5&-xOb`FSJH60#=pl!x*jM&3Y7@@&(Wnr9JE*I4MJ z^tbke--#JHY-|nBtyh!Nq##BgI1B7X)8WP*U=SmCTjk+2)jA#e0ip>#^}{K7E&>G$Mwm!u3OQ=XOjA z86CqZh7Y0StjvxPagUtIm&f_6ci+@i0aMv%#1g8VgohR0gw$anBnT8z4Am&vyBj>{ z289g5t2w9)+D$V#`u8wn;a-db8w+z7;c;3#M9?TFcoc`5K@50p~^tav;z?2tW(VqyShD06F6V9sq%CaiGQz zOdPM`=!3XHn4({qS;sL$IINb78zh!NHMo%LYItiYg!L!$AOU4TwxEv+c=pFFC`G-e z#boo9F@cFm?Zs9TD-jUL2k|OID`waVe2m4Fi32{BWt0{Z(KX|44!otM3ITzGwpaVd z0VS}KFbK=9tGy-;tXM(w$?AyuV$%}8Ju9^^dTHP_FrST$CV@#HYDX_x_*w&uf|jo` zITY)LIhBG~Da+U*VccENA-h2o5qf+a4r9i3XByCRB`ChLg|1la{x>_jxW{#j7`3Cg@(!f zX;N~?6G^!ZcSOgrZWmYGzQn1ex}Yzy3n5^GZ(j>3sW}|p0xv0d!j)m@anN z=c-q4LSu;MmgTld0D^4j0y`~QE^&KE`m+rJ$)WZ=NtP~nD1eRBpQgA)f-n%Mt`izR zU4o4IgH^{qVB_Di3D%0CYwY(Px%??gH;=TQO}F7)!Z!rGcx z$3@gS#ENt+-FO4t;KhTO8tRE=5MN2A*|^G`i-vz<^9F!$1{G5Vv>Dw&))F1zX>G^e zZhuIFLwtEpkHfgA;xcwyD-&4>;16te;-F8SD-#x3NCN;j{W<}Z6< zQ+INZhr>o1u~C^EY%>v`kbjyf*`p=X{rol0oGp)D9pYp)wu6cZtg|Up>s4dm9@F4+ z9A1ts!IuVe22RoIdh%Gv4)TdWwZ0#8_&Z|W8V&9OU>_}@3aD7B8}5mJ|3-a>853?# zgilDr=^T45%bi8T1yiv`t6eYqw?7=m76Uv^MD&_1+>eOnQnriTaIND=7Kp!|H=w?Z z>!6}6IlK&8cs3iwV0LwoxHf>8-w%i*u5hovvU8qMOamFO{%Mf+0P#c2v+O}cHVGRA zps#IWTkA0SV?r};hc?mbNn}OD067bjsQ=HG>umMjO zgoCYNc1&g3HAIX+joi?}fCJA99V54!rFMtk$tb#l*)){o!xz{h`v;CsJ#KA(OvDvO zyj1lVc`5i$EAd~8-JiIH^B=}7_J#Vv^8Yn%$&(u@Z2woeP|B*Y-0tdJ3W6*cAk|FW zeZ{K4>Q3d0Kjp&9mZ_}Uz`@X~2KVk%zrOAByz*GzRnI;2;-XmG{S5y%f8&_njK~k8&ZAYAF}Q zja!P=Ort?FQE~nNANQCT(NoQ%^03!M6Y<35n~wiS<-*EQ8>Y!*vjbo!R3VqLQYUcG zaAolJRHoX1Ca)pKP)t6{wNmMd;fmqwPdQ4xu#>>i^a_QzZ!F7a*(Yk06{C%@f>-uH zTXV|{gV!Qidwu3+r&*BF))?{^nwU3`%s*FtVM_@TzZ)k1L*d4iQ|C^2T?-pK!B?9w zF93N+%1>wzuco#R=xb!V)s9l3;#bgCGPsZr8-KzEN#R5}+=T(R+hO96Mt4=M7r>)6)yRC)s7r6E zzI4h*f3%U^UfErgw65L42S`HdS}V0?K8RZUTT{aD=(DXY@ADvVP)na;(Io(T-2q$~ zMvhQWqHVYnzb+OEVS3{(KsX;vM#$jw#MiUVv)4~^pU7VhdC-M0aR-oPMpL4mV&e7V zzuvw=>X!2=+`4bPT*{AzS@FhZMw$X!1BwD;2$sO1*AoPKgrpmsEGpM%g)@*bRIra_ zTyB*y^^rDK4Kq&`I1)_;P@M^qALAwJO~t-EM{*&7B2=wBfnVkn9-R)_0=u)W#5l>m$|F zEU+FWO~ew~EseOyH>v1Qo&&cMS6qAf57#X6ghoV5jYy<#Z=;-B6zG;Bb-!BpMCXNc z8*f{qo!I;_QHuH!=;BBjhoZ)XifLt5n{^JGI>SW8P}24@b02^y2ln~;s>4hRmlUwQ zT=eCBBZsre_vWCra`zS~CSo3aK6-K&dDzL?lgVxiZL)U$OX0TFp1*UNx_U(5YOg5|LmqWu*I)LWc zn(FKmb$TXzhuL?knMme1<|+bQ_tN*w&|=(i_r_7et{2T2<@*G z?QNb~Z$B_=b(%+{ixqeClX0utX2f$A;ZC`^RDT3>%y0n>7H5KQ~tOZiT7(wJXb?KHwGp&;_q)S3ScB09e*N? z;@Eacl7ILX8bwj9dd__e!l)#K>z@tEN*w1m=yEI^IMj8Jeua|hN- zgJ@Jec1R?4zbFt5T-Yy)*&A^QGZ71+(bCB1G`AQxQNTk~tr2ik)WlTT#>CJVuzGAP zD+)r3huUGHBKXpYAa{ykk`jm!Vj<4w;S}!Y=oIIKjx9(GFC;F=IX>Mv5vq|0p(S4P zNzCm|%!^38E}F#BODeEPy5XEu9+6b3lvL53ROORY)17o2LFM*5Mmc!=#F=YOg#Iwm zhwI5-ktq;%a;tMnyHZL=L`r8)N`FGiKy%8o@|5AxltJgq&qXhfL|lHEbNO|IOOpi{ zREJ$9`QMmM=-@jKZ-oll@_Krww(;=_(xMR%TsKE}v0D-Vfo>)>JN(M;^(%lF6ROYT z+Tf6{b>vJ>p)i^=x|c#>pRQlVu?6T%*(d()f5+0sr4f zozWQEl5}1OJ6%1OcZ1FA0W-IaIgtG^4Y!pm!7Y;Hjbl38GBV^Xa%D1h`RYU+=3=VR zUE|U+5gGcv5={W!nu#|ZM?I!u$@+&5T1qs5c(XdfAP7G_h+&a&JffLLl_l6T_&YXl zUmeV=4wFZ6JzyE_+arD~5k6^4Sfk?g!0ZB&tGE6kY-Dy}eTIJp;oUf)%MEsdin;D~ zwF6^1a+)CTcGS!Ik|K>*qAH zj3#2Qv4(KRa^Z_^yzf{9i#piN4itB?D5lxSSWxc8i`j4&CT}1Skw?zol1JAL zW>QCv_E(5Sts$(*7}G|skF5?CM$V7oGJ%yDJm|D{mSWTu_W>sI7>C!3ipVDCSCVsO z(2-v;;tgcnV-nWLjVEdxw$Xzsv(0WEzp<4lM)TYg)r2r*!UI8cMjcH!eemheVll*XZLGWaGAHq)&rv+hR5Yt{~N@u4Yc?kjs93v2D0 zZIC3Mu6ZgNo^I+V#%Gmd(o#}6lxe&BrXyD4U2%!8z&{6>zm;!EZsi+*{ipB7Cc&Ta z44C(St$e@5@E05mG5oi8<71W26`z;c7XNdQv83;Q@~_Ib)SL7h><9==#mkABKSp1} zj%n`y*SoQSodm^W`F-qZXPf*MV7fa|!rYcg4x~c?EGPA!I&R6#esUyq8e<*Ce97*G zKB>o36_y1q+#FcPuwv`=&*lfuzkhoF?pOL3bQ_;@*?S|Cr5U~$r&OXYeG8r5{_FnV zK}Pe-usm6dUVs+f($G6kY?gzNvyUo*saM0^!oQG;Fz9KI%gC#Br9`>1tZL#YDwP3&6uaFW7wUfyBi|)+C1at_2@`h+(yH82K z*%;`;ui)bTZb{j;M%!EAUX+9TSqT|3`@BP1`-36t+@2ToDVRi_64V@2_Px1coB@MG zi%AAb0>D_fZ|`<_);(H8WKpqaL{2zgtrLg<1vI zkPov4-5_ugwmU4#qoZJ)q%*p21HCd}_$#CmRALkVY)SE7OOKJr^|iI~Yu=hXP#Rr- zw}||)I&SbPv?6Wp&z6*$G1=0JS=|1QEvXq+Zi@DwEvaiRglozWOEB}rpDihov$#K7 zQhjgk%#_ZT-CJmyuQ@hXq`G+j&mePX>A1nyhulG?)@I|X=78Q0zn@>ZgUnlgLx_@Y zg#p~IlG7pR6lLcMOB7c2_;6%lsf%bXn3}v%7kju{smwpfpa^S%0@Wm{mix87;iAbS z_{=zP=mmF6s_$jaBw52Jipj&z8=^dDt-D8!AJT7oz(`Y2Fy*Ya4X+AzDioFZzHCk9>u}wTczB}_qV&Ei3HUDKPunWl7^zE zK>p*Wq!jQI%ZGO{Ln}D3xFfHQhGb;~=6gzL;mH!n4t`etgv>OxFmlTcZ3w@o0xS;3 zYn1ZyULf^svkXqCS_pzlBiLf|dNO>mT~`6Yk8qPnBLyUXk}kf)%;9Jn6WNYSpnCFB zohd*I05c8oPi7yb?~afMz1`fD6uA|I1rWF+<%KNwZRdgW!@`(s=|ea+3~3KHZ8T1f z7?F}6Z_}Sl?ag$qj0On_6IBWll()xi91$e2f$gbUt z;w$590Y&^S7mAk{?RcpPX_MvH*kZU?qVst=d&I`e#wZz;$(wAI_}<)(%q{SwwEg%|LC|~Rx6#K zRvy0F`=aLDYLy#Lm2;QX%Z6*K)jkKRTwe9QY-(A(MZH|b)p5US8C$K1cv^M*d+)19 zKUQmLJk@Tf{iAK-Yjp_+sy#&dMmu+})iW?TtU_M{j56tR1dPPQNKKYje}spj?J@aR{`Lmu*|kBDuA;rZLk z4c{MfF4sm)@Bi>)?E9m2u8#YA--q8nzCQ*Cbu^UqIMll~*Q56q{cHQtss}~H(!}Rp zUeI#HN5#9Hq*}*DI?f&Vco&N4+?fJNn4tOmFUrpR9jf^M`)BsWENASyu@9j^F_xGy zNJv_#&{)b6H7%G*HH&5JW2q!DvV=;bRMIw8I884kov=^d z!r+{LH*pES=)Lvd6MKG3X1=`4I1vW7ANi@ed{VRfD}FZz2I4%@ARx0+b2nqdwY)zQ zLxk%?*?K0g@?$v0$C_>TWEj`Fo^J~;LGEYj{ssMr>HX;Y%Y6B`ylAsAa!q(k)0#s$ zt}2}xXW0%ngnK4dF=GaA@9>kTsYVwl%b%L*y}L{7`zHr_`d>HAF*aQ9%4T&Krv^)y z(*Qaq#k&n%ogO`^k{6_x*Hv}Luyj*4qlDmO&)r~+sd@dFisFv zJtRgc>qxZ|j77<(+;`Rbb`xf}C@-(yZ{tpNXcidbwxMH2X-~IUChy4=dp_3kAOger z1=m>9eA$|d*~KR#s*8`-z6c$3rS7WTQzUXVc0QPTREORW0f%Ydrlbb87JRGKi_x@L zYwqRyJ8u1t5U9}gM&M|33eVdeXjkMu_Zj{+wCm-U4aDrx)LHXz#l+X8Lq4`9K|cZY zm*fs@_tl0g#_n3)Hc2M_9fisdJpA)_9#Qme3gr-4QtCWk_1^C#O!~a}Q@VO5`EGEx zVO~VsqnmXXIgeX^t8dX>T-a2Au?fPdWa*xexo}S3$3e)3d>6&{pGeR}e6l=aOn!w8= zRm{-gY8L2MsV+TWCelfdFXPS^!>v-(Qdv7bYpEjJg!6nMaStk)DMVB!m9<#nmhDt~ zlyQ7d^bf{%TzA%kn(PK`jhbX<6l1G?5%TSf#?^(~m5g)@L#4ZowC!wOpdi6vZG^gI zzK7|-(FMnN+M(y85hV-xR&TH!^xO$;hh(*a_h^UE`hprq;yjBuN7g-Zx!_4PLDWeY z7q4GO@==EiviM3Sg6NHj9lfLQpa!~=RgeKyb|%H#45bLQm`{r}r?{fSZwq8yqKi=k zm}zL70(+n1zSmM1J3&@Dxcj*w_jl;(|8!sW4xA}AwBZw$yxnwlQ53M1w&EUOV!x{B z1wRCWQQI+on>wg^9bnd*Hv)o# zwy6%VUmi%89{*0W`^r554jugr5)zA0O#lJ@ZOa-?K8I9v)?t0NS9r3EW(|mQyKYmU zgX{%?=Stx!n6}LLWICcebOw84(ssred?mMjFZG&zjOi(Jy*`}yMoQMU0zXpM6&_e> z(_uI+TjMgLHu6*L3E!sbnzE@`DFdEXYQ5-=(+?L{Ej=2HhDKHjxERC`3KdytH-l2> zR2`*OYOlkLDVXUv}zfo5)mmj%`r9Dg2r!ABhX<=x4qr3 zGumeW8yRXEbH-7byJA(oYdquHUL%jM%9E9QVbv%gKu$ofY%-;6`Oi?l1_YcRsY+zE z@EP=aU5m~BYI$INh6Cmpx5|Ws*@3m7TZ3a()xWJUzQ0H=WA)K|%x+iJ;$Vz!&e^C- zXHT1_+!7aYKicwrL4%ZrFN+Rwd=mS|D|oLhLdBBmDUCK#KJ1q zrrIq{^#_|8%A1#XbrCjnCF5=Tzb3FQDMpW}6HE@cJ@S}h?=uu$3 zL;_bgz0(SFPn9cUk!hD$xIivylndJh>YNajhvgb~&@o;j_*M`-2T``_o{!Hperujx zLoP0WpwlE6L6ju&vEtI+GosLGF6&^?KNbTpM7mwmr4;u@wq#% zw-2eDeAhOu@xS#qKzWg27yjRN=ZXf108Y?z3gb|Np+eA<&hn?SP5V@(ZDP+Hf5ajvOhFg4&(d|Ft`7+iz%7`LF(#yWAD>S?XlTrHq+U zOX$XsFC47&xI9Y}8WP5BTq-@OZMFX)nr#KBc_%?*+Wf;V|3`n*TY2XH>Tfr8XgBk^ z5NNeZ(z09%-BCRnI=`r*nmgLa`wX9Pi0(C3`S>+?s(|CycrC6+N8W4@unP^(**yoBd3o5U0Swp*scIqp zCtT5|Z!a|kmqL?78~Fc$dqm+z#X0Jp|ABi%eb833o`zGs-PVkhWavFXm*zx3)YZ5| z;tONY@x-K}5Fa{uxf2D?p6knmG?)aJKuSBGAbbrnCY5lH4W`yHb)wZ#7Kjj3uM3jHt|q37@arGtRY9 z!aWX!AzfzRUT|WXxGKo}*)bj>E{e4Q3DZGzBF=v}%Yf;If{q(SPiyhZ61)qM`o(slPoQZvFpFD!*p_H>v!u)b)SsZ~v22cDyq1>C^si z?es5gkA5kW%0cYUR~#P)xqSle6y#$&qD|ep2QL%8qIGuPq&waASmUytSApx7-kz_W zkegWxg@%7P;s4^UNf&h17|cj|a%m?D7q1r@+}tVu>!eI72O$hAP6^$Y^@_$CyVkwq z_|o9(=+8+@0lVp!t}nC-cb&g)&=P=lf3fz=UKW!)6YA@*c$0K%{Ig8(AG@=oLm?T? zQvXZo{inW;XT1u}hfuwMu;t((TzATMagY1t`0eEGIDJUyJ*;G?Q1$0h;CnCXJ!jzz zK&eJJ(L40e{F?_xEC6$8l>5N7?*G`Glh-nVdI~szF~LAYd^1Zca2IFDSO*7?Ski1F z#@pzl47q%)h?rVx3MkbAfVPsDm}qKrVnZFx8hsX!4yJtb>%xjj1tB8q^%1Qrom)xV zqYcA`U(WTY5byWz*vmF-3WeF@RXfvrYszuPlS^`4K-+FE`p^){06t;8i@k@;MANYg z4q&7P)o7!*uy%oDO2JJcAv7-rd1|p>yQ?y({P>l_%gDkQ&|3qYT;k1te}5YWu6b@` zgZiKjK>lOz3!x*NJ!FVOlaXmW?T%&2Uj#+brT0yo#faLFeq@6&@Q8y%rpQ-)CJ$CY z9ySK8wj}1#U?oqUPkcqI-ZjC&brhHD>SdQQ)b}&=PG?5}{0=z9?+W6xbi_6ASSD|t zsq(8e8dzx2+kj0s>SewPQjV>%#y7SxXs!!3$~0>1@p&i%6{Hb$dJ z1U9YP!0}SP1)QLJ!t!q~%0%)p{{Y;+#{EPm` z_-l=IfMc3-Sv}gXp{ov!eK{Di9Wd)nc*_Kr_@);v;U2>{Elby408kJbityy54_^Tw zIv2*3#o&CZUve&F)YomKx?rq=g$f(tSGCHB2c>;wwp2>J-@;4m*3qrAA_1NL+^=)p zesZ_|?zzN~g3?*0?#)o-il~^v?KU+AzqG>`ZEnZ({RD5mZ^ zo|@4f?h>m9wKk_Fkq;{bM^|sITBMHBf7&iRs&$hL+lkt#ZT*}x%QE^Uv`kc7AC$=+ zm|eW~Fv;}on8{qp>y$$$5>q$_pS5Hf!|rHv;|8No%Fm_L;T`Vmdj9*B%LDn0o%UB; zf!oom`<#!>tXA+tf}Y?1a_#oz)2n!Tf5t)2b+^t=d<|XlJ6D64(Cs|1=ke+-hxYZi z^{xz>Ek5;UlCrqwdSA%E?C~3a-ck#%_s8CzE!a6}L>s(5kUB6|`TNg%IWW#mj*@ZV=ythl`{b|(=@If#CK9G8wc~kcZb*a}n2|rmk;x4xtf{(klQ-;XOsy_)UxU+HlWEr@i@%*Hy|YB*QBJM@TGdbOs*{3~TC;=hH#JO6$R zF8=$i^xNwT1rLYtmhWH(AaD>aO1auGT;P$l z`6e{JSt#Fv!>5$-t=srEqkOvszTFfI8tG$KuQ}{Y=^zuD_6tz!?&nUCdM-i2( z)apfwQfh)1$7L3TW*_HdA8RxBkid4Jv&$B;Pig}q3b@)YN6g77)CP(uISr#Z%?mll zd%sCe1k{L+FZXpY1 zX<)nvwNtvesUc^Bp9uRwbjhS>#vFuGL9=ASJMsy#OYvhg`E0k}VoTApUeNf1@+lC^ zuZsq>fMz;)NGorcn|6Kbn5XbaD1cjjJiJ4uBBf$OB(TzKa8!)M!DJ$KLIdR_P#8)m3#sH8K z{J1nm^?r=LRlX>b@VYmDpvCj0#E)d0&t1$Wa9uQ>PzV`qMf~`(SLpb&rIm%pL(E;k zZF0c?O8{%Z$t0NVqhJpgKf%FubJN-+7BTn1pk=7;5htxU(zR7!_kK*XPPu=ZdXo;Y zm0ev!LAU7u{iMT=t4IgHJSZuz;%+vCU5zNJ=(D0cu>vc-L8V7@-`$vkdokZz{152R z_uh?}v;x0J5@xxCdz`#jUqS{(=jb#1upEak2c5Un-cx=N)&xJ@Dq>MB3=$t$PxvV& z{vxlGbA2ITH2hwSX$;{DtL82Jv`%)-N4d|ScAXHjrTeLrj&YX1EC7US>BQQ zDbS4te_sS!MOUL(lUDU+cgoY6J_uFEu@6My&}trx6oT$JW1C|MUaxxt5}wQ922|uZ z1;JxW?buI30uRsH5!`J?kh2Mwu6RMD_(Nj+Dg{{#>cb%D86;G&cWz$Z#SY_v|n79_6EXTc+#XuCNFG>(wO>%m!gC%8aQUF|e zU-g-|iiiitSii4C1b{h{Fji=8)HC?oqVS_G z1n(`xuM%t~hp_fwO|}rqXA!65tD*KW^HPFb;`xnC@KNAiDNLklra2=u`|5PwkqHlE z_zGtI^H8OCpYT|LIU!NeIYgM0s+4lkV-kYePtd1{@Fe@jKwRD=omeA+B?cq6D{woJ zM5ZROhK=0(4eLTdJXW-g%j2F-UVA0Me^YXfBr4Q*HMz?O7OTKzi%9%Y*Nv8XI4O7- zZwz-4ZBe6byh>KNq`=;hBCY#Ctd6}(*vT)k3dwz2 zA^q6cuVMsK0hh?JSL9eHF(OTYyh2}*4C1JZ7OXltDpY}`W)i+qi;}IuT%FqxS(s+W zmHLx+q;wU99&m?RfZub+)CSjk;=a90<9Z4hcJACzD%K0=#PZGzUBj7`-$`-+&*L&6 zWG#p|5?T~~&YlzzRRIwrYN4yV*r!_aK%NM<(0F)@Xv-aI(6X`9kFU~0Cl-7sOo_tm z!@%Lbdesj;T__wk7zt6}BxE?{9BhJ)@nhk4vtiw}@G%fqx)&8GR%X;shmL6%-^1S* zopsZ>nEtGOU(?+x02>iVxOfATExH(@n;-uI-yy}1Srso@7fq6hjdXa746z*`oMFKX zOyDob=nxU^xeUQ!;RBTa{})o!_F|k5{oXe&ehU>JD8hUP36s?ON8GA-?E52NUU?Y! zex?z{$T)DVq*JEy`%vi})Y)nO6u?7B?0((obK32bOl0~cuhAUgoO4)={62u~xuu_U^ zmLOg&ijq@`l_P-_XV>;A87Bl88zUASgvgbK{^!9TE8mF;PsrFi z2GLXG7aD(Ce01{*oB}(zc-Q_)-JfxTFEQBf#J^JF2|BW~72eOrt`QOCiw5YgT=*D^ z`1Cn)vj{hRL9m$(U&n&^DR2rl!D#Qu>)h%m^ypzSPRhN6Tzds)jOb+Hj_Ts>aMLcz z1E3x7KiVYZ6?xP29lU)ZY6YlEc@Uoux`6Qh4&+WLvc|T_0n^Mv_x7qSKElrAwB-3)C68?fQJiXY|Ty#VZ|U;<}V?J;+-`u0feu8(kg>|d9R)xFi0zdv53Td#bka)fo2 zSOLNheA;FJNF{xsjVXj~eUXi=RIL3pGWp7Mc_#jlisfXm-f|X*76WJQ621X#zjTQmY|QF)%zBik6hWMlpf)Rz zTm|m40uv%e9G=D2P>D$iI$u8Gcz1Lw;qPY2KJa8*&iFyqo!bog22s8zm? zKjDiA7Y_an2k}aj%PgCaM#q05qqi=yE?!{~Zz+2lj>C8VgnI2w?3@qr}HE$;%R$ zr#&)sH-6mEwDCg3-SUl}Hl4c-?PmJ6aC>NK4-j-zp`nrpDSN9zZmzryO!p&tQ6cip zhvw!ROSGh6&##7EzM5>AKU}{WYL)*n^UIF$y^|xG_1Vk& zJ4xgBr4E(vvlJP5CVyU>-t*)d;q34Te_v|*j7VLi&p`E2~aDC64>FcJkgqN&q z6VsR%W|I$=@;agVYH>E)3nAQ1uWY8G$+nv>aSvY8q2F3>bsy^Y0Bytlw}e=Qy>h?6 z6{#NQ(U?B5N=ydR`m*LyrlNFgY32Sx{S-9NHIvhuV7|t$PsGS6#c~_#aZGz3jgXiY zAFXXS{ZB+c(dp#^F?5!=#nr@&n>wHxThZ}--AeIPzwt^Xou8p%VE#rIrN3vLV5af% z2q{Z9{^|==z55le0qv=hp-jC2_eT~=sQ)UvrjZTjgpyl*YuD+sJFC|l3^RuH zwx`UoV5a`cyCAjqi++6-H+PBkp`kGCs34sw6&r%P755&SM9DW9Su*8*_5~;$2E2<` zb)U^?+dwv;{$XrrjH=uCq%jSgD8QLFSqqgmp$|=2rNLKBR8KZJY~Fri`_;{{S31AC z@m$F)vLn(}YU=pv!28}OVLLxP-#zq9&A_-P`^#qMJNmt+OC|`EW2+h`?%oD)y_>|GN`1d7T^w1? zMf5kkSFTx-@)s*ikM45WmJWMWe)k`N?NcGg|-5p2%PP@!q zdFeXcd3j z_9DKUTY10;6+c=;oRA57O~*;c+PZ&3@~oR~7^@viwc9sO4f5I_kI4|>m?-&ld%W>EBzn|}L-r#9{`rX49h6+|h!;}Qol^$n=>%Vif{N*iPDQItl zFI<${1PMs(uFn&suQb(jk@|iw@)5+K+{~<2@s_C;XOGmnIh?$IyFc2XO25|fvoUei zx^=~ZWpAwvo~;Uave)Ne>vp^3XR1LnrcSfK4l2Tnco1#@{1Wx-o+lBbG}jw;Pqps4R73pvyh!zUH>%d?gKmytI* z9E>#CKc4vfyg>I#OV)}hl5Cxmqv5ZxI%?{5S<_Tb5-y{`&LvsxfQ^Ip6Mf-|(T;%_ z2S-DMV5R%$P(ez}nrhN9tjRMSVzKI@()~qQD?TdWn%!Nc-$Qq-80#oFI7TNe#`QSz zbb^!T-)K3ZvywLb3W{-9U-T<9)~BMV*i5Wmmn!#dJ>S03Eohnfhr|&bC0m0hVH*6L z3h;OZIpOur)bP*Lix7edb_bA`Oe^HnkN$UM{FQ*V!F{|vD~RqbqUYmdvnj>6b1``?%2kaSw+TGNt`6-VM#h5Wne?vVu4FixcK~&vbN7?_jyRZo>)11OOT{s zMdmIWV}v`UL|sB6P&T|#vln*YGlz(4yIDwlFFg49xRz@xfY{o*(l%ID7~W4tMzX%* zf`j3^6sGF-+-Z8nvn``3a14}z-Tza#5fd_6ARWnay8VXAKu_vJ+S2K4E0M$b8uSgY z*NOizOr^@v$T1Y^6h+R8swL~lgZcOYM!H^{DPoAzgQ@2s^f)z2932Ynwb+rT-aTPd za(d;8C|O3Nh>W{0gsd7|n}^}lpqaFlxKVPxT4@aYWc2%l-}aAz4a+;#8J&X0*)b$+ z>DB!yIf=)}Tist5bwX%sa}oK>6NV*vJ_~G3cvPWNg)zYA+&i_Bl4*yI)Pb!{%DA9Y zn3iaYcrn!jegRapr)msEe^=T^vGO!oT?Y1k_tcc~trOXpWXqn$Ma)d@{}_$Tk@px1 zMR}T&C(y1yhf|pnKNZJNH==kYSB-B%uJazwZ2Wlo;_QxHXZ@aUy#D>lR@Gfq+0U)6 zAm+u7^Se^~PUrZT2uso*8k1DahmB|jDJF6aF z-V4?TAiz|47hPf}8XHS_8T+FuK^fdm3MQbk(Y_>I7&?JAjfO>14M7s2opAH+=TOw4 z^(+B0Z(M^SS?Nh(KyCBL_(g3mCC3($6gQ4uBzNKejlW(Z{c(Smn^n4%dcY?U1{IH% z>C(k`a##)~K(-Rc79*Ude8@ZWg`^xZNgT51{V8}4;_;~n(uU*}*1MgK1RNp#VNJ!F zw2|*w6z@)QU%FyR2wGa#%F?J!2UJ`TU+}9R8^Vm#japGbrz|_tFP; zhyCh$%0t2q42@6Q4tFMpTT0I%BghbM7Ai`C+$~2%hYGgzq7HJhg3+)L7HWqOc|@AI zU7odXRIrSe!KN?CZ$g;>e0y$2iY$vo%VhV$oPmrKHZoq0iVZ~`mP;La;fN(Q*&?Wa zgHV75OhGT>KPwtkfLIQ~iq3D@iLsrMu;PT<73of=Zl4{!-Ndom7pLAhdKvH&II#p5 zq?rjq=lH42dt&VJ2Eh!_vIvMW00|7u#LO}8xK0~I@te{pRx4s8zMCx{wHKu5qVsf@ zMVVL~lJRxQczUCm(vP+Mzfe0bW%Yl&zWoyFNCWDi*n5Wrq9^5PieV;x@Y^|!&*D&i z6GN2ZC$K;?CxgBKoj!#&o)lTD-*8f~&u1&|+qGfzvKb2&Ek=06 z!JHQmicyTkdGrL|)+|nAI+u7>VcSZ{IwH^7rHxK%E7+``Qzp8*nhI@n6r$$t@>r*$ zN0qI|%;mvQ)3_cUR{*r}mxsc50Ad~FxcR*B(&a9Gw-L*$cITz~ew~!mNFv$Q`}8fhLWN@)NwMx(7{-f`qdN{LJ>Tvi67>u`FcLR3;pkcd{aj z6Iz|)+K`Z2+fMH0mH80%AglM>c2e;w(#b*BTwcpY1~*_`<`_i`?2dDe4Pr<4=g{!| zIdo>>^lt0Cm1WbfKu5`!nchuso)%6_9E0nTEdQqWE^pLp+fGi}6~{uMkr%)j?ujXK)r9D31; zeD4tM0syRJ_E9eCW24)aMTrp#T4un$%xEy1w!gi)H{gIekw+^s5wEVPK+lko(O_nC zh4rTzG}iHkG-hxI@0>K)FK{dEw*ZGvs1_o{{0 z0O7T0(eUpw?CZ`x1t@IR?w~P# za@gw`&ud*TtiMbjShWr{Pvhm}%Lfu(=9Z3j z9!S>SfB_!05~G$0_qYjv2Jp|CwTHyv=Jj(xHNP$@aEd$vg!1(-bSB|yZFO5(PPtak zbOe+jZAGvg@#9my0r3)KoLu$5-yi~GbB-jlIp%o|xwi}vuC5a}v@CZo6=i$OD81@9~lQkUklLG-Aci?{kY`R;yVhnp&yN+zghSnhOB(}Pd(Te$i~vGRHhEoaZ%<zCN|Ue<_nlWtj=$bV+VkNQ2j^q}Ps`Xe((( zjA&RV0~@Q&^jn=N3fG_sG1HDnTSP18fjpajjZi;%PCLAik~hf;=V?R7@jw&>noNV* z1L=Sa8L5D*1z^e+L0t_rg`1I}4RvQ-^|Izaw`l=?#I!!Tf&M{yG{;4u(z)ubn+qz(YSXA*FZp zZ!H}i_y(ePTqaHhBH@M)?t#cCY3$cBuZB1nudNh8$UJ0$jP%=qZ=Mu1=LBSiXeX4I z$}^TNq__HD7g@p3eXOlk>bbb-Hte#{GsReu9>0+IT3S`^Mt=5_ERG0hK?!+<3?NRQx(JGm4WiSU3|8_=>`FU%X zH#=V3%)Vfd5yD~C|H)XZ9Y}BZSRjw)Eo40E$2yoXx43w9W#z?LgTOm61&%1;SW zezKu(mG9K8Ozd!-@M2?@Q!n36fpnJfmvBz(5%B|ivur2`Cv;bi95#JGVn@qx2L(sO zMNV_raH~usAY*MCViz@>eb|_F`$BZv2Ouyt3X>bC_Fj01&#T9R!Y!pGSFMrUd5?#%4@6~1<_SU>K~@VH;o$B{0=%!l`Kx1-_v;_^}!(xWA) zr;nk<(#oKQ$lY<4A;OF_4x&+A7~H15B`#|_P4GEdZBMpo@;PL{_E$M_!s1NX@c!J1 zoGC?ux{mlp64>YT=IU+rsvNffsD)p<-7>GHl6G3jWxA2k_kkJx6Ir&pXgyWb^jg$j z4k|?z74)bRXfRBn;18o4l(KUw#i~O*{|Q)mq&F)W==mg_N2Q9FdEI!U-xt0jBl`?{ zQ~ig6xVf>`cGUV^UytuQ=k_HBm?;?D7hbhTefX1?^Y?6YZ4RaQEjxcognK|i4YZX| z)~Z^ZJYn6g0<+E<4lRBQ3U@C@B~$VfkKvx#|Jb)Ob>E4JEyL@k3BVUhQL}gXfsf0ZKPGzm#oL(U!3G#=q>1NJ^r-54cipEw?6Sq!~634TFN5H zr$0}>KfrG1y*;nyMKos2s|Y$*=v`1aXbT6KXT@v z{I9MZL@pogS6^TES>Luaj<6aP@(YP zRnODp(5|f6-`|^iW1?idk6E$9g9rUNS0wd;dmGOf{gKTtGz4cn==swh`{{nFrb*I! z`kS<9CFN`sY9+~LgALKcjh_~>HjZ_UVE-!Nkk8Kk9lQ4Td5;pw@OSa$`@gS#{C$o3 zC)fHnZuxJ*^53W>=P-NQL5i9BWTr8Q#6Oza=a*5>63dqqa~_%cKvz%pVB3*L+rJ-4 z-XotOzHDh079VupMFhMD(hmw_T+7gR92XlJ{Omf8+Cl#QdcXJ&B?O=-Rh)E7MGY!g3g)>mpBaw+k{ta*Q#L+tSR_&JM# z3fI)x=?`=7gTk~hhL;gog5Bl`c#4X|7qsM$rgK#^0hMd!Tb>9>+G{G^#Zf)QZ!v}9 z*4Bil$CEyNw|&vJ_x@UFkydEb}mpGmLy-z&l|q1L>5#+#pb=B6d?D~f#t4SRNJLry7h`58j&{L@h( z@61wLy6X>ZZ+kVSlEBuq83pF15t7)i(Kmo^Q1-dzHC1hUK93HavZT5En*aFp^6szy z{;sKpys!_%AC8zWgp9r2xw7z8@~sxfmq+;wlo20e-9{GRU1?AETJpBPN?+W(Fm&|n z@*m_ZgM$mkLSt*n>%c|~+#tuQsm&zUwtZoOXYw)qOy2S_j%fk=nM3J5#lpgyLe@|1 zO(MwoshXnxA+4A6J8y-r+`lO1%#Ll`a=_fb%`BSeYFb?rbYcfZ51}>{}jcWCfj05uuDzkPfBgk1f|sd zZTc!1?TuJ4Q1SWvWlI;Mld$@_@jTcL;K8!(1edosco6N-ma~Pf?<8X*P7v)9KVY1@ zzTjMO#P<`DySj&L_{Spp;#?*h_Vw96Lr7KZKc{^tsQbw63fCA!PY$@u%l7)v#;#k4 z9N&(u$Eke|<~KVB7`rXK^=&L*cb(bko$2&u7YmWo$jL4PM>R~$L+Pb3(ph>4oO;jU zbN8csI|#=VL4j^RxI65@-aq!e#&_PDF{OJgWlMg-9lGx9g?E z0Cajf{Rmv_oif?Iuh|kpR;AyC&`G)Uz1WzYuj)=6as6m}-*h+Q>R8`^gKycsKHQLc z-a|S|L<%6ix~T>@60SYUKT>s2Lu!avjlX-O(QVOveyB>@=5@!w{Q-O5wjFuS1B&0f z03Wli0ga7tITPqa&+K(r|2dYR4-xL^vU-^`E}<_r~1&x)Q!h;#4KdoMyN33Pcpg_p+AXy$UWxTYSsB*QMv z_&8Eq_1~)Chym*?8vHVWEp0OR&O*@)Lk*JCYYgT;tV{X0hp?wi;5yC4f!7dSR_j`F z3_oW0_+6^E$E4?el1Bj?fwdZcEe=(%TWw^!h*20rlU-qB5 zAC~3%?&vr>WJ6gN|*A6g5x(Q!xQa0@%EFR@arP7 zadwq9##_YyGsw}re`ZCLs#)4*-zCvj4;C*?`MBC z@vI2WKGHFQxe*0VUj|$z9E)Ncfh?eczOBovHh-h`t!&KG=wxBi@sR_PM1}{H-LKZN ztUltewcieG@pMD0RSpKwp-+^bnO%(5QGs;Rl@^~}^?Upw9H_~{o;+jWxcYPQJz9<| z;~~iu7#S@*+LUu`F}-d%)Sj{FWQnz8o#y$d?Y$-!Hs|xw-)P?jJ883I#5uT_&?zra zhE>yn{WWL^%{OM?8`6IghTFnnB;=^p$(6pF;HYw6Wk`r|1dPS*Hwklc?z6o zdbLqMnrqOYPFAZJwFs=5)VRiNk>u^P zi+WGUAfsXv_9x3rJ7_%GINI;vyl}cA`vWV~Yzs=)#F2ld(EET@l((j+sc z_6r<0VB0BT?8t;s#^+dUpmW5f?|y?v_CrItLfYw?l->6TC3>S3@Q4?{o4Dbj^kEiZ>-gJ z4Wu)_4)q`4bg%z%C;My68+#L~ySm>ja_NEVnD>|a_Wg5TJ*?*E;rYP!(EOayx0@^b zbzDoLJocY~{aMz)ShxRp>wKf5k^LGnW-T@e3&D-imrOh-vV!~+-muA@PiBZ z%Wu>4dZXb-gS%?aJFb79Qdk-Mj^Vtc$O?EXOFemS=o+hN;OpVbkLAv9n>uTvH>kL; zKl#T4+O z8wIkr^t4ZVJYAnw|NDNzdGm$1ZH>1h{nzI^qdrA{ZGTnP@3Kza&*RIXA0Mg)q94!s zV>@C9Y@r}~ocj1`?ZRRG;x_@~AnN?P)(iDFnR?fzs@ytT@Bxr>*I&vrkM{2&7*_f( zexu!cm)`S3BjSE3vu%2Xo|BP9ZTTbL`A%c+}5y~%go|N5kOZGD?^Jm~tmjO?QcemnGdO- z86mZkXl0}odH%^ayRJ@lxu(6Q`*j?FbZO!GZTp$DNv2+9gn?IqGe;1P0QCBG=7f=R z8Qyc_K!0La3VqwA(-|J!Ydj`lo;R7!4SKW&!3s1}?tahy8O%koMq(x?xdLnLU{0>i zevS4{!*oY3fP)px52v$TrRjmKQ6c$B_NsP@w7Rjw#tSZ}6*x|vCx6sHUxilz8k z5~G5NE32oAc<@nmm5t)f?_yuFD=(tq);18Ll>cn9FL}%4_U7YsI>RGw!^*pFHo}!i z7beA!nPx7S1k-nRyrZgj(E-M$Y(Bl)OQST`>eZ`t@PHE)0*@)Wo;nka_Er&2(F3y& zLzPdH?$EXgXu~mVcyB76IF8h8`uT_^=Nc(+`ZpIl;M1LIF+lqtrokvMNPkUN(1AR1 zB%FH~sbuH^R5n*1*R3O`Qv>PEt$?+pgMd!Q!vQQErth}{=%%OWGZ*8SSa+BM=q*7! z&z>HfQx++kJlMY4@NH3-n?m4`)(OgdH>?^^`vVhJGF8n49<{s>dKcKh)4R!Yyg4+I zm}TeJLDTQZ!ZT*!EFiGjq|D1rUGOsyKfsIg0GPWt%;U3bJVynzu&CtF9vZeZ}lRX$TqK3iDo}ra1mWpHVV{FNHrV0k_j-UiZ1jYK3znQ z#Ckv45_8ep@*v_}Onf}h(1Fvgqvv&6=5d#^5>E6(t?69HX$DTj#Bw`bMBI*MofY}{ z^u$F?1{dZ6%I_BJs#UkH(Jy%er<*9cme7yUWe_z=hrxb9`D20Gbcbpf!@-8BL1Ac# zlK^!=dHhC)^9;AJPOVWUr8iISdY@tKYWq!HI({7_GGE8M!=Tq|LtTd}M{q9jf!n0? zj{dRWe_fXSbm#7nQxRJZ9*Kn_=_*u#Q>g{k%ogiyo43O&Wg%e-4w(O8YV|`r;~0DT zc&Qw__Q@qQG7AuTX-qQz4?}0c&}0{e;U(J`F}h(J z-J=^fy2Me^GD-nKM~8r8BSv=$I66e7M8KkyR#E{`DHRkIP!SbBKK{ac-c!%HpX*ZK z-PLVhvcquZ+GbBFKs&}Z@DB&iLGc>6cC9Sqk^&`GWG07T&=Wsy<9jr1KS!N~O}!;! zZ8W!bH%*7-B-CJ_hCAK(IC5MM&eTrkFleKdKcvOPr(Z7PIQP<6{|C|X4%jFiQJQSo zGeXnj4%K@&?94DWkl~2zeWooDdIC2x^jOl|0*h4BVi`148kp}_jmGkz$iqRkwf&eS z_gXo-y9x(7Tf@vguTQrCnE{~a6hYQ6$?srP$~Il#cbSfMk&Coco%W1|UB>4T#7QMMQPf*!2Em?gSRJkc4`-f3!^+>q3`J9etPr9cT za9nio&1@iCt*Yu(`J4GSb5lAFuVPmR?9BBCs#1v}_iqmuy9j(Ou8 zaAO5gHHE0k^V3*{jz5NazDh`*GN=L-zgdZ`#pl&q-H%KgGndSVxNyVuX7Aln6rScW zAvT%kc{-fkzVWzx?843D*o6q%`+HUtQ%t{xuO9rxQw{H%X`Yvb$B#RIY`=bWTg1lU zq|yrh%tuQzU=r?k)71N2x_)xUQ&)??;Tb`lnym&z!qSg$m&3CuJt3KN{r2HJNhked zW3#8jQD|qsr!?J#t}FBR#x0qtkLU~$JAlQoN+oY#)%fFot&w43O6V&0vpaAk3vaL;KyCB)npL{m3i~IT`id1@nao)P|4JG?io?V7Y!K`oE(8+@SMM`cizKYJ_KP2PXlnLp;1i-wa7kiX zvT2*P71D&N?3y&$Ths;f^nLx*M5>`u~FT;X@!-dE7Z>vOu(U|kbqT+Ae%2sVfqRogq+*Ab>^a`)ps1aA+b zo;zIwz*E%mQkutlayQMVt4x{G9t;kr+*N}l5Y5jp?i&k0t{2(6s6R|3zD^X@WznIX z=>v^E7|QYU64e+ja9tQIjrYjXv+!FD#GUWShv{h-=_Ww(B}&DCGp-ibqKP#1F`WUj zar?Ht3;scP{DW~m1LCfr6(phXC~agwKjRo?IevUKj}s7TylnOM6~^N!qT-IwqgNkC za*m5+vkjK77Ge=hw_WLeKg{%|xk9d6ERQ}~eenqG-~Tw&j?@0d!u;we&q!B-!P<97 zdV7@x#j>m(aW$FNzq5ev9e2SR@_R=GQSycQ5Sx6+_wP=ARWLf=Mc#ZkM*5Uw_aQA= zFDr5F=6^O@Z{Bj4>>51NRg4YvH0`ya!WQCpd-hql`orkT*$7A_ro5#2&5@KRxKfxmUBviGwhox+P}Z)k;nSm-OfbnYhS zdli6r&+ zK$eX1e%u25W-yXl^HGsEncR%~m& zf%wfuu9zT5*)DXrI7O&Tz5#vJ_PaQs6@D@_gbs$sN#0VFGWjG=OYRjH3$=iB=zhqU z97DS%6X3>?MQw8v@*Pw5lT{`*&4WyzWwYrf8I*?Z`3teB>40VyMw#$`x6H++iSnQu z;*GKInHR0b!5M&FSCEkS0h%uKs9?1K*Nana?v?sBL{v7Fy}dAJtumdbrwrqi7QMj2 z3ColQ9Z6Ix^~W#~Bm390+0c-DW7LIYlu5eAuFmP)ih%==4e>5uc9D^F@iPq|GS1;i zw;f&Ef@`Spfq%>Gmn)Y$ssiUzD+lXXg`AinIUD$vRQwyk%Fo$uWfi{Mq0I`=N{0fS zXXQG-;A_R?4+MX9Je#ESZ1DAyj9atosFH@E`}`m1YiXDq7a!{f9@`x;2ftt32wPp3 zz8OE{DlOK?Z!9ZGCEKK{M6CcvMWdF|r8^RT%r*&!Zb?{FKAZ9mUP-_F$D)SBOwB>x zyw2pd(@=h;9|!ta?uaR50!iyrA?HV{0I3t%6PhAIY4-t;=d6|F1t6>{G|ae3xcdP6 z@k^=&)xQtMWR+xMm-Z}fbfCezwe-d>gX+QF1b*=c~I|VOVBJI0bx61 z&p)xc|2VDh#jrX zx`m3?%!2=w;Wxps<=X>2y#JYu5}v0kMeRA%5VU33yIgY8p~-6;tem+q>Pr6UgZWlA zd}rSEDbaod)<@#`&hT6LiQ*+Tgx2}Z-?^Y-(W{lb2BRiR>37i6L7VSey~T@ua->FQ zjp{b5>g|sV=RFlVfnI$H%#AuywwaP~v?_tKC*qpK_9-Z4j(b86Y!u}X{6r$CI{ z)3#H&6Mj>*#r<5{h>cR{EJ)Jv_o!1&VdeW>#J3U@AY=<{ymf7OT%iCaehlNkQXrW? zuBX-I8w*k318N7}*?@;YUNLdHSkQc%-m$sJ^B8jjDF>9-F_@Rwo~HE&2v;0a6@7`4 zQGN@^0E~5_UlZR5&|<8@jcf%KBU`MU1?O*$?Fze%4e32-Pr>;GBcf48ouE7>&Fw;T zLs^sO$pv1D+ETXYzkz2myLrj+^%z+#85ypz87Ot@)Z$1?aer%(h1Pm`Y;@8vdI)_XU+@%vOG3`A4%y%8TWC%tfiH6hdzU_V z^Yd%;pwNZ=xKhlT=V^#Q^}^3PrH|fKS$+u?ph%AR)&NPTcyDe%eg@UC$Bu^}13Y1! z*!LCrM*+9&=I81J0?(|HjR|`=zJo_bC<_EYaO+mK#y@jzYYMB3oVqHF#KuO6yB+^v zHWj1qE%dvrMwT5bOnc}kIP(S(W$nN!@~v#t;P5n*E9{41FCQ~K3GePmU) zUsxmTFMF?fyrb?>o$s zM1sB9Z!A64JnYD?3ig-&`%3io&#oGgkiavqm*#s8?{#DcUp`stUvxRVKPYk~l>PO~ zP0e3@vsG6jo&TVrG5I8Wm9an|j#JB>J+35V8a$w#E*RX4HtO z1pD595lkzODR-4E+u(O2wQJ!CNGkWGa}a{5O42?eVrlSx;MkC8FECXhc+e(@0(Ig{ zOqG|w@^)@B4T9U#qJw?-fO*EM2i_%*toDi~RhU$gfmvP(2|JJ4p^5<*q^pU@C#U;= z7CRDuwwx2;>)F#)8W4@@$gSG-*ZR9WTOD=p?!VnfIOvHJ8S2^&eRJotdfpem z)1+x0o)-%V#la%Uurov;(r8ooROE>T0g0P&K=3sTKZyO%@7%Ly3yiMJ#Vz1}%@WgV zgye0){Tvz5PwUKJlE@Gwd}Ht^D_3-lAkqUDC0`ODo8SMDA zFPy!*fXj(v4}jx9uTHCFY*Kg}z?J|5OPGXoWoA`=6S;67c=$6JYz&O;NmB}HBN2ZPLzJVfp(^HP@8V#B zaa*WM8vxG&Nz4|1eyAkq;L{ZlB&1#X*>m*FSNL6V!3GYQl!BeMS~h+e{nJ!p)vR{OpprZ!#>SLMFE*9in%Ctb?8$Bb{Fm= z6oQd{p@fO=?K4-_glkQf6G>n_QTZ4x#9R zUAGMm_j%2~1)8O7xa-~;ec}3Ip_(ZeeQ^%HLtFjt_F6(i24}Y5Z|0;jzRTsRIcPiB zG3V(lgZSzT&};MR?>Kk2)K35E&jEvHPPnjf-woJn2}qiL{+zmX;m)d({yCyior-KZ zo2Ixje_|5;zKXukh8Ew3;K{i?-QYd-rg_Ov-wo9ybxOI+SWi`GVL~70b-s5RRCTC> zDZHz9szGResaf;DArs&aag|7^(;cloj~ zJ0Jl6#qU~oIgA8qO`C?978lH%eZbj;X7W!_UG+MPVT$+i&n|YKj)@7+{FxB%Pn3CS z^J%m$h7(+5HGA1)J>NN9Ao-J3!aH4~-vP7r3p^nHZwJwLOgi=1av z0Qgy#M_9}Uyn0=@)XBzI2W553$Vhxxa~S@X47VvPj4S zJjx{K({T~!5}s$MXkX&)rG&#vNtyvEJ(sHX`AT+G$awhJ0FO}-US<)RxnKd+#2gms zZmGF|2MoEQtP9kPE4ZYC4~)qK9+`EvJqr5)g}p+YT%j=!H_|Ri${}x%m`zc0#eUGb zul+n$C(9Zh{|>Jf-!aMpAo?ksy58Jo1fEk28EB9lFvxbyuq>&=U^683UmAfZFRAOC zGV7ds1MK=hhlT}BOfBCj26p!p-1|e$GU#$g{pGuxwvih<2N4{hKz`g1o04oN280fES2W;P+@P9%I*>aLfOt${2h@aX z5m37WY+u*dW)9iRFtN+gdyupck&6N^Nl;CBfXsT}({T6F&WNU0#&Rf??w65X(Z-A% z9b|8iXSdm6?PqmO4E6M~W(hMp)qJ!|E^vugYIS}^v#;TAk+7t{&X^yXn0CHvC!VL? z$!O%u0oEx^_UHFgegi^&<9Vn+&9uYRVx{ZOhhHVm?Pt|oC?N;}FhEWKQVGNENZ7+i z=(~dqIbv`&(bBiMcBvQ&bjgZzUl$!ERWW}yoGK?j6LHM2Rg-+YbFUkJYl)EsX2eb&vF)N! zImY7j&76jqmetcZeS}2rr@_G6p;}z~zXIlozFFP4DWRzUnW(tM`|y zksH-u1{dBAlvE5nGzmHDghOul1=bc{Gmd3_o1ay8 zKfkIJy~|)*Q>gY@s$2hEZ>QUEt^%#we*?V6T(ps1&MiISns-@HidPQNJ^+J*hD8O2 zut@f~^C3t{_N+h6`MNFHahQd}SdGnQFr|4JJ!`d#JOCqR03k{0UwL^fbGhqaj*b7Q zHMfpx?n>1DqQcM2tEKcw4{1BUs^!CBn=zBYFMd5ATN^s@@m2h^R` z8V8r(e^PRW$3gM&S4AE-Y1{8ShPutaNd)a4^vOlEeAqxoDEg^W{8Lwtr{QZ)z4f2@ z3)e#}bEDOgCm%>(=|_+0Na3>3FO!>@DzmZ$QKDJC(dhBw`0;Z6aV_5Qn-9kmNE0pb z6W7;Z%v)$PhKFkfdq9%&gOyv?e1?A;2~5V7h{qex{E<4oTC2FKJXWd5+e$p9ut)ff zm{+2c@$mSy5%-5r5g=P;&@-`(L1yZj(z?-8;hxxyhp`Vwy@%lS47Pf}(|kZe;qUn6 zwI=&x$zU|V&|m?vF)xON#r&E1MwwgFb>b6|j^{K@ptbqxOrPM+;EEK6#WpAGDE}abIw)ai{&)~E( zPco#I^2=xKI(GYat((wKz9OHkbh#JT(XcXx95~HpFitADt9rF?@O#N?k$;l>!82S& z%u0{Vf!skt`}f}SfRiu+*bKju*zX^GeIj7Sf;AVmZy#-AMqWZM^s>6BR8?z-s6US# zlCC-=yc4ZFc!-XoH1|~7oooamHh1qQJajeMS$Rw}yWo&8G^-NvwHEU5g`-qS#Je~D zecN1=27B#wiLZ%a_oHh+|M%l_(hacpiS&;u%gwKx%~mtA*GKq9^a_ji&uD+VzVX$f z?6oThnYG4Tp}TZCpAR>GM|*s;kNW8P2ppb4Ii*)>xCOKP8)Jt5W20PC0UqJ{^Wk7xBt}8nM`0vI9YSx*zJ_%Ls&Y1c1K%iX^?)uSUW#{F`>^TTwdUUVv7Xv-yPj~Q$`Xz{l5 zJbUOxVK_^Xh!mFN>zEy+==9Z9{>i_^vY!)~nd~c7llF=PMatu?B|G;~HlZu(Vt4gI zFHSO46Obp>Gh9deTa#CrZs(Q6HC8O=D!=J@74#i`E!J7PkFVVhGtVpBM?-lzMTt2< z6U{4q(r1fARGJi|Pb{uOzo76Uqb5D*sLT$CF!9aorRo@Tj)hP9sR=O8p}M8XC!iME z?wHlt46D0VH)vjAtBp;z4r&rv*o+U&4ucV{*YKDCMsQ|CXMu5N2QpMd#@R;r@I1;4 z!MX4{sqmf?$}0&15Ft^aryyM%6qkSY73+P@8&B_9&ifWE2W}MFzf3Ma7yBP#n=Yg2 zG?P=Z-n-&x4<$`13;B=CrdV-G*fb0Yn@lzE3Hlb`3Z%OI2qS)0T<#_*aZ|LQBXT{# z-(FR=vGTlJP&3;yGe;9-y+7|xhrLEnJ2T?1eRDTw5rp9TA9;qvaqtIqyY8anPIp;G zP#(@&Q2vC)T^I^hGA;yaIWU~|1FrOcy5l~>xX}T>n#p9^fK>`^F+vH#6J|{To~eAd;4N;kl&%^qGo@yz6*0OwX084^&dr`IY69a zWxjIms0AX77`aFd?z9AuxFRf?RQejE4kY~B^% z-lO|(fci1a*R{p-+eSct%rRNVNub!R0_(5iGDp10%8%>x=`-@J&0)+Rq1i^dJHRsA zlf3mtuADsiM;=Qx35Qjw)?wa(_oUN9-;3tccmHEMcKB+@b9H~O;386STuW|Bx#yu# znQ)-v?%$m>F-^F{)p^hgBo7ut8gEC~xgJM;SLuW5Aw zH%6!yfjWOytB1pcIR*e-n!Bjk38k=yUflOHN7s zgvpf_*h9tY`JTE#t=%8gqE9ilR(2wrM)4NI)5#5!o^HwL2U!=DN*6NA1$NMZDwzdl z#aVWF>)fL=B@IzL3YRewr3*zLQW`bVoFz7mCM7Hkzv;CAAdspV&C;o8C7Lg z&qU1fvjTYi%2^&=0vIj70H7kOBG-ls?i_L;@>|fR_8bPUEQuva8z=mer1vIJ!7PWp z8rIU@B88oCV)AN@?x~aS96*qAl~u_riUGMs@y^6w*s85c&opdPIf_ADL$WiL>(L^;EjbQyz_~ zPx6Mym6noZ-qy8X03#Z;J-)#Mwga0ji3>K4m7r}1UxJ+fGQXFtSGOOgJM#MHJ2Vf* zW^^)>A>%?1O*-@(nMe47fpo0IBzuSqh>d##q0K$cuW*84GaY#U0+5GkD(^39Xe^%e zli1{;<{9HW)1OOD7ovrcH!OKNv;0wD?s%Cwd5SlS55(B;{f2!KFmjA4b0ATMu@En1 zUWcEFDR?SAos}3Wdv{=+;Rtn!4Gf?bZ_wg9%;D0@ns(59|%T0o%Qe?>m3s!WT_FvRx2nN(mexsTXd2i1y>?^Rn)mn} zqGcKG0!_GW;*{t*tg9+XLJezxWc|`WDUwoOO!WWJ+xsLvxPP7MV|_7jvE3Oa)rCR! zqL`Ex>TIKAXvP`Shskmu3b|Y^&}Cz1oDY?tlaU)-$~?5<0a?k}Lgqi5Jx2i}k$tG# ziXxYC-3EmV+bsZ8;pT%0S%S=LCVpxcrek4E`oqa$8v;Ckeh69B_#+c|9e6$k!ldNl z=*oMWmp{pt_522xSbOhCaZ+-YG5Mq;UHKSv4_c#}>$sn?nt0gl@Ne~_$)#6{aH>J+ zB%PC&e_NHuk1It88gvhk(PC&4VK3wJm!&uA9OZU=Ab;VNA*O*{1o2i7$>@nLkojDU zVvsXfsBLKg<`T**o+QE72a1fK#atRh29g0%@n2_7*na4hGuIWEKS(8qah)j|7S>$P zu(y}X3*}@|vh6^KysEKS=||x@=YDu8v~aCV8B0@ZTHa_+*a-nydk9RG z-*Uz{d&u#(!sc^*?m;!%Ul^uFaNmHdE}ktqc&#;R;r|$&b^+y!mPbmAx)P*x^g$68bCNh2#j>U9iSYod@ zL?WKT+n_Fr4}5G(hIst|24m7;qA|8ib|x3?OoA?f$7`+I{aC61uo#r}Oqjrt3ID3N zHD_e#DC)xDh&t1()gLora{=WF#m+3?Y@w>$qZx#-+J#DAJ=jI88P93h5ykqFyh-U*-IMU>wfbE;EhEYQszCjMm2<}5+nmLsdUA@)?H7vrsOpCp*%2xF&8 zYyZMzg}H&v(7E2(gL}+=cx2Ii5o!?+Aq7dF<2`#R+p07i5*mdZgsei7IL0^v7|ey{ zC}`Q~Vka9&VOk!}IWkM^E=U^BOLB&gAQtk$N#vvCQS#9f&Oe#P*68c z+*3E<1+Y27g7(Y<>`{7!Mj#p_oF5Q{vI-1?>1-B7k$7VUu8TPO5SLZhI(%W`uz&YX z0)>Zz2|G-8E}<4VE|D*mI476*b_;t_f}wW)lPVXJ*2OG#OrnZV0Yrb#JO$zh`sq;$ zRs%hC8pO|*av1w^%qu^W@-t~vj_fnbMU>~pMkPSX1?Dem_b^>yK*P1qTwT71p1*7# zg(9PZal@A+j8SHJIlw&aLdn2}K-GFzvgdoIZ->T^P*`92jb2yv2&oHE0QIwhC{vJ+ zsS(}QQ6!nJ1_@OQm{U`Xfc=>xAO$M#?-*%*C&st?dac2lP;#%6#6B1$JS-HzA__jb zihgiKeJ*i76UJgoK$wEemNn%>R8cDhr<7Oc5DL?o1q6`p_?<3aO7X23IpL`E5&N-3 zg$*)A1DHQrWJgf1Li6p_!c~F25>uDL);DBst25u14byoVe{`N>HSL^rr?2p!V$ntt z*SdUkyWpr%S}a-Rl_|=f3Ksc670}N8a)kV=r6#maLAfLexh2)i<*Xm@FcEn9UB%wR z1xASeuNz~ViczgUnSoudpE-DT2?aA?77i-1`nwKfJ@TSkl+D2Pa2KKMP3{Lr%$1QD zH)LE=eNm0WV*ahlQ4Hq0GxR23Ex>|S{7e9?E;@4FusSaWYoyDVK{$6q?TQR2BqJ)t z$d5})-btltPZv&bJaJA0*@>Q{p-MNTx6@lCuCl zpJh?Ib}E4bc}*ml-5SyJc7hu<#r>hTe%M>u4{|i$WBLbbb7U6F2;*tRsd?R#UkHlR zGeVyAMV218H}N?t&5D0FM?@~zpV^S;R#P700~`f}5f&vrI!mlbxN>)bxv7xUjfn49 zyXcqVo1d;vNphV}f<@t3dIy9Mgv8}_PQ8{IDWLj8pF|mN7A@aIsJ0v%or5`!C7vk4 zvh68^sneeKF`5axZC}qGAjey1{sz>g=pt*C!7&OjxZI9t`yunDlcCfsAIwmPs)X(M zB^_;X`ydP?dBPVYZ2C7~i*^#d^AXk+v2UXzgm)5#>`pA$FzGFy?rjdXJ_~mr-e;~R zO3WK0Hr8d|k4UxGgjiEKxQomq{e^WjtZJyrk$cc^vgSx0OAj?3CnPH+4G&&BJF<4I zXhShqRdGL^DIOgy^^s~CC%ea_Uigu7ZG-yJRFlQn79-eu<8$s50#-#z9!rxS%A*+z zgb+{=(;4ldk4ciFwNiWmV|=|MKB#%lut0L2A%7|_mzT0PMp(vXh)NT-3tccd2h>!s z_JJLzp?a_^;TE{L8w!R43fwLa^aTN(CO(SI3~o8bGaPeBJ5wn@k4;AU%U_wJWVdO! z-j~$yS}VDl2$gO!iy@!IEue7BzHC@KQ{v1C;*I&Wx1knbq)hd%d#pC1>}KN1K0G7s zVx<7i5R>AB4(N?o)a)~eqbtN{#tE8K6wY4;4aIrhgYJwOeE)88&d=PoTX+n6K~GAh zblKGVxACl5nYW+mrSy{XkV>J$5~PF=L?sAaQFLYt7In!wu=84=kFk1@QS|9WaUl(7 zlJ@ZT(6@|E!T?OKPs44~k}`w%6Q=1Lu8}wPO!_{;Fx3eGOfMp9R?k4=QKK9{xF;jp z*H|lrMxftEFev66TL@}XGsh3D>+@%7wbf!hP@XB!z*E=RqVh}}>aCh~O_#%+y%O6& z9sf83rhVofG#*Kayy@i7%U~8RJYm|HMfRp7w(__$XL9&4m>T3y9ixrzzp!6tkq!B< z;C3j_FgN$Z`k*0?pO>+27}4W3Ha3OnwpquA-Y(w0!^i8~4Va1TUyYSrP*snKhJAFU zzw?p(M14bvA3(kp{~Wq+aB+gWde7LC!bHU}*X}oc2xktHhB}WJCZ?dSL^8)jLIdy! zZ-4yNc|>@j!A9sy2fHM?W5ncoBs3H3W z<~xH-z5Uu>UmfPoLKgLB)`w&v0Kx?W?edLoaJyh7~fIXD@uyHF$P@#YE2Os?%nJYuEtF-QeWIf(+l_)pw=>ius+$g~;n$g+zcg*;-K*8aG5K*hW7O?n+b{cviZD>7#` zb>_640tZw^rlp9~2&dOmE`xPNABq)kUf<#$uPm|bN&Z+F7Nta0pMIcKjh3UAaor#y_ zy{C^CtLkw+kEgxkf6{g)&SAyBFz4;98aus$h@3yi<43(I3hS~@P;kC31ba*0mu3mz zeZ2RnmY2jb%_SX%?UWN_Y4QlO61^gU2+@*!{5^o$I9G|6c{jIZ zRo*F%#=I$1wG)sb-37qSi(t+E$zysCgtV_i2AK>cWpNJ_OYJ&?-qgw6>9f&Om!opL zhJDu;3U8fJeV$-jjIH?s&u6YVYhKc&akcjQACn#&=>c$gv0CgDYwXAP@r3pBo1_zt z*aeY4``3tn_=Uj3fmm;L1qb_mJP07M9 zQ|yY?AM>biNCe5-bo^}j`ufQ$OfeR_Gl4k*@_x-w39?Hmn&sqAz15!*f5FZ#7`sxN z5O)iMtR7H_e=FgxhXu>;L2~~%s(6=Z!uU4h1~p;F(y(CMrG!wF#PFrT^Q!JFm!a!; zcZDMTLMd~HqDC`*%1l~(o|;zSDO=a7Xixo8xMl#p%%>2=LH!3MAa-a_XS~nLFR0Qy z!}G!+>@~XZLOuvVJEe~I^N9gF7Rf*tON5}DNno0HL>yoaa))?**pMD<0#B}Z^^UVNUX6-t$mlNo3Pm?SZ=1_d{ss}Q<&hrqSg zVtq%0y?R$J?;J(1i7xWpYD(U@6n>6r`<|sO<-T_MhY?q8KT3*zD3k8ksFSVt6A96g zrO7b=EIEyX441Y~VqLP*a~K7KK;k7e5!=Yr=7 zNe+^J^z}aE`I>N=CmXZrcekHa6As(1&EY!7LSfZh+r|Pk3~N;|g3&+V`Wh3QoY|ea z;;IyuT#14##U40gT>3`Q+_4>(`bat6F7G@L|)zr@r`1S6pe23IPFgl-T3lGgX zKqI*zu*_VaH2^G;hX=HLb97(_C39Ns_Hx_-DD@?Co~*X%TA)0xKKjIvF9^sHuW*~# z)$rl?^M1)Y(<#dJ;*H2d*MRqyGR-4wwUU&^&d>g>Gv`+jWzK-|`5Zg=Yed_PPB$q5 z4_j|ACW~cqffB(AMyauC_S-b*X`V6JPS5mDie;m ziP2?IaRo8n2h3bOm(w3ne{Ldv2U24zXb!(Mt(hNx zaLdI&21U^9m|&Id={2@LBQyTm|=R`eLYj_znHB;t+OlCkn{c_i^>Afx{+Ya-|gB!!Xe|y*dDm3_Il`_fV!t< zD=x`1Wbm!*;Et(FjP)-|JcfclHj7B)&i4VI|27Hob;eq-UUm^S$NH4hTqKhI{)MX8 z=2y`yF8ax+k&F_7Sve#VUb4)j3N;CT!_zF8yA7>0;lonUVuI8hC>g`SvqA!8lK5?0 zCk&~oS(I8?P7ZJOYeyPoYpEK8c;gcQfs;E$yUh&-WKzL3n#eE#NSBkw-F2f-5@?LM zwRf(0PeTd7#!4n|*+O7&yHHJPU%nobQLY=xQYf+Iv8_9$LLsDUt`c~jX)~RD$Wu`` zgT%y?83Ps?%i8cM7orGsv;c&UC~T%Gyko&!+$0d~VPAM-%TL;A_#v(PlUX;?a#UAU zvr%JOymx6N_7hGvhqUGP@AFNQ`qcaq2-e2i134~pzyUbKUcb9X6Ivptg?Y{;Bu=#5GLH4TDLV|O-wI7L>=LBLw7yFoE>2b98; zWjmF`TC}}l9KU3IG}u6hA9x3nr42yNr;>oE5#g{1RBbne@5>K~ef{4~?WvK49lr&| zV^`)_HV)9aYy$Q!TLK*OPl@wRe)>->n7FVuKHS-?o)qJE$%9?hvp+Cq z3iFbcB?3@TSD?cps}iwyvD(O~69`BVT-iHYlisc#g{R5Uy#?II=EW&9%U+lNWH?Ly zY{Yge^w5)*PsD;gP?h!R%Ie61$~Zsq8``_t*`Lo@D?wQEUEu=(0jt-qi3l!=ioh;9ek<$-dlhg7V=<^U>Esdr1yfW`b ze{u|-{Md%oXcu~1u`@Rgs0(PZM%x)}zdIY})W+3FPRTSqpY(8pJK?WIpLUz3Ry+`S zh4|uL|DmdLz4lWjW4L1fOQ>SRwp%AZeRjee>AL2^Ysw{a$vrjIdhNv}Tw8spbQj97 znO!dNHkwtwY@i5laqod*nJrgmUcw<8iD_QOr(hfB4H)LP4F_B4_6w-)q5)nmX4WPz zq3488hP{N=RZBJcQL3Epk*pGR0)Mki+J!e`rSfq?9Gxs(19r3LLhB!4OS1H0d;~68 z{;1`7RL+Fa#Yo*&wWDt=KB6?J$>fhmJ9e;C9H}T=|G-Qn+22uD$dQV9wq|nE+R_66 z&T;%Qz0v9Be26viEs0I{{D@C&V0qv3Qn>uO+B~PvLl#VrHiCsO?xB&p%j?%4daUrV zc_nreCS(`3l!(n+YJ*SNVok?lCQf^n+6P&~mKs>@ zqd`Z9ra#RVk&$gTpR>9TFe|wF_aztI=`TeV^Q!-f>~0d-MSI)6Q(gF;3-Jlf4qqjh z*@=~`7y!~Xuf6-5gK|EqL0-YVe#>5%PM&TsoPGnnwg)m7q1l7*9uBz;PC)%)lK+OgfM;H7q_?Q4!1f&>mv_FS~ zw)sLP6TVt$HDq$cFi~qDFUJ4nN)EJ(@l#XCKZ1pUX1Zhku~Z z6lbVUDEFtgIfT@?1ie88ow*--*{wps=x#1_e4pk_Hd&rS+rmiFV@Oh%LvM_x(Mx4n zuP(b~lq@5`A;8DiO(WmPqYVs|(sXnzjKC%Z(D7Snn_<1aLS5OMh)k4{jmV-7yyTk1 zS359|ERv9yQn4++Ij;E@X+m%mWkDLaHp@E2A(fLN|jz?C;VQFC&Hv>X)@D$;;%9(e!3P-2Kh>&~*>#W`X*2-y^N*v7T~%7TS?|%eL9o ztrDKCEKdi7dpoUq4Y6pE>Wf#GI`zk|b$=Af%0*}Rk+QxYbk@vfJ>swPJA!Hxt2PT| za&(*JCz^AInMngG|NRzt|GG6Jp!OCKtOdU@wbTK%rq?ca&}0O&%fVHlSr^bZfK%|l z*96@1=nl=a&OO?l!5%`qWtn63)z^+kX^ zYALBz-en>Or#6wCclW6gi*Fuua56vWR>fX;3uqV)sK|0%O+H@7SjBZZ$G3c#WFZ7t zJwB*e3v4ty&`#N4G3+gr$1!Q5+na){V`5w0g@M!dSSET~(f~|X1fR~4$0}XGL>GFC zYlCAe{iX_&766hEG&Q$om0L)y!?UMQS|~o6@s0>moy0h$Q8PfGWa)O&mW&Ie&Ef!I z#mrwg$e&G+39z;tIBFc|uBU&RE}F<70aEUlfr;=tId<5O2hDl>C3^XzW%0J#+#^>D zp-xM}uTfI>ngzeGJnGn&_NmO*Ye}D>%1xb^*yQV^H1t{<>bH4qOkB=14R)pJ&(O0e z^cPE$kc`iEPUX3_`s{Xa)$d8Dq;>Cho|mk|wF3l7 zt`qvy)NedXBjC*1Mpl#@WAQR;Q*7zH?w!p8?Bkde^|5=ucC&sk1H@-+a!-v5dysdt ziY(aF%a$37-Dsf=IDh0_+im{oiMG1Vbec>-;hr?rWKPsdzPXI!`Jc13`c|`8VvS2X zZs*2Iy^N66+=o0`pnXaSJhjrTX>q&cYNoArw!?HDOqVA+7cWJFGnseuT6By4w_HKm zu4s%YN*Nm&KWf;!)tO9&erq+HJUO)!#6k7Rw0-!^WgI?>ql}Rc4 z6rd_REMvAxkoS5`%KQ($qwtos)!YY33|;M02<_~>t-B!c)J-xSG;K}vxAuXHyxVD6 z10gO?fUUNNNpI|9`p_QQsp|vjkB6S7xlQNDfMm%zKN&N6E;dPS(>iz+a&?#wwQ}XL{vKSDKS#%ZlE}jO?MG zoq85=@G^_}Q)gDu7kc&y4nAb19&h7X{7=Z*?dIC-OKziiG?XB%>6^5L;d(mdw^A{Y!EkN7 zkOzGugKO?SN4$*=F=bBfWq)P&YSpNu1OR#CqPh3!Zc|vxmvo-IK=h-3ip{kQ#DS`y zs|^6k6g*)~0rC38oPB`J0CU;ai*LnDTmCLgW<2P7fQQ?_&&e?U)hDM8 z4}4r#m^oWHat@HMkCmyLlni38J1 z8O_s(1y-$^fwFrpu6ow=wpOLC6;;w@ewjIb_Kf>aNM*kyFrBOLP;Z)1C$voa{M>-& zo3p;#3ofzSZyJ4BraE$;ykU3W0eKNjsriWI$f7h1Wk*m3uj?sNTvdaE0|2U3+Z#ai@4u`|h*_*Rx zxnZyDUCsN~Q73&)?twzTeN|^Zh*DpV#a8 z+y#BbBL#kus@n!C?%pwLxqT?}4t_IK#83Jn;h@nJy@^7a_k}1`Fz$((ME#Dqup1#| zDjIU5XpKUAyHT3OxLCI)e`lRxQH1VfuobD0c8s|%Df{MKD7@#@e_?$(*$tbG1inq^ z*mVAL&mdRV3?Jagu66boo}BEX`b=NE&sZnjF8h*Iwoeh|%V++;JEs#;Aff{}DP8GaMk9r>~Zu}2! zX{~gDY8;5-w^J1S#IXLjx6@UWRP|}|bChWH#1=%1Pwa`I)E?;28-4lc(hQ5K%BBG; zuce`%Funj(#UJ17@v#8V^GDD0VM|4MWe(Rm3`4~i#VGf>2Y0*O%`#t`_%rIFCkc8E zsFisWSn7JPc(TEv`e4+Ra;sH@U-kv9RP;g=!hb9G_|SX(CAb4_Nj=;!R`^yW3RX|W zna!#qzI2!P zO8z&XbVaSBw;l0uZ!iGzf#+W!BdqOdPNXkEV%%ezqGkw&Cnx`aQF!x9 zC`>1<-STyQA#0Oa1U@Umr1bHC4+iWTmxQXG|1l_-z+|i)_YQhJW9E82=;1T&9aa$< zMu>yhU(if2c=&O39dndl=c!k~y=T#{4_`KY06I`fsivqc!Hp{zCqL+TSQb**A9GyduMK5qxZsuHE0=E-EOe7_2=$J3tt!J^upz6UpX7DU zHOtBWQdW6lPD(*`3UA6(R<3s&1OCRR)t!8BE@vT0_VJYhoT$YD^n=>rmWijoXPN@) ziV3RaHi%!Ky>gwx1-Rvu;4Ij3d^r%7l8rLwnf4MtkmM_Oz0MiJXUPVi{e9fV6J&T_{FZl=eAt)IF;`id;1q5{-4DXQ+gl-2BON&(EJ*xNvUq%DJVR=UzPg z@3}Gj1PivXBk;9@zeLD#5yjCfha5M9hRy@`=$EQn15A4?GviL z2dq37qbE-7EqR65=@D7pFT4scGlIqODYL*UCQI;atI#ve^IUMPotf5+uOYLlQ?NVd zpTl9)4K%@*N{0#kbEw#&aDwhrK>}L>J{;2_DfPd@MZr1@yD4a&C~%l+k-D|Kt>6}7 zQ=qAPV;z&o)yWo?gE26ywGq0E46F|W6tsq#OLxUocJ8NB3B2MlkjKY#$`79P7mSO#^+ z-V3vHtmrs;%U1tyL0jk&(6!sH8>>m!SZp?~>b)x>(UBLG|KdsXt~NQC^R`H>Li}b} ziK6jaIAy!sqd~e{wq~iVmAvclMFTOe66yY_z!1EaE1km`b#+dXEW;ADS4Lm@@Lc0O zw^MP0k2z|6&k8zBhq4|gXdbk3@)nSppU#5CXZSF*4|=|K(LPb1>B&Lqzdp;Oyk32> z^@xE3a2)u`uRDOSy+YEsw!zAISQ9cT6&W}qaMFA_D=ddcD}_G*Ap^;Ed*dqJR1sR@ z*Hn2d^Su)e6eB;bD_>}IrNBtmy7`C!sbZw+6%Qeg*z+W!Dk?C?c1_Ll_fU;i>z)`? zD)E9*ziML7F5gAF)G-l+b`Po*Q`f@tou8Cgtgdp{v)G~Wq>Q-YYCYQ?mTmv8Ac^-t z09w&qhm*9Pr_(GIrhXW!ZCh)V^!VDsvC$T}Y&Xl7Uh`g>Gv9ean!0we=aOx{%ULzG znjO;_YL_H1%WK0>S&ih*$(UdKFtc z;mcb%BdQ#fq~=|tx4SQNMzG)b6H;PC@>3u6=V=|$ZshR=sF4v_Y}X8P2`7Cy)d|&f z#bcwYhXxo;ljh%+yPqBmeOs!@BPdwaP+}Baq}kge5hu+n%$zEou^y^Uaoal{Hj1U8 zc`l9)z%#akZTK#B;$kp8HM-F^U-rH@DG}yL8O>e~)f>W=-hOrV%S&}#k|Z=0U@6W< zr+6#W_N~IErQ98O7P*zMEKGE_ohdZBAsQgygGAO zRwAtQ4*1=Csk3ooYuROqD9^@ZZ3!lHsaz__RyH;;#3@fB0-A3#pnEV$M(~r_w9DKt z<>ixkU)ROH({gzuS*)*$t4fhVL&uX=2mJ$bL4c?(HX4dk_iuFwRFD5MfE<-d&!?wM z2P1qeVEG>He2S)jBq7opY+f^bB!~*((ST<$e5dHK6-SA2jZA>G_e3KW6HK%*VTt^J zo`|7Bcm?Enj3!p19@$S32_ZM@SSy)ftk=W`cyiC>E!_z7 zVRt3RO%r~=WG6!r4MouxsWxiNSHu7DhZj6(q)Ng<+)oTq9?F>3XlX`Jz0KVn)E z%8RRep_PCb45ZoCKaww^V-@B2qOksm>k`QuLprK&#%zD&xYIU8l}3%FpSgn5bC(po zkfh@OaK!xgX7H^2>eY+7ugNKovG1c(1|C{JG4D8zpnye<``QJ|qZrjMj1uz6&N?SU zMPCpTuJr<%SJUnCU%UoXO#YdaTE?kiwRb66yO$%A_72LyHSU;>Q;GPRRji7si~^^i zPyX@;PnEX(Z@_iLISXQx!Sl84<4=UtOz3LTjO zA^T9-rVDjQ^%qetj7Zd8U5B8uVjXdb1(Tim(&A%3C>7V3Y0v=j>7!3bBxJ+%0&V$^ zQ=<>FK0Gtnn!=rs)POsVF^}hZA<2ev*d^92K#?Pu#?6!Y%FQyrSElG5IhYQnWIg=t z70xTHDY6&sJ19ORIawzp>J7C*9`YW6h4jR$y3T*Y%r4~7swa2MadA%@#545$hY zaLj5{a$ApFKd{U7&%~_=P#3H)rmdJ4@^d%CiUtG)z%Dd?&qChHP!gnrogi;~=kYm~ zKEA%FdLvBpAu3asNn-t8*0R9Wlwd9{DG+O zONeVV20C9S+BW$f{+8L!G8Pf8Wj5RK=wFPIeZR`EVj`}r@Hc`xCQpTo!ktsy7&Eh zUbDRZ--#;(N zPs4hntq#nIaKQ4Hl1IV5NMz&E555>^aLQ%2T(pGJ>|zdKEmsF;ab&rs)Fa7p8S(zJ@* zrQ5WF4(xz8f*FQou)l7Gb!RvXu7Vpn++mX?b*Sb!d&Nqm!?Nk`Z%-hn zvdb2~`&i^RI3EPj#thDP*nEl^y3q%gT%haQk%<&Cki-ziTB-heRJ+TsZd#{YKq29R z`wIk=n6`Tbtm+q+GyGhky3l;PNMG7c7HvxoA45uT8rJ_0*MA@3>Y3#V=ZrPRtyRAt8hXiEvimK3{6cz94@9i=RI;Y!CVH6ijz=q0)U2HpRdwxHtdir!im= z6pzc6?dLsUCM(rP!f%j(jRE6yu8CPNa*3$}Ky=`P5>6L%2oS^USHV3*{2a+d?|I4B&Owakh{iEw zfC(`v8Z^&_R3yDI%_fQ8-$xsg{pb*r$VSs5h6xj5hR#%;RMPzY=4oJ&*~ETh_)3e# zlPXQ#nCzv{u$S@Bab1hL`k_o#cEI86>H{t)XVojA3suA-4ys@xFEWea%F5-^MfAMi zT0pH>R}s{8uX z7(>0Cc1T`S!k_FN3!UA9+P5pmw3b*&LCu!dtm;F3ldK5QYv-_;QT-!L;4v_i?BOeA7Rt=i&SFCXRi9!MsnzCs;asNTBNZ{lTD=3%tbrbxtr%<;K zEUlVPF8M&NioW)n;v#EJnxm+!44G#V%? zu4Kb~IU5%Y*)2J!EU#lwXKFKKoE|Eg8+vQtFzsIl>V;fOl+XZ%pJ7?Y<1~~8vmw!u7cDq`cF>46IobYWY{Sj;&4xGuQ1}` zTrihQ@!BGt?Nt$d)f$tlKxQfseXa0g1D9pVdd}ps??d7!$n&o2+RFplEg*S|h8JC0 zTKf{MEwI)E{iRWzL3Fid67k-l6AE9imgNsfSp<4JF%y(H8ivQF2Ns^jMHDxGHYl}>Dr{U{syW0?d*YMU&DzLq7kQwMZ$ z<44uYwVy8*^c0GK`B- zRu~If3xXpF1w=QA00tyqb48fCDGCJ)utcpbNIi4VO!d8N_DP^!Ti${U#DI)l2SRc{ zQZ?im9;#WzJ{Z0Ju{u6U-iD8NP!?V`6FNVEdf+GB}ZV2KK_+6GBX;;Yqs=bH^Wei>=j z1=U7DB^8fZ6=gFW3h1y5l|GKl6y3EfAo;hARqDhk?$vvdZPm)B_B2Zd$_JKF&-Zh9g4?!LZSlZEa{tk-62)HtkTJ{F_A2=Y|4H_*3$ZN!Z5{ z%N#Y&a?X|<%H29CX+$E8qZj#}ICK(VgDqnQBo`o}s38MQqH#X$!fGUNukj#@VY*M` zrexkqC2!U;N*;i8hv-_@KkJ1x4k_bJ*Lo{D^nb@Z^ZE5-&u2x`rx;{+Z&3^bW$*z0 zGE7aRTSS?cU$LG@3(YR|Y48{gJLe_4mBH-uPI-E<$rP{D{zyXXo5X4KX=y0Q8Et)p zZnL`R1Dz;);z6X6&IwI=a!X5PmNbS)$2#l*D6vjU{NbSmWKxk-8c1~OKvDIaUY$OKcJ^o_D*{% z^Psr@8K!OAodGphx_ATCr}U_B1z2BGPYpoopdkD2$U|t;!_v?*Zl`!W)pflZE6tEImh;M=?y$#MnrXWgth&i44FwrukqI6NZsVi~t5|s;H(cHKc*%m{3MS zPSu&FaZcGWM$3LYdYgRhV=uA2RDGzJXdqc~u<}BZjdCziYHrrE-R&^kQ)S}}=2Jg` zQYjPlOlj9Hw(%!X@()qWO8L|x(P~a9m5xPM;bQ2x_M8lWbSvo3t(*3^xU;wQnaPa1 zL`9;6iQ9$XOUIsoat>IXx)4T8&G4Ce`dns6tjAgsdr_*7)*!(I?0!q*NN2}QAHw!w z1Fmr=tr7#gkURt_>JZ-@+KFD`kmJ3*;3AW|p(t`64GZ<_PfQzazI(eT^NhWbZo`J9!H=-v>HjN{; zNyGMVWcxU>Th_lE{!6#}ubl;TxHos9(htX6ByU^aKKsX~<0rBG=NXBiGkdcaoiluv zX(fCxGL=*^J-a+R8+UDBYUi11T*iT4KZ89VD@u+|NDjqX*(zT@;;Jy@%w_S4K&W@f zz&-M>bP#%rMj=6z`RNC-gW{WaN`B1B#7SV2IC;3c zzv9d%l}sOa#8hR)s)WJb`<_v2U{Hxg++J~ZLGQfhuH8E)I9_C`#RW;Nb2Kzj;hj1wO=<^C0AirnG$pPTAS&(MW7k%vnJ0MU4*!&J*yshUmmyY6 zL}@HnHvUOeqB=q4uzomQ>QrKxnrowj63Otxtdpx?R_xNwHIJ#oS2X!W&|G& zWhh)R%PRe|0TfLYTIe_py>l%)OXvXMxbfHRZ-&$Zchcv6*DV>vJnK2T4P}3mh@)_* zUncG(-abw>blB_P;)L>cT?UTaecYKQnMj@}*LWNy%5oeui(P1f?`=UAVa> zVaOCy6VE12V&f;&-qiq8a_=t3v7;h|Ob4#D-1{b__bxbxc*qu;09IXC0Y)U7xsW62 zdy;P}!fO}n!*i8N9?Ow8_tk;5U1I}sT8|}3s^|GS2de*LD~-x)4Vl{H#_V|aA}g7$ zRt6`DiUYR{R;Z7Q+Z1>(PrEwY zeE!zs@j&Bp_Pd+0mln4&Ju9zHj$GLsE(g?~^Ed>h6$h42LN)@+9|w2w*a@hCPNlw~+^W_r9ZGcT5hAa*zJ;%(WDF7&Xf)r~kvOm?ySg5d>1 zN^3TrvdSAmjf*%;9+MDRWhZXi!uy5kC@>Cs_xk=QRsf21@ilKI=GX_Gt&{@eQ47}a zjQwO>*$1o4cNd+R(r!NF$8W2h$2cw%-Oe#kDnr#E3@&!M{s+Ad$IRZ!c;zl}nJ#fv zn>v6Y^w^2TkJ_kz&2c+L7k0!oS>(ENxatP~zV%0=`yR8!4*Y_$3@aY!0(H z6oGur{Sx*D@EZrmbuzs&N~?D;DsA!(dzVEnUaP4z0nf4QChY>N@s3Al*7xpWy&L19 zF=JJQx|IN2-l`a~Iu9=+8>>dT66PAIET7)y?O=gO0r@>r5?gcfngqLJY5`mXfO=S& zM(6=Ca0df${Ssvh8PV8iayErQ&O&k|@iSYwq($u)>Inxq|t4MrKin#L$B5tq#6M8hn-M)w70qzmIk4&q1Wb`$H8bvTX{H1OEV?or93V8Oi}qe0+z<0z2GnP5_}zwO zT-Nvw@W;`B0SdX0=Z4|^?3|&%`iy%)CqjErC@Zv`IcN^TrQt2cK_0)p^T6`R_7G%-HiXV zQwS2&I_4IZ?=q*Ikm2A2oS7}+ZJ_Wn-q0Dzb$Pk@$6e&=hb3Gz{7j?V;yA;ap;r}o z4On8upsuTTJ`d>!@3T93e-($>I+#o$McQ%L*ehetipp&s8z1T#)7>b>7hTM{_TKBu znZ^P87JJYfX;rd~R~NFBy57$0x66=Egyt;?7_Nd^QNK*C&6SCwEo!SsJf=RnpiV z@p<7x!y?0^*6gT4$t;cfOf!^$y>%-;J}ns0^N4|cKfBXp`ZDV9d8xTN@$W76N1{Eh zNIkpeeXAJ)um#MgFnl%;rQh~S0=*hQG=YqZ*}m;RvPtAi=aDtpy&V9Swiy$27J6gS zZSqVF(?yYs{>k4jpYV-@|CJZ?dj{3b#TnS_t$7@uae~Qk3A|#uqEctz$1dolxC99b z)GW6~+T3+QB^D)?{Z|?GPS+k&9XZ&^bgKqb>ySE=WZdT0@`J2Zhfw9CbI>!+*8nx zA>$JN6jvM>{of+q2ZF4s_J};~JizVT^B@Gf)(fO&|5{fR>=rpu;PzzliW!8>i6YMQ zhH6+})n4bfSg(6QeFPEr`xx}$C`oXXow0WwLWLx1C-a)9l7w|Pr8y_pB~EQHg`1-q zs~*OPW{>>(L`XFOrlsZ5(3y0bD@-#kXSlcyp>AOt7_PTXswR-}p+~rQOMl8?H z$J7%XAAWzJ@d`qlzW6Vq)LyJ?zZx4g_34ej|4!HJ_=dA}DEz8o%-Em?_`HdY%vITU zsiS|&VhiJU4*+|I_d%xn{S`m}1rl-vi57t*ra;mt@PU1`dl6V=3ao*Gs7#f-8n?() z2HxTXYX>mv_Erh+le3wP*`RN%dKZzH)Ux&qq@hPxtFDdDgfld86dl23xo>Fw#S z37-EtA)f}qkW_%wI=Q4^3D};zIPP$RvVzbiYcw}<;0#f4e$(~=+bNkXpe2tQ3U}Ql z%h6YSA1h(TCw=Z`wE&Swpt&*M|I7a@Ge?w}ph={-$xwwc=X5crJ24mBFz4MQi{m9r zJ2BHV$*a?n&7G2MZc^8arEa=OcNa@{PD|h3mcA>Dz1b;yrucwVh-ktI|EloFDHod= zXoiab1r_3e&bN%-W7@Q5+xJD;5494QnNVKd?!3@_$h%2u0{`oJ5J7WHhHaSAp9r3SXM29BbJhZFI_iI`qFfVC3Twf-fddtf(I(1wWXRsRzs@`;}ZwV^CW zSH6pBCNV)my{wdw<~Vm%e?4`hp|%7&qQr>PP0z3wn)NRxn5oR*Ct<-j_fcM{0R^%< zubIfsgE$58kC`!J@&lrT1WFU7>16&!^6HFesN33>6=oOrvV_a82tgfbmqT4QkRl17 z6%F~56plJ3mM~Jw5F&4Y;3$;sf9ls@j?#J1Tdb zT!xeY)F-(aKI=bfQ!M5rW*BLfp=e1Ht(6nO)(QOs>=>SQSv@Faj$K9%s-y>%xmRXi zJ!enr5lZh7Dk-xUQn+M(wl6tA|307yZp9$~KwhM+kq6A;v+G_`CH<##6-_9`Orc5gq3(&?kKs#F3BlWouspkOLHoWV zl4J5%MdckYNL_BAK`wcp6^J|ao9_FR#EWf}bHD+CEV&q#e32m`2H;Jg`X{ns5nTR- zH=Z=|*g13^p0?w8kx%}wD49nwa(rLop+|koBrwxWB z(%*{O&_pvi!gwM@qfP`mPZ8`DQ3lxw$RV592xU2Y!IgdRrUz?>781nT4H8YjX%VhJ| z=l}_9-hpm@5cJ@A!WWnm)Wh^a$ry&{M8F$t{m zx9c6W+{5zfalv(#)t}gagP$!^M-o&y`u{EpBj)Y+ywgPI?Lse!)ldO26@b;D5Orz1 zz2QFI>F>(ZKbEKSh=&Nz+X-C~TlEo9B&Ln~P*rGYgDGi37@DXrO`?J(y+AvFp)2_A zUz0@W%0-MD9H;=HP#nP}He=rk#=BFqOl4j>rr^|PeG)CO|Mz&n!uz9*R$2|_o^`BKkgiuPMam2_D=aAxK^Px$bB~HRbXy~)&-zd3Ekeo*aIjV@1_h?& z3d1Q<;JmB#^7R9G_MrYl9Mze4RSTL>eV=>_n3v8~bCB2E?NIPB+!@jbYP|fncMHE@ zc)u<<)!h09K#R0Uye$J{u$OC!{hfAx=b{Zaxo1CWJ!;YQa;hun$PJ^f;FDVNyc5?- zH3ne7uWyN z^%^cK9vE;y;b~lEOtXj*#(RsZm|`-^jOq3LR0n=M?%5W*X3eiY+%M1`HvgU zmmID&pFZoCe$Yt7n!M<{wt;_I-Od)Fn?a!W$Lx(iJ)_^RS=_5}c% zKYU5Vf2lEOsqs9Yzzj=teL63cA;QfhUnVtctZH;%`oR>fnc|FPlJ*0-`Upu|*%+uN zpm%ZC{>14S{nGqOFy5DZZ2GH-DW`ND~uSz`;uZzFtD}uCJDS8QB!T?m75=0D3acXt!7Nyp#9#KhyO$1U>X4&+oSg0n`YgD2JU@j(*V^ z16GL*Q8+3m7iL5&l-0GP zr|SCbGkS)rs0mgwB8dgApc~#>wqI*94;J-Y(Juq8H%oPX<04t(y%3fP_mV&oSlHLR z-{n}N7Fb{lhx!4YS(7gy-$m}6Pz8nE8lWS}xH`B{y?;|e|IzipNw=V$N4~&%$Y+sn zSuYw`#$1-*GW$kUh2;{Cc=Dj(Jb@SyN^YP$)(9~xlw+%L;f?>caN?UjH5_^Sg(M`;*4-jrrZTpZt!7>mWBLqtUofF`?! z{xD3f#;!92puxq&6_c}^s6i5Eb9St|!fpahNyYrAO$qHFP#Wl4W1F&)c`E>^ z0wCoEMz@7*i)0+3XCQE2%RP#CEz{FJcz(E93VqZf65-k~w#PU+m@D(gP<@Dg3Jebz zGl=o*bi4N0Fu;gV0t8Xt4h=qMIX3B@(^9m~FKa*AukAgA;fhEHs)%(LsCQiR>xdN; zv9MQj<{T{|{shA|qt<7OE9qqc-=khoMw3=om-22c-xSo5j`5WW8*F78b@Iij1G+6v z_8LJC?uEx*;$iS<3`bQcI4!71RvAPg>WTSC$${7rzC1vO-;6WVic+?1uXWgKp2F9iCEW#cL1WTVhW_k+~L4A3{2Q|=h`*#Blya=Rf1@!Ns)cV zn8_A1%emvLtz4<+>S`W-M0G9SU_NrKz~pVq+FqeqLirJe{Pq$d{d8P?b*#MbPM$7k ztkYVi70;Zq_6!-q5cB-dRINVD8oyMnFhfAgzR70Zmns95)b8zhudF@BL(13cq1ewK zJ2voLESlBnS0v>@SN03PKj$v0b9d9-QR~(ln3MAW=24a(4N4hAf}q8aCJ=h~y^P=; zuj&(?GC4)=31txEnh!VaWtJ}Z~e^!p(k1)2+c zto@)bx{4SF=znPA?fl)^edDtA35g>|#QcuW|K<_9hU$z)X{FLaobaVbGC%rt6#8E; z?>% z{N=oyaWek2GwW)r^?lCM=fwACzB-p>l-uBs5ICE+zx{~4=mrOA!gNUf!>Z2ViUnH{ z&mZ=(JXbvz{URi9SI5FA2%PMRU&_{ux91u|avOVLc5xwo)Afe$6Y}i($E-Zo*{Su? zxJw_X4CH0;Q$-rxE`G;ruf4a)$APf=+DA^*rAJg9)wM<`rGvaBA}TpYw8FxL8ets+ ztHoI|)ldcXg#JyDe4Vc6^T+mxrkwXDc2unQ=4+D&r!$jg1~XJ@Pba^*blbf)Bnz89 zc=z0wt`zfwx*V z35x-FZ0wH-Ir)4}a)hxBkf6&*wslK8>=#OI;x{3?lJ8Rl(iJKw-XVywAPNikX2^RR z(WL&$AvHqW<}>Yv9d{!SOoUK6b`rrR<rpODS2NIFA#JLYR8$IG1lfez5aXYyDn`%gt72$Cr->DaWqH1H@I$fBsb5&OG zz3!daTYwcA6-*W(B@7;#l*w`qAAhZ`mM9$1kXas*``&3-xuom9JV2$)xLmeF{pDec zJ(Y~!^CZM8>czCGvR;6i19cr5rNWS{6rTgXd=GVC`4nmTv);!|z1_u`e4q+X0DNa2 z$PY;?XFkRq&(g5e6gd?>_nfq!*mOY+>MaVqsV#(Bdc(NQ(U{?-jRCu^OD8+51*td- zeg0t8lb*NCp9I(qGF5lBviVAjpb93%a7+?K%!3ka zaK)8@>kL60jwE4CbThnAKZV*b5J9J2eiEK8EcVw`&=;MhjH>4|K*eI4aC{_mirB&l z(gEKdL&d6}_cok$o-KFh(pf!6(t|x>m#MIMo@j@Ccy)Cdc-RqjRW5b>qz!hjyx#>r z*aV&z4DI_mc8i_TBp}HXpab!ev3mw{z*xJ8);#3hm%M~44oZ#tU%#Vz@!Z**$7&_& zT*?$3;pC;1wMNH!b%0PICENLna71V-*fq?ffm#g~qqxeK+~1LLvgynXMyytpP!<$_ z1G2Ul5)^7e0PeBDJU9U45=R1huz>g9d62F2F-459ery+5bh3t7xkrg0A?goiPmF$A~7PvDA+ra?6~?UvxwQC;{4tr;P*_$WKWavllLxXf6ua# zi<2*53Y5=y4TEru|78E#v?+^8B!0zbjf>}JVUCTe^Na-Crkm`62H)F7Uynn^6+s1G z+<4}2?xjokr)SSP!jLDmB;=z4+w@?Ja%ZqZfKY;6ATRJ@=2iUhI1nNLk)Hg}U@v>Y4eJ(TQ) z9!0QAl@KyKI$mbfJmFPPQpwl#bg_}jQ5)<{09@JmVT??J0UFPX3QsUE0+HT#!r zw9Ov>c2=fQk{A$UB^b?B&>y@b9N)r06I|eM@pEFtgrVWZ<+u4ae;ph=)?KX;9KnTH za-aKIr|=bTzx(`G$W*BB2js@9&u91kkpD8+FV4Cz-QrVhrb47ug)6V$Opx!zjYtWR z1TLSs>wF)ju9QzZe=^8Md|4iGYBfC^Dw36g8u8#I#i47y3J2Dw@FnYz!mSG$Ew_2m zqGP^k?$*z2PSt|Yr`ZyzqanZEprN|_VHAPKYv=c_Yzvf&0o4T9J``Xr68kLdfDas)bG-=gA%^*vx8)}l`SM0&MxLK7VaXH| z&W$|J2*P9*Q`6>D_=+iT-PyCnl+5A?c<@GM2|!qGmO&{-z2Hqxt;jkvCgVVk25s@> z3nPZ&_}?{&SG!qz4<~8Xp)bq{oMpxk?No}hgpEx+!@F&&363Oh`b`uajsZ?@p{hjy zI|3iCxYTNCP#<8uJ51-T%YoZS@=tsH5j`_dw2xooNkP%~Nm7=#QnPztt*g1(s#*ud zfoO`4!wOn4`*^qlLu=!_&$jS+F<`G&SSca}HC8VUV)M04#ZRIOR~8K3D20QX4NBwS zA5!6t-G!TD245BmKaLr^s5`f6T$ly${cgEnb`1V!_X5CI^g*={>Q@9iT?DTz;=fab zSS&*RDvF=Si$6a)g@a#VE6q&vMH67{SJ9`w>a=1+?o&KQ@%%pqe9e0$0}?!=TzMDA ztkq1FQWYFKVYGi)DIhMN;iAeu_8U5ly2s4Ev5#MUC!XI9hH<;&&^C?k4=b?lL*HEy7y$SuxPpTn zg2|`LQ!C5Q+$m36EKfgOzBdL`oHwmt`c-6}uE?&e$h}jMy(l!bm1PrNP>v6&I%UtN ztU5vvNMvh`Qj+Q590#5t7S-}tWp)rT*8bu_vA&poVY}0=P>?J1GFJo=uj0TX#R2#) zSW!#LHAFkBLiABoIi3^m%5p|U8%;gsi3r{?y0%HdY$PK2RM3q`RF4(k?Oz$1BEk((6cCJNXeU5I>Oq0Q>VqmkdKb#Ga9n_Ebk-*vK5^*FP7 zdH;IFGxf?<^?R!Q_3BIYn!oF{qw5imk*`q5zgrdMREa3Ir$(gtKU*6Rmv{LqmcDu- zTsPlfxaz?*MO`INZ@Q9xgaDP5`r?vk+CIh7RV}RE*gH&EeIeN*%EWfjT15^K>56qd zBUz|Wqi^k)&duSiOa0L-y;ySjPJ$GhEtZN`c@3^Xn@F7x7Z?K_KY8)$^)kC^MI#qC z^M@unr;I&9;>F&AMZznw`gLbOQ%DdVS+jKQazATR68Jzx@^&IuP)JY*@{b?t?_%pG zzuGsaue9>FbwszWu#o&_t?>S~duLev@vVK2k!x{n{7Y>kXWGZA+8_6~Pb{@h{%#lW zM>R+Rdn;2y5xO>Vpepl5KOBfZhzq+xF|RK!(LE(5fw9+`KIL~u`C2?8z~51SUR%B; zl@~)fDSRo6gK<(SNxYbQgsBah;?wYxSmVFxZpt6PmPqO75cp`-u;Tc2#`@tDDvfFx zRCm(-PKy~#YKR~ZL*?x;(4M1fJ(83_2-k9L!VHW;1>Gzo5)qag-jjGCE*{y`RcG`E z`P~(DqfxNB9|>6E>e4Xy%dF?PWAv{XiUuEUna2l1!1VvK0ebr*7}T zgq4U*O$o=v{X`Jqyq6wCB!@O!&wvE?0*D$&u6d^@YvYjJOu7mUd!dz9*?aFSEH9A{a|&R9{!DbOQWXU z#xY>3_*8w+B*vq=So~hHQmBJxe7EpYrg7oy@zr^C#z*VpB`8<9mb$amJjFH|rjiPL z9R+t|9!@E1sF@`48y~zT9K;jSRU~oV>x86v>ZteWYsvf}^fQVt?4%qKd#yO$Slqy@ zsy0^HA$v|TF3wK>xcG?UJ?Y2yj+hIbi}TlG39fM42Bm>FT;!wbo>d(3siV+`IOG}* zX}&)%Wgy>i_tzo#5$l?L9`X$Z>HI>_Zh81E?$%nsNJLH0K+#Ba`$$M=atu~1ITYnE zjT-6Ti^KDND<4U|n$uKL@Oy1ka61UZg$3$%=A}wn`JtX}YuA-4l5TNYif_j>D93es z9q)fwy8STZ8-LP(aneAL1|R3mxUsOs@rcp$DK7+i*lck`aP`LHs`%y#G2euC#fIYy z501|5)kBrihgz$pdMSuuT}E`2)?|qFjXFP)Vel*Wt^!Z#IQg+X-rym(VgwzBbPGnV zZ6RL-pxSXlU)a}t9Fd==1gAQXJNw^C68OPFg7zI*TX(rAV15g!TLiC)M!sVq=ZnCP zP{`+wNDpbDXRfGamf#Q8U|8A+;^ov)C~qA5P%=Ri5il(nfJ(<-mb^a=E1sqk_~={H zyhP2ILk!b-pVaJcT-m zqT5U|l|*UgU9MrLRySDXQRRCHf{e*c1*>zQljInSKWxo@Z9^q9QNYva8T9Q0{kz$Ub*xux8PorAom zj%X!uh63JZ`>D837!<0yFiqjBfbK(&5KH;64NT7q4#24fWY-+g+f{s3c|n>$k{HBG z3_=S-UxGnM0;tJau&cf-eIs==>Lwlw0g^!PoNdUB4K`dXUjTIPsNT^1{m}OqA?1G~ z53@S*cy-iYj8D=I+7EkxfJX&EY@A{FZW^#ORxbuXc;m-ae?&kZbdCGdhU6#nlYlB{ zz~?OJLC>e7kDq*xKb2c#)#iwo8^#>T!!91%Qb1o;akhK*_c_ZZU7>BSzcL`$BU)!G zee_&?1*oegSr@rkqO_plT9i1%JhEV&?~dqi3M!s|>!^S0&|oTof7av|MN}URxa!xa zeBFh6kKfVN8?d(b28fR5Q~yW3zK|))QRmWZd(HBx$@?J^E}H3Tc9e4*p+6KvV-P@N zHZ5?AXZu!wzI`2Q)-X#21{M)yJgxB>qWu;oTZaRT zfPv2_eq#`e2vA8MtvH6}4nPeOOecz=y@vphF$mo}Dku;xpjD@xT;2b7j}*Wf6(ta1 zxt|rVFX2Md)C5f&70{8|$|w*|6IIgtq!xmLwF+=Uir?G4mHK+05%6ZBnQpBr!U|mf z`3~%5z@6vK@$5}gi=nyKnjP})O@0|Ng_2UW09_;*@%LBj{sP?>?Y{&P2m)^s$A5PzX27LQD z&6e3^J;Kz1Lv(Ox9@n<4{$}#;Y-*^`YB*&R6foOpr|wH)ND5#9e4kx{n$sN@QTt8SEef}A&Aq~``G?+%vo)CUn zc*yxv1Ft&BX#RGa}%I9+Put2j*OOaYz1M^EonPu1zaBg&TeGz8{l==orYK> z06fm12Pd zK*CnWd1wcI2}xga#!0X&a{Ed2HMxx-sogIxkXyK97U~Sk*(J~E7i@RyIqh3zvLc@q ze9BXMrS%dx?=D14Dw%Y;$2~Fd!a+Hp5$HtO&D?jV13$S+Bk(C8yB%UnO)`J%d?Pi(heUwE}r{4}x@n`URn08H*WZ-Idy!6@|)Ydg;X|3G7L@90Ykt z75Mq+R+B*S`{In$pyAZ!WV|Rq8}3If(ze(stB>!VA7f2hf(r-;${Ne@2|`vXm9nFY zW%U!47!xLiTk@Ou%80GO_3d=OUsm0{pejlNoOL25v$#Oz(`syTvpME5>PC6E>63C4 z7|gLi0H`7O=t94%@?*_CDevVyOayLa2Gu5vaQo$J3-j20UwWArSr)wTJg9R2C6BMj z4R?-k(3(L}==60aPlL#r|Ay?2kQ`>JHwK+<5yqsfoJE)`(ko5nxEzR)uT6~GZY_2Z~6O)$W z^h7j7T*$s`yRt26n`3VxJLj>eOCQz2OBdYyv3s$+gT)fMFX!=6QEWeLUy6BhQ;1mt z^BXz7E8Dm*_P&!K{5g)<)`JBEm(hYofA`i+1nf~_^8=24?W#qt$-;Jm!Oe!;q1J7} zfMAf9VNuDZc3eT$vTVh6R+{eDMfXvmF29x;O->t+*s>4@CFt+@yZGaa4O4-?{?yea z)z3J!nCa2YW#x;<)q#EEYw7^IBh0pL8BO*F)|X>T%E82?>R>(9@g7FD;Z_#nDqiKE zwClSHs-g@j@^N46X98K?Z#!m8*3grJMyH%7fac5EJ=~OR1!wTo^JiQkU`80%b|_25 zFTm7ud#*ciahllRk#Uxb!?~R|kG}Q7p7_^BP*EaDt$&AQu#$loQRT(>`P`v zOkDR^FYG{|Ot$zeq4oE(-sM){6CTUhjp+V2mx^#U(_l-R<84G6AV35`VIu7sD&4J- z9HuO{lowT22Z;G<(ENerIOMz=XX4_$DPwr;lWdI(4LI^Z1g4UEPa~vgkjqWi@FGS< z56v2E>q9Y-^GSh9Zb3WdgO1JX)eYEv_EarUFoeTtF4N})M2O9I&Eeq|tH0=W5+5^E zaD~-?j9cYXi4}*N+rkW#(!Fr~0R4|b7bM`EY$^@fcxYY$Vb@OQrq5A!bAmDBbq5}4 z%lP8S+DXlq;!W=C^|`nz)SkAv<;*ShtLR3dS)D*6t4N9!zh+@6}>|rUJHnp0V|K=|8zWmsl?ckfdfcY{HwTN0Yyx z1c$wJFuCSgbqi(C;QgB}offg}XJx!SUiI}%@oQFkA$62`(s*sn!D}+^{ui`dNr`FT z`V$d8*Iiu&ITm&Bm8TY-r1O>KwpJf75fMs>sumM=HDKWz(aTAm4`GQ1AOZqh68(#A zNMn$tqTe|wZ_-uM-9LNPVE9K|W3fLqqV}rC=nPZeV|Y5m*w%EUV(-4b{$J_1ZgX~Q zoW_>y(+6IQ%{eKx_w?26=d%`DEA;(+Zg<%)wk^JD2>()(&w#bF2udlnC2&S>W+FCd z*@iH&d8?{g9mC+8clKgjn9+IX=kv9b9-an7j&XcG`evx)fBKmguoo)v2IT$xZIQ9x ztK>6Z{`+2ocZQ8_$$qWNi+YRuz~8&X<1^iw;zK7g;z@9V+KuVu6e9Ny;E$ttHKf7#`EpDkpY zBWKePu0^P+-wulHIz3M^->S33duXmG0gO)u8@Tlr(riQd-JBWZiFpMp0H*9>siSykSyga9udT&=Ugl`T@!6qH`v&&OkS&HlOEo;zH`W>C~r)u2U&hl9*D<4bW9zD1#ljGY5UQB{gS?8 zBBHN-48N0@5ip> zTiYIQIgE2|$IUWLSFpXi>G}0z?kTJBqqJdeBa!K^Qp(Q4GXXB&F#}8xI)P;&;p5VT zm(D)yu6k+1Y#PPkg)k{C88UyzpPZ&FrkJ~fqeY!=8+TiOhVvY21!?RRUs2#Fm=yQ0 zG$Y#dbcXHRzb*{7sH4c;kNA1hzFmJ@8ON>yi8j)RULvw!$;6(U8f5Xt=)JgjCJ5RK zC%Xp=%;}zd*GIe6_ikS0?V)HAmZU~0r0CNklSoP01KE&J%x6@tS`-ZyV)2o}Y8y)S zJ~a${iREyxFg1~$uYNnR)N3W)6mXsGQDVawVcj940o@S2PI#OKclN5jV-G)^L}-X4 z2a9n(JSatV3HgMehvBLb{MTpju*W2#1|sfBODjdFOrUM7sB`R-Ss18A;b9}p7aJQC z-+gt{_Fk}vW2nCjF=(&X$Ck*7gajg?flEaHStxT5)F@_XP(IF`)OF992&y5N!(*6c zq0xJN77D|3mwf=ZHeoNxRHn%HG_eccQ-~!q2KuD=o)+4ivSncjOF2F9YXq~k9G~a< zRV&RL!LI;~gu3rpcU_AXJHV0>BY=d2f5n=mn`w^B@av?+6x*UJH0^gvnnid=bbqO2 z`|waz=l77LP|G(b{W^hsDQjbdvlG@875;Xa!4^)*EAyeIm+r8AZKPM+Uj$s(8BD`9 z7P$vAx5Xjjf!Y@^^Bf#I68~_Cz=XmxV`HPn@Qf%t6*gAY8UF-H5Lby~nI&RK_$NkS z0b3XvJBG}`F+}2{*5aP55m`vYmX=ma@I;Y96TQ1E0b8nsDxN*m%$#JLsmf`fYJ*n2 zB=JG*MYxuda#Ap*5Re9XvU}PqLBitloE6CPD}B{ z&4QneG6JVGJNi{|m80*N62o-}VY&VOc?MJ~@cZm%AMFhURIJ6Aj#}?;S z8HYp>r7mz!;1s-(aV%@ZYqqA>8*vY9fo_#VCKZ?y3g^-Yi_8H^w)bf;Pkh-j`wwj# zMxZJ|fZsSv3Dan%_R)9)DMyAl8v(>CXx^tJaqnJ{RI;3ODn$>lwTHAmH~ksah^yZ*BFjHK2{Nf zf8s?DD;j&^9EVgPDr(`ML=yN!%mR!Ed_@-M$~aaL;{AA>$1IUG68abk;#qnfL3;hw z{hg9z-PEQiZGZYob^4p5JYZTrATsZsoA4Q9#eMg9g*1rqF~QU;%~>Vmatl)*6>Eu6 zvOA5@@yYT`o(S8htNh-bU@MQNAb#8+6v&m{xNVgLY_5vD0{ZD>!FAHTC@4Xt(wXRF zI5}BsHf!m4meV_33kALZt1xA*2+(fQng_GVp$Hg*UD*L2{((s&-g1TaMO4N`7ZJEF zU{h5~MjT?ggBp ziBeMUh2Z8gu98AS21FZp#O5*9HQ zV{(k=KxX2O0q!~Ydsyp5D;%E+PUa#Gqk`jJ13oGuWOY;U?8Qmg0?|mIZRA^aTO4`~ z##srHc{ZMu4|D}s`py#BBVlM294ZIsum?Mv?0fQlwdhjIV>2DsNL{lwp#Hc)(OJ6~ zWB;#+GT|>sJYku!n6g8!d4UpO16XEv%j%k+#F4UBI+L7+vm?*yoiY4C?%RNMmBDUp zFJI2=oRaKe#`BFl?=rY?CBg1dEQ80b=Q;i13%n&L;>VDcpi9B5JrG2;tb-))ylpt6 zBND8#7+DDmL{i|6v7V9+tZ?iHS;E5$m?9E?FOvB01Jo>%Of*^`;x#lLR}!6YDZv-`6g+7XGeXGB28S{>{ruuxP0m7Yvn4MF-8X5bs1YEU75M+iQCQg<8?eS#J zSXqj8zK-%b~N zySTBJHf2w_U5^uHH{WknE85^EMoDG>p^WebfCy~{+Dd8kDch66xFKzA8} z=rQ2x<$BJ5`}8aB2_i;n4W<#=U2>y6wnq7JJ6ZnmUYwP6yZi8shfM7XJ-tzTut%6y zX6TNE-W5ueaM_7y!6xOL@`o?SNL|3SboxK%HkMPpus-M$4V|r$P6>dVPY=Y#tnLi!Kr?qg!--LrT5n#oK#_gi-b;=p-Y%5HSHl5QG zEsdx&X-P&QNn!R*T;j!A2q^)V-9nX&nh@$cvk>QFu%}V?)ce|V>P$KmR(9{Yrxx*v z3hd$#V73<*u@>jl278<6{ou4wy``3hQ_p?aTQR&fx8571+vUvaGdU>{wg$V0{d9+# z$~V|0RV3ez|IJ-0{+(vZTYI4Kej&yx@^F&Z00d9^jDgs|8*pA}HjTy&l_dTV*Id#b zs#rg2Abkp19$8ShOp1LZn-p8_TO*$yi-=L7jmdsXQ17GA^h&pDzN0#q@b~2D^#CS@ zhnp?=UT&+5E-JB|&uLK4kJ9>*Oi>hCm_&!hSu+Khr;D|J-D0j=szlGiD0GP?k$MmF z;$myOAF4EdX#27{^5x^=mrpxiKJXl@m3LEF#zp1SDep7bzULK8picCnYG8cvR*15P z51z1}F>Ox^0S*Bi`B1+xsG_jc~D=a)Ydh)4Z#g;H)cUx9SIYy?`spez;hq}*K ze_AhSTRdrBm0RhSd*P6=b#gh2+GNa|OR4@#*I!qLGC+a`3fToFnyq>1D14dDg*{x0 zgHo%&KONue>2*Kfr~c#rS?Gj8`Q$F^S7za+iFt_}2C$w=r%F~ZIY7KM!e@;NaOa%z zY$S2gtR?eRR(m^D%HGC%>I`D^oiiblGXkvPHMzBOLeCxKOd>ocB7F?5jj!hW4nh83tHBxL_=CSq}ky5>N zcH*j`^&0A?LinRTOLaDBe>Q_wG`N3en0`H<8Ky;|*A-S;AgPzbD9u1A_uTLM z@~c3m_Dw3|jA2dstmx2$ni9hNzXtC1Hi2&?YL^}`Z;28iV_!n7w&j{+D1JiTt9_AF} z4ap6^#ldUOmm&tUMyI0Cba!w+AHDt=b(imP!_UV*e@4S1qsaGh^pVlR7X;;t7~aTO z>5JI=7ev@aB=5_x>pr(7;B$bFohXKvUR38z;#nA48Bf{;3@zgWh-72^4y)Uv+>=@! zO3%B(_l$4bVbXKIG3GV=Y8!u$(DxwkI%6JyD2WmV{5}`&?k{~@J-{{a91-3Eca>s1 zhsr^`Qmb0K+fmSV|IrZxr)~P5 zj*3Ue9ds*bxXSFK299|3<41U`kG~RJ6H^mg6m#=9rl48&_EC)KUd-r|%Z2^I;hBo2 z#;9Af6|s%=mTQ;OKQHqKO8_bmiKQ4POspW(Yj}?K{e7VyO&RL4@g@B5!JOoABccy` z^6GzoA3sDB5WnyuDWto!T{6we!4Q?Tq^=yQm;$QiL1boeMoZ>N)cU!Zh-&fU_oT)N z`_)7KRYzFu)Dn2xlZ_PZu z6BZu=f-y>vy^c`>F;r}FetXA!L-Cg&a65A!({M7oviCy!z8gRruV%qa8BafvDQ0fb zN?~*ppb~N5<^GOH%bBPu+D55GbRUs+pDi+XJKLK}Rmt9<=^IJOOZF>^>ez(RS*wI7 zxTaLyrdw)s9fV?iSViosd=?w^Gfs^GB~Cq_UpP*$oKe8D?;kl)82hKZFs2=(GqYJT5(g)t|G(I$0XT${d)Kt4_97SoUcA-^;2iA34|Ve zWF`MR1JLzEc~;T*2EtFj{tvZK-?ml0f;QByWRm}I9HjZF6m(E-rv0&|gWoh@0u z)q{gMd3*JIpAfA^KHzq}k*dRBpcSq&FQ{+_osP=1HT1Z_XD$jyMMwS;%(=6ZHX6?V zi9w6)zTY;prTPi87KazjQfz)m$up<}dmTd`hlvVH9~W*M_lzqX`Eajz!y|0;Ifvqe zNEuLTVy`6Q_elnCB9s+g@!}yBQr{ZnVGbzDd3aF8c0*}d^rnFjhknD5*rA8o1R1pD z)lqJc>oLT^U=euZ=7BA{oj1lc=FDaIAdg|b2Lr`s0~;9SPLQ@gFE={UkgbV zd^aciQTg7TMxe-yL-^Z!!qF)M_qINVKQO-Yd~;tGrdKd+<3Y{qMc9VK%F# z9ILrnPnADxpFtGmkTwAs{~)3Uma($WBPNK$+tKhl6V?V?%{dK^3mxjGH7AJzh@0G0 zmX$h_$#h{ge5NuFUE&nHh7@ZYT#hy@1{Z2c0yQp#TF3te54U{c)lSKTh}qDBnOXxy zWq0JD2uS}MKp*M9G$bAHvh+-k!DAnXMA}($$ys?Cz7&5k5}Cu0@!lwEIU&V=V{D{# zXiwU!@w2p8nS^KXm>owmDG?+pmoDMW!+aFaRlA-V(w>B722jb#r9V}gLIL6)e)b0!(zr$`j6b#762s!9_m0}gYnP~4nXc=x<>g>A6yIPpU_G`aD{)0FD{VVU&M zlmXN;*^oWG5T)Q3+pTm`ig*THs#NrLPMk!E4nvT885G!u(kFKo^Cr^t!+;lYBB0sS zJGCf){A}iyp6FD9g@RV)C6XS;j5Px=DLfb5mQ10Db72X7tZQN_!{as*NF{G*27Isf zh&}g|a+3&YekoT`W$Dg38hIkH{k54w!v}qug!?7xr;%7-UJDH8lRVg!Vbm^49=P|x zM*ss*pbN<-aKA?lz_S+c5C{Nf&aPuHjZ1xK-C7s$rTEc9CIMT%+p%Apbgl5q*4i}9 z*=;B&NAA|*hjyT%#0wFrhow;G#&>1j3ATNhMdB%CLwy~!lbH*9jzcHxnm;K;)<$K9 z30ltyL}l!JC(!*N4N;%>&sbCR(Q`2BQp~}%sEnw|u~&e;y1>7ZLAu#B{}qkW(jS!j z#Qe&YKPM_EDWV5gw-%4afQq^=L>iEsb`c>zE53RYo=H&u_jKAtm`2@g$oAdG^XAu0 zC91?3_m}@IQ|eZig~Osu#Sye1BTnEkb^~kiR07-wb!i-B#BNml0f@BI1sv*ASepv# zoQKYsN)^R>Oj1>l6cirI=ntvuZNYU*nIFFuokeicO{UxM3yutu@;(K$y&m}pnedhB zSK1b^9Qs)u2-wnI@pP7R_kD3ze0xHzb9erk5SJH*# zXa1m(>;~u+6ulklhlCuqZ*C2O*@AvT!qnP~=|U;if;*q?$+c8c54V`TF(g)~Ic6C>4=vitn*;xH=BpYly13n#%MmbyXQs{kv12 zm4cd;sipPb(|@!;-FX0CRs+ex)YU@v$)rt9Mp~?1Q~p7COPAsd56|EjMt0Y@%cWa~ zzUpEBbJE0_;%JaACB4Jk>0eMq%W151EmN*@GFr^f$;C59n+f@6c?KD73g|oaoq|Wj z)2n|L4PpC|(gPj)ARDK$*B=kaL6HHQ?X4MqTM7-|T?T!5^Xtg^4r&qLrq-_=(8Eb= zzB$`ircGWId4oOqT%c1(_isE_*q;5*HLloP?HMQYmRf8^lyI^2+;8h6@}ZLtdkrTAE@nk>C~e+~H{R^h4CS>Os<9Ts&c^fgFxkx#kG zuT7t$kLd@?d|A1_q^OA31@-$^&s-ETOML6A8l0~h8mBUk>}QKpgBwfFzgooYDBS1m zd>0-2q5028WkNn-&xU!;z3z)K15)CyUF8r++?C+jzbCR{P8M z;CDe<-7F}lh{+FdhGUH;6Z!JrH%*O z^k)PZZGskXf*~bd;KAHuzHyxSdJl+WRhy zrN?c(qWaSXp0WK{Z%hV%GIcdL)~5Np5rJKo%G42c$6Y}V*jXvWO8E4#>&n2vnuX<{ zCZf2zf#N~Z++Pq!P^lN9r18rp@jUkt^G&4?M?R`jnXg5%LhgMiH|&=27l1BjWxsf) zZT$PqH}0csjvyJ^Y<=hyvL{U$lp7?Fv5PI1W~LDJ0 z22|2S*XIvNINma*&x!?-c;4GW<)X3z_lsy`;R9@8pcg0h#}HjM02I7v7Xlf5?k*JM zF$%7mmBZrD<#^gLoI^>R8ZDDF#Af{CbQ6QUA=)UyPkYQ`(@)5)zR}RM&74h4C}@$# zEnw6TGRRp{Wa0vqiqb|k78!bPay-}(kjv+=H3_gEmGFvDS)vfhxm~rFdNjpcea=BE z%W6hu_qZu(F!Bm^VA(8zk-(7GF-fq;x(eQ&WGqvBH8B^^ygciLwQ{;t|^TMW)f@RP?NwYr!?0Lh7+o) zFkR(KUCuRtAb3E8W+pNW&mm!wzB8%SEL_i?&s)@A^M3aR14{$*C>uaWc|#-*pL2~y z7}Lk#zc#SZgAWbacn$@a(qubY#Bg3L5d5JsVYt73-p+u8XJfjm0u-!ZT=$D%Ro=FzxMFR*MAtq!084w#4Z3~=;mw;~UEW8v?e5#{;Z`b?u_dwlj6Rt8?%EgAJb5pTC)^p> z>N(&OOZ^}riNm#6hQE06sebVb9P<(d7qVaI7{`kl5WN(;0wo)TKYv5!E0p*#zz7n2 zlzz0E528)*!lHJDgd~R#^4aDF3P@8ijD^hCguZg^5g>yLij|JPYq^<8RLkkIV?=}m zg&G*gog5<^&!i9c%AOO=Z>_t)j%H*&_Z2fYK_x?@OXk0RiRi0xGaq8L1+!SJCoF^N z4iLn-&4hphB}RduYZc4MHcvTp*&K1GqdqPGRIpnoQph?3E@=R9zvWfvM6{KXiu<`- z#=6p9FogR2CZK)ZUVVIoyQtrd#y!a8E?^9Q_%BOF#=x;tXyP9@3jC=WL)0Xg2bfBS(fYi=(4H?fGpGJJvjmHEp4`(L! z{IgC>6+9VEmF3cvCQ3>riVlaGW|M{!qw}|y()R|sn!IG&{ zVN$*JXV0Ch= z)S-cV9&s%culpcwWrLKLs(G__9-iVb8OBlBAQ$}n!*tW4rtRb6{;~2Ew-w;bhW*cze%`>^eW(^E zTqHP{y^adOtJPRu9V{d+`Aqh?8iGQQ1T>tx(k9y=n8qY}Kr0%YcAj9yIllPyveBZI zf&G0E3O1aD9@TZXO&27}-Ni-CcKsaBr8mr24iVx#{bXUM8b(m5?caUCJOZAfZdxGz znpTNT+ix9F2siY92$K0&CT0mf`#c zpRLkLdED&UhtPQoyUpBtp6Bcc!^75KHhaLJI9a4&^D3oek+%YU@QEs94kr*2)IZHLyG z+4a&(b?f|*NY*}VE@_oxyBD+74!K==$< zcj<^}{BVP5iMfOS&6Y7gur%~D5A@M9odDfSZf%h@`J1dHxpXVSS;(<>*;0AS+GoLs z6AraGb279}?40-ecGIX%+kLgoU=S)RapMm@bo`mVD5dI{>H2PffcwD9zf4_1%WtdM^Pd~^{ zCL+y%d$s@Pta7Z7O<;Un*pL07#~Z$uq5GtX&gFC&0P&noC8Xhl+jRrkN)LH(pCU%D zdEDeadF-Bea@|ot#MiIl?z3NOc zc@v6p;QcKFy?y`G*7(23+?IeV*$M%gz#VMMYRKlNBT-{axOL=uFQy-gy>6?jzecd< z84)eQhrqNVJ{dYthg-*P$`GXJb z$B}{>{);`Ue)?KL)hFNXRLccEGE*kMc-JWL+wdE|>?)31Pr9pPfMcwGgZqA_c-{3? z3Vp{1fJzTEb3*Rx$iGH&`FZ%O3ul)OkScY=D)Il^FA}7aBP{g-#grSmK$7v=>_<9c zvx%&)?mONGv*=GToVL#W+BCCo_Lw_Q-Bcp7yx5S7{3gKS;=f%Shon7+e(fyZ_%XuS zoM-7fqOUzx6NUEqNN_CL2|w5 zeI0K-Avi)Z>fA@bF(%oAXfnzR8I^@w7|>V*Mr{O*jU;>Nol4Lkme(G>xL{11)& zw;|62Mv>+7U$LdDGzoaH%GE>O(H?nN*ZEDd3x@6LQrADC&|f9YT7o}>^|M*YVI2Ee zD@_6J1OpKY{k0B`G8{)Hj^k{|=<)C#NMC7*5tRhRRribcLtP2KQxy0nMpk z6LYXL^1{Hj(jW}fO98QQP|?Rsd`)fpi{W+;Hi%HDd80LBWN#Q66u%D3K3b3)^c=dk z%d@8@ad*VZB%A5aodC2;BmK+5@^bFhs+w_9gCXJg#DJn~c z(~tkCcM6E?MOC(ReM|a{yd2J=kvL(3TaolQ^@ej1RK+xJe~e!py7i~0^$n*|42~!r zwqo83>vM#W74HwRk@ci*Brn*~On7fYZWN{dE;M`VP^oVVcJUh$+InnIMs;7{L;bMv zzoT2G1u(6(lGqxX1^|o#gC>e22b^gc3^Kh;T!-A)WL;}*&6h?}`>;2dSuHji0Ht&w zd3M0o)iP6!NWd*UwH?8Np9H)x!csXvlLL*VP`9}kKtJwP5S5E`#*HL{XKK%U-pBW( z&!<<;_}Dbu?I*IRXZhK++!NeTueAQ6`Q#6%?^;gXp155zs5>N_%0=l3{M*MrhqwH( z_CWWOftS9Ox4NrAB3<_pUq6pCcz5K!oXpm4wc?G4x@g>!ekV}8f^HMS&ZI;#bf$ly zDi#}iRe{&BBd2*|&3dn@)39TU;7vS8ke(UUQ3QxOx{_F-Zk-cC8ewD6BwEfG-@X>j zB|*S1son9~8~o-e94DL~^nHcnRQ3Td4If?6lPU00>6e){I3Z=h7tBT#6TvBpo zg3bIpW#raF`ZDDcZcin|ba9|=b7v+=AljU=y%TLZVrQ_KuON& zDBDw#&Er4_C^}A!ab*6c?6u1In@`uppF681X6A4jO1@vPq~}lsxY=H1L5(;$Bp2_3 zxhJx^f`)I4(KBouGJZ#Y*IRO-z+y@^h~iWvkLMmgR5iuEQ>@(kRk>)daon!!;Lnm@ zni|;uViWam#dfeOe({4BwIs;-zmJk2Ekg2xeOfGy!pfdmi6Vdov#JWnGVAoGT(owM zY24<23b1u+T-g=CXZ2U6KdamTD2+!}n_o1)-J~sTe#eRvqD2`An48&cKeLmnmWj&D zOqxuwcpxt=?rjMz?nPKI6`LE}5X`c3;_mFbHM+@Uxm zn>na~1d;z8(5N5Llfi$)OYAv~Z#f#2pQ0Q%LN-U#(^fjas=S_77wtI-@IR^*tbSEy zAfE1#GM5N?wVlY5LRIE$-Kio`0mvTHbt<09Z?IG$vzsJnh#I?Tp)K&LRVzWIDeoz~ zO2fbWR-8?V{-#@*3g~`kke7dYgTZry1?Ug)du0=?rk6bw@_b0uY?3J{ zH3wBHzNqu_rZ9-YHuY9pnccFS`%E#s*jpB9WJZ^qaiSEGQFgrTA68@h$$pc$h}^h` zk`hhOcEXcb&o?kcF}pIUXVsjsVt`T1vl`p?)s=fPw;8wHH^(xp zE2|cb>CkEcQSlZ(Dj;&lr~ruH74EL#ZdUCsDU|Eyer@yy)6Atbfx_yZUcmkF#AC3Y5?>|x zYsE}d$rQV(->xp-ikYL3R_vdyK(1gt!LZc|4WG(-BqY-DO<0hw< zo{>1h0-3|JrDI+C@*dW1k~`S)spshp;iK8K7ZXe+95h&7=2oLB#CgJ#PTjw$3vZu% zJ(E!XtuHfV*&lB(%p?5az@|S}t|3<%jech2j1GATST$g&G8z`v6sdSkDY+9b|BN!!RNiuuO;oSNDiU1}*Dg%|mxwTz*;aaJnkz=sje9*5 z#``l;(vN<=@{u z6LyL8Vk+LKur(^99?|meeTR$l&?+4?b~YOMGO60mhxeBOkebv*<8-R-s^orf%c#%hw|ias_HjOT&_+guB4wn)|dv{liPirj71nZ z!>CTjoYaIP2 z&qLBdU&=1Tdj^e$>oLFdOfb@u{~^QP4)*NRXV=e^QcjcxqZrsGEwYcB1Urtjne%LG zh{cRsnJMpBnG>eRz<+0>I!9RU8l7a(CXfHy7!tk_&iUX&2fqupgt`HKV)5%niPO=* zW1xzhX;>5T&K1SsJipmD${am`E>o_EJ*#V}{oJ=|_h9ER{rAY!)sW|~Ns$p4jTUuo zHPB;z0e~2v=Cb{3FHtVW$h$0b3vHnAuj9{^n78#*C8h0=nQH`@HwpU{L?Q4e!ddY5=tSJN93NAkWa?o!cf$+V!hzTb^o2#@Pb{OXD z07Epz=4Z`0L0k|^5nMiji-#{>OK(p_B&jwCNm%qBd&m3mdOZAKbuJgx`;XE*wyPelh1_&bp}K)+8iu`=KRwBt9J6$vTtR<5uc-6}egKd)qL>*0f=I={3yRRT)5uP7=xX3u1<~+#Cy*)3?IdxB1wKv30W$lcqk{-k z$r4Q0Dps~~c{C!Ph^{i6t=SXtCO32J(~3{BtZ3!K;qxQ=*QSzsJyYbVT-khzk%$sj zXB?Z4G(^^W0Z{@mz#)dQXdON%U1_+VGmWb#JKX?0L`%S$b`4#^ABBM5Xv#w17)5Yl zmwgQ&EQ|EIs|u{YWZY*BEFB3EEF+Pl38H5GCK_Pm?_nR3h;+cF4w3M$5wnylldJX3 zh(~t>5Ae<0AyS z*hB(wjEYTYv*U4AA@pqOgxEdinFyZo)AM%ASu|=pC%ynSf<>S8F8@IB93?zK&2RIE5e=(;H&?R zY^CJ8WI**adyE`pU;3$x(6H#QGx{8s1(fdijj%TC2_&M8%iL(;1DS{uz#^!O)p7`o)__|xtvdAsHs^ZFJ9MiDRcvaC$^t1J{+VSO?l?(JK{{whQNq9*0I?R3t(|_k6f&@PEZlr zY(Cm=jE;qqUD&LqUbKJL77V+YQh_cV*r^{mw^GP;*EX42kaFU)@)|C5q)0VUASWF7 zi#Rg+9*J1g%1<^MD3)!m9ZLz!YK@5n_2wt(zJ9mS?W@0>edU7JN%rd9gAq0=$8G&O=r8Czm3EbG!_4#~~kERL$y z5*k(wMWQQoB@2yT#o=EKIsq&LvVamlF=XjNJ`*22Ro4DT0^H28veuKY&f{@E%K{3y zMfWY9Pwn4Zmschevs}2jv%eMt1X%M`^TEMkfpz?sQ(l6pYi&vQPw4Kwl4jHN=4V0M80o!c z>@5j1fBisQC!8LQ0s#1afgx}J5O7s8N&~nlB7gum89)K&GHNX9C%~D+9LE}q2jdX@ z#`#9(@rXpEywB=bQ|ahalx`x|jpnlP3=zv}$MNQulbPyadlx6o zwFp!YZi0FaEj}M7Ue)~9;CzLpyV+K|+~W1F`p#rq z-G|pfn-ec?zOMh+6?uB_k+YTRb1#;Hn#ZIa)ie;#BA zC}L&0@_5gS}Fcf!KaornS%h%N)<@{qp>XgZ+vkqS!%YS(eX1 zRb_egL3M50!9h*q2wCi~wsq0xu&#Zl`mnzH$H8GkA5{FPafs^XEu+mc>!Z@`O!-vp zk5NVl70~lRk_v@gmtWawnE0#)czm-&Yct?amBx3Pn6I6{zRj;)UvsGsI?pC3^3*S? zOB>WK280634+l2sx;LoG=+yQU9O%?8I|mzj$!4AP*S=4=%?y99jq?dA@p= zQ+HCtBhUYb_&^YuqUl4@K+5!gVZypo;-G!WS7Hs|(zl~k{T_CDJ~s|0++4;SewmP-ua#6QJr1M3rTjnU-ZQGHhJVxDDWsEZiVzTd zLhl%gbTm}y22h$UfFd>w2#5_6dN&9NN-;D6K@CMjL4$;o9Jxz}`)>{+B!Y?xv*b zKYA#?uJK4wFeaG9omg9dlxcEIrbER5gJ*WIRQ+dO#lp)ofz9je*Y*3iK6;Df3HQCC zN3XZ8;$>EUF;yd$y+*9d=wsapH?y-OHL`o9kFYZ9-EId>Mz8f>2BMyIv-EL6@eS^|9I)_ zoQg!VyW5q0;-#N~DDmQ%cJ**uX|MhwiTm9h+UFLMX}DtIgYGRS>;$hVYvTk{MPWUY z7@Mi%#WEiPZB51&(jxkcxBTet+TOWf@BmvvLfUsz5bVPWnL|1$7C2w{ls^|>k?~e3 z4nB)lFb@tXshrKJCKelX8pWyZwC{DhzL*ICCerqa0PSjlVVLSz%_B#XpHEC)ZRju6 zKGV~8V0AH@i@T|PS|Qm_`dd!7Q-JP4Ijjc0RFanxps!@zcg*M8^?LeE1Dk0qE#h15 z+gHkYf{z_?{b}Chvt0($A%o$+i?q`9?aZF`D6`Pk#3k!~lc!HNu*@dC8-Q>*W%~OQ zX2C5s;-r|Rn2CY|xy~uy4E5I*Y2|%O?xYB=s!dPHgVdUy!Y$5EWmQ9mSe6}lQJ->q z&)(syjZ39l7GO?C9G+euTe@j9P~mc>_i4fEQW-_~7B${scjF0YiOpfr?HRq#Zkl|r zpr-D!E_P7N5Yt^BZaGINXL;@xA#ZmvW8?t`$j4od7OMZSH+GoFRVpvjoLX4 zU%jN!!OoA>1wuo+tsH#{Zr-aacb=)=_UL z7H<|Ooo%kGp^Ud&iI0|Xlv@Msw!eVfaoQ$!l{ul6;ufvNOn}L(Z|gS2yTzY`Q)GqZ zb{f7gWrfg^eZ;fcEXp5ViwgOnJ;O~fT?*chRWI>IK!U@{6#NpsD%(eO&VVnyVG*G>VR#v*ER-@M%Lzz=e^&7Y9EA9 zPs=TuC7OLbOFD;Ny0JGp5ophLeAfgjHL|YQ!MQ`M$hr~*=cD#WE-3Wz^bL{88D^jf zkgHvHA_p?Q3nQ-->kWxF$Zn8e>}(wW$)ctFP4pZQ-;{qv0`^!{krCs47C@$=&1v z9{dmvj)2(xXn3i|jLzYslT;G~M%zT@5)+K+wo`_ZV=Yfz-}WHi(7Hy0bp(`o11)T^ zxXDl5!efg<9sP88N^ZUmMU}i)>B2y6X_m8kr^rrJ^m3q^Hi{8LVH7?|YK3 zZ|bJC3lE=+!XIjsla@@7d$HyF+e4fADa4rk0TRnzyh!9u9Qx;=VX(`a&e_jGc!3GfO%^GSYr; z+PrVJ;Y-;5_B0qFLS{s=+jMCY~ye=JCfuz3GE|wcrxg^wrpCB>BbZE~7Y=tR9qLS2OBoD0A$(gA?4m_MeO;kC&SqCPGx@%D%WS)tO zat%TjYGDe6<>}z}cu+kc0lA?Qhfa@lD3?B-qm|JuI~;}gCITZ}`0w)vvQ@Wqz7#nV z;r{hmRN;uMq*8+O6>X#MF%`t*8l&VoujKlOtlK$=ntB%R=e? z9ef=D!WiHux{gqH97Y^i5*X6Bv>Ch2!3^AAegdNup=lnWn2CFtg~KeP#qM3c-2#2P zk_xRx!I_tF4>s$9z*nNbkVT9@!iUgt+vL4jphtU8PLng1c@ZVd5`jJBKvax3KjA|# z^H*9H@RJ$f#)c8Nx-+BFH3^|3P#v3B;E^&%Ko9?q4D>!9TvugIwjCZ^a6xzdFpR7?ji z#yRk6<^!n)HntQ5ytzWI^Em=ZHiVT^*dzTIxR&Zo*uxgOF^|4W&bnJ6ef%uqK^R^j z3CyIUpG{qV_&|E^Jo+ae|C$PKwa+_qHm^nw|A{SZ!-como9|c4XES$iE{1!OP`Min zBd6~CvS9Q&pJrVvWJy1kOTkLs%YT1XDtn%QhhYr3@CX(?mxN^--$+fz?PnqHkc37k zI1>&Udo=Pkn$7mbcCwJ$DF}NiQqUv#@TnL0$ZVb~{*%<<2wWKz{)vvUq@W}D$SJiO zfB8r?@S|$X$#r!bjltd`p`v)`yZjO_2dPI4Z2uu_r}51jI?l(&ZW^RJ21%EN zn3RS3l!c!wi%>VI$t=rtMI57VJJDN~>Fem%s21C+@it~(R4*~l#62D`mPDt=JWm*B7kf-%O5^e#-%BMEa+}rv;{zNR~<8bqVt#G+80>lP? z51>VnqvC#YTR+}u3R2$>JQsX@+X{^p1MpCEi!gd;xx&`wfl5!Pg#Xo zM%0N=eCP1b4h$d4mi0dk7aX3WT>hkRkHSM8YQyaV4;|S-{AT}cEa1n+oMCLNNN5h_ zC}H)MW(F~#(2OfDU{W6T(M&^8pZHd0IPgRMXK`LWzFC&J?7 z*hM|F&)x13pXy!)m6+s=-}&{W>BpCc`#QJyy!qO0I6BA=4)R)C+}XR2_t`zFcWvpJ z=c)DYBS-G8FTXnTb^QlFe(Ud*ciE?Y|C}ki`+N2C{ja}&&3A3xSX+8|YGZxn!`+SF zYd^jULOzZSAnmwN>3Igqi4B$P<|0hynP3VVu431M@tKbz_OlU&-7WZY^U)++A!?^x ztLXLl7*(f2jAwVNMC1QDVpZE4%p=~Wbz4tXDIv&#MdGy?gze4?NiA~wfe{^omfu2h zbR<$%=78KOqbLTXB3{71fB*ME#ys|%MIxW6NorSu{z!Kp-EvZvcN zQshwDZbd}}d;1ikqs%ckR~qR`kpseQ3maZa@sMOtEuUnRTidDL=xW@3Q#8{XL&>Hq zIBMn(XT@diA2{*e_|;)mwP{K``T2zLKJ^-BtXRI;GdX;aVlw{+2ZEE_Uv=c&0^*ij3#nZjwi}TIV1Inl!XW+UUNi@2Z zOnpolX=i|Nrx2GtXxFI|7|aSOnB4RNbkG#S*tucarO-;Yfy>_Do;*LP&v~jg5VUag z0sX>OPPWCOagx8?Qocfmf`QXHUJNu^LPj>hY7b;MyjA~ZxcJU(PK_yN5irR!Jx77v zI+%T43MD&))MclcX+5}ixzFr6x9$s;%rCH%=;PZOC#XH&(Hrdyp|W)QT7*w%PHl(K zV>J%Qr5rZ9C*zrP%=@j8Zmtl?@sP+)!#Y>t5{i}db1uTLQO84bE{nxh#G1fOuLb$& zDb4V&n0{X!Q5&-lhtG-z_C!6PP2RbBHmuCX^p~v@2A;v$FA@-3jQ8EBkzi$eXqZq`|*%3 zd^e)Y@y+7j>hHVfUiQ6NZv63Rep{|S!Yy@m%=6sBbA@foeQ$rS{%8j990t;f58W_q z#$f^1rV8N`MyJl=(>O8B_7j+`?^?oI=#d$6EPrA&u@$r>C+$oDGFM35&Zq=zh+kI; zu?03%meO48_IVU4XV_V-72ZF!<=09V1z*F8cX}relj{668+#?Y|DCew&mL-;;Hl~~ zt)lR=*Xwb*c76Y0?O*bJmhG`QU1skOFpLx29=k*iYQ9zyL@Y*jVs8SB{SIiC+A(zD z8@^b|*%z?tX(rcRyHp)uJ`PGYH|XiOtYQ87M|s<;bOh?}qe~?ZhCSb7Z=NLHcgCg@ zU_&Xvu=&7U&AcZcFoWc55gqxr@t6W3EK4%)X?$_}X!YgtBLTVB**I;u`~8g7pac+x9t>wM~{4|NkGC%Sp- zfsE9HkIz_aBs|-7s=2N9O{CN%^WRQefBlARe;s;vebx3v0Jq$5N6fO_d+&0oAMbz5 zSH4_djH*5}ZTc6hD_ca`Y!SQf^RJ%?4<7AgRbqc97C((jfo%BsHHS01EtcG_MQ{E@ zjW_OZ`OzpAO$qU2>9N-3vP=&xZoR(x;MvH5JVTLUG6Rkh?f77NN=&Tz*-l;ncr|+y zApsO2iYNq}l7UFM95Ka42u=`b3Ad`ktC>O&JRh+C!1uX3ttD@_^R&bTM99TCg?+6; z`&zbv(`5Sz&}rnpd0VVRps&b|hUjv=eF%#f%ZL~Sq3Fzskc^m^57FBo^P62F6tBD_ z-hChH*5EnRMH$N`dhEp4E_$&gEZWMXUx)&gWLyg+ZXxZG)!KBed1PXBEM9QMkAdmtg(H5!EWb`U3O~@kk6_Lf{C&LrLIiiR>Ihlh>!+8sSmAn#|GDZZh zP*T$=sW@X4eI_Z6f?CT!JQ65If>u#b`4J!<1hz@pT%$qzcB40b4@n$`&@5 zGtZV~CtpthzxAMl=d(pCGIxPFDV*Z#qwuUhUuqG@k7lp%$eECN7F-8q5S2R!hC4Zk z=+Bo_QPLF7f>o>>(6}TGxGYGhm*$bfMySLd+^Rk3aV&Lhqx|Y^ROWI{fw5oK8YnDC zX2OLxAtcyEZW*ctb$u);hn=h<4fv{o=^#3dniY8V)}fCGwez_Y^fM%ev%eb;+rQGvUBGC;@nU0B0H1&a6W5YP|Sn z{9of50=tcDvWSFf4b0-w7w*2_I-Jqdcl0-M#eyVAGN)@l$_3U-oT5b=IR_!kZVj5 zc{Q(U#ub@XsW+$&4A~neHi>`7i@^osiBG|FJMjF&pq-Uln2ulri}O;4iL@xhL862v z=z8Ndac#SxItQV0n}-

    5if=JrnB#5`kfkNFnJR32&QDc+YS?R%Z`&by^loV>2G8 z=rlOGMT-b7`}xLja!q`5AD)6XDpWsg+T3)?fN)x|$zH)hP@ao3n<@`C9dI+MZL=v= zB%ELLEM7A44+gue9vv-hlGC#t+?ZAJpHxA+nS}d4zGPW_)TU{fhhO60M-;(XUekoB z(h1RR&mEf{RX2OU3E!z$YsfYTh`&WP`!&8<#gu!nO-7*8?eK2)bu;$R|LcM%{_b8v z&hVZ&YF>tj@TG_94K4UWGPuFF1wShh-mAT#n?dL}4KuKVq6(pLZu@~h$#|+G*ilB9 z2Og`)C~43cIwbhDxU`_ByC8U$9ewqi}04}ZAfMagpfhq11S>y7z zZkJ(#f+kok37G5YdVxR$32uw)6l0-ZQK3EZs@^0p#tr_720MM#3*MqtliX|UC%DX5 zhN+h63Ri=<<{?Z8YYgG`d7QgDkwep*n8*F(;43_cvoxDIws5mAl}~M=h2A?@R}G!u z66H$W8ETopUqOr9_om<+n-KBM=-Wc$Pln;~$@^~@hJU5>YlWC~Jn#vXhaxDYLDqUP zEW)K>o9Vrvhjmklzur8XWY}i2#oXbds4i+i-Y^_{9|Q_$(y*bXAZx4`IBU}kidXec8GFJ#&K992lO~3J;%Vmk};YA9`Kj|qaB#QZ z7G>8LZ;Pq$NEYk_t$i;AeHQrO>_R`iMcF;5Za*85zd?grSHq%!nOr)iz;woW@lXTb zw}&Lem?yaLgtEEFY&ND2n7*<_>F^tDJq6p&McUGYoxryTBQd^%Z|ptZzu1Z8a;NtK zs7Nj{62R0j8h!*!T44|S-8@uB7bN!&1==%;$iG(frr-G_*0V887Lv(B*9V0ZoY}$K zK3xxBa>9< zehrpC`vE_HN`C%_O91?`>V=6f=(k@N-^_!5Er{+|5I?veacO~gV?nxkL1x2Z;N=3f z=9D>Nkt%v5Mq*a+FU5U^oGWJ-W2e!W)$|sn`Fb^ilK2_LnI94>zc1K3D&CO8+W zxgkGmF1bV@;*uR9kpBv2Km^UaPBLWSDX|T|x26-*CpdPKDCtSl_?lj8SR#cXmCc8Ge7m8Gd{GeGjW2R=$4n zZ#d&|ol?fBF+1Oazu^q9@SDni2WQA5c6mb@rqV33x6~ah{R3wlmFN^BB&ie`T{gRM z%Lp`If^X1vRpqAr4QIqultFJxQ_PohRA zf3MFILGvrdh=(a@%u>EPsm(o@xruc(WePuos=&|YS_0}G>8u)v6X3Z0jrgx(ZTM}F zy93hB{?dZ78c(Yp=%6Ak#?YaI@Fydi1iDtv)7DL|=_EmhAe3CDw3YB|0WD%~62&Go zcfOD8DV>w_9Cc`?#Wmca(YvU7WR`kudg(q3RgMY>hmeCoypG|Ve$m%FilB*%6``oY zK1xvZ;U}*~-G?$YsPet`%O?R9B=xi<$9!&iJbYM^p$VZUhXYoqSB!0*;6}_bOD&28 zC=cN?;t)`K$dAbsET$yHx7%<3g&E=913C-L;M@_Rg{LHo2~Gbo%F%5>s~`PdIC#89 zboA~rgEKuEp1|aeOzgO%62JPT>ENh#8SWrBFj+{XrWA>n*>$M$u3 z(ZyS{j^Y-`EJrv^Tp~ZvC2Xwq0BB_a7uc|aeB6qLIp#tTI0+t=TxjzBme;^7kNdsP z@0|Nynf{6?%Jpd*U}ePxm{;PS-g;5r_*|~LdijB^80;J)@38`-H*Ix{nX~J9`C@m%P_X`Fm)+*?7ANOG1 zB)&g(XaVQ%bA2s}I5f>7sY3R*pOC9xp zKFh3l=)j%GAOC6&J#ZIbGTb)NhD(#?oG3}NUA{#B${&a4e}CF*wIk0N`;6fBWmhl$43c}l?E9cU z&_&PhN(+8Vh4;oe(TjS&-a)#&B3&L8>BqbKB_7!&t+3^fG+tm1vASJ@jU>k;fHQ&6td-QG5@(z(TSI{8AZ6!tTlO8%@;6J0cDHH%l(^?&6-yO{ zvJBe~ZTc}-vML-pn|Ps-beY(F7smUzhj(rS{;|$#`|CiawI!*pUhEc(nqYtAN!*Ud zBt=ruiKsPSQqD@KVu3U2z}=`#17Eh?{mbuDfMmPiGDb|!&Hb~r6CkmR>Rx&!Tjna6bKX(jk9c~o56@Fjy3i=s85UJB5rfvv| zX_magZ{$P(an%XT6kjN0#sXla-`rg}7OxR7p=h#xT#Uyi1t;tWZUWKFwLDT1ogu~u z1&L0tAX(9#L&&HUBbmI(-1>%60g}PAW|F#rR;~hN5g_N0=8r+2Dn%6}U`q(R&f&Ur ztpJs7nw|A0pg3i)?q@-Q7=S8+grYK# zPzpd7Yln+nwyOK}W=7@01-?)r^Lgj%Gt3KXgtvH#;!QG(jpQ!FkHVE350oC=TqMxZ z#GN{Nfib93vWW7vnLvl2VnU_GvTi=0IMJX;9_2kur@eh*J8K7Ll8}4VY{R1cYpMOn z_2Z`w#BvEyi6ecHq!cpz$6IZdZO*xI*c0#Reh~Pw^9^YF;S#Vj@*Prn_Kg3-?4zS9 zf*Rzakf1-}qgs_CgH*uSF4PlSFouibAc7ZE&Ubc#LJeWIR~V4_<821$SSll(8Wckk zG+~jkFQcSJKrJIM9fC_d*r5!mcZM^Nr_-O5AUqPsT-wJ*v*$wE4L@BD>*>p%C!rkhtDmdu2OIK~Q zK2~ruP{i6b`DXmCZ^qE9gBNoGqGt?{n-YXYg%wZ1BRU zcoT4ePKsPHFl<8-rVvFViKl9}bdmR!j2J1$VfSp(YRgVSS-1)nCP=#-(UZe}rk~_^ zsT{wb9MmTNxWTAMobGFCSrJNbY&r>#!*QzruG^sTvR474WQLVkk zY%oG)nQHzkSp22C;Th}A55)9$PV5Y`B7CMwaOA;vE2&}f+oz(^Cg^dm<-qUr_=h~O zeRA`AUch^h5N<(UvAleuh%n3F{Ee(1Is?7}VSN+<=ONqetDOKSek^CvYJ_2h!q+I9 zKMQR19Gnj5DY(FNTo0V%3Bv*o-5{YzAka9IeqbX6s>j;fs|(w~BIFUtka++hl0G5= zB#_`QT%p}oWOd#BZxS-R{0!76(%O2MBP0#~J!VijocAc05h2exEreFf^15R1nnYHh z!<^i42O040YIqS}ud@~57Z3VV;2d|{Rd*2Xf7MqPzRuAVw2KfDoJWF`69LJqr~P#d zAYj%zOQar;Q0FRN)tbieRt%koSaWk=!7xKA;RstlaT9P+0p!rK&~osGh072?8X*Q~ z%wNm>sIzDhZ}>7_Xj!k=qAF+Q?;n*pgpk@flmg)k z@B9$~lY@1W^91eKrO{2=8%NV0Gu7AT39B^2M>^VY5sf((VVxmAP0Virh3+R3pq4_L$ zctY6eet5$azI+i^S6DFjQ=Rxp>AE*4XlB;u2@5M}f`iDvT(>Vb6dl*iADlNF2rQN` z0e|w-j+Eo4c-jU@Y?Dt)<%bE=d^6z|^2vb031Bm|vE=w7eukwbDnj@Q;Q16heRrJK zxvMpc_hBMu*74AiVN{uHi!x7;wYsOC zjyp?(?Wf@Csjd)~cUF=`f`j(SFlr^nKa4Ka$;aH~V~&ae$3PCI zE$VZ=FVj%o7$lg6NAbU?FlTRVh}<#v&Tt zJij|PRy6|m2e$xB z!ZK#RMpMbSYy0uWM>OmsE;0(l_4PIRT{-yVc%x3@qbzK~)f3|$?d)LXLl5_KB*k{` z2_d@F@F#Uxy z-It?x{Ed^I6ES*WQh4bqCdVj#{F6`)LAeDIs zEhgvW-|L9e`AhJkv#syzQfZJFy240@3!ngnNNvQN)atAK@b@|*QXz<%08ej|1@bAo zAx%Qmww?Ta8_?;e0~X6o%Y#OV_g+##%%62c?MXSFG*oWEX}i#Cd2aL644@iJj(a3`xM~dttGQ`B&647o(XG(m zBd%jcEN64v2X9sU&({$W$3IthD_4H5={K1DTpOAW!{6k29G|Uo4LT`x%>QK zlgr0(17i8+iw(9x7PpK`@K!GqCl~>#z4lT6=cfc&T_5}x76Pa_zYNIF$Mq&(60~!4&edwqc6;rV^MeRo3+mHkGC!MSGMq?!3yxIZ{ zzTHhR#fKJ9B2Qh(Z9#Rl>Ar;2(Fj{%C&egNt);bBYa1WfJ!$$3=Y65rZAel4p=k9$ z?AVE5Ym1@*R$`DLl9BKRLSOuVIo~7(Gl1{6U`5`sdHHpQ_v4sy!QDDmBS}F94l(c% z*P-qRKCVMGg&`?$^e&Vl9>oUIqorXMOzMlFm!~cTB*f%}k&nw{@5*gnu+z}5dPXE8-gM*5CdM;Y+!jmCBGdkA+&&pbHbv~K4yYCw&q%pc%L14j`5=QD8MX_~K=qU>OUTmrcfRt1y zGk(joU>%|Ufod(@owa6XXX>5gy`k1!?y#rZc6*?#Oo$+Ws}ToX1p&Ook+hQa|DOQ< zXB~lb;6+IQnBKnm03LBrQ*Zs*F`KG+-ft6 zN>sIyb=>}0N03u1{s-#_(m*>Pg??7#2Zw6u+;TINF9cG8E2#P1Qs+R1mF@RiqAj3n zb?=_&%)&~VaHZEj>ximA=RfNRK>+`Lo1QvL*{t%ibW7D88zqG2{HnVz&1Tbu^$JZF z$O!j$=-s%E3iD?}!pQJ4%`X3lq^_B z7(VFxuH_Rm-hY^PPp%F{2^W!1{)6ryMzzBZi>4et1ZE}JbZc;G-YnOjX)>9>bnzYE zu6~lxsO!EP`Th9YGm$@<*M$Y>PE+>5rAbMIGRKrD2hzx1EuU~MK;!}+AmdtR;I?G_ zeZII_F=8tUh&Ru3+3Q7Y5vwOB_9f9ND zeU5ip4SS^Rye4*E<2~s9;EJb)5>b`^>4x4QBvxwGM+rL~d zRyn0~|7+{`$NRs>3i}tDf}>{pz6DFaBI%!bsLJ&9^TEEkdced?>-I^nEREj_xEq)n z1?)TSgSuDO!mONog1nm1(08A$b)3#IL;6Ctl#1h%%v3E!5quRT@ zWv4d;>xkx!m9AaC7iS%0Il9fOFQ5Egez>tdf4O<>!>&u?kEizkAW(k)xV-Uu_U*>n zk4q4~J-5Dn^}X~Z}`qc~rbU<(jsp$cYE(J&_Z zgevG37zdw-?ae;iYY9;8z*7<6A-lL(Fz!e<7)OauqkzFi@i2?{-XkzCIVRbwli_CU=*z(2C9R;$d23N6%B7e(N$xaMBx0&#S6gUa5BAnF&;J) zbv^+X=LMGA#k$*p-2fbFfhtY_1&E4(On_UUpgM^L4I1tv$q+CRLfPYK1nQGOeNa)E zZLUv7$FWl&WW=~C*x6tNYeDDnpm-A4kdrV_u3?W#g#|~UhM?O>pa5WjurDKqAajAB z0A0b8g?_1m7M5Te3B3I+?SXFWa07@=OogUzhw#!8K_GZOdDBruIwu*X16i}X466pV z)}`S_H4YFHok252DFE!ifn;e2Jr$mg*7^zmy{GR%#kTWDvoMhj35=m%&9K4epzw&w~eZ z(Qq|0r-Z9Qa+y$O5?w92ZX~PP4ut`RVf934kaxt*x8h>9CBiZ>d`jRT|8sre$V`3!rM z4oZYEnl%0(uirbja6>hIXeJLAjG9i2o=Hr|4+P&n0CxqVI?x66lg295!W(us^j)Ls zMC>lP=}hv3r^s&j34BHe_?gQ1s%y7;P2&@nt@o52taI^mi=pT(iG%MieryT@jXkZv93AkoM;q? z61;LfOGnzCLmK&L*nBHi3qGAIT1*xEOlLbeh-#Pli5<~M6uf&e0bkGS40)8wSQJat z7llqr-eDRef)Ds5X%)+Zdt<>ZV>kOmRRDNlV!+KhxVi|ljQ#>Gfe0^ucO&Y<`P(@5c&W-6G3q7mdRmrdlbim%-Vj@}g(9@L*kW1wz3XeyFelUTyVwvZBDDf?rgY zD1D4?P(UQG=9jOKZ9n$wcF`H0ra&xk76~F$2jMsuW3wCV(8rMv-6z z@I;dOXUwig?Arz6Tl0LtXC`2c9cTkqgViVCEy5jSurfpa#q~3Vig#-10iKGkC@ZjS zLjuqdl;|X|o-UZTm`GcAswu#a9aES5l@>-O6*Yp^^90xX&;&YYMW*0%py}cwKj+CA zKDXET2BD2ebut{nK5McW_|*!NX701*%Bg?>_qYUHvI;C&+#3^gFcCaPhWC(h4^6-} zuHmW$_^J_9bR&GG34aCg2Q~xWLT;sp)Y-I=;hQsiP^4eyqC1WQT(-kH#0!bP_oi`2RT zrE_~)E04m>ODerJce>59%L`*4Y%FQdIh4IP|7gT zK{#rhjSpOWq*qornyiKUhApFG+G&0*RL)S05j_qocn|NuhegqFb)esTadpoUf}24& z<#Tw=5$D9f+HsLBfLG9b$Z)P>K7QUBvi*dxbQHde4Rc~4 z*n-!~G_IYQrqplO$ww{Lbya_+XmyHm#Pt?A)Dh;XRc0BdVvm4)2gn@jSKVQA`JSQ_4$D$DMGNRr24?i1c;5vg{^OA4?mu zd(>?c;ArIvVK3?jw5=>cj?3!JFliNt$V~f7uGGCg5Ms6yYgEe>n9r z6LJDJxevi~Pcu%u7x>2+F)9`*dZqoc`71b$6qcB!cgXJx%Rep4;csWexur=vID)lF z6T&tU=qaxw59R#rj8Olmu*)~}Z)Zf>Qo#SNGs62b=i5htGotaS8T8)iYZR=q;(%rO zmJR*O<~Ls)t1Pb5jZqK8jJ8#ptn*vJDCnsBliPw;1WbY?G^!k_l&~J$@zW_L$`ti{ z>IAJfe0)yI3C@obw;!v;5g<7%D#kFcSoi^^6p_AFXZL0+9Hd0T3j1bx_7p&q3C_E+ z$NE9Mr4=z0y3JEnKS~298*K@^k=fmDtihGz>28EOeG(Pw8J`Bvph^gqT`2Jb7Hx8V zEcJ?Mb?Wv)IODygkG>{L7-FUXR&POGJi2LJQJzO2^ePZ6FBp{^u=FDi^`W{jiXj$j zfv)iDKTFtD2}Epdnt3(mXm{F?t+i}FuaRdeH=cg%_xxY1fy=H{gVGv<)k zNdQ&UJ7~g4{DkX*(DmlcuFA#Sp6e^S``B-7pmxdn>(qg8;ACGOcZF45)=`@c;Fo>HiK(Xk198|G^Ue zcLq&=umsH#vb=rI!+oV!a;o|wJg)Y*TvggMuvnt{wbflG`vvU_)zNQW7gx#y8@ zIy}GS^B=H;tb&8Oab8{OFW8K%SSROMH=)*DG3ECv0>nH3y2XFS5<-PDv=F9VJLoCxEl=dG#|9=>+WPkFdGP3Pko0up zzK?=I(?Myx#BLSVCqKg!B`omZ6W@3`@<+;Pt`*7h`~l%!Rlq^DRP;n~*3EmK(cWl4 z^h>U-;t8f;&@`X)nG`F7@=BR7Axq7X!0W0j$tLGHF)B_In7u2l#6eD+VgCgFd_(q| zb$Wqd`t`yHB`GJNlfPCxsd~p(40H%io_dyy8}RZz%@TO^Vv=Vfg@}fD?8%waXlD6@ zW`pqJ?)i$VYwxXzu6uOz4mnAX-YVV;U#QN!q?=beBG+Uz5wxH7a9W}zSw*(4FQ~6c z-k)2$q2d*ATBJhri0rD0T3DR>*~O|h;Zn^$!wD6wIIJWz#~@&dCmJ&3^J z#lq3nIKZw^`KxSDagXJA?g&(}g*96;7xl#E(z{`yQC|7!hXZ^LAF-9MUxfIauWaPsD+ z$rA(84@qwi6mj%BKTAX9fp^;X8z*-EKXko^Q&Wwjt({&ep?3_uV?aQvB=jm>x`ZZO z14vW!4GE!_(3EZ{Dk4fiL{!w!y97i*LEZcd&A%Y(TeATN{ynk!9wmHI;I#hexl4}_Tiw=QK53sTdV3mj+xeu_=|^E# zUxyX!N*DiHtXBMSbc`YU=sSf|Sc4e?fA2xdX(tHwuc#^=xZKa_bDBAA=`Q}^#C=qt ztXs9m?3nJM$iE3sztsQw{Q=MafPJPayO;L@HP>T(Myn^W%#-v{%2Rpny6lX;n;A9k z!2`&Z+h387sd)E)jlp$Sl{y@mvU6_ST1Vel4&c4and0-+Ykc4Dzk2jJ)q4atb&-Bt zELyw`(7OzFNoBzSoSWh{tKcX5edxzK1u3R$BIf&mwnn+jVs`J*oj>ZiDH1Qg$02$5 z9Q(>+fPe6#hfYlYeDUz_*LJbd4c`89b5fwMH(czt!vFrjr+t>VcMqW<>4u;Y1$G9ff#A%G?1 z%1>DEKkOt9js6VTwlb2VAm3NAg&sV3@crV5So*HmS=kV{b)U++1_2rw`Tic}w>KFI zB+rTgUV0-&xrqnqd@1ANKe+Qy0c73f3)e>yzgeqpdJ7DxVCWpoZxt?H@eiyI1=HdA zuSx?Evtmm{2p~iy+`kf|j0b~uAU0)EpuVFxJH!PR0@(ow1nK1E^)u zvKs+FJXNg{;{h1l7+V5kl-o``WFWB6RbKNxvj(h^#d9gojP&gALS&oc~FXrtU?qvjJa-V524 z;()|2negEJIw05?2Sfzx`R_wyu-Q)#Dx0HB9+Cq?im2Yg$p?7N!J`rI!!ip0=J=l_aj(Qp?Z zN0w+MWFihaP=ach&tk|*4t2-w;>dRdG`JMKQ-s{1K>JVyOq8?HdHEJhDI4w?Ri;&X zeqR+?fv1>8aZ`(QDhEMS{ilS8C;?n3A(!*Xl|to^4lm2@MO?Cpx`bFMK9Q^V?kMtV z_65<=vh9fSzY&+`v(K4+q!Sh{W#LO~(k^F~=E`O89P6(%mWzK0RD2N1UpvFQ=E_fA z;ftGh0y6miW%0ekS6@-9QWZGY*kH24FaeTzm~6<+}9)JkY9lha?!X01zp8Aq@`jWnp_|D&}bqP*Pw?XUfog8G>B_{Cw>#F$V zAhSk(5T3?@Z+wKSAe2`Ce4|lyrhV{47Cea?SuDf$Kf+YME44$e9LsRgP2hR`vd-|H zN(3Va&(i!GB{(hO2Y|XRAXVms6V>l9R2oQU`)l^f_~S5u13do*p6@kY;|C`BmjECk zxZ(0@A)+q{(x0T>s`h~tD}b_G#`1k7Y66L8vxnhkHkL^$e51%@RCUBf+!?*WriPEA z3qpXb6A>&xsIq~jicr(v5OdyOeD=39slh?|=M?wI>R&wgy%sT-1+-?H!g@GSpkTOl zs@Nh@HLgjcx73iKV=nKeRpJrQ&5n;iGot@u63FcTuyaFyVd}6bsby3}dQb6hy)tSvEekh}jJ> z^K)q9ooz*T@Xo2rLfyiCP%smQ0{yv|RxAE(^7X}5nafrJC6@3*cnCZLY#f3)$`a5a z%PV03T4d!pg|=-;<#>`r93C>wLjImHm}cIP=;K>p@wv*&)g(&qVfjlR)LyZvKMM>8 zE=Q}L5IP`V%?;(xaS(Vc2-%+Ob*91 zB#7KhU8w~Ec;8c5vnU%_TCHVdW&$>1Csn=dIpj_%?A5 zAK$$OagzJSKq1qSAy~v9$B%#MUKR!Yn1NPqgX}Q*R+)UaiC_{N76a%X*61&_=vQt- zJ23d34)T6spe;C1KL#oZTBnz;s#^;Yo)udlA&ofDH4us*(r+E0+Czu@B=T>vc&)LJ z1k&l0W%!oKfCrBn&>Qjy3yo&;`!k>nI{ZKcQIAEtn+|8pUiV``xI&iaBpzc7g2IGG zEhC%o=tQTH^Q!?}M4pk~%RK&A_-``QAAkzN!yKN+SjCQJ%4-fXk=9tgH1?x`9aMk9 zSf!?_Tnv}yfLJpiaU^6S30jXwi+GP0Qyva{MU}JBP0QRg6MC70aQw=zJbc1! z?<}J-m?ya@N38K=S?4uwY{&qFa=RhX=&2&zaUgc&A|Cne`qW(~?-k9b@6(@d)IQzp zeY&;u^z-kh9O>zE?xVX-D*XY|`=++vYo`-dX}>j9Q}Hm%Z_}BjQ;~o#de1(cLlK)9XWZa)7&DdF-2w%tiem^ZKGwT6Cke8+9FU)fD5cNm1oLv6Dtl6gj zZFu>gn#d!7D3}BI|CeZXgjhw3A34?a|1Htv)HN`4Q?Q!fAbkvqG_<@@c&3Oj}DC|jh8RG#wLE*)bg!RUHTu1Ci6d>hVrMQ zw?kvQzd6*$x;6cGP2@ikO~(HOBLBl_-2F7q44t?HGXj{8_aq*Ub&TuyKN8K`cfmc+ zrh1Ls3OtV-I?Qw7r|--EmS~>0`E=%q*nuE)M-NZ6o#L%I|NX`4y?_2A(d2ZD z{YRqt=Q-p*5>0Vz{OyeE|0U6EsSNLW**Tde>|iiOdp39P?fFI0K%oJavhhZ579T3F zr&#}Afk^j)e6CwZ1W{l7MdUlZ7Xgt|1+c##-u<%=Rck&k_y0;Xu@_atvptW0T=^e~ zW;AmBvg1X>`$~I0u0&JvZ_9rqn%AoLUiviZcRBg2)Fs@Fm`Y(AzMIsYP%Puo8H9wQ zwYwKA@-;h!_s0LXMDu5)MVBJi@X~dbE79!Yfo!(a^Uby3Yp%6Mw*sZ}CjLjF*$E>% z9{!I+^Zwt}Pwh`2+-m^qFKF`rs)?{cLIt>IsL)$?`@;OU?=B^O;?_ixO|%-;F2#K2 zavJ`(b%v$65>3vq#=pILvl@{M%KMxDKK}jf)4z`{!ZbN7h*&JA524b=>|?X7c+da7 zKhLW(u}A$d6tp544QM^vmZxz$l}C3JX6-<~s_LDmb_3-bjcLM-XdY=&^DzE0W%yxo zqoum>!RB=9EFRn_Vd*WkH7RvV%+eD;uar=|XfTi>s$HgF9uP3R8kZv-hZ&rkS370FL_ z4`A%QcfGQZwA=SZUga}EK%qG%82U-01L}P7{=0{;t9k^c?1itZz;t!T!*!E^-?tLC z;~q92{!?gR5%T?MCq7%{?-zTQV!oNRiU?UiXTRdto6IK$+M2gPe{_?cC&s-NxCMj= zk+-_C|C!rft63`j{7|T?AK+t zq21@NbF<%M^gv=ZXh<~Vxm^m>oKzO&qwUqR0VbM9|mc$zqEIo5ta2DSnH_{DqVUZC%XS5RCW?|Vs|6{FTXRnz57UJ@qdmUGNC|%Uu3`O%E&7Ng_DXoQ z3uaN|gKw5~v6}Ds^VN-lUXf<%MLYtXeCmBUW)-hEI%1P|JFETYP&Xx5)8b?i9d1R$ zc=XuKy78%gf49~~P9AcV*ki-{_Ct=73czk~6^l7kggjZjVR@GhVGOtCjYgUU8L zD4QGoLgj{82FwyJCAQqC(?iv)&e5=XN-D3;^RhLcxA67c6}#u4>{>lG60A=bFDHT| z3|4Y!FWj*VfVE2O4%!d9dtH-vb0fBo9ja+5Swo}<8_e{A-gD&Y9Th$?Htd_((O%yt z)sOF0m0i5%;t5b{vV>KuH)$nM;+lq3RpoMy*Y=B4CyMF3zXQuxX7D^@OWVJx$UYtm z5Q9 zBxQcOO8POuhMLnSJS%b(zETLj2hm@fAde!?~X-S^9(Ap|1wkPx?*SuuRXop}F zxGAJxgyUyJ?qUI8*nUYas-v^$)&6-_1F*CWkp&U60ZRnTWlW|9MZiC+MNclLusuEh zYTHTN3xs>ifRar-s;|fbL*@*~jB6ZDme^+@j&nJU$=j(~RLRd7YD%gzFg)vSoXc0l z?Mup+&#itNI5g((l4^2?^+(i`sd@Y6WUGbCW0d%9@ll!2HuPWB4vn?IrXcWz|I)b?jy|95A-VMXMsL-pQ?Mg>3WxIOZ}9=Ef;Bymw1`^x zv87;PpzHjrxvQrPgvJk8K*OvnqevdjeHLGuVd4kz5se!kb@JSX$4COZM;=l3*%-ph z<8}e76?NjCROQ=w3SS0QCmb*ivWE+6VzQl=<*%5=0r^T-@~SU5xb=S$b~_qKH|-&y zn=m#Em5_BmZ{IX4)8R{3SujJzD*n)6%c>v5_dYJJ-rcexcZO-9Qv#MxU(hK4bvz9C z)>BEiHe~p3uezne&sXS|5l%g$k*uomnPTlFf@-0mNcL^Hjz;VHvdN|QKY_yaqaRgG z8#3MYO|Ap@4OxGjITWei%MdXVq1r!GVPQqQzuc~KJ%0r2u$D2*v=pdh(6ksCyiNvZ z62GvQOgM63vImYoMo&E5y+qv#y(-$Fl^I+>lm_zxF?bY*2zSst^Fs1XMfZS(SMpof zlHFm6w-5YIYd4y_1{>89LSCwSd3}}ZIA>k|De#@-7jE@OEc52!6*vLXzeRL;xCqr* z>3;ZUn-uY>7umUHif!N>$&()m2Hww;O$tn~hAic5F(y9D4iD#)o7hh+t zskrPHdu_97tnth7DR`oiH80&DkybAkG5ZQ5PDi>6mtkcQG0({G2XnV z-=l_=-G3tVBDZZ%2Ahz<1RMy&2H9{fj#PpT$Qb@8upx&IB!floV?=L&BLT62N6#>p z%{Uc4!r8)o``n}8z8%Y{A`&z$frTz@0c`!Q859qmtUFlKLN242kN7+$yL9fQJZCpaZn%5I;_N z1_vd)A=LCtk0@d7lU8$XMs@wf`RfVA`-n5{&oRSENk2yQo?y|}@yOHIvdF4SY5S~W9w6cT#JlDb84eC6gYh|T{CpKt3;Zg&5m>(SsTm~DvLV~zP z%#`F5JZwMr3in1Sh<)Yn531e<1!Tuf(R+mDX(GeUe5?mD!Nv?QfeAiB28UtcWITEVZ#5&Y z)uiM%*J-+FVMi&q&$%ncR?LfJLV?Sbj(K1U2IQhWPy7qwR)V(I<|!X_o-tkRWKOOa z6lBf(uV?V>oRc9P=L#1ZqK!koY-Ah~PZHdzkQz6vI6*mVfTE2wtKVARVto|cdBR@qj~ZxzkX9T2Q2k^mbrERYF?tkesQ!G_rupc1XTXw$J_jlSL3CVF-q z%=^t3`?8q`NJml3V(X!u2L8SZR+;%jJ4{%`HPsALDN&y5IJiBY4rGA)T1$=b^cqe} zQRp>ny!}{f3rpAiab<8}w5k*4MvyB;-Itz%=NV|c2nUwRWw<|LIF67*X=$?BSBop& zw{ArX`hCR68#mtbb5bFgr&}5Kux=(}p-$?U!#^91mcf@f=d^<(vz}`_h}WEphD4DQ zAv=xGD)=y?O+DCbkE*jbVE@mH+tO%(n|rE8LN_~&1e{`~B$7^vnSJJybdydJK!vP;0|z+!-V_Sgf_pJhP~N5K+F9*#x*c0q_3%pwx(o zTyp5jO71M5!D}|(bM((y8;+E1Id&#mK+*5|MH2z9L_6C()I~hZoYgq+v(cOge&u(Q zEFSb!CzU~m*s)-VScsPKJ?%wgibjp1zDaui&3|6C{)-Y&+S6}2(Wz|L(jC)&Gp}_Z zyhFeQGLCTwO;N$dL0>JPdw+uZa-)R zH<2F99DIt?+`)@x^x`_~hq^j$p^FbKs%~{xY+I`5HAaU+HOfTwtUN02J$%wg#Vd&* zP7@(4$+m$_?uF-uc=AP5TkPyBE~mjV@q1Lh>=TDU6n^Y{`4g(Z0{qGOeZVCb$gY61h#W-Piiz54% zhyA5@)cTa3B1F?g@|gdsR0M^hzDs%gLmylDaAdY0Lp=OU}0ME*34qoOko znC*tF0fXfM=Q-yYzwk1i7ozSw+%9A zEyE!`@N)a}uZrq2??={pZFmSg@w(fQ;8@jYli8`Yri)n+j9A~)s;khNlh=AM=-YI6 z@=Vj%c-y4kc$2w0W+J_1u3rm($_(Fqb!ls|zxI^jHQ%xu(8AxHp$}pG{Y_I8ty{nG zlci%Lm!4c4wxW(dK}!eu+VG?Th7!2y4i5NlYpDSPl0DvcbF!)7Zf`Tx`QEU!SK36! z_oFd9l&vPilV2v@IqL+XW8WD2Kz|L9yg`DC05BK97VvJB6_BTK)B6O+>z%cy;25`%oITpVza zb*dGIDc`93`ySr>n;CkuS?799_%n1j)9uSAHLq71KQ^D#D22V>HCWO=oU*O`do?h9 zTN`=J5k7osZR^yV#?T~kP%@ScF>BMAfPf)kuNC}i#@W7;V-w%lvx0qNAx72(cOG;E zpK_e(`RXOS;(u+b-~5Z(4@sVUT~soQOL{@$n8-ITgZ?V}v@V}X$HPh`xsc^^#0S)M z0IHk`(_MgG#G&?W(t^5O>q*FDMy?+_F_tzLJ8}XsdLoexbzoPg9^lB}6Y$l#3%M8I zQ4G)6g{(Mn!082A7#o^r3v<9;0WQN%w!ArAxe$egfO+n~1K}k4g}I1y66ST#GE6%P zo`hXaWG`zQg(lU7CaeyturwF7iw_a5WZxGNWpBwQd!< zu$m4)ocSJZdjVPhJ?%u?tLr4vTZzO&O{hle#vJ0m?JS?r^oivilUy{n% z?b5f5^Q`)urfS=?Ub|n75uNfW((Y%aObg*HtHsJghZ_qg{_6Gg%$wXBRO_O%pUI=S zhL&X971UQ$!n)bEg=*0qWCji%&4QP+pRXHpU6EJ250*cWQjyQ}RNbR_)>`MgF^KnZ z@H#SjF^LEyYE5_ZJOZH7xxpv-!^Jq_2yxQpE4s!N9tJ=?0etjcB)$sw9AP43S@6{3 zPnXhp@Vsyf?0sB5*l&4a;r@$QGOQJ+raiCI#fFkNsJn5mAn>K1-B1eoj6N-meh*ph z3J(ILxN5z7e##-FU?25>39xB4g2 z7q0(%%q$^=F}q+EIyf9=U=!;ois(4F=DQkgMk{~VttO^zJrQx+OP6ZMIk%`GZIjAl z%W_pc^az>2fIe6Ea2ke_)ha2Nxdv^h9Rm_Xggf(|I+Z^R zk#5c&#f*dKkV0b**get0RYbu4AD# zB&hN|7-6|S^cA#^iz$$hM-G&(_U+^EUVV{*yONoMW}2D| zprk|^Qq+*VyMN!x-W5wA@2|~Nj}(e3y1!Tm_E4FwGfG$*uL^~`*69ZpAYS&vrd}F_ zJvjSAuyXRUe$3-YHHtM_RPXd+vs+mfZ%se#^{D-kq=^cHXHRdf*(a`} zh4fQ4Geu?myX)Fh4w{!ofo>z8Wen-8+}AdIujT#Td!8su=Z!KVEkC`H7?EGzp4JvL zO;s_uaw|i1Jy_oECd0AbxX$*UH$ti|*GCtOpwV-`e_Y>s`=oudRLZ~e zQdAC>2(h=UppfO1N2CjNvMObZeTVxS5Dwf$p(4{=afQn|x>er$m6mkn%WCdp%EisI zqUN7T@5;k2HR#%F+)^ACaacq|3;SovT@&-?KFO3b3T*UHqG8*PxR`xkyW?VhFll$K zGFHCa6?h(~b1>l1o%znp!8A?DmY?vO?i_luA(Q{;EQc!SMbS|f523^hiMv${hL@SD zz6%u!$O-lk_ej}w8zbr_HSrOS_w7`=SwG(yciUHuEwd{e!&TO0B4L#@r>|>#dRru@ zRRE-U=*hwFL~BuhZ6pJIO!TLVh_@%#Ca$Qhs z)YZY%0j8X4x-<9?fsfquu0(;=D-oH&6cKjCR^f0JqE}5 z3JVQ<{1poI*kp-QPaZEczOR1BrXaN*=iL8LIgd}&HSFrKSZ6c9X?$0~q))n91#Alw zgG`^2gQL<+z#8AJZ5CBfx0(2^2+zUR#O54tD>5-3^`k!QxI3W$FkRyd3n3VkP&Ex< z+MA`0d48>`O{J~x(3*1#gGKRWX}w&6+9PSj$gxu@)_>Ca>PPv%`kGO z&hLyBA3hFNbXO=wl5J&j)$BwZdIrJ50R?WlBYynY_lv&*>bl8h}rp?tJt z0h4CD4?HP1Kz(6z?QU*g2F{&0l^bwptSE_x|02^;iphcM_XG>KV{8aqTN+YnP3~Hg z5Dnpp4fr;D`3dB`!-=Dl^FxZth7T@%Us#6e25|dFK2#}PHTX-b2)@aKuzpcCnWne~ z<@1Z-BUugDJ#e~RWx)bTTsi{Ry8-0YKL0^?h7HxnW+8)!mLvTVb+^n)`DGlP1?Mn! zE{Oi(0JTcD)diYH3jwnWv{recaOEfagL%w=1vX^W8h36-gm-K}bPb#Dw!}pbSrmSD zWuMHR4dQlcoeUeJ=D)CO38VWp4jyt>;$^)GKNF3;-^uW}KI;gsCix`+26K&)isvZR`Y$;8oIxh~@?xCgG8S{xuh z31`8#^<2tGF*MUCTJ8s_kE_fKkuc5Mti0w>;Mlgp*GYyQl(p(9f2sIaBrOsw8|!v# z`)aXoh}NhEqyc6SS?(D^|OSRgv)E9M+*P>6^%kE;37ZmS3fu1JW z+fF_YMk{LZurv$=IuAFm@KIcaa;zX&zdex3?S;W@Hiu>uyDHqiF?L^kzQ-F&6FluR z5VFOrA1VY1{|mJ~@ePV{U}i*m0~}RqOGTc9hZEO6TCH_qX)o4-h5SD{V1;`{9)jF4 zNv;+GOYCvU#Rk6ISjVU(K(=uY0qMR0lGs@79QQm`Z-90ZY$idq09SbvOg@U}<`52T z5Umpz3Pdld)hx8c4#*u@mu51d-Q>y9t9n;oj2)sf1-wj6J^2H5` zI_3W5+Y$_ld~UV!>&?+|xcRpq6fFBID)CWcAaQHM>F0olz~ZVU{;IIf#SW;#*_&UTZ)4UUa=JZ$jAX1Z35cI4K+QkJF8(F zFWn(P%D&^U`X?tIWtzDyI9@g3}hx9Fc08fFBE(ew&c{JfQF+`LGQ*RBm?BRiJR}aEGMBNNB zjWRsFkf}*tyXpR~-OE2ux6}~2J0{>H3q$!V&EMpc1gq#Y)ctM38^u<)g$CT^g`PX7 zeB&~OM@7daq59$`&%s&qQT4SC%1&alyj3spAn%Bi4^Fcik zs5P7wJH`enk*OvY%!6ATYOYa<)44;(HXa~;QF>$03+`0G{DR?1CW}r{#8M|1*JR3g zKVYi>cGR=ybd<`4QSmqZJ0IneF@LKD9R~-G>2%l7p#cE(KV-0%14wCsqPMS%Zn`#8 z3GVD`JB$SzlKVBVV1vrak`5eJL1KIVx-lKBgr|75f^RaJMm>4CKTu}7c?PZ^-&pFy z86&WubnarN8~$>sWM}KX_DrHQAgv4%rD<*g4Xwn)+);v8H-wU)T^tC}u#LEZl}VG! z!DyQ7gB);zscZGc<3#{=^`{=N0uw056d>m0)QM|+DM5rT-*EQHVyR=rR{La(VFt_* z!C27)(;5+ZMc6S$rf_q)-5Se8;t+vJ1u&1?>r^wWx(X7=a<-!y>^ylvwJJ#0bKM8| z0T^czbD)_PDrNX>1i4gE%E!IOxlAt=3^l(aBDbo(wkzU7q#AJqw>~m%bvpP1p(7M| zWnV!YP)O&#toH)HVGqPtwbV@j7WPAv|0C2bgY`26Y-(o|ZOH<#w45MyPID8Fgs%mo z0B7RsiS(lcI#qkL!W2NO_|p5mmEYh~rb(nS<_>s_+T>`*{EVrDD}c2yprSG3l?EFWMI6P~RQ6%#Q1IZxl~hFoJV=+>?ta1Gy-&fQOjkl#lI0 z4>JM&y^R2=pX!#Zk``QMy9Xju+m1HuCT93-x@fl;un*dq5&i2w#v5-d>yYI^1_zb2 zinS4x2!cl9Q1vL+R{2BQzA#r3`01vmikhNcOG7SkNZ>~6ZFPAT1#8Z*L;R!xjWzBh z%=mO-^oUe9A=t@IM^v9%mfaP%7O;v3^b~=9)QD9fToHtOWPk@djCNrJ+~YOqB2#p4 z{EUg-CD#)B;vBQbbF*6O?gdz3h?+8yc*l7`_-G`L>&7LK3ZVmVfSbZgH81R?cL2!q zvT}O?jkS={&719f6EgCkiq`S^8>rHgm`vtmpN%n?H#m1dHFmZTs<=E*iz+$Y<{AHBDjJSBK459 zET?fWJ+1b4i%m1B_G|;qjbs1?Vh$L&%1fAumyiQ4c9}Ur_v?4te}_2K0X-I}^lL}t zRBna0RD~t_7T-Itt6_y;NUP$H(lA7phhZV7szG?phrTsix9yCi5-6c|m5gaPhfCUe$^}}_AA81 z4lM8r;@wk=jjNAtg6=iZ@Jwn4wcJguzaq1&dhrH;15N@#r8CS6r)KyiLB5oD5f8sHsgN7C;MODW?o-O*&gR@yI)eE2!CX0&tnu&Ft-S4RV4MF3s=y~qy zGIxglSCRhmH7x|hhayrnI8(2`A|%`W+UQk~>d}ywpcM`^1MAD1RyPm4wB7;zNulbG zDtKXGW5%zg-9%-B%fiu_3?E;YXL=2@4F^C?-wlZK$7=sOB8-q3{*0sRKMO`biMaQT zPWo~$UUPZ~Nb)mG{D9j*W+ldD@CqJR=&t~SblsRFV4%I4x&VlWTd+c`88~?5%b$SG zwB}a}KvMvWwd5mR_ww*U<{nk%;EQ>ThdmgXbvzOr!o2hM3+7(`=ov?t2{ur6vrB37 zaS19UEdDM`KMNd3ZF5i;TN2nt!U9WP3K(a(;XsNc@V}GKZPkSgb6ig~7~awiytOJz z#EQPC>p4Gg*2+(mGi?9K`7ayCzV})QrKif{LcsN?{Ef0RTc}Ru%TQZ z|CF_l&VT(jrnKOo15dF}p!P6}Ix_~GR`Z^W3F~0f19x0MVT>Y%kK-^zE4iJ2Hfv_!C)&}$m zTnEoQ2jYF+i;f2v>~yt{KRN!5#mh71jRix~!iAo;a;80dxO2eqIQshsZQMhH#u%H^6G1@@|x zGkdjg;QwGE9rk(ow$OL4d*0_{0KxaQtxyJ3BU21sa|2{b_xhEi`pL}2H@w)C#oc_N z;_1CQnc~@m7N;GeJ5QA{BQwcBcZsK{hl`l0^69A#y~9%9^;TgNyeg{-v^JDAT`Q;e zAH3f`!TYIFi>RuWDmKkx_Cz`>Qo%(MlDjf5)&M-&MH43ETcvFcYCLOB=e(p@8B@BN@1dsSCNyc(q<3}ujgAYDS!`_}MCs#|0rOzCcO zD_hox4N2+?dEYAS3-)67`3OQ3TnBjh7o0$u)KLK*Z|<{-&3r5SlqHBBF3f!;^nm7i ztJeJz+868+x%8&U%CSO(r_eF;*^x=nlFa2N^HQQ`(JOVNvf8{g6_JW7x7+pcP80E> zHRJ9p$$Pf8x!y!a-W^fWCoMN%mIu~eFZD8>`K7zm9O>3`;3nwQM;#ue{u6qWcaSFa zo$hhJ!I^%^G{Icfwjo8cA&f~I8H{sfmapg9;iv6faZ}%JDzU8S+PkW_*(=&C^Xkx( z`?F%YT}FK~FSI$33CM#d1AM7zmZ4pI4v5U|U-pC|G0Z$AUMx(p3~X*!nC{mcL!)NM zZX8?6|L98XW1guQJ9C9VHH#JYDV(QAk#1+4G=!kj9dHfr@;>k1-+8ZlK>7<m~Ol zxHS3fh?w*L1ke(mf%L+~Oz4p2ek4r_G9jyK$e@~VMZ{RK!QdcLF81dRk^Z)NVK2%TG{SD>d3FaTgCHz z0z`4B`2zZ=s^hwVz~isKz&{SHSMzL@(fBiRI*Wa(T}59RIJs=>O3}8Af^&lG2rfQg z#B=2+u4O4%g1iHuit2OC18hh0D2)XOAL776uDJ0|| zIy}oXF$Rk_uR;JR?$Qph|3Y1T#CBhsA$9!v%>?G=onzbN`l#f)OU9pHD9#kGCA zOJ_Ti_A71$4U%Sz!$+LObSXAt54MbSZauA!FZpckB#v`UUWl!F_pzdb*lzO9_*J*q zwl}cg>*m@i-dg9-j2RR$-{9NUP!v$%MZSCW;fppL< zKsnizoJ}>!(*Y%!k}1nTxKvEf&(@oPXLo3ALFpO8qTaC?G=adLnN~@J)||Rjf-of8 zHab9#7DkDUEWkxRpP%rXbN3hTei{8x>)z{gzi!>@WPi`sY(nV5C1Mxka?}lf=13Lw z>%FMcae_tUtH|H)SUmjgBzFr4mIv+JOC|>FI+TGfRW=oaCVc937>tL*N{Bb7 zRtJupGu6@=DUgRtB*)78;YJ%G7!e1L_9AS>5^4pPE`Als5sjWK;LVDyn8?N8Nj6yUPOfM>BGj=!~Ylw`nFTEIfYb(OuB z{RRD5zRyIz>%R_qIF*$$A`-aTwefOtrP6ACA*CQ{T{T~a+!pU7V;$f&64095Wgog* zO(Wt`m@^YP1!KRAE;l5;yf2l|n-CW2pZEA&Y3pQgw)zO;@z2eERW&D-1m;Svj%{bX zBF9nv2kKDlBmt>4Qtl<~Kl)OTtm$KRMM8Dx-}5M6z2rjqp4aCO%=TCEpJ+)1Er;C{ z_A56Yk#4&^6D=7%cm?(+x+Nn^^uVuj+6v>{vH~OcB?%Z|T=^1Pz_uJfjw7IvFAWP8 z;>s0|xyrj!e8!YOq+H&U^2&#Qlz8M);$bEe{t#n%O`X`>&<1b&3#q`pX3I3A@I!JRhqWwKIG%8)7=Ky9~t6 z3U~2=AZC12AwaxI$d5ks!bz|3@$;!uVBIXqHH9ALN9S-0g)HnAsh~k7#~_YJ3g=mp z)w#j8N_zKdKK4twY^ZUDd1ERr;Z6;8#aYrI9>umBqIs&7yA>oL_09&P14pSU?i*#! zXZuz1^N{d}P9$NJfd2RpeCRV%@EArI(;z5fVVzX%a2trUCterT?S%b$UCi^jcSCHH z;ilWt;N|DqFFN}n%lNmtg18()nrHMF=tTx25(_@QOoxZca1;<>Z)G+a&y2)lnuixH zFpsf01{o*|Wgx`8Og$(4bcpcf9t)||(iT{pj%Pa7k~EHZju zvF>V_WNM7)TJo3#0FmBIOF-odJ-4KO`tVM8Y=I6+*Hzv+`d6s@zlqh(bm-mFGyeXk zkDyMZts3mPNt}*1kiT8>Q8<-oc@<%R6}O)_6Nwzw;V5MjGa60tXgB#kHp&5&`Aw$* zv`C1je(bqB+?jUm)V}A{Lfa~OvW_#F*|x}QqjH#XA^B6VOkIg8RX_pK7pL7PY`_T? z9>Hn)lLY_+7mpwN7(S~8DZ${0XD)qLTBY+W)rGMsS5W7zi((1aH-fEQS`jGM(*Ep# z9|VyDG6?E)vR}0-07KP44l13d&`jGDJt`mQT>H&vCy>T<3#GlQYlhT1^e|$g~!zMK;Wk**>{_{Xp_SC>7+i_L< zb)#WXI)nBAk4Sb#y$Q)JDIoU9@!K!Cmu8hm_vbB&A_cMneg7zRj@~?Zy>cMQ|Chq! zv=e?K1ow+8bQob_Rb0))@oxA0(c2|7QLbNBl7q`TxrQ*Ax1Sz2Jwgnr1z`^251wW9 z^pD$T-&=Zr?C67aT`cbhP4#Mf7hg{ui=dYog6)x?P6-Q1&04MFa>l{|g1uP=lR!-S z#_x4Lm2c>aNNL6 zuVCG8z7_pMj`xw-Ba4>K76(Lzd~%0W^cFC6PWi7#sC2|Qf2!RbTf1|Z!bmw@qvvXG zzTEaOnp@eHw%?GhOrRC5?U7I2w*1A@n5y5~KHfVEI;1P1ZZH+>GvpUVIM`xkYdB#r z)-cuU217Sc?~h!eT+ERf|6A5^2QzaqZ%RoQg$iyBQLp{z6hhiRlN@9tl57Val`-`u zkKIfj@fp_DOU*Vq3nG{tbO|@m0+hdo2xVPK77TCJjeVf>`pvfup;vAcY^sB-aHHI&XEh5bi6w|FXH;rgNwxL0EufTU`Tyu; zS_crsG#woR2l4444r2s|DhU_430~a{VV`p8vye9(#m9lJz}!`ZZlHY$K~R`5HVLd* z=#v)qb^qvVhmgPKN>Q;Imq{n6zwdjbB+z+v=z=F&FYAilaRvQVYtO-~p5OiXWQ!U@ z2-eP)zSpn#2-IAm(43o}KH5J^C)meQ;t-bpK3JUDbe!Tr<)3xJD6L5=H;27UA$tYM z4)S~}$dY_BIlix;GYWdJ0Q?pkbRm7JIc>^Um4OSeuvQ&8Oe*aBQ=;;6Sc657;*2b1 zI^z`UO5#q)_GCQM>C>!zE$NeGep2S7-CBGvNRpnjyw?0Ye8g{*FyYJqeztzvl_kXi zo)kGQHHG*tEQeMXy#RFz9kmPA2^M);DvIb6h0M*$_-4|v(=(F%ZY3IR1Qo{dM@|A$ zGH#-}V;W~6IK`mR06EdTqF&YMS8W+8dRd+%ajDP9D;r~;;?{ey{gzB%IL{)(2z6{_ zVI$5J+m<01*(aGE8Z{>29_LUjP=2a9)Bg8}B>f;mYQGO(J@w7ADXRWj)GCOsihOKZ zBQx5kip_oc+Ge}Qu~*UUzI49s@Om*1kD|zmhjA9gzSjHo@LhqTWumQ_gM$>pLO)y@ zx2+I5XFoRT#tzFqeq3<`%8IDB2;G1uoQkl?vq5*~99EOMTSuYdczKik_(U_bQfrIP zItPw6V;T_>9U0gKFZr1%n-?P&a=awVNB^Pl+BS+{IT^Y?Bv0rkDBusS)D9!1cWIQdAblc9HjO*#=y-moC zmyR-4_|8zS%=(z}oFK){leEjg*a0P31R2G_KW8P*rdt70tq!kd976P$Jjxaf$Z(3I zG_s#LYL0JqoOH9AR)h45MrKIaW%q>9cnOQ7L729Hs%lTh>q1%ziTAaq>Lejwb00X2 z7>F&U`B?<*%`EEtwph#PzoD}tZgC=j*Di%M=@U?My3QKc65(~jL1v98sOg=%r7)AJ za@rTB)IvDV^XU!t`Wpzf(&}}xOg2-LH-R)N)9kbu;GyPQm{_?nujk&DP@sjk5=)gm zZ@?=X$$KFql6GuOXNmjWMC5uNM79~9xUfGe`zQM!>%fd|!34mVY8Ox? zkXK@7sxT|B0s5~6unVKcVYf0RBZ2>mqH~RB`u+d-&SnSZG;?foKIfcM+U9%=IftB+ zkaI}d!THpjg=&r=G(r-!%~>iWsZ>KrI??H?)6akZySuR)dt9Gg*Y*0m-p{AvUbZMS*Cv+7=;Z2x1dF3@u{vR29(*!$?U zvZvh}4&J{EGUG>xR;f=fjJ#s)1aCU`BU{#p~YKarRfW-cBFH(YY-eH#k-O zY7unAF+7JuvVCXqTT$9R>Ymxw!4a;6I0s@1N5?5QgscoNewd06P-Rlp%BH_eM*D?m zF50Z-Mzvh{trbF>yV36ajjLG~h0Si>_+Mm^>I$s1AL`ljuqfcU-ZU+)oyuRBoQOw5*2O}B zU&gbGwPI)r%P+jY=kLDyup6n=Qof)WK$eW6POD5d5}v=5o^5&~2BUI)lw$ECwJU{% zYE9yoK2=_N29yt`LikgxT}zG~o|hyrY8qFLpbP8$_e1|J&33f_BYRI~^GF*AVExa_ zkMn1rzq(W!IQv4!>zLk^V^757b9awo>Y7*>x1DVFcCI9a>xrL;RGPRKGR4C$j(rEc z+L;gNYOUCL(xGhCYUy4xm$L;pH9Z1a9Bg0Iz6{zGV8ERX{zVo;C>rg+E6e%ME31BH zi0ZA9_&?Uj&H>$!;|cRoGVMU+zr{D86$x_T={)X#&($t6S6Qw_)(Ux<04qa3Yt??3 z1@@u7vg!cF>h-H&+hm$%_@kd|XJ$VgG&uAv5K!VB71-iEb^0$#yB#zxkv$45NQuH3 z)%c_`UT0Op?<$Q;g=)-1G)xM9NJ07H8*`5i?;Ff4TxXBmznAT76FKgyR1o6eK0T)# zq+IYZQ%P3WIpnZ2y9=tsu}_@_rDO}tlx>&{HfsKz@rd#+e@ohcaia6*RkHPPC&*6y zFC#@g3FVyPgluBIl#|s9+cIkR2*PIOD2d6D_`cMu_DXFsR9)kWs}sr6<-HT>W`!BdDe0+g+f; z!D39$8;;7ffKMT#)ffL$)fe&%g)hQ(3E3tz&ofVMmg0$F@2cdk}| zmt5Mlc*g7K(+w?sgCLlW)cEFfh)mXa&b>mEGz8R-|L8BHXu#bMzz%?8#hdFkNLoS5WEN(blw>SaH{ zf$=x#d>$c4RT6r%ZF$Fl@KlJ+J~IlStL~9xYEfgv`xI;aLI5`U-LIKWgI{Zl>Z3H( zRjRa!+jLc4%EtrH(0Ai)6MFOH#YWC>Ont6J7^pmj+CQgt309Cw=9GISfyIvF#=6Tm zvhB14eZzf`n*8_%Z5~I`_e=U`8<}5G@=T7NYS;K?-n&m42k?AxG+P-?*IBs+%)NEP zFW1iP!T4~`z)aY{Cg~*McmTZiylH&cisTl=;mA3E3ICAq-F2OU1`m3H2gST^y|$eX zF_P(@@y>E=hwsy-8t&*iZTrQScm_jt13*}<;;Sg>SNaHN=b@a(THxDMQ3%nIM@83M z;^RwJ4`<5d&vx5W#izx4`z^MR(=+7P7f?yRA~|~M>+M{EWCLp}DTaS1o4hu) zy^QfZsbalZTcgxw*s8%+aZcj);2h~vYlY#E)S;s@}hx`&%v|9jna|AP+? z=%lT_Cf7?RB^t`15RH0F>wn4R%22{hYz1%h$h0pQknTL zuMdyE+J8rZSlMeu^~jtvcurnt1NE#Y`rDXKV#uN9!ek#wehbGnt-v}0UcMQ1Ir6^8@MMG?&3(!eFJf+0TU?=G?|wBDp9t8?=y{Z zIc}^g@U=BpX041pP>cn{v#p8UQZIB)yxMItJ>IQA{G^x%RlDMwgBayBmJnL+w6bG+*$=n@MzQ(3D$GwqM!yjcV_}b%br# z{^J_c8^zG(Ur0@_o1TGf%Jy2qQf|VU<^NKu<0gXc#rzUvymJLuT==qAMpMkghxxo) zw)wEA;bPdF|EyfoC*cX8;w>!ct!>PW=BtNa9Nsql{_;N1Oi^O|-OBs%8^@pj2=F#s zJ`oiJz2o%r``f3@1@8Lg5Lb%%dCgaA=LB)l0k!Fm(b_M9b%Rq)z!k$DzbE>OsqVjN z?`l{DtGDi_rhB&OhBhxTL_A+uvsf?>Ksjib|*a=&)x(;YE*I-x^JKOT3>wc ze~4}6+OVJ*dWrGg%A$pz@2rMeN8zvJS+J77^PcWEZl5BxUHqaL08Fs)M?&>?=;% zm=3cxBm@Nhp>AI4)X49GBs>c*)!7ETt;vH;Og9xh1pBoC0IwWteg4KPqRn*@-qs%T z7ZaGibgJjsW_`j#Kf6QID`d2GAtMy2zv63k)bS;pSPI~=HioYK+Odj00=k_o>iC(# z&DY+;MTj3Y7Q7>NV@BSFUxRfpkM#>re_KTbIMa&_iM?+h=0nQ!=bgTA50b7L8&6_M z`SQxv!EF%tan-{yva>3eGbc)lOH3!t?(IKZW&bs~@$|^iK{ma%H2r+PyWgQ1u<(;! zbPQ59o??YN=BEG8y?0ob^)!qydfnY6K?Ej5vb~YQ%kV zv2A9>3EUX|?u!F=G7?cft5kF%&crRFX%aVrLx9kYq^!i;x6dZJ539Ny8Q?38{x-?XyWs{T%#6FQM5h%%IbWs z@z7d9Z2Oq(He(8~vR0bPqtDhdA;tij@KmpY1YfFb6IUdh3Ew9w{)@MEjA;^!vFBc~ zB{{h9FnQNZ>R%9lAw~qPvHihSDT$#);nwyf;krc{CY%ZNiYfF)v7-l{Qscj$5 z9c#J5JT@YF7CSx!{%=!vVuKQWk!jCA^*V6Cp>J`Wdt`h}XxlFb-Sfk{FTcgOS2$$? zF);d)<+-N>uO%uflQ?Tve0IdNyH&EDU(HloaNYY<(O@JpsSe`6jCX)qmStZ5q9rQp zWa(HFKU;vWn$_jcmDdi(uBksvELU2>xTE7!Z98XR;AvaAM2{ zAxirT=~`m0gq#6}!Dn)8Ib|m-93;LV*lO8p2ghq4`3MY%0-gf$T(ss|L4PDT#xX;M)6>_C26sym0wgJA zT5b|EU($!a7ZTe;l$u#Kz5r}{v8Q#t<|X?YKs(Ghrs;Cp44jpEw$k^?3@$)o9A5E! z7H*_7{8a8+PB{=^%p+m1fBal6VpvlNh{m(oV5}vn*r&2Qb`ajG2{>QaCzv5VY-Feg zAszSgZI+qAQ30ZOAR(C~NDc-md!7||I19WOt<)zyKR?kV;eyCBO2NK$6YzYe_vC2h z*mcQsWbGJIN$mHgu!L@y+5T{ydPnN>gs*u2h2PZE7UJtFOT){n87}kLKf|BTZx$Bx zKftEN)2}>RK1mE2$8v)YiUG!^%mc`nG?vxK(oR#e*>r+DEiU;QQn6FX3d7IZqc!rR zd*RIrzAlViUkTOTVj3!iF|oB?c_O{+^Ie%^&__FfYV&7tYmdSU;`X$QDu=1FFwK{w zz&V{SCLNMj7-Q0J0EmF%d><*7xsxBcXFA*Ilcs~e9whV_6sV=E$xKW;yTkGht~84A zQTr8#La}x~WW)0-pvoWllaxc;jnUir7Z2M?#N|1w9C!wi9%kp!k=FGWX3Z|%Dk<`i zujR|+ib>jP^~2w__nmFO(-30~*oy7J4_j56=V_@zXW6HhAO!2{1Z%{h7Nz6&u>k`S_1Nzh?QMI`6&MAqZ(XQg^r{df zGX$%P2~uClXi$izeSU3j$4h(rIs0*(E1wj`$Nmwl*ezc|1-;Z1jr~Ch-#>~DPNRub zlBKN*OI>q+oKKr1*v=B(1?$2h-0aFfhdoqmFbr)kUX#!v*zB;y+~}_j$sZnux^W8> z8S9d^RN=v3v<2tz|02R|ZQpYpwA*J)zh8vh;?BA;;9%#&OI+*~G8VKYT28~)DcbE# z;f$#$HBMsNhE^t3CzB(&s0-L;2~jzfQ6WB)sEJdwB9TK)qeV5w!Cl_&qU;Ahp64TU6I;v96VEQ9(^g$SL7g zR60sS#HyW+*mnFcfBO3niW#~(`lk0oo{sDKL=P$N`WP(}MGqHhZGwlt(qygj)8 zmB}aWO2=N5J}oS~!Yp>We6dfa%HY@jsKd^hMN+Grv4LKW8hUA&BJJD1g{q<) zj&N6nBZV5)Knj;8H(^ZIM+FQSWtWVlMy~ z#`<;|#Gt=Pa-020DM$3b0f`yi^djl4Vq(Y_(`Wb2G^8y=M6C>4*AF z{|h2%8aE=J^J0U5ibrmkK|jqK3&unit%86U5aFL&wqWEV;kZX=(IWNbt;f}m6J~d@hahMk_h>X3i>ka>t%6-+L6~`-s4ixdp($2@5I4=HY-?j2cO8^&%r(8K z$_~H2iAR497DqwO%p&GJIcC?t-Lh>I+fV%P&B9S|kSN4^wBmVj^)p^-WldJRSxzlE zV8-iYQ1U~>1Qx_W4^tqgIA->+%{N{j2I+MO+YQ%z_45irvEw$Eo%QoM5{Wcnaj0@s z^NCxEjrkn0k^JpanwL#j&<2+?P1ek&iq7(CQ-Kb2s-w-1FmSL#MRI$t2F@f|sv0QW zMv{4s2i_HTh7twRLL|+8>QgvEdICp^*Tfc?P9Vx_?|4aawQ~XX>FX1KvMGE~O7HhSa}B9x6hUN*vE?gE7ol;lUMwSzjZ>Bn&e1LR0>scwjccypj8Tt=mjFTX?&8acrXld0G^U?vA3 z9yjQo+Q?UD@IRrRm$be{C-d9Q}zo_IhmI;o%@&JnhZrkBU#oo^LC zScx1*xqRIgKSdozZSEVhlHw*@U2}!iA|`r1WF;xN4WW-1Q_=H8r~JnMeMWzXdaBob z$|`0}XqDx3CCpYMA@tf=o$z%WF$9?}V3b9Y4DYey$1hl_#!#>bmWou+m9C`d!1aKR z_{u<2K#(cG9$4)_MT!EeJ3>Vq8x@>6t~pfkd@7|R)o-cUiyUe|s?^c<<$oa>r9s^{ zU(tU*;XKc~?vZoocOR-&->?BF-NKO?0-8o01GMl+GnJByJh5zQZiGqf%S$RBF;o{T z!)_~C?TN_GT--E^zn5m~w3?Rxvi)rvzlTSw%&83NXQYf9)LBb>OcT0-X>_q_bW&v6 zf#+O-m|>!j&Kgg)Wovb<*e0XpOt$$4o}Ab9`Q)g)M9pWDo3|d?#{NWAigq?%+441S zQ3T_Mx5$oJgHFZ^hoja-iLqjJ+0OGw=gDkG%t`02X3M`3(>qMMagO(Pw$@^)Vt=#H zGG$w3S2cgyjY69={eiFwFF^wR!D2GO@GqB=lV+H~fQ9+V6CL9do;WE;( zPZmhmkeshm0uQFG*{7}@{!c+x(K!aew^eRZICIPzI#>@(N{zeep! zB}KmRNywRo{W8e0r>Lx3OP1bOK=@Mb;6<`Yl93_U$r?#+#@s1F&q+eC)(Y*Y zDsGkNZYkt>&Z@EI?NCsN5Pv9E*UFUx3A*sBLges*#J`G&^a06#6*VN}c(7PN2wrsD zsyaj*N5P1lfmr^kiMU;P^3npybjj&u)mgt9(rs}pM|}L&!R{t63;yPMjrJGod6TB{ zmvZ+Z#_-HbH<>U7Fyz6YwYlxbr+={OgN4^Wu?hPPCyyp%XI$)*B!&n*C!(uKavGt6 zTLA3OKQC;aiwWs`rHwf0PNnsSDNGAV22h20MC1xl0s@M?^2rYwTk%{KK+y#dse?;j zqFcN$gGBtbqnJIA%=IWC@hgve0&gxd`_zj1EFbh{oI$dP$bQPj|J_7muRONYyoe~e z_=a-i@(uJ(61tFrvi)%Cu2{ieN>AtqQA}fNN>NOgnBt>C$$$`~4oNkIfcsu|BZPu1 zx5oeombUc1$KRummU)Dz6n0a2>PEOi z*4nCtm+QEsh=UQOqtaRA8+P-1LprB-Kcaqs^h_KZ(sz~wk0ByGoh6jUS|A|;#&V1L zJOSAkEV+BtM@)MZ4=nKCm5ThUi6yz-uk>?OVZqzaGX60!YWmNEk6NhJUARp93zme0 zpubWIto9otBeJu#&?a$Vl=A$4)f_`E33o{94Jq;~9x%)k1QB0w4*$CUWcKsXnW3H; z5bBb?S&16w$mHpd57uLD&8;GL9xd>G7=?FQx|1}TfP|AIMAOwx{7W5rEZO0Ibpw7! zF2)4hz#spD|3$>~O`@S3VE_n&KavI5UE6rale0+sx^o*W(j;e^q%m9eSVd9Be>m5UiKkL>VG7cQ3}$Oh zo$*VEM(2`yvujDlgq=_~AOJjHZgao7J7{S3=eC5iFKb}D^mdAqR$M?>Le0zDmCm)R zLmBU+k+w12ynarxph0f!=a7)N^W6n0sCZuRXt|yP17MAmA%*J`n%j^UrO1Q%oWu{3 zJ-x$OQZK&Sc(Z&*qNbW2Tpx@J8p`^mWBc=IxBuPD%ZDuopUN8F%U&}R8hv_WYw7yY zDd?Uj#ds*6^dI`}aPrRMN7cfv&e*F)nc*T}?C9V0-6sh^F<4B6jDC8+sE^AD%Esj< zFV$w)impDuEitwU!V%4y`g6o> z;RI_8jR`_%G%I~|P`#Y?bw;^9fI6k(r2RGzpEV+~AS>1FZfhG?Y^EWb5|Hf9pKV>6 zl=Dw^7m)3E2(;@?94aeoKiy8Xl^)4jfU*MHdu@A9v({|oGNX2(@`v97W94nMZ3LBF zz0UoAla;%#t>$^YepY=wC?#6Er+s}^^G3_{+-wjNFd>tlOv^tInk+)8GLcT2Q%S^# zv5(IrU-IQ2c;+O6GZK`YeWJTluIf=)jhF9w{*F{me^YYkYBF%oBtbp`_Fv$6qdJ>F zKee730c|co?KNfdpC};>xMv(1(7D>1E7uH2Vx4WkPtRCU4c?rF6Wj zOUe`P6D29j{sQrR1u1vWA|A!0fqV~2Elx|6EFP{=%DOyVHmSl+Q+=Bgk>V9vGKl$B zgpXS7JyfQrk*0rMv3dom&7S_csA*a1yXQBs)(eBSq;as&1_8 zBAy1kAm8^n(NXkoxHIP7zgw@)-TR~-=QiT-tKQIPsg_6M{Fm*#Gp_C}5Z1@CGJBlO}J^e&}J2>xf)Vz>@x;@^S z0C&uu_b>fwtx61$__DArdYqZ99RRGxh1!v%@6_If-K^GMIF;3BZyVhIMsj>aIV~Be za02(O$Z2{_=yST?rH@Lr^&+3*)z1k%C))`ccM&k9-$ZoU)tFmq+JK#vI;ltblZN}9 z2_+t#>%N<|ND{>w)29o2@Hw?{Bh&q&3dk7%Da-9`wK0-06DlA1DQg4-`3?S=DB~xE zR?DbUZv}B`gY3L}OC999aH6WRwLytQ6tWrq^1=3an@2n$1vC#33l{}E`-g{{>`+z7 zXB*btTyfX7KrcQIPW5et){ZYhO9~a4?=fRy(X8e=tw9yzHQl^8jmIMNg&XF$wu5u0 zD*`ZKF1&$=h60gy)x~8f#}$Iq=~ir?;Q8HMXGLXZFTiZv<|4`dcRPNjh zR8mO8K%{yw6mtMbILpM5j8I_E)s~o*E06*CBN)j)V*a%<@<=ij%~Y%SK1`b$6;*QxmqH$VM$A37^8nlF5R=~yZ*--Ag`0%7X*oE$+o4`_lR186&7LKI2RWQC*Rd|U50pc!40 ze>!b$lhC5et%je2!8Jm0IbWPpnjcJDA#dlqQO+K{$pzl^dtx zKK0eyLv0Fp?b;3cBE6?6FwzhlcPc4P#^t;0-pZ8ehud_G9Rm}tsc&z(`GTg|pX0&p zPdVpumEIH%_C851Ma8kp3amA49(?*F-eQ=$uLFud75rC$bDJ=sP)^O)#I3;{-MA7x zY?z}x2WEnS=uL{sABQVq!r5;VdcJK5#m?bkaXA;KL#wZs2%*!jV00Om4xTSC9quH+ z@Y}r0+fA)v*DVViT+0CmWC;j&9OyuPZ_x>yYR&6`N80e{;%R;bacQlvEf6f@)u7)q z6PYx6xQaelWENn_{e)|MXH3bnVy8NATbS;%pb)mrgH zUObbpSE$pj@G|Bn^x)7sGH}Ej*TSAqfryHnTJS`euu1Ykqk6$3G}H~sqc)DI%5CdJ ztEqnzlHxueJ5O~<24Z^n@9X4C)0ge)#d`3?40lXJ_7(IFRXCCj^{6Ck|Kiq;S`}RO z=^{xys8ZOZ20k~Gv5G>3-lE*ap&SiYM*_yuA3h-eeDxx)^A|!6|AmJbTXN9#jIO9t zQse>eIOtEYa-2TsUJK*d>7QHk(0?NbNL!K7U@?Uru z5T&-b15M>2(9IWQ5;K31_XUr;2{F!3f3(TSp(AzNDz950c`TJTB8a-PZgX9x2u_l z#qb0=<1f@i>>t`WX>(Q)bp_z(`%^xzIY8FKq@Q=;^gOIwxuCp1O@bW7S42)SQd8L$ zLb(R`zO+JP#0k9LXo75%+S%ljh+#%>J&&d*;hu#7m;{64cygNya+M5NW7vUu3d9(H z@mmyMEyaNneiB*1? zb(C>Zh2mK@3>c5d5K*jLk{EXr4hRw2K3nKCQyDaA_n#eql_n<=1$Dp$)*eym;tm<( z`^kLufmDJMAnB0&`$%;wzbPi-j)EWNtglFUm1ttV$evLq(eb^SLz9g`)B-ZH3U)T~ z04M%Te?0QWKwy*z%IUELCPjeuubwje zZwvQoUJ;eai*8p>S5<(gvd(dBU?eugIhe0yk;teOu%HU`1S7_Yh#G8M z`}a#NR)Wz)sqGX;*>7dCWP=tk{CGUVyWPl|jvc26L=gr5yLB?%FLkjjj!(c#BA%<{ zl=pO0odlv@3fM=_3uch)kG&BDVuXb}gtwSN`cEtWy}ugOUl2)0R>o_U`tGZER9*NY zz=sbg8YV?H7aZ_AX)tO>NNYKy8j3tiaX3xQFT2JJpv!){CE^tkD37>YXX9T_2^x4R z5$%C!A)?yws5^|{!@uwk$yfMT&C^8H>-=N>PVARt0dg?doC&VK{r}9`@Oixu&!U2C zWFR2sdatq8FAAZ;F;fS{x_YSw;`K?S51ZZdyhqKCZuG}#~Y~|QfAW@fx682a0*X> zfm3A0qXK&oV{F6~MCVnF&M^$2>3PT1jLt?g6n`YVbGGyP_I_ulS?5iS>nyX*8;;j+ z`(GcPy?$r=`Y597o<**!gG}U%Tdj2fdW-Y z;TJMb1r!R~T>s~N=xK-a&7TKb9>e&2SYNilp;@u?V8k63vWSSd#YVP&58UM#Pf|#) z7A`IUI|`Li#fk#;FeL{kqh=N?g(aaEdL|1Vm_*-4QW&t*6kXr5=gMcD(sc)NByi|v zd@h4)-_AS@_C3UPA`(ROXrKDMiUjfcpo*SUemiXJ+2 zgCTGV8~;b8d(q5=M)H0lt~?Gv1pPpkk#1waE?-guj69UA`Xq+f?x_eYBR6Vx;1HGP zL~)R>0;3LQpo&Ggoz`}tPqw5PB`J_I7orn41-Mp1RM5Z4_oWxuvj_^8ch+H6%~)AK=cU^{ROCV#0}MT!THH^;$JUGhIYrerE%FX{p(Pu zjEE^vWFQ!ICm1nBMEv_BiK)19D{^1)BUM2;@c^{#)Q|0eq%n;fjJVH;0f|uK2yS}~ zJ7cHJXsdUi1a3z2&i6^eR;LMC+6vyUMF4eCWx9e@Y>8SX;r|`y6x$2Bw+=PfI0?c^JE4m1Gy`gpP;nj-6`Sm^tuxo-S-A=r~WdtT7()Bi*p00DEn|-*4*fO_XDkHHx-#md%FQ@QKS5fxv`& zhszM}LlFf#{!F)_59=jM$tnp6s8|5vK3FX{%YkPSQ zg_$@EpeG*nZZ7S0rorBthj_Dtxhi*5M5=j5^&B42;t1FNOGtPjq2rtcD;X2K?B~Z- z4o_71t$(1!33-o2KE0!qy6qV|cR1$n;Z?47wTE_HU!riY*kLNnh6R;@ibi>B1uVdH zM&)AWVMF?slJ1(Av#FwMn1TZ3PiQ-?E4q(INxEbWN?Pg;!8zr1}!Pz<8Br`JlMB9=x7z#uCB#AIHUgkvO{6Z znaeG0C!eOHpPspV>D<3%U~mg*UXa7~eX|>9QT>2>lRTKs z&ST+5d>S#7OaYtm)r-5}7LuAXo^Crft{U~+ircaIY+G!kb6ad2eM$Tkfu7LRc`mg$#~>P9N^K8 zfZ<<48FPN)}s z*EOdW3j06PFgD%p@|mY~D@adXV9DWhd`Z@D)8X-)d2 zHdT6i*Bhr-%V)a5CT@^UU6p*!yzQI$N&dYdL3znX+4k6hV;Px}@UoeC7WwnN3CZC#;c`JU(~XkFjMGoRxXZOesT**~e3)>_91sQP+Ew>Zd;`31(lu?hTvPL9P^uaS+UDHbJ`z2_Sm9mOQ&|om4pPA80LFC*?Xx>q) z#~dpVbdTKun*>A9!0Z@yG$pnL`+>jWnCcE%q<>K4!LZ}=bRW0qRu!>1O>^$56yfes zXE%t$@H>+oum@hiC}l}amF(_q>6-Ahd|msL^Qp^#%4?LYfL(-m-jI>Ud4R3tU$Vu7 zfpzQxa?4l1h6xE|Z2l+Yo~A26nqRgIZZW|?b=c84iEnHjpPr4~|6xXXI&&RNVt@DD zf0jm}4!}R2uhw^XJoK4rvfTSV=zp$*UF8wIKWUcSOe-c0Cz*iz@2a2d1W&L51E4bp z<+7!8sj~5aQiSE<*RS zC@POz&P0gX)K6Lj-u3U_fqtz%?42N(=_Wu>QYW}zG*5<$k~9YvVdl%4o?SM4@_u;y zW8vh-AHKlE8#O*$9N)O9sr=UcUs9+URp3Pt%$5N;0l)x1@551)Dg0Ga^W-gdFD9=@ zO~?PubjTP?sK~@HZgog8Pbddrl(p*ak%u_~q=|${@oMjf=|#YpGv&Akb)52a|HtoD zbb~oGpfcj)(}feGl^PQROX|nkhFTVX+Z2mRS&q`6dp0*UbsB&zi<$n*F^_}1zyaiq z$V%Oi!9|tJMal0MhV6fd{!@+-cd@JB3aJF(RNEYCLEm*PYHh{B4JQrT0-k-1n7d?j zW^?t~x04NFt)-I@NMFjacs_ho8C9!&{Bqb>8~R+oc0hm3uTM>p;=MurL>ZXVuw<`m z;2!3W^4YYo4(AfVZBZglXLvN~H-dM%MrWrjHANV(FRz;BPx*+OtH?VqM=%9p!XCHg zqjSVl_Sl4M57wf+OxN|Ei~=116J&qCy@et*fe!9(R&THJ6`dpx#pqAsLW@mvtwO^K z)h~%u0NrcDLAT#rJ7J4tSNnvQ?MnDWC)-HKdYMLu%af#_l`gc^H=>R@dgbX*l!3ihv?tOXp8yYu7c@woe3G%nP&Bdo+ChOlWA_#pAWmwk2o zdaKD@K)Bj!6zH_Ur`1@;&X?HB^Tn(&?Je-);}v)n>&v3mxJO zm7^a%#cw3(&pY2NdbB{~Ggg=5!%_}y`Zhc=f4%`0K4KhVC3pz*Z2SyK-0Sy1hDlGo+Er^dr{Dh0=d%va;BkaSZOiMpnL#W|J=QlAAI z)@$(DiM?m{c#zUn)>x%o0*pon& zQaYt&c}Dp*I*w9vQE~1?{*)<6$AbBQ>Q-d18#gQ%S&xaw0RB#&Bq(z@!YlEG!ShYo zBF)Y|sIki6xwS*5)@Ju9+(hw5EfG2#K#olQTL0vhO`%5%N&u~d)G|>=XEJ9hxweA6 zL+zn$c&N7XT2U{4Len1Nc#uLUHg@A?^!>i_%sP4M(d z3h6kL@6j{#q9i^UVP6`WHYT%J20E!kR0~07Zuv5Kc!5J*K&Ot=;CIgNVWwM&y+t2f(+JuA#g} zG$%@Eq;j9EN8#R=e2F5;Tf+JjT8dQ;TxvuY5(`p7@`(1yj(4um#6Iy_ZASOFZiPcq zO7eOwISz%o#4^}bzndpO1~fhfwUx!^NnYd3jJq}$9fySZo&Me^G73T&C9f-oSbO`5 zx3lMoz4aE`8x7?`!1x`;hxB6ucwv>C4J!Fg8h##U$60;hz%gh%ZQ z32pK-)Mw(YW_2gvp*i?5x=3Phc@AY9X1im336 zYp)RP>FqKF^I*nst4^|U`jIIrByA-g7KsoV;9 z4?WNU&aeMiGT%_# zfTB;Z9ACODg&sFw48zsqbgKTcv-J=4!<&Pj27aZTd@b**0s1y`8JM-BzU*0$lm>0u z4_GwgTay!cq0SNlh`gktk>)M#aJL`6W(SDAp*z|3p~jtGNEhFaiK45vqrSw4yi;NF zWYuh;-zF(El^h<5&=3sso>zL>@N7UTH8y_@BBxrBwyD%I5z~Hb@C4`g)6xRcH@=o? z`k?51zk;onz-tZ_sB0THY}rsKormk(qRC~49{nR_|8P5$e#eTgef!;zn1cBhX=k)g zZjTLfwukEGraa453@AZxA8PV;3b9fFyA=Y4vRe)h-NTRvr*6~7KMFFBhgUr=7! zX$6L;x5NLPb_JO2=19yaw_LjFeRk%vr-k$3&v8o$9kvU(kc-hxH4eK6vP-0-G$(bd zri*`#C)gLPG(AwRjNu&EJ{(bW~8781lXue`U$#>*TSdzRSj*1^Ef1CNg zw2hmeCow{Q7p{i6?TmiOWZxp=xY@5M<~jyN#(%Vu85g&! zC&Y>_Z8XHwj=1r%S;3YM7}(7)=#}fe_Ke>5$GNA?>P9{kLGCxW`U>_So8wKT7o#R2pa;sRg94PQ6uG8zxJMTe3TT!8V=@9jm;}=; zJTcFma1HU$hY2}iUE>dRu>*jd;B81kd8hl|q7Y`m#)sk~CgcYu*;dmitCax<-Rx^f zq=PQR%8jhzJo!gm=(bpH`50X%imqMMRhQIAxIU;l?Tbt5; zrO!4?5BtfNPk_Fkji}s zOLjNC#p0m>O;b&+$RPiGOyO?_L}(P)(q8?qI-?(BXK4>EH*YFh9dUmK=`xub`bJQb zg_=gul{XBZ|3OA{In;*_w%bei@AGWU0nl#UF|mH~p>T_YeyH&Zjkr}r&Jb#Of45b) zB&e33szN1}#?JLk8*fQnSF!;EVP0Dmx_9W^3vhK4=z(af8^;k|ZuEKbeYK{;7LO$= zI_bVK_7mo%>s*=%YBXA`C~E}OiGbXGwd#lK#byblRrM7Srql4D8?q} z3(*DwtJ-Z%5T*QS&OTGL`?1~yCFGAel(Mvvp|3t`MPKA&4K%&XRudk^cm(=WJq!nU z?X|+o&2i2euaC=}`FOVu=K>9MI~`hZthU|>b2Wup*EDa?Os;zlzxD1{PVi8+Q55)e z5gIPD5MxGaF1uM-p^CAW)A4Q3TxIy*Z zaz5Z}9^5zJjnIwQ(DmfzXvdFuTDozqIxpCbB)9ZiBwL#SdbBNa zKniM4Q+m4}qO{2ow=OJcWis3gBt(EB!s*b!3}{~mqr1ti;S%yJP`ZJ_x70mZ^u6U1 zCD)S%ebR|$lDu9Px*v;09cMrfMbpiiJsnOX{4u?p_$7>%>!A^L+a9#6lK zpDPj7`+64fF!Lc0am$0@4*hJ1JZ^IfsfD_n(3z6t4mP-*)qx=5={l9|(S@Xdc)FpR zfnE!R;DV{tNPl5h6nS zrd1tl*G}jbx(_^DWab1hpoX>j=zm^mR)`bY*E~Htx8eTZQ>qd&(1zpxjJ&1i$t1rIKiQR=IGI>%W#TF{M_8Ww(YaWeQpjJkvbN=Qym%DX)RGhd`!kfz*<8YAaxO1!l6mub zS3_Ym%{h5j4f@$0T7V9rxYP>fCYL-{;$sHo|qOO=%mu~R#MQ<|k33!_l+I;WLwBv)wE9q|NE_)00LgUJ;vLEr<~v4hoV zgE^=JSQ3x!c_W3t~_u=qXzV z1dXJS3u2IkPaMcC!>{|<+c^jTXn=TzM00vN)9!O*4V>ag9nlPYX zv}5=&Rp1^C`JPP08a{%Ht1>biMx;p9VI6q|P`Cm=Fy|i`9w4CvRd~PLLW|!tka22` zyJ?Ep(A5Bl5$%{%IUAP6r3yde=iu;5T!@j_K%^HGTHzQLN`X~eU{vOD1>J}dI2eVw zBbrn0S)|aaP(iEj*(06hBcm_|^#BfpR6#EzQOXFQYAjNkxyv`JC?ArLqyHcVHyDV2 zL&%-(U$*TuO6Y>$KntJ7Gg8G4zfc1>fEb^?3{ZAPFq#K(5N4_t)MvhG2-~LZ639V9 zWUT&bWPu*9WrMCbyhXMRSK~vdfQmm(R;s#=FQ9~|+F1@wE&A-BJhkbvJ;ATgCm>oV$%_wD_{aOa9wsBLs$Bw!y%@{2>>H*56(8?u;qjN zEfOQ?1mZm&S#Z<3!IauC3T(U0WC`r*bwVrpI(4&1!pJCfq^jNmWsQsIFhEo_!=XLAlzEZmoiU5G#p^)zBzEafi*Qu^*@c$Og?}V4@EgGF^ z)h)OLK8mmLh8Hw^irauPN+?I3t?g1(BKjo^CpFPY(*n5`+M+7b%TnbIa<*!WFpNqn zvOw@=tBjd(8mEwjHV_ULUJ2pq1x$IXMtUS2AztAbo=eDI&^0EEg@Y#!lt0PrQ9hg~ zZk;s1f>g3%QDTGXkp(y=vJ#G9Y{LZ`f05*U5m;@G6;G!u4iH%E~ zC_mH+mbg@BR93RniW;sejy7s)MH+N^g*z>c_D=5KJ~(6GRDsM-{7&IdX2n80j#2pF z@SbzgG*_B2R?*P1tFVK0gVt)gv~}x+gDpedv!;Im5dR)3y#GzcLfVbK*$Vg;hM+>v zyO1KQ^60}25fPzTVyG~!Vvw{r1vkizx6*J}y#x@vO;ZCyUxkgAM%BBPk#joZ7g6Yc zb`Ix}QRn#z4vL@%VY9BVr>0N^KmY{b@ex6|0!nxVMok__mDEY44brgmq3~!@DH{$U z$eJJ#JdlH6Fa{3`AFis9Q!H@ zi4bGxgbeC*t`MJ3A(zw0?%bdhOTiJ7EuP}p1Vs^q!Xli=>66iwgFA2oCcsuGu2_qG zNnk1^Q4*ysM1wAv{w*K_QA(XwavjFGgGc6@B>(Z7;JJe9D?1d`;u8PE7 zt(o(ypu>(HKOXEQF_^0_n~2eJ*b5}fmM&dRT#2jKFEV$6Eu0yQ51wNX1FU>0wBbZz zUsT~#i0hZCO~57&jVg7j$b%4Z*&;^C4a%w_ZS}H6i>An5z|ICsi#8arV8q@Edn?x% zU1P`Y9wS!wEiO2Aj1d$DbY(AEh7G@xMN8JJ#*Sa9Qgur5sLG%=b;`Wy5+zE40s#t* z#||GpY?xe;(*_NiG;G$qX5(hI8#r=qQ{OA z=P44?Mkj(LG!ZU4Z4!(vQ2Ey&NMR9UM;*k>G?+*ilJyIQ8-~PTRSZ@XqKLQv(@Py| zyh2d`XB~8wi)$?u6hdvKC5(+X3KI;Da=n!oAZ)y{%rbfLNMkS(q4(G;uDGH~Wlw?< zr6-qkl81v=Vwt6uTY?lKTa=Jt2Qb9Q$l!Ze0fh@KN3L-cG45%3p)JCU^2I5}z?sm8 zvT*5~M797U3>$bDBa4{_&Gbtbeg7&XkuZD+LST%q*r7^$RWa(PM2I3}U@&g*@n!(O zR7BCCqi&SyMhB_ds;jT^N7FHvkO7LQz^D||hP(25VR;v#7uJ}b9Q2AXB69d*S~})f zLQtvW!iOGKS%H#9AjGuSUzX7k6TlXupv0-3 z-DQ`pP%^3a#T^vN*y(|w*b&yLSVk8NC7~{e5Me;6atBxj9jtFlz8-4efoxpz=2HTX zSn8;#!dmjHH1Ri4ihvvw41a#A6cR$h1kwd1DaX{S&b|(YRZc zDZ&&Ku!AvyCCnXbs3K~f@Bh+5Or57FcwVVt4c(DgD$hFYvZz-Cpn7zZgj@H@9!Nsp#f$!uk;W_W zj+`sc%vm2m^mYUwY5d*u-~Z<_ZR$gF>V+NDAc$T}uVUuuj(mhci8WlOVT=lkV7gGX z1t~B(zo11Y45S^IDF1L@ArS^J%9aOUaHJvK!N~8bB@tk#!VTNf-AaNniaK7G2)eq!HSrO}RKOU8Cvaj!Oc%2&iR1i1#E@lRylpj!-I{u-@7OL<_Sd8HbGHh;NJG&697PpbA7zAmQm?Ful zsH)?ri6G_>Ir#%Nlf&P9w%XklF)>f9Q$vWYIdf_G^n z3QZ=`iQ7E~J^vbt$W+F42{oi)6SDkTM`&>j2>vWnP}2`i8Y#2Fl*ScD@}G2=63PDr zfEa*SLy1Bt6;d9~Rb>hWE;8b>WopQkue732-1194_*0h>ov0xHWU6ST!3_f;W}jZz z3pt=6TxnEiRy<+BV5G#I1q#uEXh8|C=}M)2gGxkWU8^tRg))8C?qYiE$sDJ9VIHw^n4{FfcVDzL=lPM&9 z4Eatk0722W!qqv!B8DvNKn6;@6c)7k)?!z#dT~ui!%`_9w`i zdgNHA5dXw%JYhYsv4li7#1*!%att|KBB?|%NHAUzh&zBnLzf&HOXEg~bb7?7gsKq2 z{uUx)JQEbg=psf2N$WOK&|Kt|$f+~c;SsB5x?AIN|QtfGlgSosbgx?roTFtb4* zav&Mx$<3L{WD}Ioo`%3C(`=6L7n7C4phoeFW5uK;SrJ4V@N})2WCc>9Jt9Tks|r8l zVHAPlp3uzo3rcA(vlI!&8UkV8^ERh*bR-7S)&;=cjxxg;4rN0&u?0RLH^d@-=YoR) z2sGfqSe+v3SArpn;>n_GkkyXHw4#O|BGzjmqRA)#G2XL4m}n?G%PTg4KR!@ZCU6R} zssDmuhXm;>E0^E{Y*iQ(u%K`hARa|8aI)IBv2-POKuV4aRG2S-qMdI$h%98Yl){lE z&KjOGKve?25#yPn5=@vdPN9Z1glmH>+EP#|atu#=0T6ed@pI&)6*jz?Dm{}3EjHl? zL5xCg;0qb2&2-6-Im|3aa>XbpfrmES!Kr~FkEb6rs$M{oz}5oPDDJ@7s|E}z$GXHF z7#mI1`mLlPvCj8fSLU(IdEPeYzDA;BY;p}w zSrxem{ZwGEp$nrphF+_sreoZJ42ePxuYmE2Q3wJMn@|OxT=cR|0~}eRCSfmL0sjg? z*dgJ3*!TA6ja65qVTRdaN*Zn*AA+hP5P6`4rCf$2VKZ6M7D7+l;LtHfFQiVCO>RH~A0h|mj;cvLU6{j)z=HD0*#h2QFdEDMNf;!_5*V&H z_@y@iicN0hMQv%3s$8TN{@CIbrvL>d0>Otm*ntvMwVow=c65g&{p{1r)|LdqEnUtEVd3@3sF>T5sY8TQr6W9hAPMa;(UR6=B=#a%{vcQ zQV|3YU8nGLLCe zWKL0;O$dS~eDDJx1aS#aRJAQkeEU_2;f9W#{%sN&Ysfi?tI00k6Q_{H5|PCCT9@Ie~ z#29Zy#kLT`9sEmtK_J3}L@?k15z&vUIF{ic3LvOKAP5@(vf-Bang1cR3|PbzWc`GD zK*Sy9%R^iR9i2}v9788;fglir$I+is6{1i~*c?cY6Z%J|nG%pK1q9)OVqnnWxJY-L z%hgbyN5qXBP{{i+N}w>7Fm#_8ngywl+LQ&tC8XdhfQ4C<2(YbGbcGD=v4upaLMQNn z9RPwS{F`gxDtmLgDb2-8?<3HZpjt^0%J7B9hy~H zlto*3U0m?UTi69)j3Wv8+x*E=LY+k&D2AriujJPq3{yh& z(CElq_!J{c@W%u?1v8@8@c4lr43`XE(JA7>?r}ySTpH$_g8wT}A}nr%T4-H)mB_t` z*Dl^cFGkZrt)UV@B&QqLU zHf;nNAk~tAVppjR3bnx+SPuqiS1Y{;L*W7i=FiN0LjM5dLpU4+Jpg5L4h4UtBmOBy z@2EnPj6zs~f+u)FCwOJ=HKZ2W0dF{^ZOlP0)Xd8mRM$WqYE*Bl&Axug!toW%w$31wU- zD>5MR`KMO`pGF3NS{w;tDkQFvh$`4oI@u(>P1;NlgCE>jSIp*eaOhO91GOmUl_rLW&8pqSZyoWC$N*xFQ~U z4=JGqTehW`>IEOTK{7DQT%wREosu5n;j6+4?KOmy&5f*L$$@x+9Pps*MBQ58$|zJI zx6CC?D?2>r4SAz`^RP9+qG3p^(nR3mL;E z1i*N#DlD=H*X2%J3PxM%MLFWgK_-SQ$O4l{Mx0v4fOdh14k2gUX=wPt^66Wnum&3ZnW45pZG>mSC7e{=0skIYr5)($9du?gU22p7p9(&PVgx`+bmWA- z<+2#bu(GU~+Q_hiqcG$_APiS|%_Bq{2CTZORUB5a>IqE1kQ^-w}}-IrSEF zNEjyBVsB#N9kcNP99%6?vC3=`LVQ60!~@u>FGFN+`u*@lL`I;*{0VXv_sWQDt5`IK?S#c&N^uJ^PDL~^M-r|9>&Ow$MPA@VUMx#`1VSCO zM`BRMlZ@t#_NNK5a=-@cROW#lXzm;wtQs7I!fL@5AOsn}MxXkH8>lWGXn`BJGUNs< ze%?VI@Lgy6=kMk4bVesxE=CJ>$Bx9sH8abN3?j48$VIdP;Hqra4cYvamlPwWEl}dz z2JksYambXH^?Bl0B=S6WnlY#n-H^&3({uKA*(fZ7J&1!H*D;+D^eCkXMeNoWY*jlg zVL?0eoIM0*@xc_G-~U5fw1#1Y^+k#tKJg-lYq01u+yZbThm0`H!6oz;EG~pLyDPhT z1mRi{WTb*FkeUaM<`+C!XLM%3N(koq^ybQeo>FYVdMBg4MjEgN8EnDAE@c|1!EZbz z+S$QB~wK#G(L9feFJmk;&a< z3oWGWuLPD@n29g=0x$$(GR(r51b{I(pD|FVUVO4#9E6!J3j~YBVKfH4HU^UzA9Y4a zor)I-E+2kU?Eh@2ffSH%@c>5)y8)t_CvN~ppE5TajIbK)1{`Q%ujN}HIA2%(o}2>T zrp~r31Vw1I;2w4vTynBn{%(cdh`%w;6Td1ThnX!fYE>BuBL{LV(sg}faWHtoG8lG$ zm&>5dfh|)=KI#jpIM*1Rs0-0T8YGz1UWu0__?6rOoe04a$N?{u0xXLq_m z#5(sHpg}Hg!55Ih7ofoxTtOEs>I`G<(3jc%OSvHg7ga!(`;7V_vlDWWY&NlL^>i4wx_nylYE*QfobU_{rR~KH3hIGN@ zkrUk^gc}fw=MY0_5Y+TuiDw^#F5t};V8alc!5#zxFA#&=1i&r$f`kc=N7R&wimj*i zf+w&+VGM9^iSt@yvx5T00l(}uzii6_>9I6SFN}f~P*r5uv~^ymXK1i~@&T1&Zj}$L zRQvR8xUd>XI~pjZ!ft_5E~RXwC+1!(9(W5A^Q{I${_>>#X`lpvNWiw3WFbT zMKY)*V4O8vyh!5=pKTYYlw7KR{wG#zCm@uDe#(I}$O9d7eeIVqe_X;AP{J`VHvbN; zNH3(pL^Iv@_K7hh+*# zMn}$eC4y9mwZ9Am8 z2GGEfwFCe9mD#DRG2ZA#B&;gBqzR-e_K+xzykT1t$5g1S=A45_k7;SOG4fFOKuhGx4GVc^DR57N(711IFkT!^ER!NZDaOJoMH?)I~SCG(# zm>mQOM2;;yd4;Y!gIVJezw-2ijGOiZ6T2GMsKeLigdLdRf+;%57MF+trHep_iBBwU zdoynoEfoFbD`M{x>lZ{nj89@mdvT=;(n2OIE@F&H1`9s^(f?wLOYYF(60g8-mpTm6OW89!bn6j{g804msn2ZlTq@YAQuvL^Rsx@~0 zRUR6WAH1S_~I)JhL}6H0L7Su=l<*@VNO}T`6sQlDGgOh|Mes`*3=Vu zV@Aot4=nJo*+D#oVPli=1xg zv_yjZli>^*qPaJX;tPQ|1_&8=Jz~(L6T5*}3eDpQHONJ1ZUPB01fi{XJ;-z#Qw1A# zx4;aL%tnA|pXOERC7e_-HGke2^Q*;KTC=*FA@UY8t zw#X%v2tbOwf>56h?l>GGBTEDo)4)`P7RCrfO@s(6KGi`E)G}%^gJFkGh;ynNJyRQG zK|o;jVuYR>SR3R(A-t8cDQFnlPuV)S9RCGC4r_QJA*Cq`rPf3{!pZ7W5cZ2xeBl+= zyHi}g05X;iYaqZ#L);Dvy#ReWbN40?* zBM|vI6GR(J7-D<@kg)_7FixQcbhcKe#1PHxf|Vmspd^g%#9uG6WY$%R5k3@(Buqcs z+!O*Md0zmJ#@=a*V|0*2H^VJp&V<@F2x?%*-~&pwTbRDoA&BKI+hfUe+&ul_6>>_6 zL09Aw9R60l&ebnT%tH$|IFxZh%I{Omv(&D#N3iuJ(igg#;5!*34V&QQzN& zp2nRQIVjBhCGsx!MBO|Ar45Mu>JmM{hWVvACsqN*CT!YU&oEJERJmz~dYQaPRvFJ( z-tSk;SqJVcE73S11|HgA=1Av+DyYQez^ba79{(yTdu!x7gOLWN5bPwu;KMGrdD6AQ z))lB6 z>0hA-5V0Qhthw!wgb5?Q&HqlxIHg^YgdL*|Y#=QLnG6&(+?G+ZJ%t>6RN6$!!VPhg z?VLk%irow>b!@=H8|#$gf%vT336F>|{Kk?DmfIq|KpPx5Y(QmOOC_qP(ZyLLUO61Y z+P?yZ_pnN^zBFmVsK!MaF7XRlWbCBE-~$;Zw?Kv8oFTxdLmG_M=0Ph_w{FNLqgq{E zV^AB05Wfhc?H~wr7R)?qAk)5)yoNO?9V1!61=J{qAA8%$6I)m-&dH9DFW?~P0`tU+66;W!kx1Bx#^Z0;?R>&BsO3^)KP?-w)=CD=~>>C!TaVkC$Yab4nP@2NarOC`N+?RgU@0a)Agd%6SCr0uFSO7YR4FNppPu@ z=v0yPMG$;2S@k!{B(z_?Byh@S?Q_h;H2f3&7y(9bPN93UQ^FIQ00k&UF^W@+LKR*? z00*#U;ANsNr1ui=7#5Hi8qfh7P|E)4LX5+!ye;`?VRP8P4R*ul24*`>0S!to{>-g0 z)*xyOPetyjq(Y8+G;5DQ#$bp+Z#-uNDWV4LuVC^3s{U&Y)PM}gpbNHO3&`LL0;mn( z09l}l+T?%<<^RAAm=Ia);12L05BPu*u5c4Pf&cnX6H4Z1)Jx&RH(Ab{3@4dh@BUWp1@2N3w+61D&fEEt}y_=5MGRJ_FUNgVKn> zW`-ld%KytAorxmOQ9>Su{elG;WPuEXWD*5KpscQR;0RcPsu$EC4|b*?D^Vgbq7+j> zO#(m>FftJoArY?8B3~f@WB~&W2pGh14I9uH)=(TpNtCoh7j7Y8Fi{o+&w4_b#6DPa>X zAt$%c|GIDhXEGBP$SQsTd3dk)jNurJ;Ts#U_Yy}8DNs1tkuK}9E`6>Yg=2W;vRDYk zDv~DyQvk&hB;mzo z(*J}PbU_!8MDCg+K5F3>ZlM-@K^J_XZt|cx+_EHt!52s)Bxr#EU7-~H?Dh7~Nng<)A95liKD04(1@;>_8Uzzz;ZR6uN*X0FV^D z5ECa*9m9}2YBTLl@&VmaCB-luFNB_q$qx0!C2T_Z6e7w(Y~uiNBH&{VK2K?ap$+C_ zYM@RSWZ`cLhYSKhcq~)$K+=Ukax*t`7G~ilGI1bK0Tl)UBxfN2G86-E;UMx#H(vo2 zUcnS32d&aM_vArro^Akw5f z_A?>!@@Ep_Y{UZ&@iZ9N&^=Y=7#^_q7}T!fg94K^ENo&Xg|z=bVG}mt3Ms)4T8G-) zfEbYl4wAA7lTs;>r47>UDZju;*+320AUiRo3Iib!qO}@P@fu%Y)n0*9UH_pT1ArUb z&;b|F82S|)Rk9qL!G0sD0Uht)0Rbfs=0XT9(me{=uxZyK*~T>#-)*&yB0fDEu;3#8x*e2^*sODVUt zTbU3Jq*My0uv)K>D?OqA`j0nX;cO-lJ-Kl`%TOhW;cVHm0aqvtRsT{fj=_*9hfkBw zkqY8scfyR8Mi>GCB#LfhWA{PmpczJiWwo(pGBHDEl3r0k6w)C8@Sz~mK@?&E0PPi1 zO?ES1!4*(J6*8e2LLnOhpkoWdct^orYvyeD^kBR9V9CNX4eM#a7f#LzFPm1OoT(k- z@g3{1YMB;2<&#Inu{ONQcAbf38%1i0>KXgK@d{UIJJ@*`S1VIRB}^k6YSs^oWoz=6Ig+De%MlmFNt_JJU>;Tp~~R0$$O z2?8WTRTDn;Ae13jPT>nXaV+O>CPy(9V)h%D*o^l9AMk;8NA_sH82JckeB)S-$G6_* zn2`R75Q_?RE{BKb7;3$jF4?y#&et?AQJY+03oeH&)>LfSumRl^9C=Sp<#bJZRiVT( zRBf{Vl1$%qcJ9F_^1L~bY_9xcaWV2&GONh7^p1j;)vJIkLB2Yhv-t; zU?a9Eo5NY0$Jvhw0vKMw4b(sylvtCP*de}Qr}_^eME{gt2|{=W;$yM6dR<5rVgW-n zR5zQq{sLeh+?k-!*dRVt6GifkrxuVO8lu5hIEXM|@M#L@6_ zeT{Evv9@5vccLs8bA#2F(Kc;MPbPU6pGa{?aq=cTp%b(u5SCFEwXY7abr-KROP?|T zN;z-`cUzIt4aiCgWtkvy^8aZ13+qu9(3E)vaE;vPS5GqSz;PVol5z>cbZdA|MOvfj za%%fxbU+TRJNm5O8lwr8H13C;CsIPXQ-$dMkI@bzRpWlyp8E_`lKs4ZdItV5SS4^f|-T4eo#s zwxA0x!6%cH4*@x$zQfu1KqB|*x~+<01qy~JNdvCl@b?|(v;@_JEyaP*Z+XHzu*g`v>1`_6`eaPr*RrRK?{HD8qqXO zZN`1o(_hz8EjhO(Of7%iuvgL7dr`c@&wO$>LBCT>6Rv?EEV3Y6HX=Ns6!bbIB|H&6 zf({m3A+*@9@8nJRfS_WmFQ-X500S5jPs)B+qI7GIg6Y12I3^0VA#C+vQhGh*^cafl z7#vwx;j|p%Lnc#{UWN2+Z#r6|l@hEwNojEo@D>P#+Le!ROSSb|O&JM$kPYVJmArEk zVj~O9G+wdVeWi8+R~m)-70gwV%%{08Yc(WF+^n?&7&-wO+T64JJQET@&R=4nMU>((jgNDi-d6Km>!lQg8xBg)&q%_CK&F(6G$sM90!Th;wzG`A#0@$-Pd%f zZ=x(iN5z)K+jFb8`nCHtPLD%3n>B#1ae$+>gE=@%u{#e0p$?D$u5uAsI^tA>Fe>3r zIxpB2r!W?&a7q1OTBCLU&J-*qH(}0Ewj;S4!%>*aFc@Mj0Qy1O^$X8?f?i(%5uN~_ zAL1HP#7x2>7@!8;?6EGZOSfJxL6@c%*2Sc>42LC(@q$4R;6SRpRxSSVE^wsHU_}n+ z(Cz2YRzE~+9iCW;6&>Lu4V(i4EkiwX<$swsfS*-3p^;s!RXVry7Pq1f7N5wG+9{E| zxSR7i*B}a|&^x115L9u>asPT0By;HZJ0ZS3BKFxJX!I3);S!!er!=9U&mAEWfmU$p zQtYhq2nSLm$k%>CASTTX#3@%A2Q6-b0?)!MUt3r=H*LS!Gh))z zPhFFB5?WckgIfm=wgL&+;0vU3oj?De1RNnm{~_*y^bO+lJK+i_0Tp_dzZ>GWObhWs zP|$M!ct*j|=n5bL2pmYTpuvL(6DnMYuvaf)m((1yg$ozMix@L%L?}#<9bp13ZX8Ln zWUm0Wg2{nnOk}~60&UqcD6^(bn#U>cV#E=ip46sI3-jjzTBYwyx4>4N3DrWAhtF*3-H*L}S*a z*RW&D4zQ0lTfe7Lsj7uY%cxqXHi;rwTVU;b{tPAx5Nq~AT(pSsnInv1Xu!^^R+I^B z4k%%`c4qI2E7&PE*2l}mWlLBf>b4xJ@A|738A^q*6Rhahm%-8wg%=D#zszUgfe0SB zR&kVMo`B9|i!pZa(I$VIB9!J`;PKk)K_{v4qp-skgbOjCeDR8($wn*fv?Em+Kx<`L zHQXn>1kwemuh8>H%SiA#uL>RBM0=gG5n~)I< zi1-$4F#olCG$Y7BsGL&L!UKI$OdyKZ5^lH~m8GhOwj9F-9>mNVZ)k|BahZwnz6waN z2UoPlDZyCOXr?^jB8(r6g?8}HJQwQ6B^y%JV79LCaR#{J(jrT_X?C*4x*}7H3oxCq zksr$O2D6DBj{yO7=U+i<_uU{$SNlC3AG@F51Nvxr;j z(&hH@ElPJ5+@2kqK;3Vqb2fIb!4AEAMagAP4}b1q?EbqB^sJ z-;~V82RF!ye$hIKEZkrt6iO>4dALJM3RkWd{o)i~P{r9FY2HMTgW0@GNHwiLL)^@i6l*T7*u?AVmm;+NEmQf*cQ83C|=cJ6uW~78S`Wj zTR3Z7b}HCO%%g^>>0)iADMl}30Sj2z0(wadq#!o}xbC3AiBPl-V1(BzVTec;cmKlL z$m~<3s2NNccCgorM3^TK9V3Rj+F5%pK?Wy@iIQGdD=iQypz9-s-LSuwL*0U$;ijyJz|mTQH2i6qbFGzW5WGE>6fLx$R1cT_-~ zq!+mddN5k(;uULftN7lg zi&=<46=ZGZTfcA#;92#r2?T~6Hq);{{RCB97wRB z!Gi*&Aza9?p~Hs|BTAe|v7*I`7&B_z$g!ixk03*e97(dI$&)BkB9x|(AQrk@u3*E8 z9ZS|@&1z-Ss$FYvn%lQ<( zBTJr4x$@hB)1+b3#kR9&s5t|89ZkBl>C>oFt6t5zwd>cgy(Yv-t(rA!+Jb%F&HH5R z-@t=wr3RClapS_1D__pM`SRn{qHDv|ySjCc$fX_Mu6_G)=itL5|E*okyLs=V&#Pb0 z{`<@9EZfVUPrttX`}p(g-_L)4&h6#-2j5HB*mB*02v%fVbi@s~6Lir4*l439HcVQB&4f-e+2oNTR%zvxSZ0Z(lw5Y{<(FJ4Ddw1DY7=IeV}hyX znzu0+Uu{vYDW{xfqG{)yWpbm9o_wM?=bwNED(Iku7TTqmN#d#KqKr1`sH0zUXy}vW z759=gv@Ap9rko=BB!|>E#n@^ z>g%t$$|4Ib1hs1Hv90!^>@UnV>+G}8HXFb%!2~0WFsceu?Y7)nd+oR2hAXbP#2AC> zx#*^=?z-$It z^Ugf??6b|b1TD1Cxb*T%F9EbVEigwT>$I^+EB*A;tqyJV)mURq_10N;?e*7SV{P-W zKbLLx*=YML3$1Ij{YuPm$1V5Vbk}Y7+`+G9%> zLnN$3yH-R?%ar@-H_SFej>gIB9%`d+Djm|fB}qU5iS@%(rohw=jmu0jf?rw0l_yQR&p$aR$!f3Qm zMF3PGi=#nndBqE4w2X!eEFMD|&TvB!wlInkD$RD}8z1*FXp^e_&}tHKmH&#!$&MY7 zR!LMM$PltV{h>{LPt2OJNcW0SPy!HDlm)hoA&g@@2^u>HV+uy`is`B9m%t3BFoy|D za{)pSpxB}+XyrU2J_{JQkb)4tzz0C=(H6gW1t>Oghd^k{Ti5EAILArOa&Ajo2}Dvi zpkag-2w@Zml-)xjNjrMl^PUm8q|h|i|H*z@=aWbbizr9QIW%r^B3|3v?23kqP6PlC z0muU$@<53InCeu^sD?0RAb=JS?4s-nsYp*XiaZ3s4iOE+B?RFLVNkD=tdfEe=D5XE zyy6sr$O9h&aEDCos7OsJP}e08f>i?>0XT&qC~=8Au#{DloM-4F zd5{lsrF8nlnm@`_?i}F@hM-@`NW8 zC%C#bu5bO)7@)X=L?O!4lh%P2DC}o2Xu$*|purDQy~HILdxweIffBYLrf5e?+F%kj z0LNIyF=!zSTG*fkioL@r{K&n)|Md`RYzgZ=$;#WYn6*}5k(vD@*F=G&FO@&sAVGTZ zik;r!4h6ZxC~Q$HVc1~=mjK2xYb7^>?hF(YMaUK?L5$<2#dx?2WE%-G*~)&w4RYvg z9y%)!lk(vX*#&Fp1nE2NX{~w8vev|s(EvciZyIO6`fddGDkt<8r%5BILr3Jz1PJ8;(pbmAXb83*zLiY+-I0o&Qg5*}C zcUr_4MG}-?gd#9u3wDqwK^z?bN^D{in*Ft~hfVBa8++K7_;n|i&FoEdf>ySGW)2dN zfD!m151S~V3zJNd@7=aoU@0Hc!1g&moBJey9*dv{&BWpsgwG8j@jw>M!BYr?*AMNi z9o*oCHt@R(Yv6Yq{LSxz8~or1PdLBj00%kXp|guwlNV2*!Fb9=jf@ zMV@(Xy6!uYE4B>uBJS1*g{?li#8&?Doi&0Ff}n#Ui~s{tV1f{q9|R#-|N7X^ei4MQ z{UUV#``q8Y{}7l^Wy@EY4{U$~tAyMUB#)2VDUAQ|ipN1>Pyz{32tW{a5P&rBA?T6T zSZfdfN>G3Xcz_6)fC{*PN&s?9@PN^G1soMd0e}LUw*?Nz2eiOoCqX*4w|gMiNxi2Q z!$n+Zlo3CaLm81Qlwb!Fm2!Td1vn4@B8LMBzyLES1Urxe0e}NO_=7+gghDukKWGCs zpan5keiKCr$pbS3^Z+y9eF5MDHXsB@Py|M>imb?r zs@RIE7>l*$eY5C&-bV(0@Nk_42%|s@N23u?m}G+|Jc36Ifq;JjAOr%T16Pm-fUr{! zRR>Hk12|xWMp%v5Xam(~jojFc6y1eGlik|~@O4m*9_i?Y(J5{tq#4pZN&x{!h@d<^ zV*{jw(T$@+loTm-qol;4fPkQ&h@hxoJy<{9z5m0x&wb8yuIuxCd356?8lr&$AW0Bi z4Dd7=8i@_8Ixrsd5=h-8y=u<<=9Ql}7IfC|66`Mjn38~XylV;@O2E=gQ5nrfAUQT@ zRtcgTcCm5H5C=AK57E_V;JU-MV@}%37rP7d=YDP#cu3+&A*WBHGxS;^p&0mJKQe^@ zyU+!TL>1{67im|(8qUCsjw^~x28%)up#BF%$=5F@d6I&P0X9sS7#h)lH7Y>}C;UkL zfi7`TvC}QePZLQQy=?nPA&H4Xc#^=7!winTtV@Ah!uYQhn#q5QjI<@h{49<6=@2`q zvHZ1wr!IhE843$3J4oWWOoVu{IoK;W_=slCQ6`y5Eoa@DmdYE#+};w9rVJnt2B1bM zY#^PBn=Et1pMM>Kl2j?F_YSgauTnLJz=-#;A~RurGjTT-M~7V5LL>-Z8ms(ABKB zOk_f(+!F)0rht1?P|dB-SOe6HrvoTB?1m#t2f2nd=TEiTn*e* z!OuOtbY)fS^OS|uuSU4QC6DBi2n&P3^Ov}+^q1Od6=h7O1$e5Mu$eY+?_RwpQ+38Q z)8+7H+L<0L-F z_P9(yaFII>3b&y!dMg+lMEfj}V3{o-I#l-fY3oQqXgH>&$cGL-1RGFbkFX6Vw$42J zY2vD!KKS$c^TT4J(AEJ}k+;UWLfz)?23rH;FX$zwXG%7)JG4 zqPuOCGWoNt^;q$-{zLBlf;|k>hT3gF6`9OS_a8Fc5qFshT7i=1p z#4K+(tE_SRy*3}r{6M@%vHO;kM|cIT^QTFcBVM2O44K4$CPt!+F_8T|g6Q$u&98d4 z{krLK)&wL$WBFItSzI|Z2z-eYd)c7Xs0wpWwa2N7|Dk8k`4GFmG+p@&+qa6STHX4$ z{l3#r@AL@vt664#E3UeqjPC{W)S~DG=TRmUFrIDC2`UpU=(_T=bZDV>iH4C6z3tD0 z`!Z9suU;Hyc6N9qyqGjf6*uvr}^6ZNV3>)kLhrq?{NRs;eijmOV7A{QGkCxz~Da3pj2=Q zwox8GY_*2}9CGW$*Pw#mBg1x`XD@{J(R-Fn_5P=tKQwrM{kQs~EAW_OMlQS?d>YH8 zw_R{-oO`=;c>l$NPrn~@|2FnP0T%V(*0{deOfZ$i6RCo_=X>hn;5{B-8MwPm;zhHh zr5REHhmoj#!rj?qJ815zi=z!b66k=B>j#bX%nc6~6yLAS!Cw`}wb0=(yDkWS#%aL$ ztJx2BxgTOB$8<(YnFm~+SXYj(YD;;jHvlff@x&mR`@{F}`@N9$-dpWA390jjrqm&OnaM3<@K)i8v46VmVVPk-nFCtI*6S(yqJ~Fn--^ zI*n)Q#W4QQ9y5sllqqE5wb)&;0^^8~NrtXbM26bv+50JDwe%U))iHJXP>pf2Mx~EY zZ?4AJc=?Ayx3|GOZ{t)OCo~44yfR8OXi%pmkme-g%w=p>V(udbw(%bKEP1u`rb*58 zs2Q!n?6H8?3xP8B>f?)h?c;Jr4|+@Qj}2|Cn+=)HJ6K35HpBi?fEJrn8DSs{;;APM z!yw7BG{33hky4HQg4*t?-8a+O==x@36ihh!ferT^95RZ2jSPSTnPlF}rP+5cUSM*T zIUt@0zeG732MFYSn8@{$XCQd0!*mngNh;`7;XhtFROb{99CenJT1{v~n+Z_MsbUm0%PT;dJ@0#!~(Klg7uL@#@)U{#}yEl$vWo zM8{nF%6~q};DYOYdb>tvm-l5?_}5u&IOeS*UW&H!??UXLcDG-U1q=nF;IUx ze6}=dd+ z*iC=OnS3Kg_>jEMXt=06CdUvLffU$j4oNJLVZ??eV&P;a%=9`elmd%la`qvZ_F#Ox z=jDX|pp}=QW?4nyjCie63(=UZQ;(l2oFYS>ljF(oYiyV@G}f-w)$Ip43G?)w=qrP~ z#V`LjJjr}{_z|AUjCfMM`2C;2l!G@l)<_$3_w5_oRdmiD2a+oV$aicm_=s%5a_L)z z_!yj%b5#?~;w~EV@1fim5W~fK==IM%w}h_b{j?t?;j%>2chXJoiH<%VUUNKSC|RHz zE;WgdH$gzgdp7N2*ibTs#5g8#Ki8Q}`)Yrm%vD2%hj$gS4qRHEx|L~iSCKfY0FiRQ zRr*Qu5eD^$qH$C==elXTp4)bl%VJacpPosiRwdCrmYRON4a zkdqqfFZ9`x;XPR$-~JasHZl|&V$%PTwSyFR;P|lF+veqG+xduMHZ%%@sAx^oHe5u1 zd}hOjULx$yG^Pd-zX6Y?LoRIYnf>q+`u7XI#Wl4H zrfeLjetSVk3m$dc^-S<1EEEIv-Gnv0fJ)78Rky&Ra4>%c)Qb#tS%wB;&O{K0w2T)V zpTJT8To1`SY_TbD^qs!!1d!R9FYVns5krZs(+?sIg3XL@x!j$b$V=D-PYMUMhh4xu z)A)E%CFWV&8JKTZcJ&ktF%JVjg4uU&8dbo2nE&{)VTVfx(c}dnc|VD{7t;kjGTbu= zh%n&(4xs_5=CQDN!Oa4e1z;83NRF7E!`t)25qk)Dm(TFmjk zA22TNvG3Ir_PExn%HyL?e|XsabT#{rlK_d2FDHf%qdTeNpoAgU^St7w#b#|+taRT! z2B-l$W#qzgY8-3HRG*;;*A{@`-&Pr#)r>g4O#Sj&f~|g&eHH#EzQKyC!jy8XywNO_ z>5Rc$J3??_rshRde0HV=-zYti+DR(cJ+UdtE2t2?xHuhhW?tMNI%O#KjZ~hLhSgB` z9_T!_qAV1Ykoqc&TTCahd^o7b;!&QYG4%+6%Q+aO(Rf$;DGfJ1fp+=K;4GRPz^IE2 z%73%n3RX3JzsWW?-S@S~HUou!8Z<5Kp^cj!OpTq;U~hs?n3w7v4xaeB5}gMC9X6bK z^#=jDXHOpHE!Oyih6)kQf_iKh&0KV*J(c%Ho2&ei!xY^6*L7wCm9+^-qjP_P;gY2@ zK)Bo$8Cdy)G!~7=InO%-9h}F~1%%{w7okH6jbX)y*4jJefPMAFW1?C9;Ma1`FGLGe zQK9WQ=hI*PxQM<6t6hS=Uo02rLyj81l{kJOz2W0b^thEb@;y~u4lJ#_tKoYqvYpY2 z{?-26_g|=iSI~8Z{uST78MW1W0d>$a05#TK*cpJAbDxRgZ*~r%AeoQt!hlvN!)4~7 zP|%O<-p7D6madqe^COXD^8 zVl?3#(x09voA%jZrzB~0)1uYj=dTIJ0t-buy59PVWl%jOLa>a^FLG`<#GozT*nGz( z7=Dt9k_DWMN=j59wf2EUef;ny0L?)+pAuIP;4PP3`0Czqb5&_np{;@zi(0toBPbAs zhal4o@dr$5)Jsr#L*9v3e9VtcpyAhJ;y)3a7DE4(zTw(_dF?mfZ(_nQpBbUp!qjLp zi5z>7@@o{KvONVpVOqZ8d>uemmgUuBAN=9gSz%JM)b1P+9%!C*uHn&Nrqu8rlw*Ur zfgj0ZTc1PEr|?O>WpiGy-y%Yd&GSw__+kd&*aAlVL~5>?H4jCg2RayS^UQ!hly~s6yl$MbS7}%8X?@@y@6V4;dJVm|D;4pL+Cun6#VQ9ChYBU_ zjtUnupa#V|*nd|YlsG+X3NFFC?KBz&SI6bu6?&}Hf}2xobcgG8Y;j*&NmJ!1Y%1oI z)8WYz7BH~(AbB>$x^AL3JQ%*Rx+Sy%nk0w>3!O$<5HEC%sjXP?gnysT`UeC%xq`Xw zDIX%1Ga5X^mx1-fItiy5@#icv(lw&CxNX>}yqok~QzVG@4*FGZ&s(Kv8Fe(+bwb2V z+dSA|Jb#oe$SN=AF$Pfc|Ji?b7G>2H(hB06#ZI1;6`O7)#kx)7#%h$2B}#ERfaz8X zrPtxwX|Xvej@p?TnKB520XvcYBzMo{OK>?q7Fj)*CUA{G)3XCo5>;%i$=z8ReKG*> zxPYBU;hg$lup-0giIm$Gm)gd-9piX64RU5H%dsmJ>5qUEou!FCZartyQ3t_nW1#XW zb$V5s7V!t0k}SLuAP%c2ZGET`{HlY1za6gtzYhlMg2d4-qp&ZvC57kbVpZ z=T5`Si8P=jC5Nz`h{IHY2mF37K4BY7ySBJ&>AB*YZ(tuczsA?zS|;^z%475b6Mu$t z3g{qxu>{2%SiUFR$AqY)0L?anz?ZKHNb@XhnQ@pw(NA5~CR26MQa!%8<^qG7i<5DQ zw+jBrI}bNv2=S#JwQmB-MmFdlx$V5h=znlelINfCQP>2&gafE6>pYFowG#~B9*vNl z6k*V*n5b?Ab*pdxK1^#mJ{`@^Qz`W|&#_MkgG|DbB;WAWl0sOT7tTBdfrB2A#?*f8 zK2qxc;nd@0aq{|WAEkM1F;Zyp1;M*K=0bHbU*{zD=p=~DK&lIMU$9o0mEqWz-JfXZ zRVTTc;j})j<&+zGQaG8%dwiC+1_5h&y5wUnCWmGyt4QOv$}T;2=}UaStn6hgVe4q= z*?rdT+Pmk(jzuoj2d^(upk^fCX+5orNT!3|vUBZGDzC(S3yd}Yc-=TpsruM6tMnq+ zwjV*H`K~KUEm+&UtzJ-bVL_2xptbvp-zWWwl@jWx%jICAB z9Tb{ld1|3>mNKdB6AZ_5Y=s8Z#Ux=^YXJE@cN_qEixW2HH66+Dl{s)L3@%Rj@5QTQ z^X0QVQDw)F-}#Q~CQyZxxbvGGM)#P^iDT7KOY$m^H-<=)!m&D{tp0QZq7t>779QIT zZwYwybmje>E^A_^2}F{>;>t1tU$6L;ABPHRh5|G7Tk(}F>_q~>Kqn1ByV1aul9-zq zuX}Nr|87V&t2kyO-ur3czb3Ggi(Ofy+{pf7n*ulMwRFHP4hb5ROR!SZN#m6g9Y3%X zb(7%<`tttGWgtd-kpd^pZT}0*<@PgrJ?GNFs!)ktg9|@IyLScgwE&_D8J6>p=dS24 z+wZqe!w|Txk}JwOUxgc)aO2_tz8w2@haCEaO-<;D1tj349@3Ry_OE9@Gw1 ztp|WOlS&R{P8xPM1eR+Alhe(N9>z5crNx?rdyAf~gSuti5;a5T1ZnSrhNPyA+*^g7 z|6-l?5j}kbGE){3Z^Q-xOyB?PY1*agan38~+jrFz>U3|;<>864&*S>JsGX8;WVu&a6uO|ELdG*wa}F* z5Fta;$W&{rW8AVWRLC*=B$KByA|BIj7GHUn+$O2Rff?zUs2ugiB;jVJA!Y2|&u0&# z7AG^rjac9u18wcD4^)G4T5S={C_c|*px2mqYaavFu%Wibfz@qJ9E4QA2kRN3&7aB8 z)LIqFf2-&i@#(Bh@gjqkbM=2eKCoBW2Ge=@1GTrIY}qJN4gWwJM$u~3Xz6fPxEAFxpwi4Ga$E) zs2s;bBXgn%mo-4@Pet);#HAvZTD_t zG(yNwX%NIHyQ1!^g{jYNQ;tg&4mL%n-xx>e}RLJ36O%EmY3qe5z zfs&I^2<=n%TyC9UfpK(@*(UGl%@Mh~yt1~o%Ya-BlFsirMH0mNmN$^(4KGgJQsB;;NWHbg+Y%hAv5gc2gOaKS>JblE)ZtZ1Zcy)PnB1=Draz;?kQ z#<;bSp8Zz<8`byN&3&nV69J%dN7y%QVu{s5U^{fWCoVH^h}$pRbbGzGY>HNNb(lm~ zfAr;K>7bnZ0gcCs#_^Fo(b<6mgLf!RQAn8Y07RMq#v4KXFqym^23NSn%w#e=(Q|ri zR>%?b?0bvw!G{esVQ z^eSkZqUj%rsRLmCkF}3APo)P?zz^ybHTiY8&KCOgK5-oYYhb&*byuT?oQsyE%`xB) zw$t6VcVA-9&Z|k_x^BsJ=fAUYbBwQgHd}+P$$Rbs)+hBHDNkt~NwN>CxhrqLr}fkk z^rY-OeSa=LO%AB&~R1Xgd3Q8@^xjv7(ps)UIen>kH09-zwNXgFqVMak-$AZgi! zT+>}p|MyDyg1a-6LY0Zax0NSO1JXm!8i>Tnq!FRQ>N4g7UZ+!yzNJ2l^jn&4@|*d7 zTHLIhvj&r>oB>3d3$Z*wZLZ8))O;_UT=xL8k=C-?KsV-!2@;cNOf%aB8IWpCKRTo- zXJUdgFTBY*Zu~-YPZIeaD@IPgDgQ0a80RB@n6srGkb7kMs6O+pY_8Lh(qK}Kq@5jW ztkiR0{xhLGAgS)S8{w60l#8ABobs~k!ZwgH4fGIm;isO@f{johiGwB@X*T6&!!y}a zrcw1vSBB)$?&u9XTMO2(@PpwHX`!un3(K;EpXnyMLy*Zkrxc!>+hx2$+_uUh#a+@i z+=GS~L5+nf3NRVN8=%uh1$yb(&n2LKM<9K4|F>^mDq%Xvo?KUEz5!FQI8+~haAT%U zXdpLUH` znbhNrVTcb&mg5~wm8{Q{yfL19NTsL$*GDr`11Vx?hfE3e5Por&lEv~{IDmA0{S8ON zxeblTc&u&0q| zHhF%?a+bgk^Vy`GlY}C5>>P{a!1e3fn?7D?)*NSjY>qBht28^`Oq|(zV z_N#>Qmg(`<)>ps7K-um6h8k7|wy4*CmDB{{las{VMGEO%^k3*6w zq6R&)lHFXA)5q)5)z$__ZdC3#x>>j)?CG2>6a@v>~|p_x(DP* zHlVQ?ZNi{|FXBbOTF7~Uj8)?fI+Rs zRwY;G=jh$%-B=jMyJ!r9jcugljhMMUkJedw@I&N@yVd%wO(vUWuW-`$(pUF`rmF^M zYF;!a%E*-Oh{oVjAwbk2mrJBOP=ZLER#h-n=i+w|zNC-uOYr>P+m7Rq0f;^pR=O8h zzI>Y#Z(ug~{Dibyx^{7x7wyzp^eN+FtH#@D#?olBQ4PZE-3!?`BG^nl^UE%%?NZQl zSMfq)eP;~U-z<JFZf(biFRHK}6|)(ANC;SJ6Odas{@Y^00(k_B8c*j1Slx8y1mZ z(U{p`T9@tw;62|oUyu}Xo0xe=H^bDN|8>x5)1S~Q)(1bemzqQl`L#sy1zv7689t-B z<|d1(7nQvtg+&JqQ@yakHZam=mhmo?@N|B)o|Us8lEvvAwQ0xgLJVMyUULEWrv%0` zTY*tvo!4MKJF8M=DEqHf)Y(GEa+(H-Y5>4HlULmYgSRURj`x1@;%sQI8D%@k!6L?A z_ZIZ$cEGEY8YAuxpmh4q)#{sJZEqr?hu@2RRkoqI)zrB&@Kt>aEIo(#@|!j;lY`az zyE=kM{gZqAm5$RUY-)uYr`D^a5PidSmukXn_8AL$=3zD|o~}iN7G`pvt1tk3$!^*# z%}k^jbPH-E<*R946z#XOu+0ecqB$xTTf2x^vSt7S^)UizHrcMA!bDpiE;HkFh#1sN zhO`=N-#Q?N{vbWKubyqY(k~&4s|?%f3OnhUnLSV!5Bfw?66v16p!qe}H)CbX6^ zsD~3U2&ykJojCIDeji$8a1d$z7yUPEI6GC$8VTTpC>VSBn;RD&QnjLnMJ0~YosK{T z#Pl3Zdq^VZ1BMYXG!uHx)BQ28Zi@$u*brj60h*(-^2uygyS7HxS|fY_$xT~NL&uo* z50K6nPCB4ykw(jU(rR(zdwvx~JUw3B$z)@-=FS7KuI#O*wS~#mzE>}eatiJpW&4~yt{dq<5f{0gSkym5d zI-X{XTHd^tbX@WM>qcoH5o*dbHv(ijwo|3R8M7jH0=R@NyQlsV zQB7ST4a@5a*6Ng3%*kA+rb8~7avT!vr(mD5uf09>sLDdv`4+-YVyE{q4 zFpCQYH&p8-bDkEy{UyBb+2Y4)-pIKj;m2r%;2MOTDQ3RIzr-#@7RPRP{z+gpa0xXz zK5YsdvfMLC#IHeJhKkS3mYCK+Hdx^0`I>Jj2P+Y;9yryQB`qfe6{hi48(jF&>0*(= zBkrG~jj@Vo#TSV9M6n#E_W~4oxV?kV;tr!X<%I zsj`wWQ`%>wK5nocNnIehSPDe=QD=k3jqcK&iOEf<^H$=?@`bjlgYrd=CO_qiUFeS#AHn>Ca0q{C!)d&On^4!&HqB=Cn<3-!1fyM?PE9 z?jeE@;?WQgm-h5xMS=h2J0&94SE-|q#1s8wxg(tZ7K->;gsq{lrm2NzL}MsDtwg8T zK5@c@=)y_SXPFCkIgdMdyL+vkT*?!2UxLLkcE-)1xjn ztBxf!S)onmO`MxKo?eNAOVpryy=Mw9MXfyYA1cT=*$zR?o#`JpNQl1E`X!s)vfXVZ z8tn(FQk{~5b9AsIQ1()-&GW2fJ!?DLzJJ9U+xj0uP|r&uZrwL{5k36ZVEsa8Y6hpR zIW-++<#z}bi}4%CxF#60n;{X;xO_b=M!h^u?0+;cu3x@<2UpVZ?}0r>3Q$V@5~aR5}&W#R!n+bm&E-_(igUTlH*HoSa6 ztnI_(*SA_Dj+^SjxV6dKK@J4XCjLS8gpxRtH1PjLMM<#Cx~c@^&6hi_bQapRz}^oV zhC}c{MMIO^BM{0s;7ct^PxzELXhB$C5~-fbocKFBA$I_rq=u)S^p7jI2pI`J-+-N5 z(VNnA1R^sg$yPTGm~swQR$dm1X9JvoZ3eBu&bT2NET~JtA#4FXO0<$9>a~p@H91j# z+J}Q&=`MYlmJIrY6SW0};5wlhJ1i&twe``dF9mkT3)EJ(I<5vOxN(!Izmv6#$!Si> z(0|hcV-S1Sp5%l|-K3rT0WCFSw_1A=3AE)+nD|lKoSy4vWTLOS@z*z8rW2xjClIirl8zWwGE#d!R5+2?xt)C(7J6zF@~bj z@NJzHTf9k=DDO(g5qk=s4_Yb>Sev|QeJ#|Il&-dZknX~M9d5@BAdmFe%I%ZjX?BSG z@NP~~L(aa>RC&R#h)y49799sb#b+$X$V)E1^{dh(L@=Dl-cJrAR21Oit7^iZB#nQa z3pWBk2mydjJoj0wN4pz1)F=Q3k|spUIa%BZ3jZ9fXP*pr(b9k_pcj2 z(?;Y}svUhTlI22_<-O24rkLbLS1;i8twsi%6uh-Eq0`@O51LSWpRfd&aeMVlVaky-$N=20S2!a05a$`?uHER!j1{JsxvD+9gHRXS&u)HBHk@-7az5|bH z*T_%)!U*Uh_ujvpy6OfX$;(0C&B6$ShzP&z*Ex|wyI%Ie|#8I!}A~yd@ zhV#Xs{kA?aA^PR5_jgwn4G)>uJN9plQ3eRo%J;Nz;Yz4u3VnTh&bLN5@JwMDW=xT< z!sOl1v%&e>HR|SH`1M+4Wdc~3i2t_BN|vH@8i-T@k3Hd^2@`x&K!vBdNM-1Ln9ww1 zrSeK+_q-4+WpWoH0SNLPgWyOLW3zTw@gAO+-Uj$N%sK*NSDDMD2q$%?- zvRtxJ?TQFjO?Z%i(Lt)nHEmM8i2Iu5Le|1%%JCS-#Vjr2vz|REp%bL|49WE$HEc(- z_94h)H{?$}Z|hHcg7s7GbHaOk*GM3~xGrS3xP@@IQ94wt{>}1u#$ext7Sj!+sZQ6H zP@%(lC3^4c8?HL2&D)X~<+=<_2*G@>o2G(niGxo}osy~?%YMIUY&wFl{-ok;=wJKQ zbcJ=1+-f1(N4n1Af+!hKIncbEl>z+Q!tGB439M|Ed;>l*yL3>c`+>3L)c*X$B|24t zIb8FJc>ay=*ii!hP_o&jzJ`$*lW-yGO``M-kvp8(wVi`(0D{**ce?vRoMd0%<#Z8l z$%=4n9J*Av!a3h|PNx*lfIe=NN&2fb2}15Svpk+XX*E%~#? zmhmw!Bws;0Wy}vPei1ivv3S01z$oPZacEWL7psdoQcYQZoDhk}J^DavR`fsk$8YH8*&fk#yH4^^BkxT#(CafRIvN2{okqm$BI(W|ID$wj<)6rP`+%CQY!0TAL0 zAX?lD&B@bqKrnum32g>E`MLh&F;KGfsj#Z6O2md#6kecDKx`5CL`HDVxI70{uFAg> zc>lQwBvpt}Ddi_{WecxZfKIyPnIv{b=>RC<#}bJWx>$mI-z2>@Ag!EHul(Tg8TA(j z8;c$Tc+nN00tMt_l+LT^cR{_{rURn936xApmHg(=Ny+K(I_Z$>gZCemB35HYMtxc{ z{z7LDa;cJNZUxKI$jnzh+LrErKne^N$Dp-AOu($zb>AV{jM+bwS7(6}brES;HbJ@( zs4Qtw9cu@GP@Nr*rB3?c0o#CwQB)DjW$1lbB9FWNuW=UCLf>Ga4KQnsShD7~=yZAW zz3!!2q~$SyP{DMD?V!8sTfNx>0GLdz?w*^bNxEI=9}&A z;FQ9jV=9*6&J($yQ#n(=O2xDSukWV)x<8KZpY7lud%0DsG-BU@3ALQJD?Q*a#B(kK z&40TCTdJwu>k}7#L6Wxx&lAG{n}C%RpyWSq5RO(sF7Mn>W0D6sm&A!pw(L#-O`Q(( zVbuQRy!x6k9QSfO=J>A$=Ug`DZ-7{cTUMg@>3qT{Z6cLl8K13g53tF`ZW8}_9o9V6 zEU}H(isKLP5L&}{5RBy6NNTBHVE@WH-UuWrdh}Wnq3ZFP-Jjgbg!~`n4mG)>lEiXV zX6ZD~>Urgz;K+sO~jp-mUyuciuJKdS`^4&k@ z(()bBERf3Q!yEmSeF9oXGg?RKiNT$D+yx`T5{*E^dG33l(BXvaDA4f?Yg_!4lzbRJ zk~~2&d_a(9q)Ot}&R0tlw-th?C!D6JN`3fO>#0vN7n>4VtTa?6JfcGCSR#IStEADz z(57s6c#=1K$L)H;6#k!s^SM#fmFRM>_P19U&hsUiQlwP=@O=@tqVCl~(f?gXUt@{< zQGfPFU92&+%@!zPlWOEICDU9uGbocgj(AdHgYiSWnL`NcsRGw@F4ysn(eTlk1SBbB5xU&Y-bPJ^C&Km!3>bD=YJ9-ok{xjp~V zX>s*aH8n7o_sg|U(HW&eZ9qu~ND|t5e5#-`Z=9Y-2yF&RM-f`QTmVZ=2kNb!Z2Clh z=kI1-h0RfV20cRkR_!LVhG<=N1e7pZ1(m{>D|a#la(@eRX;46t`*j%hDCZ~CP%KiL z#%(cvTYaSb;s7Z8M~$nspNxvYvftzQE}&pIzPg%VToR$U;hAyiS&os-)o_+m$<$S; zymWl@Vr})+0~z;Uo=_3qn$(rwvR zvX_4XjlJR1PLEdGisaLsL;<5J<@3sBo?=gG_L+i&!HkXDtTV)xu3SiEn{7eD3!TLZ zJvVEom)klAsr=Yfsq*XQ8>uOq6_Y8g6{xuyz??RbZeP#3-+edUj*qz1;9g%mw%ur8e3MhM3L0;Ge6z~ojrH3285rr^Ss@*9b9{rpx zNZqG%1axwdB|5-TE|x|eM*h0?dUB*w_q1;DV#(%T=`P_if21#VYE(r??wT3zMSf`K zD%DYH+&)*g(>B*TfiVAcH!$-nU9zXe>YoR@b)_PZb5+jRO7Xr_i$O&;)-RU-IUD0SMuuU+@$uJy8_1{V ztK>b>jaAjUOBCvBN~eN1-*z?nY9rjM&*s^$$MdLa^h|dU zu>uryYVk98tLG-j_p}Wth_jLClYCNAC}nf_AmO<}2mWzfdYp-arzP)tEO~rm^W_4e z(J#AwtttJz^WRY`{9Be;NyVGjJcFsQDRlNj@%R9obAfhkP`P(aHApjV!lh61%&3@_ zu4QRjv$~M)aUw`kEVS#-Yv=Lf@%n;sMF`G5p!Ux%u2rn^+bdSaxZcQ4gYyW{gP+n5 zN4esp2(XETdKkEe4+BgQHPh zDs~}`l}^_$S)PeY9#z0>WxHIzTv2{9G=!f7lyddGM1Ycw)ImWnmtFKp1ok zFUr8{{h;#k@!Igz*1ygAx@&z6GOFU1E|$Dthq;4uq=e0!g7RUck-U`9Xt zt377fNEDgCJyAPuFS?FT(1FCv6g-&p_TpC(%l+^3_Sv4gUAUJ$UMi|I7wvQ=H(At**`*UCOEnrNsM3Bx-Mcw0`{Ma-ia6t{= zb5`+Ho7SHTk(z{~DFru#LiuB$cHqm4_An?@Eg=ZA4&AzWA^AnSw%@2IV$^Azlw6fa zn_qLgbA09@7>-%L3`j}U-lZmM>TdcL`wNT>r8%aa*?W9Dm9j<{V*_YR-lPe&N)^Y#_lW*7M*v#c{&v)Y*HNV(qQfTnxpBWwf$r_y7=|7J-PyIW52(L zsvoy$_zp0yJ?3)o!g?mJrxe6b3v1u*4^RH9TK4IAK!51M=+d{P8bBam&}35h`TA(0 zeBi?$_~iVUNFm`uJ{6lIL+7>HFB#$EW_A`k+v*2V%>fco;s@ zfHw;`%o};7+;L!7-7kBN&mbW7f^HX=ycU3eP>^lfL=}VH&<_xE>7CPwFVLO;c6J8s z137ki!?*7BG;;i<8Mh9F`?}dqnaie)+zIzQ{71td8IW^RJ>enk>Lq!`6Z!fpn-*P) z6ZK2>p3hjOE7EF`F!o~{;>U9&@F{EkjxmLU+!F_HOln&fmH|& z$>h_~AJ$sM-2e4f=uO@*P2lGjoW*rO7sgsNaQCCrYU$80muSfP0PVr8Fa8?cfzadr zPolng(_?%g1PhN_%l+B6NgqG}NM5M4rq}v+Yx#^qeQHF~sSOZQ0iYw`cfepJMuS67zWy z=^ms2-uW<)bi!A2LIcw`ln|fV#RBE#rE9N4AF6E{zsARPWjIlmtW1h0%a^p!d5N{ zFY8XYiF^V?pT5&&A&pDr#$oW>*Dj3lMKPe~4n{@sSIT?T%f*5mwDiUP)It?P@soe* z`4~s}2>dn+ll(+?d?ii7tZx(r`d~Vu%@)sXQaij2S7#j&0R5ZS0o$pWyFFmc0TXr$ zZIfc}R(A!mTo}?y;7!70xF;G(`TKV%7#iQu_(Xx3xkr1SEdknD3;ZX2wX3pDnjF zMzk0?#uOISxJgRvkdf}+>d)x2X4MA%Om0U*m22VI`r%t#kpq@>*4+j6;f-=b zBM^n8pZs`E?pgAYLPRkcYP=HUf7hNb&JqqcWY+Qi6JjC0NXgJ+0C{oypznorh`J4s zH=1Z6&i-l4_V1OitU9;jAbY)_HHh1W6L6+%2;W{wjf0PmQNK+;N%$$l(QTD6kOd^3 zT`0f+G+Ubivop_z%0BK5|JtX-ZR-{f`kYABr?!7)^2=GIT^#T1wMO;X(sMVvTs+u_Hny9JF~%HCa?UXLqe(fF^+| zZ}%It^X&X})A64d0>SDuk>Xv^unZ5Ksr3o9K1RAVvfj?~EJP^%3)n&$l)Myzo6RppDPfCSLXKyjl|@k9#@L{~3MSj44Fd|}2l1vZ*>pn3Dd>x~dsJM95w`@pAN z8Kxtz9dfqfr$-4Y0ZK4SR-1+B8iULKaCI#an9n;Q^dNME%1b_gw5QdzD?E8}?OXr7 zzs)&0#+$(WC#T#;46S_qx6X?Wah*6P+js-u)*#6lD|C`QNYCmJI7>INvZ^@qQu=ui z_xn>XwXTb0;&@yy|Ipu+G&&PJcgd(K+Q$DaZapLNwaB<^UUudOTres=rV@K^U6P^% zH{$W%y`_6aqW-l>(=E*%ofA@TM>C=L;y(AF|MI-@RrytI{zbrVA942m7!ICLtyc**DV6=y>Si&CVD2!l zszXi^h&y9!bK%0q=i2{Hwawn)4$+wFLXuN#1Ww`(3nypZDlY4Y^^1YanvcZzLJ!7n z=ep?lsPig4xffDbQzC0j$D{6zK5?A7T@)8$jV7&wPEHk8oiG?~ms9oDN&$)lt`j_| z7>hS$R8dN5Knf7OldcA$1l-B+G?QyBO;zl|OP-^Ql4YSLTXr)I-JAP^M-3J;W3N8N z9DIs~6tQ@9933}1Opckahqp(EiMAzv_=dDCZcX4-)p=nj8MxM`5^_h9N!>`^89DXW za?2BfQzTxqt%>Eg_d&qR``o-ko9ITCxR54bXiG>sPw^as&tsdboHHTS#yy1NVN>1? zY>#zJ*VshyxqTWaXK?>;Wc`Y`3Cg_*>lnAry}81^$)T{f0myz_dBFaJku1WLC73k# z$SsKf-ww{&<(;AkL~Wh!57BB5bx289>1b?9409+1E?DxQ9(34_Z-4TGLb@H?3RxmJ z7T+cYMSAZ}Ahu?_M_bDPw(&nA>$$^6rM82lmhn=XP5)(fqc7*1jT6+(#?+=jWMw?> z8X)yrs=@Kd=>N(f#2p8Yu&a*%Ao{nIy2<&dD1sGH9RXs4>AZ7e*gL zcF{Xb!TN1O_P7xI#O(G*v|k-B!S$B2g}O03v$Jlm6FQ=EXEgrCa>M)PXNuk6y!bz<)?V!e@Oph zk7mAnaP1GQs`(smAC9|`!)N1o{oZj4g>fu!ooQT^iTaucd@q!bZ)fwHhcz!9$7K#b z(VUkU14mWTC#;=NuJM!7k%E8zkD|K{YpQSK06tj20@%pWqZ>x2Fgm2ABu6PA>PSHm zx6v?gAPvGsiGZ|-SffK!N|}H@BUMC26vcQR-o5|r?{l4VuCx1he?MOgPZabp8JjwD zj!WwTDsue==$2F^KWy-|4Qy=r+YE1iV9w0WC@9}WG{w+l^bzfozLEObS`Os&E3Ua zq62u4%Idjj&@k_Rk;=#25GBu1G#fdeKuNvUJ^g;%eo0q%HxjTqe^IXx0PR*(9_H1F z6m8-Vmvt5&3q--7DE6R@6|*X>lhXr3gx;G z20FuG;%vE*J1p{FxI>zc6Y5R1rT78>RH%pP=G zDK}GV56=T4`FBV8W`iONcAeZ%E;~v+pNkz!PkKAsei`u+`lKOBv=jo#@UV#d=`!9- zXXoRh7y*JTDvDE*%251H^5*$T_#^+jlm#+YE zX>6F+fdn7Kr#XhAoI+8~!&iZk3%No;%eoFkU^*|zoYYK*`tQ82gK`Z58vh6g?f$bva0!hif<%&$JS=O zlea;>Ii*43mq%^|gz%W55wm3P>4Z~xCCJH=|7W@UBt7k1Dhf%0`@a@kdR@2vQ*ekS zbB3hO8p!DDR&2rmXx3~m{W!2qNcolZyR!^(ObB<)F|uM(6z69e9a zYo*hJIETHk4pJmei{5WSdjOt&qHsQsU3#;fadqt5@KXqA>4hHuV4D-ywrW01nd^-U zYliafy%Jc7i&A#!=VWlNu;hUNi5;W1<`pH-NZCXe9M`N$u+&2S(B0CykiV;YCflXM zN=UEEBh&I~r?N^{M@!MdHLNy(Ipf#*BiP{N^S83Uk27OU-)`|P;gBO|0Oy z-a(PDP<_OpO7dxR^17xgI_nfO9ZEg)A3^VyguZReJCqAId+$4VhG)UrCdP^bJfPx0 zDyz9tO|KE;A5N?AO{ua(CkF}dQe#7LFOvJ@UkN%sEPoxTw>yA}Q9{EGXgZB%t*kC4Ge zp|B>s`Y%4j3R1ePORU*Z-25bDW?9W1{$72-8XnR1qa_HRtjhGwRR@g)?RA*`zZUizJ9}` zE1kEL20x&srnsYcvM@vT9U%=)4k{U>P~+r+Yw7XNBI2ff+FGLI-mbhCERpf)=x257 zIrINu7sjAdWG=2k^hzwbV;exbLhQSY--gVt{#f%!X?r!-ulqlbV&*KE;FBsiW! zIMI@M&XP$Fhs3gAQxw(ASdrtvVID<_&TsMGuuWI+i12=CYP$0l5HE0quch*F z=gmFZS)if4X*xMORL$f)BBGKusq~K5UGp82@V+U!`V6mb;q&);d$kQb@l81H0o)Fu zz1n$1o=G*@`vHf-5EA@x`BIiJOI`FUl!ir>s{Qt2S!@V5|)y@rf zl&J>{r5!_cTV|{D&aL!wQ5#q$#8Pv_dC|g)@y4g{om=76S<-vXAUcwJ)Ad0#m5z&DFk|zL3m(2XKe%eBVJ$4GVD_GPV;_!d7SI1hfhyVbSEASo;@&ojcQ6cjWhubhA}Pc?aWUpFVORR7W%I9=H#c8Cj#7j zQs(|gfi0QJCmL+(m>It#VwPG@wFSPubU4%bUjyHjb=c0dHnG}j72f7cAHT^)wV8<(?@LEnB8SdM1iPkaUwL3SVA@A;orRV@mP!*_hO$c~PlUR$R`diQ(ZO$$QP^Vqy_A zlAYL{o>yYxzEM4Pz0+b#cH$49C+z3nzK*kBxKuf7zgY8iJx7|jZ#gX-J7e{mD{Kq{fktn!74yHU$MrQy!sbB0YY2&SR|hU|g&Xz1e=Pt8VwWz9M+2?XvqV z9VS#fo+wN8JiD^`PsNfaTxsXJ^ejZ8bk6E!)frFNS=tD(1Yy=}&Uf|uf}6#Owu*r< z)vi|?y{%%&gPsrj+FBxptS|mbR1D}^qi0LpB9z8-9sF!#FBO|^m5Rj@8y0U1f8BkO z8x@hXv+DTa|7B=_4JutRl3o6X?b&~o9eHEiwbmG1nwAdeX{MKK;G6_xjm6D@BqN>B znG!4v-!vxMZ-`Tvmu$uBLeIZD*jv_t$+aD0+VY9p47XFbMJ@nr0e`bZ{_Zv74~(;z zW<7aN9lr9D0PJ2Ql$8141RtY^N1QAy@lW@xk!?*z+=z0H$uVHkD7kX;QNPy zcx<6$CeE!>bH!2 z!vvrIx~1$QIxcZ}Cl4UqG#o0i!MZzmLB+xM)=Y)g1(Gj&mz6h#dqOR0 zSnDBkgjah?&ei|});t;pTh5Irs#l@i(p=crnk;6(k^5YoCvx1l`su4V$VvwX;;hlA z$YXZUyh(=Vyx;k`%z><%j+2-R?&0V+fE-roJS76bE0F@sSxZClCOeD>?RM*#>Ycw& znnFja%vZV)t%f3N_(DE^g9Sd^;O{u5+W<;FG-U$@nvNc)W%sTV@6J^e07GvGE zBFfrS;IEO}!^&AI4n5qVl?`xvBeEcs0n*6qfOB-S|9zLp%k?N2Pab)Cp=>;Izi&LX z`meX>iCV77cV-G3H?A>WZjTxu$#gcH^bl((F#Fh$G-%>(qSpI10J$j??ML-yZbKB9 z7>>mD4=A=R3&2~7?2Nb{UnN;)pQ>yQ!iZH^;kGnWpPjQAQHE?$bfRw{lBOI(GHP>@mzz-rW?Nd_BZ}d)Y8yH>SUWs17WiLf>z+e6v zi5bH6>CI7itTziUB-HdwcGFz9=l{Jg5a&YwCY(y(X+fJ?ZzL(&RSQJ&J!boN0xO8q83K#49Zh z+a$F1g0(Nt`+G}-6Mx2jJDDC@fd3u_FU4kiemg7(!l(cyG2`lF(nU-4Wj-rDhDaiQ zo8!#bRt3)bio)?rll+w?kqN@6GGV*9l3JPuDajIh4iA?w)qmnn!cK%L}%>gd3}{RMGtULTrl_~#U#tup&qi|ZwTEF5I)v?+kt^gZD!oCdhFktHKS|Gt%``Fh8b%)uQ3;Od|A z8gN(nzIDuhI>($4im2NMr_+$UampZDfsioIt~u~coC&xW*@r_lG1MPmVJeFkQjma4 zNI)76V%`iHCMY38aSS4)4eL%=#B45T+Ib3C${?aJaK8#uIeU_Fk3a}R-I~b{w#v*Y z!Sqrg+Lsh11TSrqxcsp|-EN>00n83t^)nDncyAMBFM+6d8WkeVg<7;qeyEEIwNt*$ z58$?e)DYs^5(K)eP?&6ZDl*hZCLT}DdC{P@{7vA%Fe<4VLc+&SmI{81jN-A<;`E3P zSr=L*r=yqPPZ>TxynRsdh*k_jD2`Vsly}oT|5jA~?cDtK*8DqD`Caexd$^Aa`jiXq zIuzWCD!89p@SwHe(Nw_`X2Iu4<1T@GB0-$IuLRt-Q2)XIA;RRK36{JMPA0&LHl-ho zhRx>kw+keU0bqmLu*I3siVa? z^dK)!AX=zrsqwIz^K65XE1H-Xf=S5P5Ex@Y$a9fUI?SJ)+$MrVZi5`Do-38a<#?_z z?hMbIOkEk&S+pm%CtKYzX>&f3e;6O(4l*NiRSk1(a_E!xVRz>=y|UCag%u+mAhTpa zgi6w>cU~DSkhHmACuP-Eov4&`<^|>x*Uxxveh?#Czq_@qxfH(a0GiJ`+zKv$bY-hg#Sn# z`_nk@Qhf9~uSWptEcL8lsKzZkIhDZgdnVDvRx#=z_{0Rh6b~}O11F+^(|Mr&In-2! z*&qRtPTY;?yFjFlfOj7cj(pI{W_MOWI=~F%SfJ>0DE)ZnRw;ivP-N~ zop)i@l_qU@u8QLdHGohy0_VN1rs-IA8wq%aMO?n!pax3^j0tCyr%SbHWK5ZSGqO0; zBP0&v2XWBBBq-JDY>A4ZL@EksFR0W2gIMOkm6|T@G|hZR_EQCjLCnwBZZp~3_2ShsiKwn%`Pr;cE;9tV>9 zt~LH4{ za*<}#Q;{HpZlIw!z_1;tq3oNT9OWj4=tq`*_E)05H-ghME~Oxdc&KFt8B@oM@GD!2vUu#}$i53?Mb$_tlHcv*+|_ZL zkymYPfu-z&e@AJFtW=fe3q;3L2?SWsa4tB;-ELm6pcj%(7-U6y#{WXJGobA_R2jCj z=IQ;W4J!rlafBR2XJ!{qO*hNn{@m-fw-CR-i9R)GY&_{M4niCh6} zi*lutojxgP$OJbCLL3mJeQ*sDH9$;wg7*c*V+7zD2T4$W+}+uDjJs`$ART^91i%sP z`G_G3ibko{0Db42Cg&1Y!{AYDTRIYzp8se$Qu?r1bSO}Pan;$Vlq z?6-#8XB}8A5)+t+pr1oua0Dd-PR;)Ahyfa>(enUNiYNaX&Fd~54_Q@PL z_()W8`)=4OzLk6BtWR=ynOL({H{?PH#i}iJ;%H$6VTJT-IE-bzGov&S@1k2Fu>k zoF_$ICm|#z6TD^e^7e$9cTToHz})YJx+VV4e&)zc#+|)R<;RI za!`RJmfT~xM~mY3c*GF509D$=%(vSkq@cdp9~5dP7-8^yy)i=sA{plO7NnILS} zE0M&9CnpKWr}&Ub7OZ+cuyjAJ+p`oVuJ|EQwvnLiYWhfhZ#3>bES>?m=`Iu}uDT+a zlP|0HHz8gNJzsjc@D&*b?%}$EMT|1Ib7;p4Kv$O1x>b=}-e#}S6G6=rANw>j;T3aA ztEb1hE9!#}M6Rrfbh;bV?W56f~eHUGEN)LP)pLV13jl zsl^wS3VM?nw;hQg1-*zmD#(cO^vb2a=;ybLXe;+R`pU2NnIl2wv>gllyGx&ePb5H= z-Ir49`l9QARt$@(#i3rFGhun}`vF|9w>$r|xsIM}P0>;M&;jG1J$E36*%tM(&DExx zuT8NaLAl+A3m{MYt|#M^X%e_q^BA0}x?=1O3L5Wva3}Nd7p$pAqiXb-y>pdwaZ@ZS zHSdp^*E;mkJoFX6ve=0vL<_PWz$LiO?OQtzcKxKxLr4Ce9QJHVysOm@Q0c{R1>utr z2c7&$q3aKwKZ1Q&VH%VBu-#9o*vyb$-qCzv@3TIiebm-CLV&)jntbvTc6B|bnaT~4 zmc~Cqd-g-;C$-ZVr`3xF&J0U}>FQCrt19e_J6(%J?HP=Qs6^LK2f)vBhpO(4+of52`F8iq!RI z99g(h|M%UEQKxouQt~7fR#tO=G5Aw`*Ek6-@Myz|1J9)(b$>Ojs9n(GmxwwsOR*Ec z6+wWWtjHNA|G8!+^7m4;^|~}LiR+y@;`J;oY$-kaVgj+7JCYYN z#dS8t{Au720MfSUI8Y|V_NkD9L%yKph|P?!LDJrA+~&mdF%!{`v&C|g&n2lCi;Z=l zXMT;T{IC7#O?#w5C0R46;Wczgxwg^kzUSRcH`oNbMGD0Z~%dnf%3VT9$UB@GCxYy{{vkMa@E_Sz-sjA!xe)BtN@Ach_@7})o zb7_Bl{JPThe4c95b%7em|fxLI`l8NN}R#{9VqIv#}Oa2K`yW zp*v9-=og@|?eZTH%DszoN~kb{xz(K~*Y| zVLrz)gd-W4NE&yTW_RrVONd1Jp}wDZGHXUH?7plIJmB+|dS3{+SQs5TB*?C#Dw_8R z2(RsF<}n{p?{hKaf!kFkaNH0MieA;fS=i`2$0 zT7;(Gw}zW?a%V?Udlu%fW>Wy$NW>k}8Ih3m4qK5BiB4DDKu`jZk4vqer#~cJKC3(^ zk;Cq6TOI=My<5_4$?ZMGkmZutnUMiVlFQin$e+5X2a~Ps`%eG{r>#eaavB!9kJr=b z3HyonwicYR)7~+nmblZ|Di_8(%HJe%-TJo9ZM;}3d^&wMtx%JSB^O$szLT$N>GfJb z&@IX;^SUPzB~LB$8IqIBf8}odQ)$^RBTs)TD!fo{V9-h?TP)0)*Jumh$YZ*K&)_j^ zx%c+BzPUmMj}faoidS)f@bcx#zucK6Cpiy6g0BqM6G~5QSSS$d0`GtO?@y5E=Mt?w zB&B>p-Hx#DSzAfz(E!Dt3mh|=(20oSG6-z&FHxgBP*4MQcSLh)7~8-9{8-}xy`WLy zS;(t6=g>JoZaAXVCIJqZ?~X5!|Gi=Ihr z3WrAKPgXVN4G0q((T(yGt&I|Q7v*lE#xGPwuPA)RAdZ)wMGEkH#(hs3z6vIyOWFH` zB@D=3B4?1mcYYOsZf9Ja8Yvc*t*zOUt<&?={P_saJChs>-&(7rwpD@pSCi&$9bHK@ zqb$ivMvez}nEQzQ8ApFIS01*Dckxultto1@W-J}PC=V1hFN6FuEW_i885L6JM}3(N zf!h_i%xlO zRgQjrv*80p+s=b`k!)F@1=>Ip)$`-Cv-?-S!>`kzc1n+ZZkj67)n@#~{gy^DPtn?= zC!(9e+D=Wb_UG`NZU`d{=!$Rq9kwlTju+WTV&-$DEsvItG>U_t7I%Ra65=Roc~Yl z64+f2n*QbEV!c6}f9M1Vd5|b1#dPFP6`Q$xi92(@p9nrS*bn7>bHm!UZ8H09F}*4V zGb&7Z0M;p`Bf?lqs+`!|Y*(+L#pVl1cTdr?{vAON1G2=~zV#=usc^m#=S8ob2kQSe zG-A#8R1#D^5=!LSB#OS=?p4b!6;avTl3 z=78#8<++3pQ7v3>Kea<&D$| zHm67wVHFedekW40tq(t>v5Qf{0Mv0%OX665KE4Cv1oJyBz8Z5k%Xja-zUWD3ZxfH4 z$~Qfk0l;k4CE`B$)&a$- zfk7h!$ZX@EP{T($;iuWN-&Jpm{2b-u;vS#^|EozpU`Fl$@jmw*lMTSsu*WOotX{)p z@vzoiwBB{OD_ZslH!8pytDU`^&+5-eW=>_D(ljS?>HordJ ztG!sA_Q!aa3jVx6_CRJA!OWmfjS9~RU5Cr5<7)t|B@##QDGZ7d&M@z7gF&-TvGvgc zU{+0FXu~|an1%36#x{1NtB9r1<66o@jwe2swuZ38#u(f zF6A~=*k@AI{Tm$e{xKjW8{n7ajRy6}S*Sf6;rBPK-js7ok#bUQHszP+OE5YhA}dkZ zCz+i3Ol2M!87z?3@`w}J!>4U?n^+9ae@!m&*P?rH0HD0K#pBIdBs{g$l?2QpPVdSw#ja)S)A($9EuBv*KH|JcJr);Gj04yqoI$E3$26m`up}gO=HVPs^bjs2~Lm%NqOY~xyZVt zZGR|stnv;jyEhfgTAeCFmR?r*t->IG?>|R z%xD)}Y-sb#1^{vZMmd-8c8z9E`>ZEFkdV`rKpiU3aHwkRl(r6tk3GhFi_35^5-A@Z z_&TTdo%JNxLD{&poK-V^IEM^pg7i|d3{mD^luvA@fY+Xyu?^ZzET=i<(LDD(SmVPv zj2<2XytgIRcE4+ka4+7bM_V4E1+!n2)8`Awuo~-kHZ3W=@pu%I?QukI`JghmR=GS# zDgBkT?wEhuq-ban-QGJ`qgrLkqB2m9h4*<(Jitb|w5B<#`ES#+``HBUoH(4*hPo?^ zL}383OsLnN=b)AcN|!4*scYe zrUI1BbfS>uJ@%i`I^BP>e6cs%80@kwkX|=Q7T5m`BcBz)xGUH6V>i>lU9{sVLUD$X z717RXmSqsd`=m)#uy1G&12I)5bN9nM5aSuBqJyQ%J2DW72CbDu6UT)Y>ciOQzp;)^ z)Eo2slilvOHXDT6fck*UCpyRwB%(esJDJ-x0n4?i?z!nD6Uqd|!i;WI_sEQz{z^j; zKNy04@w}sWs{iXI`?P&XrE3b!ruH(TUSB^bLH_%|sN)+Yd9OoM8)AV2{$x_$_Zg?w zlu}th9b%h9yR~otdZrJlxG`*og;@TPTVT0?ge*B)hmG}ND?-yAX>;Fn>zgKsUhei{L*!2lR=&bppwpsf?z zEY-whxUfOkBdFwS&$c+8(cj|o=hcBu5^R;!30s-^l|N-&MEnZnI=Q$`%;&$Sg*GHT zooAi|4K4WaKu0wyvnN9zDe)d|5b*wnd1$?Pw4`Ir;!(}aE;poe)T>^0DtBJ=g;BoN z;B~OV)aP7;!5}B3C*L7YP_7tkwy+%eRL%?!6m4)cbgn#=B!D>g=m&=1U``nj>ymr7 zD>V*m$TIcKeVJFA6L|i0V`+;9OHi-1WpnqXR(FfiagWrM54pw;N~V5(mJxTpo`yO? zGhMhr8ccG!$(23TjR?MtOQWJ_#d z7i^FMF43E8+w|oeg>~$42K1f!8!?Rh_kJ+0@{R10t@!I?H3bVlAQe&jOb9pWp8x32 z$eutDtcKp4mW9IsF9zfbB%FQ|WH(Y!#iNRPR-9$_8tP40Ifa-0VSHz?0fdWsyK`6H zw7bH1j#B}b5uDId_a@hbb-E}@YUjh9+8_(JV^Yf|f2ST(@}Fp+Au*%Qn|&q;GIZel z4+i*tAGCc3T7%K3rPkjXucsklXKh|R@yIXrgXnPF2;UDHY8-zMiIxdKk99BG4o#T9 zr2hU*`7!dKE#*a7USDVC0>_62(&Cw*{L_j;e0#-tKc+7tPQwr)T1j zEjZ=UmGunYBduJQHv?fyQ+_}*riy)}R``3+9ldM-?7{jfe&oUQ9T;!*@2({UzIIN? zQvgW68+aO>6-mpHk=%TvvDpWA*%NEC7BYwks+g9o(21tCo&yd#;*+Y%8Gl=SXX;y< zn~&B70uM4>aMDfyusKWd`&Xc?CiLX-w9DJ7*D+2R-@G$E(xqJDGUEAfeLmDMbpPjY zoKv1!r;iW0P6e96^Nrv{Q~Leqp;c$-S^THBbK2b^1ek|-FX4Cj zh3OX{DslS_ZjQg@+dE^Z+gbeSOy2WJ4^|(3;>{Z1tuDA{=0|O!weA_6TF&-FeqNZ3 zqpqc8wGNwdga#ZRMW2PZ8|&;`r3)v_^T-x;jL|z@I)q<4Z=#)ePdkw{l=pG0(qr`M zJ=$#~ZAzk+p5-1O`sMgPu$x21+sk$9#{YQANI5E&MgJy$I}zfR4ZLKfRL06!x(vlR z)}I7qE&A90EUx!uc$}s-|AE4|CJeK*VMCiANn#X^8$B1!jB)c~#>RPMB4QO{pLs_v z5j`T&HuBsRp`Qd^KbSBQt8OY6tI8=0+(holDMC)Clzexx;(yXMQ8a6OQ#uuSUP{Xo z3a!p4=r^A7;O$|J20f$ZAwR8v{u@E)lnd-sur|J|5n8y7$QQRYnhvzET)_tr0d zJ2`Vpe;cdKkb)q;41g`VGkmElb?#Zd%5VR@y6l0yvpAG#xek=9yHh~Sa1pJG89Dt= zDu3={&M#l3+{#T%kE1B2qP&6JuyGcpjfGgjoH~s6V{MOie*b)BCvlxRyb`sKFFk{> z9;g~BJZFiAj4YQls7HG%jO14a{Kr?H?uz_WF_fD1Bk_86@j5J6&8harsXgiud604D zEBklhr?@j(3mH$hOQG2|#lV00nO|ova7SMcCcZE6_s)$G%gfNqXNDz*8^CTlfjhX4XfAQ8G>Elm)P3YwD zJURnY(SH1B#dE`wNTEON?KOSdkz93yaADR->ID8c=y@oc?V94$8MtUR`p(Nn51-|B_6g6mgrjRoh?jp{b-}*B zBF>zd(7e{S+vbfp|7YX@UHNW^*pM-A_yvc4**&<{-?Bvce3Vk6XD`KFN#Tfjot1m? zgT|NB|G1{t?OA?_u2$54FR1SxVsSn9mwCxgg%(_Q$mR;jav;Pa^k&Q9EyIeHKl2g| zeg4YqiZe?L8(+mEGou4(?ajaHlsbAPv0F#&Yt5J6i9BiBQ)jUXMV#~uBL+ofP0Vo_ zC9;bbkCpm2R>>Yjv+wADDv8D_l7l)T?gaO_?_Diiep}6Vye6^Y-3i z#P64DfO*h7zpPf$<-!h1|b1A#1#b5R|b&fr19Yp3Xfa`p1A z;K!Z{r(WJZ)fh__({B@Sb1Kz@a)PG#XlBVr%+QAIA_;?tIb6_acA=M{Pgii3oV{9Y zr~h_8^h%kFnEtti?yAKk-a0_qE5SH92Y1>@_AV)Bv*FpI6BxXUcfN`QkHk}$_7uj!n`P=jo)dO;D zYO8o18=CL&;zwE~^R{O9c@DnLv|n4n0}>7EZyt(hH%Uem~ZtnL-|M>WiF6cjZ8O?Cw7Sftm9eqrN0{?Pi*t4Qj_-l+PLFbDw*bNUmo*#CU zOo6aOXKc!rhlefNQF&Ht*erX&abSv50N*)ib;H%@pG6wJCUH+9OEg=_RPm3B@rRgD7lT;D&fgMN6`0bGa*|zOB8}pQSazL=kgjz%14FviZx3 zmzz(-v^loadCf_ldwB3vt$(h;(@6oU#|oGEdI@ulhdc*Yw6*Y2Wm zOvcNc&Az@O*n{VhcVXD=0C3CvLEzGLvCI^sd(tJp|I(Y|Ssx?}Wc-1GMzRP`eQ zkB4-h4~;n1O2pKLIY-}efxNqB(PjTV{SO#O(QY(rDKe4#_U7I{*RDPK$~az$>xnrm zI(n*2j#(h(6_zSda=_DhQ%NO6UV zrA#fPJtw_D418B49aWm%ZLEL%dssmUi!Du*$x#~v0DI`tT;K9fXJ2#MnJG9&m+7^9 zd0tqy_0R+28t+u6u|tF~S+e0J!{gd($lO=|7V=Ey(mr00LwGZfLj`%`f{*_iD4+D^ z)46E+dW{%bLvFQ1iaXQeYYlEPgvJb$sn%NL(8|?fRUB+I3&X^4$5ov-)My9}%OH4FZqY|;;_ysgLk(&QjTbgz-^zfMNt#*aKm&Hm36 z=a6a#N0iISMp@tfDpEXX>n6qptQ@;_h#N=__b6WOv9pluz2SEl+__MgbqU0cx)*W( zR2lr|*4-(uFDdJN*Tn+qdUn})n2D6EGCS=OdCjkRy|vB1on;FE64pWlytR^^thm?Z z4;~}5EO90+pEVv!@dAQGBS=HM{&tueWnsOl&8gSQRM%q$d%8LW$R|Z>k{%gli5+}1 z#6Og+dKR~+_L-FvK+$Y_j1cQUP_GO!5|^hiKWA;Koutz*R7-Y47G!(r7TbbuZzZYJ5ol0{+Y9N zB)M$WU^&&*^9S{xP{_k-+uN$cP-7ghnqF=DL)+D5_!%iC|CBlGUQLp*wolO0E_hioj>Z}oFX~U-dm`a~Rd1v2Q8J^DA z&6rQSYwt93!pqufq=$%HFH{cG9~n(3d%{Zg#421bFx(R015nGRfrtJS*5KuyJU|DD zfBM|!naf{cM(zTHs>@wx+yxN6TkE`yfG|70P3TJD4;l?;ZF#F)>Wx+9`PWrUmB(0} zEM~zS>cJ_oJq*10tMHJl)Yl5Z*5Z@2P~I*ylaMq~8L~!)`#p6PUNuoNV3N$@Bh(2d zC~j~0t?(Zvi;h=yVdj1x__;oX8y#!QQCtQ&GKe=uV+K<2m`dsd6qV0wSuv&Lnkg2uHopUNh zIbnBv=Mb3>F#yrh>N`Z>s{}4W5k#Nio`q?-Fa3_RZ1&>Zl$I+g!f-!Skk1yn)Nn=* z#~iNh$P&OrG*_9aC>GNQx6WsfCJto=1eP^!kNg+uYT|bG*^D`NZt7K7bgoB_%b`!N?&!Ff=HTMnFs=+p7G${~rCb7>sj*9;^#R0}p&=&9M~wuPyRgil>~ zaz61v@N;9_#Zh)@jbbD0)K?MDs~ts$7&?3HL~!nD4beQyRk)I9$QivW@2U2Vf6hI9 z{OnsGH~$|^3BKf3>$Yf*d)F>Gebl`*E{y1l^00U($ot2+8Kw$%-{seN8-GB*FsSxBw&_2IQaBJ9#cgBo0#x5PTGwe2&@3^B zl`2Up`F6_J`NP!Q^31XHfX^c)XQS1dRD~5Qp^DZ5CD*u)?5GIbqYcq+;e~q4lMTTd z0LXI>!|gse62%*B7QLpC)4;*2-*q%{9%`Yt+^NYXv28QvjXr40v|wnJKxu#V>dZaJ zw8PC0>*9x`pa>5stc0VItzYhW$ct^sFf>qu#UaYp5XZ!oQTV+${O_hRvGrlGeanMx zvEnxcG00Qmt>mA7pIN`Q5&@A{{AP~WFYxD| zM-rKL2%Nn)_4oeLs;ESC1n==Q{?m6W5q!?3ex|y*gfxg#xpgGrXckeFf3xt#zupsN zFY{IRIiy;xj)$5gqXfOg6FDK4V~i8Q(0Se@_Yo0xP&uot_s*$f0*?)eEV0B9s>1&{ z5ie)pu>-P}@~a#fTkR4=Fq#)?B&^4ehP7$DSGNmluDSz^ZXTC0mj!bjl>_+~9N6{OQd-RJL1tuxKV~2XVX7_$s#X@)s%UJ9VxMb`Mt_;Z<#Iq6AKYg3Hp5wvDp_K zsU^peIQayk6@ll*+h}`hL2gaV$-Gu8lbZpq9aH&#vtpSuV}*Ix_cvzOo;GQKuuSI{ zsdcJH=*nL-HH5FF&@($%s)sEV{<82YTVP@b3+D>0(Lo25eXV7|%Q z0PK%)touma>CohT4u!OwY1{2(<&u#Pc-@jP*VYk&E!>m;*~i;YbL9Co2Fc+b?EKpr zhjhw_#{BiW+V;1Lhx50Km%Lh{@Hx_c^EDEzk7fb*Cd1l6Ld3 z4l}>e8A?y zT#PysH9i>`aVwd3>MO$$>rN3{8y*J{Qy@6g+FNFWk(V1jRD92Jp^%TS4NV2PkGLO^ zu1`t&q>M|jRO()F)U9yTd7hSZANOkF@S+V1t3yiy|3}ez$5Z`(ar`d#a_@Cr`&xCc zybWJZ#%y~|FevQi`=mDD#szrR2Ke%|lLd7tw- z&*wWqe<1hNI}zd3L{PGgY5j#oqZ4k0`B7>n7SYP%c+ECD&11kw&$uh6PjE3g)gSV1 z#42%VmL!U)*IG}zXPCjP{=`YEu_F0K(-U2);#2H|M)bQF9Ji-dg{P&NH`5+8Wm|W$ z+D@dNp7IevN}XO3#j=7V7B`v+PEp2Im#?D)JJAr-&5+>x3JfDEX`OIECZ)N&;jcb6 zt~{CXk-SdRX#+p24(M5M)i)ha@<6nkn%0Gmr0DsJmJem1(=w|wESv62eNMRx?~{%L zT?++CK>Ch7mZcniZeH)C3d)c2p8!2dSqdS{>z0FYY-T4sW#>-fs3%)t8`Wuon7>5C zYFVCg+|F*3k-iP;?jA6!H*7hC*P4PuyLf^*pj@Q1jSSy9jIyLkS{gpC zPcXy!DA8JkRjy~rw-d#F=RhCZ0Mz-)!p!JA0R#-l45x3azNB*dE<*YDPjNeR(3T(3+Z^wqTyFj2n zjUT2!yoFbu&OvTHmbuolirV;u3Qgwo2VOnO5E5 z$)M$pZ5xTc_Kh7M|iQ9 zmrfONF`BSubEQ)S>w5Xs*aR$%&PSz+uwGs@s!y`s%8u*9JgCn13-q2kErb<3ey%@a z=xB%_8+whI!#{ldqp-lv;aAjrxuP3X{gJnvv!=&3c>#Kx*Ke%f1s8~>$t426xL8M0 zC!K%Vm>mjAFo{A0+KSt*mwUe_{A?zsYlZAbTpKU@TNbZSdsK@zaT}b;OZA zVoBWKSQn5R0=RAjJ&!dLgizeDcejTwtM8_`&yTA6&{&WWV z$p_n!6G%I2k&1$N*Bibq9tLvSnz7OZ^%j8nB@xh;UfhET3|MG)=vYaFudnlUY(~R7 z5$KKZyt4neGr4H;q!zsl1MRQ~bAy7APIvws6KGzZ>}AjWMWE238$C1a(6E|dqoAQ^ zY@SGb=y>{m>cgeEFcEU-MqnrtzAYrjYLIhBqsLI`L}mw(vZnN5oExgmWiLz(?n`=J zRjC=L8oAT~1*?fWp;W%z9UcdknQc0K>e5v{qf?MRUI^0`t8|K$<@>^jO>ke$k#v@@ zg@y3Y0}qR{r`G0}v^77J+^o1p0$25cz7VF# z(!u?(^J}>@XP|DWH95_qy$13iD&%tB`S=PUw8bvgWdK7uu0R_UWLQ5O6Y||XUAxF3 z7~&hR7v<~!negp^@615VC{QBqt^zn1Ve$I81 z<}IS7Dtb0;`+cu)POIuus6)QT^4)1rd#%T5Wf#m(ofj8y=e7nY-3@GB(NW~Q>a##t(1{;<0In~`NuwFhHz)0+TC{zJp+AZ zp-z|DQ9V8YbOOL5$m?k;8b-LY5Gn+rxKAG*F3?kl zz$g7Va{K(3920)yA2_}&VsiZ#9HEO2Z*XLWgs-4~DTE!`(v>$=$Hb)Tl!6Wr^I z2x^o|w@3n>^0j)Db~mz)o!J`Kb2Q5P7c9I8z-$9$=Z-dcZ!~UIej$lgN>?{uJ5ntd z2>T1uGXDH2nRQm>>MU)fPgVM2=exqzak=$OvT58+7{JCOSU#jsm@}^R=>!%VHc_95{7`WY?YSD+-;>=ua3? z?ODBNF%EkBL(S0k*FxbP#(YI)FhySwe=~?S%BUlLWi^n35cCH6PfZXKYxF-Hn!kLh zB%Jt+K7V)-pM8sj_nnChOfymqy=H-|_3 z{qxh!40Bb1iTLv_Ms(9OXAjkq?x(J{%6u@wPY$Ja&){11q@(Oii*k_QZLcoK)eq|q zu4z9v=7vJzdsgq}H*L@~0EW-bXdMQ>8IS}trT{S-13zrN4Klf9oZ8~1Ma#UN;oa6T zj90_-XQ%9Qq`Ab0i`dRNc^IhpjOKBLDBKR%<2ND!lfNRdIhXKyVPPWRu_+e-*({S& z7j9Xj;L!r=PT*x;mrbiOX8F7>!>qAFDqXm1INE?EP#|n&k=&skPa-!L+OP0m_I!5b zI}`yJdC;7Z$Y!x^v^`&9HE=BWSYG}lW963f8zS@-*dr({GP{UL% z*4uuwzWYkNkHv8O8&;u!uH72NV$55gNjjgw2NehCVYD9e1<3@A58YV`uzilax%N0o z>}vK`K*vFXI%-PJsl zCxVGsIJ&C2hV*L>WcFZ^6hM%#P2t_p{4UmLN?=|-gSX)eS`lzzZOD2#T?>v2yJ zSmqlg$&TJtdCpGc6Vc^qc;f@RdqRbFWlR12+TTFApJjjb92jO_!$b_Fi*7Rv5$cL| zA8pJ{aNtrcphU|JuM}@EddTf6eIz|eS&|O0=1k*rix%d2?R))vjIob28->F=A|h-7 z5RAK5r08K*B3_u>%vo9%^YOfv59kREqjWmTGK*Ba3#kxCbEP0vAl@9WGcuajxEMpx z1tX+|Wd*IkmyUHe4nUn^Pg4I~;9Jd*7|L_em||p=lpUS;zTfQ{YJKnuv!k7le!w1z z(ko2B=(=6>J{CPMvAk!PVF7R@XIliD|KvYEgDrfUl2pLLZc|DYIL8w1+MmlBLQGh# ztEq5%f#d*x%=WK+cwq4@OnE3@F_^_|YJ6d&->vTVpNzJ^TW*qU&I8J#>YDW`@eZl$ zwpO#g)M;~jx<(A=3-T@&Y?C*4uWWA!XRVBLPyYQ8H3L}_oTBr2slMmR6-{o;Wi5kA{m1LV2 z_$HuOZRhj-X(E~B3cH74lJE_sw5tiO?m17u`CHOg>-g(SZC6p}KqOG{dTcTNRrxJv z|01Od$z$Dbo;-;c*&{!X&ZZ3Ofluw~D4UH$>`>C|=y^^oz8CaQ5{J4?Kn#<9nknf3 zJ1Z{X1GnqfJmYi;mXbsFN;B3aIk^ra|*h8_nFJ`J4o=MJ=;y6SUyFEkg138VDO zVZd#tMA4aM#RZ4P)2TWqHUkqin~ps1T7f+!uYtIEYHFI}ga$pKxD zE!wnig17rr;eiy%A8O8Ftz$#0MF?y?J-{>1QRGd`!8aQKP4U!l!#4(W_Q`u zLbn2jb|C^FyGkTZ&f__QMNrz?<_|7NY$y!e#pGAs1NIdp*q7+ro2nll*AV&MA}XQN zVVP0)s}nBG_+3G(pQ_j6Z8ATw>RP6xInYCG&eaU^v&SQMy;XHf9s2{1emfwbeTid7 z8S+cEO=VnQbTq)*P{<%#iIRK+6}aVTZ&;-l_p*Y{z8&l?t}?3Lj2dW~2+S1}&EHA0 z-ko@-M44tWAB)j_MxtQ~Zi$HAC+5s8u?jlkriOnsAZm9J5$k2z-98T*k{agG-$+I`D(>g@2xT)WtY%acKEt~R>8;YGF2`PTsal;M;zj?p3`AaXCuKfpX z$PnPV6hP!-N-vaKsa9CfEA>N?kO;Y}0T&_IPebL%I; zrlsa*-UTl)J4by#H-z|dPs5?B2*+uci>|T=l}?as=5el=!QW-rwZSMH10(Y2*T9G! z>36L-=a6ucLg&SD$Xqf3EHU^s_}Z6F?c~k^lJtcAv48cg^Gf6PCdqtHP~5Ts0Po6D+Fw z68X&^$oy>0zV1@MYZAMErvCLMcC9znqhyr|&ju>{xOT+&{iIX({j4x6$s?2MxA5BH zm&Du=F{UkufILY{baWGPO>_Wi_Ep%mZ`Y8Bcpt6b;qc(s&)bgDCKqU9U0dytAz{z0 za3RHUOqf4dG+ekns29g^>XI;ii@?^Z`yLbYIpr9?oa9{yAhSE%b4&3gLT%-@YIy~= zCFc@zP6P(K*XDNZ#r*dslnrn5%ydR~tHad@7k}xzF0k{+#*C@|C+@3?JpzFXo?nL}01%%91AxFTkGghucGqr-T{EDae;wLL zNC`T41BMDo3xv~PWS*X7a=nexDG(;57qv5>#G3J^^Cc#wQs#D_OtQCjf~ZqoKPj<4 zT8$1?pIU?)wDXA4da!6#YgyB;eX@6-HEa%()_3uuMk&1MM$0qUfBpC6SkS&W9A z!sOwQxj2v*IxB?=nx=zZ;c1F!Z9|Bt>7-^CUdx||5VfgUwdD{2L1K-PN~*a@xnJDG zO*QHyQoPyuXl!g?zzSgTEJ~cx%WnOM^>o#<&#dBUjdS9#fxm>(&WCJgtWfJrpVE8m zOQhQy0MrJF$Gw2(9fN%az&?W2vuE0T9nUx?F=TZ<8%w!z!8}I97p5gnbh&|Lc ziI?*us+xg-P&wZCa3^x|Sg+vn_b{p({0m{)Q%&rxinkj$*&jB`RO|`ni_vWLwKkf- z=c^?>K4I2L3IE32qVO8KIf~-L+>!_uFUtpteqwyhfVVHWqb?pa3??sNoiMfT7@F^P zrUJ~~Crw$-1IKGml>@2rdEod$D-l7Je4$iR#U?4qVd<+YTG;PeSt{%_Z+=NB%Pc!S zU!b%NRgQ4%&22a< zY9yT_tySSoGFQ%bIUO8EY#*LmAd9l?NLj($YeklWKr~$b8$jNRun75C_G}wNjD%66 zJ@^NGE(OB#U;`yhqzS`B7nvfzB9xMWJaY`icd`*b2MvlZJCTwxS+z-rGanj6oA6!rKQ4W*6WDv7Q+=e)=oC^Z(y%`>8(v_gJgoQf z`^y;uFCAw1p|}RK%D+wdF!Mcp`^%VrYT0cm?SB^c)iwqjQVkXiuP{wiA#;cXFql zrSdo2MLe-RfBw4q`{EO<92PNyy~UZuDA2j1@`ZvYXYKJiuBb{x@U*o_toX9E+>+@-6U(XeZUHm#C)if^X5_KXtOBt>9N1Qab>XQW(aX$UbrZG*y;83?hHagqX5|>Y=0 z%)Giu_(sfVc;TJH;*ykDYl z+2(%@tPy_I;PZU*@d&d~Z(+9B+xHjn^iN`}i3ULa2hNTdXNPn2eyl3B%A4ZM>(?u5 z>5WnSKV>gLsrZszyQ9~N{v%PoI3mwu0#DpYDxcflF8Zx#M!-ww_NiE*jy%$&L!{rR zGn@3&w!HJ&c$CRql~!f;Y+k|1Ipn-8DW9y@Zz$_gt2(Qprd!FaSgD{*lngFR$IAsdxGNwv6~wZF z%BxiLzH5E;dis^p^e-T9YkdhpjpDw@C1G(=^)W|#QWe*CQPD&(j0cq+J{FU@Ef{wL zx8oiAjf!j10vHnU?j@J*-*C9eFXvIoQ-bK%A>d`LS0K~WD4w?j_63Icb6yYXro<>O zf27?7T&IU!Gy4WXi`!YAV#j;PU@zmf%Jeh;!$%@bBuy}A4wanFKLcq zy{E2n$=K8AsgLs`rkT|Sg^N*{rJI`#K3+bx<(j>RyC|o~E7&KO&+kw6zGG8@YpKK; zQgL8xf^+AYI!z~TDqkZGVaa!zwF}qRf!F*2DR;VhnOw!jch$~T9K|7u&qVGNkp4WZ zauB>q?suuvC}4lgZ;X3bs+GLc&dxy(lC!<_tKH=i<~qmJ*?WDMa$Ys52&%xL(wIW% znuh6oJ9`_T)OQc@cv(Dv)8j3GmU=UEkEHb>S^oiR7uI1Y8dn!VaP@WHU!pIV>H9Ul;yO;m z5(fa4;ksKAIwSyLuY84kP9Gj?EV(+UcI~0StKks%aQ4zxxZqa>7=`P$xylBgmqfvXpc^s$ZilDr=?|;Byxjurxs;uSR zOre*OJy6tEz(6sC1$HbIwMTw6wyU&>1emz^qt!f^-|405Wz;r$u<%43kRMEVsd>On9&l8Zm7RjTE*;=RE>U_fi zS&`T46|MRqMQs`89lodB6m&yOC_DP$9ThL?8!bwr3W&e-qb0Dic@U-VqN>PqVPBd5rfH*Y%@B5w3qhE(Yfj-rC8by5-V zEBi`le)Q6r&`ZbrnwufCcLYs~eZ&HQ-6Mki4e9-8dRY1WFp;<^whQt)-kzsb5EqDV zlZYK7cmW9U75(C{o7YU zcZa`$URnL1T=+xSq@b*wn%UeqT5tnZLqy8T^!Cy4X@i{+CgySeS8+qtb%X{!{!+Ea zRTd8xJ57%-aue%3Va_LYd%y9OaXELsNYc;rf*iI zeOCLiU-Y<6(3{aDUidfXm&!YD7CeOx<}z9 z?!SK)t?8=r%%tFbShL6Fn-?}GQIul-8?L*w2nQ428lFosoY#0th~M3JP+oUaqB9zwi|F6 z&#szy^3f6RZaO<|0}pmA_fq`yg@f&YONeZKbznYe=$S88IdYwdRFw9vnWyj&7v~)= zR6<_4AU)%}Q+=c3t}AphVH1MItOnT%ZZ~;FGyLAIt|~akt2^VPS@?3i(?5RZKPGEH z{rK?_lPpMue50RZGWGt|u2PBU&+A3D#xfUe>d~)qMC&cnd<3JX?sAH7{*HWU!k24S z5MR}~I$exEQKp_6pp0xJhI)#c+>U&ao^2k)%1x>m`>{VJ*aB!>x-(|B=$PRj*RrhS zX1C5odm8t7u3Dt*`YNp?;q!QH&(y`Wyy2WxB%|(L{Z_sB`6t|G(O1ER@{QHF4EZX5 zp0P8Baj|xBr`3mLO|K;Dr{NFT$9e4i*l6k4I9c7>4!w1&LuNC4m$LDcC2z~e76SeV zd<$I}t{i@I&O+hocCv!K^Gf>4`2t13D(CVI-A1X}u%lujL$_=bhsJ?ZMTJgohL=6%M`f#xoY>f6O^vn|pWG#e}C>)^05; z6+6$x!<6JF9-z$x&uhvnwxP);r}`-V-t*^v*q;{Y#hS;akpEjvyOQuNw-TSY#QF98 z)(lsUl??7VF}W&I z_^4u`kx79Hf3MD-k=?mkd4;~HEwZvnG=fw}Q#>+p+ z=-5EdVjS1BbFV)O-?hH{@3)4*ft_>(12o2$ak!slf}|yz0Dm`eA5kr{g~2AKed|kPpTj9b zfFYIDkyRhT=uDN%0*SoM)DH{w=@-c(BEU`|XBtVg^NAT+XCXc*$h(7rVJh-$`|EN8 z%zi;Wmp)myf|OSTh=g8279p{cyQB0pyMaC%!O;p+MKGASoz8W*ILRHX1OkTSD!xQ*4C<`2Wwq#onCHfDQ9#}CBACw@_q-jwiEZp$G%Bms zqZ=x?pRE1!5mst9qpdNqohf%RFwCP)A}wJ%OJR|qDg|wdC$m9?_IDrt%@MyM>QRkP zzkkOfcs1#?wvk9zQ>JToGGA-PhWyYWr#WP~AU>{|??3exX%tIA@WImKl2T14r?31v zf3PC&3^TRSFK_>8{s?Io6;opc5iYz=HI2AiMB@5>2XH1&N=I2E%VU)%=7cxkr`&&c zPLzy4vA7SbXDOzb+Ep2hDtWG?)zfWl{p$ooz@+SQfw6d~3Z2o@l=%yy82LlR3}7ud zRrW?rQg9S04gHZiV#%$5*Ril1fi~SJ=8+23`*5tZGyv1uwXMj|Wm8z*%_`b#&Py!q zSALPM@R+Ti_ktFGmd6I{-$AnfV)CZdt3Zc#oUaP!6O6QPZ<=CvvQ9p(a7j&F$6dG| zI$B^aLs&TB0{T7l(N@~DV{ z>=lqk@?DfsLdHYw9rn1sKc^jk{p2DsR(P$6K7fpHnE#WK2XEmiy4T!wYT|f#yy$~h ztosmNS|9m~5Omg?&^KG~R(Vb{M8K8aG`jH+77MpCjMDe0f4y*Rc|8zNKbThVvE+f6 z>X69c?!!IF7)4=s*-Lg=2%q3&q|7rT*6`y>#FpDHCLjduC9@BAZ}4VkHVqO@$Mxc% z6IP*h{VSLeN5X&^eIwEVyW8ZYp)$fZ#DECD?`K;4(8nZ`z%8-^ILKSAUd)W+o_SXK zFUE+%Hwh8@tt#UjuAhS;wxmoeGo;NTF4W?zr{m02bAHTsRPf=NbLhlJqpeBbN1s8r zvm&OKUi`cm0vY1}+cCr$8pYnz)-<;j2iI<^PMPaU5n7G$tAFMj_F&J!xoYX7evxf> z+aU;>9G*SF+sTAVmMi*)BRck|S-^~g-&3U@K}A#iEIp}$dJi`@sYiT$E?_d4;q*!Q zt3$4au}Jqve}lJf1#4wlpfd?PxAmPT!)p)qEpoQ?I@;AnOd-bn!P72Wq1jvx;wuhA zn=o?muZ2b9J9x+GRO?dKx^ne9ilN?(B;OrAiRx740X*EG@>Yssivst9IE340A9e;S zRQ=^A(JMu7`~SRn%*^M{aR>(T9(f{6-(To@yi$qk^FQbmNIE+l&ht*OMHIiWoQZSg zjJshAwlZX{22gXJqCbTg-x3ny);&C zS&xyX%Kmh;nE7qf=DUO07}da~k>;x5e5|s$kU&fIXp!^@0(`WkX8gwgivzP(zlnf1 zp|4MhgW8vO2sF5ed0X9dshEjRD=+24bggZbdAXatU~jef{lIr)*QK0lET3kH+`@lx zF1*xQc;SljL-z)e4`b!Ge%8-ZqrPvw8}E4Z;rTTO(9fW--PeG?*Rr1SbisB&K2Ep7 z^7S5btW-7V{lt^jPcIn;*$YcrQO4sn5|=l$y3{`=H_%!;!>t)Zg zy~*{=r#+3YpS5j$`M5T$l>5}-8vuU2I3Da{l&d~3UPnq^aG~XDyb0r8N#SxbT}kEh z%fO{BMM>jQuxZk(8R8`_tLcl?{-P-yWu>dx_#q6LrnVrxmaDbFDwaHN+q#@jfXb}X z4fz7r3+CtQe3OsVf4`=i8_RqwR#(}?(1<#lH{%#MSMh7ta?^RKX0F^$6#st*qS-1M zrJ~7V#I+pNap6d$axc2-Q$^y>%};j{;9{Q{eSZUT$}=SEKi|#K*!rwIDh>{)E_Mps ztQnQB+Prr=W^D5|BW)`uzPcoE>pr7UQ1(8`jrRVk+t@KQDCC!f*~f>S8-Z&%p*^1& zdCaZO)h1E%xT;%k>PolE#-U#tnijW@w%g{M#C<2#752g(HLk^}*U?FPwzP~f$v(F6`=(CRjxoR_P7am3{wJq;w4>vA~TH>WH zFYQfSiWFwf2Ah2S`8I4=;n$KK7;K3r!>WG0PyBTp^6LWyrWm&z2M&z86Jy^cqXu*9 z&&7{JroMI*56?9|`%>b&JE#Fp4c9+==e6xPOTg9kna2mo7X3$l4T=hM`(z@3&7Wcf zxX&^0bLS~yQul4=-yL;4(DduUo99xG{_anx-kI5n9aqVcC%^q~{7ui7kgjRr3m>xO zAFsbQ6RARrO^kIq=URN0yZr6npIwgJpDzwxUA{Kf0Bg`t?4z_yT)U3ImZ6QGyja;0 zRa|=`tq6oCozLZ~*BVr5^Jdo+#{xhZ6fQz#M|U(HLz{iOytAR{eei{MxhVCO+j={K}C4(Ri%E`Unprc31e%Dzb~SXb)zUtIautV%JdKG3}QW36dlJ3 zI1OlKV;IQ-ru^xATv&>zZ>k3dcSE#@6L}W0jEdjwm(W|u^n~;WjJuEjI4OZ_#er;M z2&RljCEk{`k0X?IKq*g|PR5XN`96*S9y1F==rZO--4LyznN96vhEpELf=`x0FS95W zMe}4$Ge=Z%Sru}pJdnWL)uF5R$vUq*fx z*(s;!uPZ04q=&z8$d5%Es>~i7BYZqW+04UeC|zKdF4sCLkzPX;`6ZzAiNeKmTtEAm$gOA3TFukNupg{T9aVFGQ&<+OZUGg<;6%H zVdy4IH#iyd9PNhBn@;8t24ha0kwo6&Z}(&cRj!Gj#VrCkr>M75co}GgJ}EN|r5Kh z%3(kD->$T=@%+cdAGxYqKctb;ZO^y~<4wXLPvkG_-AGlVnQHbr5#vM=7S zg|LriC9;B!(P4S5w?A2a(gC0R!hDd5UrT;O+tnAhn7cAPQ^}YK1|pH7Y$5{EtO>}K ze!iw?cI)Pvd981*`+Yy(udgm-jubz8v+jpf{(~^Dd)>Y|@s+=a02TKKvR}Z`8ZKFV zaeI5T&}MvMCk4P#avb2nT4`3PEoK7zw?aeZOqKF*>7u4MHZ3NV=a956)(=F5`qLhF zOnwc$^5<qQ!H8HleDYAi?y`8?-!&}9lM#bPhy)(U zrgg0MgRpN4lh5f3Pzhygd2}OqZCY<*;S5wLg_5eUPJkJW1UQ}^oz*y*&berH&D?l# za8LKYP4f@QeAPWHP^37}vZ-Hi2K&N_*)3)>9_uJMS=eUUM@??!mln(_iRMea}!pz8v5`F7&og%DYr@}F&AvibAoZN*O`>11}Urd0ri z!sbFx?%rF5-}Vx}8Qr~8TNGRTBQ~`We}hk(!#3gWv>)CYpE= zSzXI=f$@Ljs1X)sRARS!1LjNu1JNPVB~;-Ius|JE8=Wkwl`M`)7Q}>znZ_A0fIwS_ z7#1K#f|xU*z3Om+vEiwL#6Gh6bzb}6Nc7}D{ETJ_OpI5tCgAL2RT1y2yvhd80Pq`V zK;#sQ(K3~z6RgSvASs}xPYGwISmLIj!A;OWIy8U*4W_3BcBTb&LPHPJeCwb=l#@?v z$zguUc=+E|4ZJtyGL06Y%1JarB21yWbTEetB$)0`S%xJY@3QDK!V62U6uV?zmxdI< z;tM-63ogZ_NyVRS0-vLR#jt1&EQ?7kRC^FsJLRlWow#Vko35VHHo^-vxyrvsKDC$l za*l@B3mBMXyFf{%NukqS{59wh`ze+i0OZHJQtPYc>HE^NrP3eu6|b~t$bCm(=dOz2 z)bB`XDnjy3UU59(XZlX~$-9C4&N;dyh`SRE$bh#k<3~Rlj~L;~Rwa|EgTd%F2K89OPyv){#Q0wozo3Od;O2zMK92Ad3AeU~12Rl?qwGoiMsM((I4 zWZfRDTtK>+QvO{VvZd18Ss=0E{CpQ4KgDtuoqRSc;VhFF^Mo4`$Mc+|?@WUDlVGNl zjI&!{TeoUtxS?nnntE)?8}a)lN$~!;Jr}a2OzdPQ4Z;EC3Bj*{agn1;>@u zD(vZJY;j-Rg4>fI_0n;W@C+gV-iJ4k+pD~}F7i+EezzOic2@Mn`!ufwkY@e zUSD)|16O#_`m4f|>b7jv?u{TKh&>qgtr1(BD|9~3hN4;!@TumRGeu^9B< z-_AEIOq>J_u<$m}N~;|aS&pUoJz%MjMh9InJ6BNTJjR!+(-H07227BA%g?!JsHzyL z@zU^-lR-?xC!@Z%Mz*t#_;kcZ8;kbSaxDsM=!6+AkkFJ_L%7l$Dyx;A`3w?nxa3}= zqOJeoIQyAM7CIyI{Kcnv<)&z3W*4QXj!n5o02ryx-_iZud06{tw_BJb&J|Ona&NXn zo4Y0P!M&N^s)kkfAb-!wvz;3!BW_S&zG%o-w&E0L*vo9o?B8Xpqv^_OMX%pJ!wUC_ z>h&!J^_Wiu)jjP7Vp#}AeX0SM6_+aC{dvZMsl5Dv_vpz3<;>?EX7{+L_t+{m)WoVf zn~Hg|R8-v5PYvd7&>Y3vG|6Jp*a5YVpurT;!FU6M*uvtgMT4naH5cRu6Umwp5<^z; zn$#JoR4(MbpG6ApIWbIAuf##;98H?faIC!kC3&rA@|hMHEe8+Hted?d1|!`xGs8EC zfnx&69!u4!?{l_&kR04!q^EUl!tk1KPga)GezsZUtj0n%#lDiJKGcuSY%5Sl|GlF6 zg{C5Xpcc=Cd^E*&BMcV$85;Z<8et2IY;tdsWZ{%dC%dFwXkr;$Vrf`_df}tP7bk)l zArS!B)7!8hbWoQbEP`Sim+l*lww8ShjSDl+E%jfYfF*@p0!RB%!!Csyv+Zsnju8%-J(tWgk~xzx0%NR!8?-|k&8027@#9hED-j#up|J?c&ec;J<0tztatxmqR`QQO3}s{!-J!fq{3feaA!k??W~>|!ajUK4(L&2?{IId%Z*%Yb?j*lGr+ zSiery;^DDP6Yf|T%b>T|V{eRx&t^bEA^`r^h%Hp(b?6YGmw1#S{vNpH+5OzE?Q@1F!EZ9M17>x|Hx+5H|XNai0EED6DOIGT-dEP;N znT9yJyAZdJXvD(@FHFV|*v`$_=v|dwPe#<*+W34neMCY=CrgE~=s%*^tv+L`r63CJ zrDOGxbbH0dFt!*9G;TM7J|m^(sCa?{w_$gX!V@(qVz5+uOZCVFae@(iqdG9;7&HJxG!a7pt$ zeAkBza>qs+g?;rx2l<&opE?Eg%(2`XhIT!3e=3m{froX8EX6Lfo#qK($ni=ht%3~i zixfOflvA}4Lk{i2ZxPtycUc0aSS%S3ciXg!rS2^YP~Y8P%O(~!zDzd)^mz*O2`|9^ zGjzOxB`A!gW1c0TX*`Uc_US4t8kvmixV~K;``<9^Z;h|pa^U^-7scgYblTW@ z8d;qG?+q^gr-A}?V?dF`-oI|Y{4ES%09d1^99)=58T=t<>RDJTHd_d6 zeooUYv#V{`aeEu2i?5-`-0Xvct#RAj%tD!RQFaOdKC>)St|Cigfm0tW^@eF%?^IJL>R$C=T`7~n>#UUx_9H;eS z^xWE7hgi9^LN^u*`i*PGG(sHjxzZ#@^Ax>C8gK^C4Z(^t@ngg)$(Q9PI~3AvEn=nx zBEUjsfP={k5ly$Y2IA(BmD$4!?OnyKX`}r0!EfS10v^i=X6sd< zBIu7Xs{%kAXx%mULDNP|Jjp91ZATiR^Ou-lp7Y7B(C6f2 zHe-y>c7H0@xg}czw2ki*n^O5n!*8X&g}*-*5E{<<5`?dERV zU=(I&_j|~mYy-!+fFbdyDc$Sh`K4A%BWuOL@z$3Z1(tVF<5qJN8c{DTf{ak;S@eMk zwXrT=_srOXu%AoW92|NVI@o^xd;+j0+bY;j0^pn$ZFJos@62Ph^Lnp+cx)?D`QF&+ zJjroOm!1akOen5AcE2pM62l$b`=1k?@Pd6^nENzZzqg^q&lla|@lIOtp&a91h(rkzl`UKr<~zE=4PtM`3c7 zZUC)uYCaC+4DZzmdeE`a74+yiR5!RWNL)zUT}^oRx)rF|Kvbs9mX>b;vCAkVFyBFn z0ieBpR7cxq(H$$j&EU{fjq#`4#6`MKw&EM~cb-ec&F$BA)^;DS+d($(B2<=4Lo}W7 zAFOztJ)2qho%Oue;3^xR*ZJi`%tZLzGyX_Cb5_h`>rrSPD0EP*QT@)F2;MY$u9N$u z_3Vb2$Y8EclHJEVJ-5ioJndbVwe<7jVncaqg;EE0)|s3ZMW8Sm%OCSDKbkyuO0I$8c!gB5%?n-j^HPJxej}g=%-NVisi3_+UE?*MmMjIY?oRXSj~Xvp$z$^A|G9 z%UzoHK|B> zBSlL{ft?RKunw|k5!zj@Q+O9ZO*J2q+h|H#USzv^AY)T|iWUCY1B3~(U#?;fcRSnq z$R#(WDi=<78wbc>8kft37N+Wf%IP|A`!%Iye|6+Vt01ybklTEhQ*!~ku|~bvuIF@S zak~*JaWO?Uf?v;j*~g57Crw^D9A^8bm!pblRNY0Z@mf#6R=;a-e9Gx{=EP*}+1G58 znSFJM(#>^Po*vCHBY-wif`yL`0OCiag%2Tsg#*&7tS+Z3_lr7n+ znXxpogj7g92uTv9ekwiw{_n3>_jzB(aUJLRJwG4wTgB4x*+TK9#AR74JAvr<(Idi2 zV;<*$!8 zS>q_CVH;{(v!wRlyno1v#>0BP2v1;@sviw7fL=CGIk-H3ZM^__l4m*p9<*?0??vlfZD~gO`eJP5LCc z(0YF@n_)n>t9499V&$skN4_aW{_{5Rb1ih$09L3Z&EvHE-ek5PW7lb>V4|QXNziF= z=?u~gn%KFUD?BBNK6VF+!-+SQd(x1Pd0xrk)LaXbBtqx57bdMk;KZywdL}+GxhW0j zu>$m=u`@~u{T}N=hJ~qWqR~5&CVc1QFe-^2;N=d;r)IhaHQo{MaqqjPm}@4?Aa;9* zeu21I9LUH&Lt<)&J|!s!&M7%dvEq?PrvJ^XRG}e(+Q37fxLU6OP1$6$RUEX)FD|Ou zOX{1m^AUZ(*%WGs4548FoPt!(RG&X24TV{c8)YwIM3c(~bT9mpDvh*#iurFg@we8v zM9M_G*)P%yx1rXL4M36W`#C4Byho~F75i$ilD|chu#m=I#M5^>&{HmFx*omz5}0^4 zA^&@n${{MJX8o>GK@HTze=rvJP#U}T6H}COD0iI%QPPccG?zuPtz>y}F2#GCDsC41 z&6&1va;_gmNvUp-zG}QX{|>Hx}cXY%*8s40%igHn-tG+aNtiil4< zIAe9`-hdj*=$1JY|L&WBo&026b~yf*+cS?L*8RI)Z_?iKxxh4U76xG`NeN5L%(vD^!+36zpw>S{mO-o6AX67l+jP?4hQLvUNAe9a0p0AeCb7CEdhqP^B{MOjDeRp7b!Ud4?`)yI zOg(ty=BW_TfJM4-2-w|0+sV1Ay-w}~q3YD0x-lDM0)zPS;C))i@N#_x^9<)Qx(VS> z11S{-UU@kaN6U@5Sf$73RsFs(YLxQ|*FlQiATu6)a8JxQj=pH*c$nBH78+T2w-ao+C$&qiR=)UXw_7Zr8?w~~ z-oq84J(;%;MS2X3@iKUTQRwN+T7a>#4CQ>gAr=HFD@MzRhRE}|l1y~QjuXfLo<7w z1KsUVaZY$(RO31yWZvaLyXyHMxXHSvLhx!h{eU`GYUxpW2s%&HM{zzpI0i;taMJIO zchd|7l{i&K?51nMD7p;hr_UgbuK&Z4EJZhwL5y8-N^l zg6EA0c80URDx=@&4^C_!i)b{@JT(hxf{XoVG}x`dCFQ#N#ue&zgE5s&e$G`;vSD@S zq|lH@Yi*0=+kU^De9!K50PBu1rP8}K<1sg*N2_IPy`NCyTHKxP%@SP$boV%mZXNy( zG4wZ7x^pTNxWrLtDUct{pK!)V??U`)i&tu@OggG$HuJeEVB<)zdzpckOh>zn;VwJF zo1LAvP_(&Nq+)Tya-`8>TP?6#?BL>!M`4jK_oBT2!XVXx6bEsQP+s$xW}zQkN}><^ znn2sb-vD6cho5_qnPAJw$M0K@ePQ41@b)J7KkZ5Mdi#ka=Obf=LxxVNr!BWA_aZNS zPCrwtl=~fd%)jSaH?0FQZoYuNHCgty9el*J{A?(VoCB|$G&5j=iVLcp_j?XSj)g3+ zk6E#~{{v$t_jL=ycG)%I9x zN!(HiqAzc{8)CW+(slq7u`^nV7WqC*2(eFi_05$ZZv=jMX19wz+-b0)feGsnzjdri zxuUa_sOl6GtE_Fb2tII+gPJcr#T&v=4aF9iNizan@g?sMaI|7tTjvv0eW%Nlz-e^S z+-+oOzCHXXH;q_yPg6~tjnS7@(d}*1u0_C!o0@$>7 zlqf5ZNvMJOuHTbxDiC-DSE!#08Uib`fr{&5`8FK}pB;?KG$_s{ICLj`g z0#I{y0HjQy3+#Z6&sm>>i$4y-Lj)+8x3%Oc_19b| z-$S9NgAy{&;ctJnEqZnW9z*7vk7(73tpzOnH>Ti=7w~i7i%cwnZLqc&Ls#~_W#BZu zOONzzuLl!clC>YjhA&+(%zW!z_?=KFd-0K7i-8FM8a5fc8TXb^h%+(GaDEBzF!*3t z;&5Q(0UfXnQx~C7B~AZ}EO~PCv0pc6;<5aj^_La^$WuW;oq6q}hs!n}v=;Rjg7*s1 z$DbQU!7W?7X_kBev*iRVA2hA{cPewO;7GqUm{^ms=Tc)1Rru8{;l3wEG|fAL#_NY@ti<9V@Z#Q773%4BqcLw z+Ykai=hyiCbW;?YURt}|(1;x}>TXbBl;2V`@hBvo_7%8MBWU0OIzcNl+b$@ie7r#h z-)OWws zyzKJo{PIu+c5&?=W|3r%94x)>!@DyVEpzrhd=2jw5XSitW{kJWWnpH9G=RP?_wSbM0Em@xy&$P_jVObwe?H12nk zlO-wy_*a4qU!a=gx=VQO_g)_V1To!{R=06{G{bEFusU)l#_UERW>Z8j#{bKndegdc zk7ov}uK0-7y)0u1^$vO=yf72O`L1y!6lZl}n{MWDIOLleZk>R|RSyi>#0eb?Lg3G!u`EtL?HcnU(Kd>%4hjZ33NO%J^u6 zN+O~Nv-gw5`ztFpUSow-U=&$)&H=plN8OMPlV%%pXX4`c>;g@rWqiKBH$fz_tE>Sm z+3T%ce(O7fkv(MIi7HZ*zFd$a3@$9x$ad+pjk}FEFQVnHn}V$Ly>%GM=1{^qjW+45 z<^XDxzw0TWAGJ^`EN~Y1t5g5mhK*!(gaw}m3l^`!`>*e9eqqz8NNcM&MVu@`VeQ3V zAGUWl*mMy*^-$7K z=6BPtH)&e=>Cw0)Sf)1|a*XoEMhcRV%%Qj2QO_RRV(C~i={nnL3P%eq+H0xw0?$Bu zz8|N`K^d6z&$8ju<5wP*3dD$Eb@OkgtD z$-mI=?4uvMPmS83E%OjfMcs6kb-!{W zFN$~a-?gp^qX~u4RUAMjgrEG5=Z^W@`Ph1U(bpCxQ zOGq_3vYw8qo073)N>6|G`_z9IA+7L_)QNyU`e!*t_AGOM`XzC$vyiFj*3S^+bJx8? z2sPcCSA{O%HLCtVjKjmqK0oPBA8uEyUWKce!KI%+^jma32D=xi*7r!he$eZhIi=Yu znQ7@j1Iz*gQT66fs1908$|UUmf1yF9e3sjEVT9I!+=b95P70x^tXp;0*RmD^o0QKJ!+l` z{G@D&tNQq#oATz#ksgRanaG>Fj66s)w+RQEb-2$nR|YBGkcvXx>~eO zaMS0!pp5aGdRHbvhJ3=MIwv|~erPTT#XUF(8BBjHF>_}eL#z*%wy+aMpC04Tz8Goe z`RfJNtaJx}pTBMkA4Xm^S(`U*o2>{OeJ;6!Xbm4UNkk%r6Fq7&u0kzdYq>l4KFj;N zQEb-z;uQPl{~#&lV&xWH4B*zM$7hzl{wwwU6X{cXjfKN6JV%`1(Ryns`{G7|lmFhf z)m0Ew-V&h8&8r)ZAVnYnc-tSSphOO3ITQZ}dgSEQa!<669=EdH4lrP>UKuBEFe|HH z(Milp66V_;&9Qa8D~<0&5Ae&@s1&5jTwD|f$X{gLeXnXEQXCTbWR5zlRcdym;dH;* zNCo~`KkbdyGZ;Mp&^#_BQ+jeZB~SApaaRAi{^%eQ5Oc5bqHx9iwsIGI6_1>y9-%gH zy5fO&$IX}^!FoZ3Se_zGH^}LKZ?kkj>)v=^|8llW!5?NugD$pbt5+p03*dqp6Y$)-JerVB4XZXowtn$rN#LQ!b}UXhwkr@2HA@~f zh~5e)znM0C=dS+9VjZ8%!O*IWz#|7oae!#4KT-z&EM}Qc=g8GA^qJu5m~XMydY4OY zUzvEgJMDhL-Vr-&dO<&K-|>QCCbyfWcGdgBV+~!-Ij1~~#KDYYZr0NDk~`9CHdmWn zR0@$WTZ^BOtJs7roc5En7Lbk%u3CN-d+f+b{BTfvrd$y@Z|P2^4h*3Wq_k(s6zyi5 zN{r4`4=z#dqGn#YMYWol&sJig@ip5VK3Q6K=v>m2V(O3czIpQ?4{7ijy{s-e%V^HbE-uZa@1_QIe_EUCfLSkYO3S zpBq{eg_bb zYwFMFRdtPSCqLjUYja$KmV|!&@jEaVr}Q=QpRyFBAQ!xm7d=TrC*Tmlq0Sb+R|mC5 z6HOzS*yMY94MZWAR>j~dsJL_&Sw-JP!0CQSf!O`8_U-^FT-@lgx@p8Y1LI7b;f`c;k zDQs)G-VlDPBpMqXSm6#de0zDCWS&=>E^C5gIP)Tlsh{8*tU1YBd@cG11?>Y-_Xj0! z=_cJWm%`TvDQ4*kH=WVO2s2Qxs^ku94)ZT*9#W;}{>_YHMtB7aoE$6F? zoF>Njh&??JX$blD`!qXrsYebnfkN*S2$QBJxVqV;1g+fkDU3Kl*Gf{BarS%>O{BK! zh+^`b7dZK`@z9!6wKHaGUmIQJpwim_!Gm+5xwKTHhGRl(2O+N5Vd_>2CkG?MnZs!w ze)7x44?O}Bl-DG_r{N5WHJ_RMg{h)!9arAn)s!-tKMAU2YioP3_eD=E1nNpy8B9p81pF#hU=!>r* z-=stSWpO1b1Z(@PMf+ul@-4w)ygdIxX{G=zBAGX!l{a<+pzty=+TxDhLHeo@k0Yu7 zKfMhkv_@3%rFmz!jl>dOu=1b#>ob;X5hhd=F}$&>V!9~J^p){%iTc9GZpazzKH@(_ z6DkgCUHB~sp?tMm11`wtn4%n7kNSIe3L$v`XH%4+uA}25Oi#MD%xFj7`Stpdb z?y`~6^sEMSDc{vqNZ~%4&tvvQaD!Y+y>g4L6$B&}!vslg06KCyA?^RlICgdZ&@5xs zE;wMV`?Y0AW{B5R;V5wMJf3u8p8wZ!+1PD0QW!8NPGyu;$ zKg&HCQmHO{{StM-XsN(Wz)P=^CL5RTR|A9678(E8uk1lCz(DsrXa!52Gp}k^LU=iF zus{r96(|ocFOa_O0a?0gltrl_p7B`n zSa`GW&W}7p)eIWRg=fsXdZ(-EaQKqMqQP(1D|g0Dt?(4|^GFytn9N$Z!*XC4W$7;v z#T_`#;qqr&6jOFypWc771IwD}B+9{OH{gCsCQc=Ik(YRW)n<-bt0PTTzM>rA7$Bg^ z1}f|dJM~Cwz8@=Pjj0y#VRuOp!i8}N+YkVs&R|J$Hwe2ZC=vJkFDQik;H3U6ayycgE1iu-v%Mqx42 zA^1|fCcPTJ(!NB1lx&E$86?@@<{d%fvP-G(s<^rB!SW>N2fL_`n}_g z?OR17b>`A^9l)IG;=2!Higp{%j-KR`X#l1))?C6JN( zTqNG%4dq5vMBdM4U}Wd`kvS~sy-}emfa$9Tsxx==*wXM*d{D&m?O_ZJXG(M^zVo8M{zp zD8FPBt9HgpRyyW@DggsZ5Bdrv=gKkdZ1dnDimx3JgP0hgSOK+1Rou1}I9hb-S1qt( zOzL;M4JL*PcjUCfa!ysHmmwgJ@NfHhLMWYC%$|q*o){_{86_Z$dFRfa3_fy)BNZuL z8=v8=>Vlsahw?e-jR7$$KwbPZqp4C=WNEx&sg}xZKjmk9?Vi+2~I98QCJL*|u+DMY0$%)$a&YPXu=o$J2yV?KBRx1`b*!}i* zX9ecn3wBz)ddw`2DT8$2wCwIw54Aq{aG_I$Gj5pI)FfZ@PMNP_By<2|r7a@N!hzyy%z+oKvH#j%a4^-ASw67nqLC zBVjEesw}Qf)N@Zahx5OtpHfG@Hgi;0#?B1Nu10wQY_g-Z^JPNbB-lvDzdQL>yC^M0 zST%--=?A?O#B{0MueXZkY`UwnNKf({>wmbTs7TOXF~B)bKRH{>`T+re=iC;6$d@t6 z=Wemw;4-+;7B)ugTE^%3n?WP5n%Ko6tI@(E@4+XJ6a8O1;F))k>5oEATwjN6PjAS1 zU>eBxS3zSML9~BZo~Gu$HIHfXRbu!!UeA!rqt23gR%pujm(sXlgCs5n#~=S!Zco$I zU>9^qY%dRTjF&3B1!Gy<8P>u>RB?P)V(bb%d34Q~#MzgsvO@CB8Yd5jS6|SF3swIdS@6X5%yheoH zYoUrk0LU+cK^|4k8P&A_djsK|;{J~^@8e<|WxeEF9@heO;5X|J3HdPLgCwr1Py090 zct3!KR9Tn99=G9fzHY_hE=S8p0{8v@C9TAge?(jJhz}xx3h<$ymz?1u;&HLewn=7N zh?_0^p3Dp|1qa;K{Z1?ZN z$Yvs@o5<16nrXb2pPW=6H@uw(l1bvo@fb(HJiD;DATu99o+Y^j&+sZe?dB@=mGq)>l_qq>)| zJ~CXAI+A!%AV$_&4z{8`|M{`W+HgO}?e!OH5WmH3*ToplyY6+5!LeV1uYcJ*=r>E~ zYpc*a^e!yA*9Wvmp7Xr>aI~-a)!meY9@PUXW;;Un8K(K&!>2)4w&Co^{Dq6c~3zsy9wHB!|=s=^lG`GCZx#H0DFZ{4}K7S@r zudwC(F6rWx38xEfI;mg&-T}(weTkbpa{1p*&&spTKWJE^biA*qtb9gQTLjIY-=**C z(da7ro0F*dm&H8d9Qs*d+7j25{E;DM_Q|2+i$e{J*ddys*SR}OZiHPB#j`jz zJM~W7oTc5&nQW3RxpR$imvP)Xi4rr<4t%)7^Wp?1hxUUooB!**{_a|$wqy!XTPCKK z;(z+m!`{ouS?eJsC!OqWDprfGA`I*@$0IJp=~ss~a6Y>k0%`ZqaZis5V9qn5q0L$D2%%E0mA?jJ$7#`O2OI3CA?0@78Xm+vYRo2^+VEL873KKGiV!Eis9 zob|C)ZsJ_l>!6)yMh89yQB^G;BCd26>GYdpTVWz@F)MivkujNaF+g1EUUA(O!<1*o z$)j8kKJT7tRF67(X5j7^XKH%0%0XaBBn-i&HX{AAUIJ530X z=dUl5O0H6`Z!&%lu&@rUV{V<@>QH$>r%a>mZT02C zK%aV*=j0eZLZz4TGo*gd<4aK3iq4o59L}4f-?&wWC`37 zx$lvA`^n#5kB1!-`-^JxJ2@Y;@I_|!!SCIF{)ITcMCt@|1#`fNFxFC7IwFCfET$3z zqm&26ei}lZ(!9wcrKf^Ep#o+Oq2t*E8;7UaalIphl0>Cp5u&j9)R2U0IM0TG;R+ZX zVH^ak+akW)JO2z#Em##g5%+D!CQCjVR;rb=N4w70+Zz?NnuQOd|BbXPY@uH%SH9+# zF!*f%Emb(BXs8JK)MGgdYbXtiEB9E?`68uKbo~Qy9?>ACUwGqYQXdI(N})tYrd}o zqKc)iX?60zMc#x@$u~w#YSRmy)1^${1i+56ljSy#E=E|GRT9vdjT;ap7Co$=v+Q0i znHxk@)aRQmQUCc2_|!lYq!I1IBzm(!bH1lhgoOcp0OLj_G;&fZn#^m7R?0L-p<#8 z{8}yc3-4)Z6g=5{zNsPZ;wt)F_tG6GLxMo$&%mi>TJB7C-0%HZqkKoyql_=M_j66= zeDr?GK!nH%TKxn2Hbdd5O;7uR4+HS?v3(j{uU1~ybo_7N6E@&JtVU=M2h1qcomsSI z0)hkR5@A?5&tZj6-=Sp!|9GyWJ)X?2lqr2i739wdc&D#F0*p$k8NvPuku9TV+f%ib+GhW@ceT z3$l)-Tgz>>4w$&aXGQatF!O9aCv9t)S@<&z-ZV{j1}K&>Rnjq8mPJ5l8B)=Q)Eq$0 zB!nG~Qyzcr)zMzwvrLCKV8_j=nZcbg)JL3gH#AK_eD0aqRNH~*@;0F{%%!lf*u_p& ztNd7)hr!joKR5MfJ{bKZo;z|Fml0pV=Y;z!17_JokR3LiumTgIP2SM?nW$Lg6G;lH zVCo`i>VCUJR`K&!^4!*XBo`)07LVhg^0Si}78F{2^8C8ui)loV`A4Z_2fC~Y zF?W}k6RT3|aQ*p3;jl`s=&2e=S)R?UPvNd-y`%osKPV&;j<7-tSLRd>cKWvE^%(XVXSh=m@~Y2`R2CJ_PQ|k;{oRU-Y*oVa;_*X;M3JaCZOm+(jSV?N#C20qOscCjKB`MJKOj%~A%K4n zcUpf{vs89tu^DIkNi^;8y&=MDbK`V)1WxGQbFcag*Kj?+JRlc?1Ua!q-g zJ-+aItb+Veib{E*MmTcgBb8yV+{E|?6nBv47sC}X+#J+vtuGp^(y{vjv<0li=eKoQ z%k5IOEkFP$BerZn?kC=+7gMk>_$GDO1F8y-;CDyAP`7Bzwp5(%I>ZfX4c|K-@x3O; z_1zt-z-fW?7$8Hhc}W5m+vcrVDASfci~Jsh{bNUba4dW9+5)>`f-HtVQMlvo;%9$arD zU=*ncDDU}vw&ihobjOZgRrgq=kG`M*Tl+fsq!CovwBs$p3)#(cH`7qfwP;p^uh*}r zR`hndnoAw^ddyR?r}7)@5%0VnI^lVB;MiKx9=fZ0P_8R3%hMz0XqfWU?1F0^f5lLr z|2oK~b(>spy>g|4l$|TqGYVY>Dc^_NVCDf?o`WlHu9-XIr^bpds?DXgV;51I0K1*; zJyQ6{#haIixt4QWu_FtEX)8SnZRt+h0VeM~@|13<$q4A^)iFP$71ZmcE~7CLqt>J( zwO)~rh^MCCjhgjE5D@GEFoKw&7hNmV@4k+d?EUr?FvS1Ym+i!S)EkX%M;*DkHSkVfSCM}K_|dA|B2#^X(CB}b z{&T@0vqG_uHpdDTx(gfjlfL%W((V$X8ZCYMh%&<&rqo7@BR~2^$(oSh3-;G=@=TYr zNv*mU>@-W0gWSWL;__zK4Bqrr`s=(rUebOF54zt)cyLw!wW_Wo80q;o0B0`qI}M8* zyuJ8AmzYji^K-i6cWG$KNjUssG_2k*xG2eNd6(egJico;Fd;22h|EC0nxjn32ETX^Z^?a zejP6w8?(MP?PfZWDKUOWZ7W3bH0jArQvCc{OmK{dnw!Y=LA34{r4k~hS#i9Th_NGR zcP^qSWWFF=m_i)A@*2o}^Xe;}!7srSc8J>6E$h`I~CF5H9(67A^e-Qb7Ay!}k z5P(r5*Eot+9$#{ybuIVp^wVOw;EJ$H~KSBO>G ztA!dTCyR;UGoBe`&R_>(exL{&lWWAL{G?<86w&3NL2QJBA^^$J zl3Lc{eA5~!)OMz7gBP`>>JT6*A_dr3NtB8^uMGjbaiAiTI0%XJdjAkn2PuljXhacR zBI+_3b%l&d{V=*&kNRn_W0|212cb7Z5KjC$2I@+fWdmoDB90@L5U#DMmq-CAO6XO~ zDv2xDqv2%H`-7#zp71#=fT;vnJM0P7Vp_?ON}-T%ZYXo0@M%T#?v~gyP#K7As;+V< zM@E4tX2inP`w5bfVXF5w%`RjgtJ4Kke~_426otpAXn+02qN5t0zX+f9m|ql4v$NbB zTbvkJBz;0ReL30dC>_zhJ51mGW_Z;u+lPV|o5YIjFCxgx<;@C6N}-~_{q6X>SU9Ir;R!U^kxh#2)zn`(lA+J;t$<5729EFI)v5CU5zE7(iH){2958S*veaeRCzT(A$ea6}Gfd9|5tI zK$h1%)QPpCgLoxbZ%tF%!%K_YZAV4}Nl0H$sUOJ6R%AN~B_`QJt3~=q3d@h7OdLf^ z$#$VuKuQ5i^m}UH-!sda`JJy z?RDQ=O9dAR6l-N1W=U5Q8qGatRE6qL>0_e7)T*TPJIE-VoOE;^T_Pd;8-=S@b5}8x zYKEvommP9sYc-5xg-!#7?uUrJXN%Tk2zXI|b|HK*6n^HS;QucMQxG9kL=qLzJ&ize zqN+*|5{iPzC2bV(kdhmXBA#{SAks+cACop34(YS(BMEid=4UqYonw|hA|~0`F_2p+ z()E)GV8K^$>$O&fqWHm9jn=y#4qr^zEfvuJT*96v1mZ5ouzE0l2W*0k2{~@ zqGWHv!?h~MucUv2Krgt59?7eHGFc-6p{{mmT04;JCk~q;zGmr52-(*n-`G;E*60P- z7qg0hu_ec4VoaI)kkMRRm)s0tM!^f#@1&*J9B7#koCfP8SvshZQR%qZavb z+P)0$Iw1(hL+Sy(;)61Uj7r}#J+HX)yIqlMGR&wY_s3|=FT-Biz^6ja)iM3$1fs_G zq8}W0EjPOMvP`J!xa*YZHP0pfPQr3F21!J8>dI8uQW+FJPS^sN6 z2LLTG2oXO?5oiD$${i1p`*OrJ2^WWOOR`b)*-CFaDWyosE`rcX%@=Lf_4@@(;ZN$< z1`CREDIKkcMMIVV|4n+1-g$Xc%*}jj0ByM>6qAhtcAKF+t#$LQ?ueUDg+$Qf7@iXkB6ff9YRU(*4I5Mr2QD(@kp2A5#lfQo(~F{Z9d^M` zm4~PX2=$-&k=&O`j+yA2!XHERHPsEvQ`NZ2SC%f#hDfq){HZgoFF@`ve{^PO7Hw4v zOOoZ*mAd}vd`A=JvD?qq1IN!r@Cqu$;Rw4sl1*n25TZ~Kr_Jd zvZirMvbLuYUdke!ixS$AQ+uok71p~VZbVoEdVezPsy%!@#3EQyX<-c7x+*eD5$>W0 znZ<%o55zI1G+7cbLD?9a85;z>Ern z<8%J!rMJ@#|8w(f+KNHBq$r%2AmeROQcL6=Qq*dM-xCbYC55)IdXm?leZ;acl4UHk z??0hO8ff?F)Y~77?Cexq1!+4c{+Hr+AvOKkyL`mG;4F!&sPJQ10wO#yL7K$TEW6hv z_4us2uL;W~&K&N3s~q>;qK(vAjZnxn-?7@sao|Joqf?`yw>m$t0>2)yNjQ7ugF0+a z$|I(&ZSBR)+@3UjRXRy4TT!}@gS@mM8bplRS{eKkM*GQo_?;me^;VKE4gnwv-VXsB zQG{2kh9*^s{S*wS&d4ZK4R~@pfW4a6NfCHbGn>L_KY-tE8(a*Yp6jXV6PlHsgs^YW00Nj$`#x&Harfy(Si1On!CM14{29Zz{&yP^J%|@h?^)8ZgvVp#N)U}ICBfmWCPG8b%bWHKk z%YPp0uV|}ebUB3wNfs;@`5F&hxS~DK%Whi}6r<@?NTjVs2!B zn&}XXe@JE9#>|cS2=VvJ(iQh}Tc?>4BmNRT2i@tK=47E#O|`gbbNf8?sOEcn1IGlH zQ3RssG+Q*BYLZZx`%KNUIsgIM1_q(rD7 zLxCzln<;IWlt*pcW|HjXAtNU$#2E|35Z)EnaAbmDNo>AQW&OHO?ei2yCqtbQq^AJw@!?c4D19a;Red^zhh)slyrS9dq%^zBklwfP{LJSNM zIT`Fy@gLXLrR=V5>?MJYh>qKjmVqfMZ2*^sl=_X{hOil?K@gOzR(k>}xPlz;0O;TR;Kep*q$vts^zLvlpnW_d5pS>_m?dCMB<6AwXoE&_O}S^u$E zb<}Onfju^mM-2;C6%6v&Vb>-7GpHcTQwlb4(S$=!xPqZ(&M0S#da-fSs zDT~LSYfH*c6=kAp_CN{@@x00A7=y)m^y@S-Q+II*z0wGspmB1m3+j+}2!pcE0hxLS z4Yi^d;Sfw59AJb7`|^Ft(6K7y56ioQ3K)e4)5KA4{aZAoH5(KSRfL@usAzx01oqy# zLA2*t9LK|z^dx~N9PbcR|IOCBo7P01Q9(;zhGP7=@}+w;bnGGA(~D`gpT~w-vwevOyt9-u##v!3s8cn_Dp?{c}iI;^7IM!cumZ=xV+l%Ycb|wym3Zt4q$;?Nr6dN zPuI{*1@CLwDGqD!2nu&?vzk`Rb3LAip)uqGc%TC*1 zLG$Q74wbpLj2vVRNdA-HL&l#IN=;P-qwzFZ>=MiqZwqh%=AKwsKHdL#ju=DCYh;1Y zk=A15!zJ~SbI`*~3e)NJB3}t^*ymo;{Wlw#>{B}iew>2{>mHl-f}r>#ah{F$k6ZN= zd-`^vsyuM2G2(fV$6wyuZBZ~$POi64uJf!|e{dBF;Avk)J+uRAofbCCIB9 zJ=iLom8T3?L)&NQ#ViSjr4C@W@L9(;m*Di&K_y-NZ1Qc8Wk(5BechtKw@IQd^6+E8sIJ)7Ev~iHevA^uGi8 zfr#t2j<7Gbc|j_C;4^IN_6EyffAc*07!TEOXoGQ~Y$+gn;D>BsmNC9TXsUNYZxSyU z+6|>HzxqFl&N8ma?tj1=3&u8J^ytx@(x7gPE=MbD#U1>w8^QjwT5L!7Zyo6_6mUr&zCP`97J^>HOoA z(8BbW5(?-sEFSO}@3NxL#dCR&T9rlae*g1T3qf>5EEH%1gw8yAb-GEX&|Ee6P=>qN z$ci?KjCr8$X;|u8=y0ZQsr34s(o1(<^R+cq_xW1xTZbb$$`+r?-L$>aIUp;*Gn|m*n^UntkPfnBf z{;?Fb)D`5p+pd}ysx9_Cx zHqI56#bts-T3Swo>oe+hZLA)UU!mXfmdqOvmbsG6Lj9<{cK=-tGs8AMsD8t zmJ|5*qxA8w47N`px4%C%<3+J9~Wmznef936y-ZuvRFm{#fEk2iN62 zc?QAF0g~9edQDSKeDUAVcosBu51ybW;n16s5M=#QSG+sUXmXXymjkW#iL92Kq+ugY zE|Ita;Y=lX2azRZBS;^DQG__S|4h;o)>Yt&TjC%x?y|Y40D_x**$xe`dwH3cdcA5T zl5i@;fp{`q5ArUjS;fLBavmX#-ee18*(dklu+-ap$ebTnD&s^-(ovbNf~-CJ<{-fy z7N-v#>>GQAJBTxxg`&jzHqbo=7Ni)>h}+*?Mgg#hSQKL;z3-=br-*2r4$4th_57A* z`jBb~7MhT8&5|#B=3v$b+c})u2YJddW4~|d#s)|=Ii2o8!;&=w; zI`HZ}WEu;WP8Ti4=Bg}k()T$v8gr+%aD(XrgT#=FGZ0E_&LAlk5r37A^B!#UqkV)`W;{I(5U%d#gJwfek(JUHJfPJ_3<}Ea47en58!8%pOQ$8{~NC5KF$6#Frin zLB_0b$zFAHB4?rGkXJD%kB_3JuTf(FX}?fZAPR7GE91r%>Iw$-i0FIq9r?HudLfoGE-a5|Alaks z<@s;<)`AT72mA&J8jsZ%>z3R~%KMb;ZmT2F94CBY&myhx*RREEwp5P4O2jt8GmQl% zY75jtk{zIeA2+!o8Su6=%Yj&dM02?C8p1RI+!0e8lSWx@nUxR7I{W6oHH&ZvIX1*T|HD6)PJQbR;KQg2`LWZW8olEYJ4 zdao!6>X=6$`!KK=0B0LYsKUM0Zp1Adh^)f8QZVlNt_X?%-~|zuzH+N_76zPwUAuaV zvV<~*H{jcH+YbQEwZsp(o>Hw)Oikjt24Y z`>dE>i`hhFvCjg>fH8t(NnzccZ4{G;OeJs*0|IYbC2-fC;UU9%u?7KY`5`ibNixVx zV-&Qu;PPpBi&!t#iCFhsRF|S%(P>20nbi2xT$?7T z0H;Qfic1S5M*-1>QTds0c5b7yix{rac_9EV!0{c+0>EMcFo;jrl494gqWXe@-36Ju zGe59r_FLEnk{ZmIC$T5fJ&^A6HW>=Y#+9ohd%~9r^`8Nh=|P2*;t zF3cH^yv%}5772ZcEQ_$^N`bk7#F(Cn_r&C2J{<6psL~1}#@L?QMFKRs5ZTH?-bHbh zlDNuO9*jgk{__ZOMH}9QMKoj1{%<`n-Nj^e!{l=K>8K*&6%6NQF{cj$?2m;;$)0=I zO+>yjUFuT6TS6oDOo!K>e$EMr>LB>Ka9-?y`mn&U#PiDnru^ct5!5!zuAvg9L+C>rMv05kGv1A2$Wd(lW zs($xsQ@*WatZLv~N#{?hiY(-TCl-2Z|8KsAPel%0Yxs#hjDNs(iPWo6`c;`x2jGCgijBw%f~a$>=X;TpkNQa$z{cJNkiaS zB-m{N{GfRB`wut?)m|V224cXUx41g(xU5JZX;FahXOKZ|Yx!ia*IhkP{~AB>S>u&i zDQ;`2>#bu2zMpP-0yKQ7;85I&hh0a>9$K zD`|8L83L?hhf%oHR-o*#6&-A~2l6SW#acj5jg8kbj~|}5iN6sSQ)CnN((dk6JHhJo zTE$A#c-TNzt;D$|(<+jHeeb&cLU#` zi0~#L!w4XF@gg0XrDBwCeD`=u-HD85Bsw^C3hAd2298=z;S5Xc`<=xa32y9DafT;C z)K^}zUN~8WU`MIwv)@n28O|yHacBK4RnDB_@*zyu3pgi1q%SL;jtG7m(M4#-LF4J1 zXC~6qjl#Z=`;|^Q)Y`#87j^rF4yt=Z3Bo;UvR#;6LoSbY&2I#)2aXOs_)pvJCRc zDyN|C-Je~R%=VP?N5=@HV6Qh$yuMJT1&mOi^{pRqQxOy;Q~vjw0-cK-@{OJ|Ac4E5 z_`!lW6}B4ez<_UF_>9gYwOM|Gpp7WVa-O_+|4TWay5rA}k0tcsF*De=CCccL=?*#h z>lDQp#_p}N&z3m+xAp!(C~_vfzHBoC&00n+e}h=!A112JeLD@t(|=j6^ad_}w%mJX zup)hw-}><$?Gy%5ROHwyww(Uraa?xNncwih4x3TNg?sTAEA8Ki=K5cJsov%DjBF)c zsvwZjS44N)^z_s|@#ZIEp_YP&CR;+ON%~8L2S_&85DIWz^4q@Fv5bYJf^$WIBfTN* zd!W;`2LM#;_;KJqUQ6h@%WUN||1fx>)pMvirPei$%R%>CXJNGsErf`}v6<3Rv>j zh)&SBQ;l(Puit83SWcxr>tW21?g?(GH&NVuQjhEx-xgrY&5di3&; z8+;9UW&!&M?a}}2cF}CXX*ED_TAVtGm}VPRYl8&tSO~hh#aRmbChl9JLrUVT#9ZBA z*x(!eq1?KMbXqy@xu{OHiut0fa?cIy5HF9~q^gyScoD2TM0vYTAlT;*yt%zDQMobK zZ=1p&gguB?s9H;zQY=l2+Tt-Qhp{;2Dt)4An`4QTJWmR+qe0-@T&tpir|c*XF5h^n z_92?KWos_&zAX}L(7Dbiz3rB1;}jOmCC7ljNz0NiXQ~69qbKD6gtV+F7K+i=uH_qGGiquWC?&oi!e<>A(Sv^eLrdaL;1Ow)1uR~h}m&&1Gib5^Foeqik??lWINPrYG$d_otm{n zwD7)5J=H1^n;cc!bo-`3AB#j?EJ)x(sepX2Z%E{3>cJFesl1PQ352e-f>tOmh?p=vpPMofXKftNDgLSS$zWWu z6fn|C-rIGaV6GmVyN0+ITsdLD2YAp5KWB>Z1t@2N42EeW{cImC(mq_zC_H+t-d5X+ zoUUHVD?3~c;x8v~n)&U>{4d(aBE|xVqpxD)5Q1wRn>|Iz3Kl0X4zmU&)mP>W>nX~S|$XbXfgPUrghOd#|N-3 zfH=a-xFuVgZ8{gMQ%gL}Y>@67K*FLUxmDL3lf%U zQjUstnX)lk%hC|k)m1{IE3L@$tC)pyo?!tca`)kK9L`n+NYZ|k?z27GhER-`;E`Fx zLx2sNXTweiulYl!L=uFG884ji2p8}}582firN8kRE31~V36CbwbV&O`f;!ICPM~6( z8C&km%%FPD-uge7TSAq8($K9d765qA*y&BzJHI!Y?F^1bP`Ce5_@iw=(z*wTH^A}G z8-9M7nz;0a{_LBD^UH8xGH0-xLb0YSCR8@K$3AgYNE&#DAd3c^^#gJW#*Fi7|H{d_ zJuN&I3sT4gIvt!oC`{NAkjk1(2lxTgH=|%uew}sZ`rIO8OuTov%bB9oQ0~j9QT>ry z{K4oUUVoH@7G-v7AS?~tOv3M)nNKwYILj+acuPCXpJR@?-+vmKrLpn}qff65*QtGH z)$7I=48fx7ZSZ0~kcUofNC)+kgV+^P`o;ggRUo%t=$NY_y3_vGfY_%B$E<)FcUe%& z6?}+wk#1Sfs!)P!tvN*}!xi1o%l5(pIj`GphJBHUl(4sl5{NV7AN_(QAC_5=4)f z?Qn>y-2)=*yzO{$v0NeJyc*_qJ1HW%aNTi(g3;I^1)u0*V(6#7n`(++&zz~=g$=bq z0$xgRWUQ}cBq{IinyYoWZVg}v-RuRD@Z<9zIP+3Ne(9~+S5msEjk2qC{(P2*E;6*m zb2>!o)T_*o?%2N7^Y^twLDwq$81u)aE*=4Rj52LF+wKC1X(O%qbp}F^7_uqS_qOr7 zj5JLo%X8W8;+6f@2oP*6Pb-f!$H^Xj<0SgCIII(O2JLz`&v$YV*YXH$W7uVjn7`ciG~ z7+Ah;GEdIGLib)?{`$!W_9q9+4C1Ej*|>kr2_fC~wFKoisqfA}?If zaY!Xngl^q|MHT*{H6P79P%Sf2JKJwL0RrU5#rl5s4NNls1J2ZJsTIJ~U8=V{z{}Vg zy+d=QtM6c;XOk^tKY!i0_xJkcqrY`L{>lyVf7>oo4Tt6ST?AKN{w=o_*^`fwdyNOg zMYguAVehG7rXp6;m8;&_pB22=g0$feBAN4KK5sRDMNHFRMs|0ttXn_r;3Arprp8rp z@c^&8h8{l-J%N(v+71_}f$kHfK2-5G*u#pB$WK78bVKHUsayX(_}RQNB(}4X{Wu1K z^>8+PbZ%Y<(BCHDPduj1Zss$k?9dK70aMNVhmab?y3jk`qnuZ~$l#739u>W7Mq^oq z>BM^(ur&MM6we4rMVD$JvV2AdB!rpvxBhJD3S1b-0sx@yvSRpar8)qb&4~=3x>%(BdcyM z%tpDBK>8>!QClv+ww{GWarEb;$09Vj>VVzwv^|DB79{SLlQw6bhT$LCK2e7VPI4g* z`$4*kX;o2}{37|E!4G6xrE|QpvKVdW#P0+qL$Cy1EO^);f=a;*G~1e4gci%zX6AN) zs_fYRJ6?uAiz-PUH#Hli5ob8miTrLjq30{Yd~z~u7n&B`jLV{-EuLz?G~J)bZiA=k z?VWUsVeiB-BNO};TmVWe4y|V%_a_uJpSphIV=Rb3 z%q_7&&{GTPhX?{zsh(>r(7~?JqA)I+_fjj*b`W*D9Aq2|GG65QT2B4KnA|I;er}yq ziRaPBf;Q0knui=3ha8GCl-&s_BQ!bz2=342j#Q8g-OAruDeQL0 zUm;NSVD_64`QZZ`DiPE#?7VGKK7a&jaJKw}c0MT2H(3-mL+fYofurKA@|=Z#CDWW| zICKlg(i~vF+J^3XNz@oipDPr^zwE{h;0ZxueWF>ih3ZFa*jGH}EDO|4#KO%CCuB-A z$eHF>5jM`5#%NPWs8+8z-@9+mSuV6+HrzR#XaZ5s6@Ra^Br^mB<~eF&$X7V(AX?2d zm!=v^Ef|2sv=bX@|6Nx`)tx{(do%dN2AURzJ!gIV!!o%C&S&3Z+CE=MlvV!)&m-dR z;^=xRbRTcJmbn}>XquIrTMa-FSE#Q)L&BWP!nP&#E?5D>3b3p)A?~!Z7FMCV!k4!5 zP3Ry40FTikhujQ@lxY67ZHhuI#1oVC4^i*MUiLpTRS{nx#}VSk%D+q9*pOkahV?H#&Ren&vTsTG?2VwUF zG^)A!s;U}4>$+Li(MB5k3QPOx_(nBR-nx?AHdXUp*DB!2s}JN!s?h$SFz^dv77N0~ z=H7{M-AO?{@sid%$)_l1Sl{#B`ZjRt*n8N?=edzwS!@YSZ5{Nd`=2*5c$3h%i+S_0 zmJ+`YGVQvkxP{kD3`*rs&alLS<{WCk3#R&*)l@Z`_YD)j+nZxaCEvZ{vulZ!*m`>~uP@nYLx)H;x7Wp!z12>r|9wMsi2SapxMpe7A%S z1#-WLUH(;(#nCzX(*bJ7q=v!Do}qoKwHY&~QKn{(bk*nH?0d+GX1&RUHT;&bWp@`` zdv{4T-Gm5=PqeYJwa^@bOMX_q*OH}xz`VY$!*i8ZBLTUz!@qZA#5-6DDCdmp@ZP!i z{+B7g4=k;<2=b4yr3zP$Sd@+U@c}#t1=gcGL5E9v)#i+{i-Ortmr!*ocw$m3g9-v^2D#YGFXSSdjkW zii+6qjcpNB?<7x6{yvPv*Ww(rc@%JC0@>;Bq2 zEbBMbPKOi|bn89bKY+UuHVDAgjsT;+r8{8tlwH)F{laoU)-%em5lFcg1NH8hEPOL$ z8k|+(M?Djy_th=X^q7XL?bN#I#u`X?=h^}qAI{0ug`R=+IBU4iZp)eja~}3O&n%Yb z8NYNsta(i&+AXG;9&$vB-sV_vH*0D5FS$*pVW{RR(uYo?4bzTtPEXQWk3fhgjad=y zh=#L(VLpY5bwo+|TvMhJH~h7tley z^xq~3SHySRQ)^L@+8-5Y$twA`XSY#pXfb~OrrNcJ$gXjesL5CN} z-=+@>V(Qv4xE_?3Ucaz55B9PJmrheTsZKF+CF9wO&~t~Bh6z52CvwL!P)`z1{r>y^ zIx`EbK($irZzY)(CeHtb9p|J(RA?QRzQF2J3LO z3eizVb$Yszu8!%hUeGIq7|x8RmfNla{OPVMnW}HRfFRcp82E|oSjK35OBeM`SK!WR z{yNZOYzxT#d9!*PBs3nD6PNo8zf4ubq?=hB)5a0iMiORRa>A8j*3*y6-vroDoxZi9 z*eEUdd7?`0s0EVwPn({}Cs3sN8=OsWD@cP0_A#QJ^5_0-^)^#Ti7R5?J@v$93;pFvVNbv7iW> z#A~k&u65t>jG*2^ztM1)d60|^ZdWu)Q&oUNPh8Z4Q{6TJE^>Z7xrg2J;jX_q(lu=^ zq`$7Wk{4(NrrRkd$!^x(oSzN-UkPDzTl->(P7>^2pHD7BaQRIc22#oOm|D`e2lFL> zDtP#%6!6l9S>1T%&0U)EuZsi#a-s80`%b7zpu?zy`ujxgIpMj=3lR!CVL~+TF|BHToko)BO zg?pu&@9=`IjPSKwBidig{k{j)RZgb1O;2L|n)2+=lsOs=pTg{znXcX+txGL4oEGn) zzFP=;p!5Cn=5We<#$8N!v&2!iS;rl^R_F|Gy6#U9@6lelI?fkMHS4Hy{VsRr^6w0o zwO|6M|9?-j4$E}C|CFdS8Z-KBf2!J{-gLb@RQlpBLclMh% zSWvmN#}l`c#8coH)v#v5<>o zoN}?>W-2^(6?RK&0F1OC!*W|H8&pH)lr3jaq=KOC+Jk=PqY`b?VfOwAcql@Lxrl?B zZv-)mF4iXk;n5;a4gA{8FQ;hBP!!Ibh)Q#`_sNVr3;p&25LyYMKik0L8y^PWdrT*@Q z>V&!eP*3Nj14LR(L#-Wvt=vy^6f5%L)M3wXEayBqK8eIvPJ53Fc+|86`^EUY|IuXe z@}5O$+{(Sq2`!sVA!n_I{!ZJPnn4{qU%sR?W$EM=bI<0xxAorVzlvL++a*s2A>GU0 zzou)qG2%E$Nwz|y>y7=dB@{yUWOB9D=mp!cqBpROvO{0s$+iQTj8)up@>m9v+u^~rG`I}4KR znX=he;1n$Zhvz)iDl?lrxmg*tbg0>Q zFn)c%W~xmX5W2K#l3e^UIX5mt^YL+=`Z_+}g@esWAZi%o3W!3q9x@+&myHTr$BXY^ zGF>y}qkoBe*}_Jlgx&D8M$xkKhpgg!GcGj4>w|)y4u9i@^+nbyuT@|3vuCi7NVqe6 z>e1GSR(MX_gL>QfO-A~q{!iG0s(;b}`w%Q@$VJc$Bl+12y%^gl!n;Nl-ekxmTiRx3 zZu96IFvKbZ&jr{Uk4nyw8ehNDv2E7Ag>lo7Ki``t`&AsZ@!e2$m&qYm;&n&-_P;sY z3RxL@%WjsBuq<~-h~SmX{M?i{IBo@p8kC!o;FCuZ#%n!%2J*%9_*=3_Iu(;W@9hK+ z5Zbl1mZ!MZQ8F%t=iAJ=j~S<+CG#O;mnh$~MY?RX-A2+~B|_{7!zlOM)od;1YQUIZ ziSJuh`ew_F_7%at3*Ln z7);QAvAw9ZjkfTovTzOT{u4*9t}B#8(chF+xGDHl&H;YH@+lx2FwRlrI_qv-vh5lb z9-s43jw)UG(!P0m-V?OXE55^khj>AJSF2Usod@}&lgzoJvCRqE{VpSd-+2O=!!Fyy zEv}D(cvzU{M5FMBl3bx~eaRz=$}*W)Sg-)cb<4UYmCARCVDtq(ZjFFiIKhv?uh>2$ z`6o8Zb=(}E(0c3?#NyyAxvqaol|7<1PIA8EkfGVkOyg4%8w@`)qUbBQ9o2ZHRy|SZ{XtOhYNLvU^65nX{Mk}jG3m!K3$YW_Q~e^Esf8{o zXbZm5Ch#py{O#VI-XgHIzq4l0R`YYKIQiDy;W;smI1NPDW!a%Qp0Z67_}rR1=7^i6 zNO{e5PX5(>@?ih~zy||elV!BA#7MBYqUSpTD*pxD>Wd9R=x2h9^0U+!R#Ti7HCI1O+{^<%O_C-_Ey!$q!>t(Jr>2Or59Emz2G8=mOUYkPWv z0~O5#8y+S?1#D8LiM+ zT3sCs=ifQ$7r2`3S{*FdOawU?ta6=uTOxBU?-tQM218_Wa8nS@$Ssg%t_#4j! zbB%ig%Hm}xOX29nHl0Ox{|t5f=&ZTM9-be_n}Hg$f&z(nQq0u;gCKgW|&UHd6UPfeCNZ40V}=H zx3-2A4S?Cse*Qu}yj+2eRZ_udx!so+ZP;)zQsf0$Q9$;h6TGjA(wTyBdBgnOG#D2D zB0=?$Gep#_7bms+R>g77?(vI|f&Cb(NCSn#xTrbIQtUbWihZW+|ARTwA~BQ6$+ISMQ*skU`VWld ziHDJ<7iY}$7-Xb>`LW16LC#>jcEI}e4L}Krla<7+;CEtrd#CtEL>aTPeKK<1%JG^8 z*7&~QV8QL}Ag&`Z1o81*JnakV^3j&y5d(NP^I1sMzH%G(?KT77YAmv0i&W6TQfRwd zgJv9vL}iC#NV+7{XSqkTq&Mbm z_zXpTqZZT_u)A8par^xpX9oZSD7=UZ4hw8uB1@+7h%<3wGj}{7EHS-;-~EB&gmj5% z@~?Z+hy6J59`bMQWicjDBJ+;q26@i1Mia;(0HCOrOWm$9KY8X;WyhyBmXBL)o>_`7 zIxoLX^9Rhx;OAw$VIH4S$;8J6wCAqNn1EO?NVx+@yMT!Gqa5kii}`1CTP%d{x!;`O z;IS;5i&?j}SfBthB;N|S5>|u2!kT*S$hh>iJ-bbYS9s#E3M%*uEbX+mg>icjcFvZm zz=hKVN2X1~ooI@-Vdqh`~Ps} z_z4*#M;1t9B&7+1A~wK(*<^`oapn8KKNEo>F*uQx1`q!=rLr{%?N>i9d}s$_fBqQz zdBi3c1^^XTI37_nN~T)9Y)Z^B#k(qVN+d0Ar}e_XZ-vCB8kXF_04Y)k6Gy~_ufJn? zPW(vYD71*y1}n4J0?%zLuUh~lEc_ZzlrxUj4W)w`*$LmxOX*}a81x}mS<*~MeCLd+ zC8stTk6{3%F_lRHgv;$t zi)Af|q0ku$VNd+w66XLz;q}CO>6F1^MI88qxx-Mg9ztlP^W21FY z$Dv9h3iGi)NTT!|ILbF=&)1Ky$p%;c95|!{@c3768qZ)bPM{wqTc_t^TZ{uh&%J0X zAjE6&R1$|+`PAHu+}ivb^p0y0Y)EU5Eavv&{NR?@AnN?gpkzBv=!wt-z@J$WZofFF zvjG&_nzd!vmpH6YV?sT?4qL+0bchV?M?pPt)|Se%BC%zlNpqoAO6sKSD;dm!yZ>t# z$4epqL<8A7bf74MEVdYU3`o8s-XSf~@S)nSS;7V<&LW?7ToY@-0b+ua_``-*O9A{u z4k%0dXAl6pV#LAuT+ioWp56J!<{}N0?sETL{}rw9#$`+76-<8CX)A;LjH0wWS_Anm z;9cIwh-_qmIp`RSTyK^E&k-|+~fo_QLTE>VxiPQ zF8EPUquh3<4%momDqL;MSA`U0tD4`dl&S@qhw`xh*be6o$MwH+QqJvhtSTOrfpToY z6d`Bh-a%GpBzu6bN<&GlpSJ!Ma~6wbw)1?@=)>~mT|Xf z^qp0o5>R3hbUK;B{gy1zLDsSmwqJSItf<@&A&-mraBACx>#(>gS_+@fel;KaY<4e3KlhpdxT7DO5E z5qlrMl&^WpqTq~L>{~bMy?C)(kmaD|?tAT?R=E-h3Kl2P%@L!`wb?kAls9IsU=kDw6!h2!*PJ@da@@!YO@D^H;QEZ_Nvh|6NmB&|{c@nn-SFdeP=PB)v z2Fkfw0YZ0On$BBRB|QXimb&k~)7x(=fp|mm>=M~Fpy%e}+ilnpolERL@k7RmptE3e z#D)-0?+?SQTZx_LmhRK<4_8=QeD1CUAAp6t%hGS}0jmvK@f-J*t3qs1n#vXr+F)RB zz8(LXACZ@GdZ&xBYB(PXd zU#h^6EVLs1!qG#*QlKAvjdZmbVGsSeEYahy!{+Q+RD>mRxB;O?D`U8{gGv{ zL+J2*$t~+@5kLG2TO<>j%1&u&-&aco{!d~cc*VjQ_?x^{litA=TBPtquy>Hjb%HC5{o^3?XX|+VLo5U6uQw24BjP@+sJRCehEb%oQ>Q<>&fHJA{$N3bxb))L zZ#8)YDK>R(UC-WzM^yWNX8$4GV0aj(=+Qyyx%R1s;O7f+R+_CTV>Yz8aSr7OwxnCp zhX|N`B~Kv(SN6^5Au3lg*SJyb`nwlaH{LFbO04Q`vvBfrG6FjCWN}nWj@$VsKK^ zmNf}e^grg}%7}{N+!sI&ao7|K&siP+Hwwr0AR9VnR955VNH z`hLjQfcIm@K=5)fnK8PWcY2TIG>?^^M&v7p#k(S7flu=HI|Z=yjLb%soo=~oq%Yv@M?G)i8*yuIM+kCic76ujtI zG`cqqtTf!c^adOr+5t*bHtU};`o#XEF;&OCLEPZ7E^r5v1_grDYea2F{Z&M~Z3*)6H6d5*ue zt2c&8D)0osf)l1O2|Jgx1g44=7p;E05qjSX$rTniWa?(0zbSq5#*ERmf-`^Mc>pV& zbh)qJ5i2J$l-WU{;E4Sl)?UgHhhUIw;#aiUj<(_e;*0sXkns(fY5YKpN<>MnT@PHO zd=oP>)RZEVUZ9yK_h48e>Fs_!pFqO{0o?;_Mf8i^==&L^bbc#O?o#VeNdCxe$5W&eH}%hn zrLT*j|NQ%QF|i9_D#o2>FOkYWu4y1+4Bjv6U#$N;}#LsR-BYvcb zRk4-rx%U?5yyg5gj2pix7)Ujp>K9ZRaVs~SS^0^pTL>6X&C3;q%m=tV{)r{V0^PTD zK)vhJQDYXFMaCYEM}{WnUB3H2(wes^)ew&w#2fsYO0#Vq z8qI+bM;xdcgxEX%Anf+q^ZS>}XlMhoB_Dgs<&LV!-Au9^ot^YJ8$B859Oq9p5u3PZ z_?DrdI--B)#$i^bGYx4>>YTwAS?hg?FS%14yOV!Ky~Wn#+EoRB_n%?`W8FueoNe_g zOU^tSqV^wCk?s;{l_|g;ckPHCnxlHSTzfS4_W)<(n&+*TQ&9_!dt*|50FdC7m6~6R zDA6IVAsz}!YKX+n(4vRNoEx0}OgVoB_*C2c1i=zpBvo)oPTK#HagCP>S&GGKgG zN(LZfNxpTS+5_=M;m&~`?mznYwY&WDhzcn89!wwRjfXW<|DLO^5=Pl7u|C%)={2?xI4tf8DbPPeaPrLw!YX{bcOl$ z{wM5TTOR*f`-kjHn=+Qnq(oAq+XVBGAK0D$Y3w3_{NZ7 z`-xuF@5!*zv`KdN?KPpNNi?mE4$**dif|V_wDG?z0#z*Jep0WRj$rl-A8@EP!+h5g zVIW`|9>*5GK5nmEo8DtltgG7U9YKlHFPyU#KA8FvBY?2g$wMF8K8s-3M>o3us-_^f z=7qAa_=cpny9+-#O;byqdWBH!VGRTJNWiw4nc2FBPc83Wqvd2eV(RV&o<3<3u`*0| z**r;DA@SS4X_|>Rq#X<^K1WYCU;%lYOWWN3M_6c^1oB*7p~iQsW;*%>3xsoj%?~RK z`D@}9|BTq8Om?_Gu=eAA3PcwVxq#3^hTp>ND_fp^GxBr11)q4AQQ)CljD5T6r01k! z`)V)Stji9a+JaZf_!pCtyhc_L2>bMvRc3g7akM{R!sp~n)(s;s)VgBVarFz_bFcFC zuhIrc^Tqfb=_Wg*hi#F z`Yrbla2(FSKK7kO>;}eL=5#D?PIGrRdD)#4bjou-vdZl&HL&Vakc@_(SGqPI^D~&I znfT)-)>+UpVL7 z=Q`(gKcA1sGY}=sT2`DZ4U;GrQ;IH654R_{MR{-?eEWW?ir<_trg$kn-DAOzzlZ)? zA>1?l!R_D3uxZn!A}@3hhY%+5d$TI%%~wgHaT+c6E6=YwQ$>i$d}Q;a zSlWp<4SsrmDkX+4*-JxyiUME#qe|WzI$`qRM6!&`EIDLA${FgfhOje|{AjbzL|LPv z*PnCq`SF_IaDP^W|MZIi0b+a4zyCYI=UL9S(tPumHNWjXpC6k^M&rLs6dPo3ClHq? zq_R7Y;M>aLH!J7ZA@h?~UU}jG*L?f$oYlxwiod-J%p1Sd-VfGElPs z)EJqg6VKkX+@@LCF!~U@V zJRq`|!43nyM_S>FSy}MJ@q5njld^X(EplAbd{O&+$8;`W zImR9*pQxSyx?Qy+?|bc(b{8 zH^CZ1Im?89nMOC*-2nfUJmo+p-&dB)Pb}qt=lR!H_P8Im ztmzp9zlRKpjwAE@+73H^cGo+VYE{1proe zbW+!&QjK)vtL**K9^v`pzzWWnw0WPe7oPo4SFNIL#(&hNjc#bxQ&MH6tA5>r@FB<3 zY{s!!T_ctU^EUNzS>2M^lceXGFY#a3K~Lu!IOp*kTP)_Ix=ECIL>aezuTWDj*0%9= zonW+I5%<84p2j_qW2AM~OqidzWX6xY1k|p{Kp{{iDER8;8mISx+8v9(JFC<{AgU_f z;0N#NnReN~E26t>Cb0_Qmf2f-E5dCA5?2KV&&IdOSph_|#b4w{6L>UmC;JEvx%Pth z4o(+6Ra%PFU$@t4Iq@oG?dCi_K_x@3R{5{tx{^QNT_p{f!*J|IjfvAiKY2~*<~sAy z;p--pq;Zaj&*AD;i@Ia>s3RNi+_F}>3L3~(U)v!1kqftH_t-g0?C<{M81p`v=jm$3 zpL$mSUW%u{^Q1RS_9iRTlxgNvto7@0KFHPla#h=iXCpHJj5tpQ-Oq zA-P0GJ%ZR4)P5-=cylvzFu2r6WHe67=++tc$P?}Bs36o$;^2rRdh2?m1xYW+9j^U8Wfz@nK z4T|Jfr6A#aciyh)`3C+_Fngwme^T&f71mV+#R+1-v&MLz3jdbtk9qlABx_u+oF{D$ zUR3|IYTLrbLGwWv`-2NTW9ec~cHYlpQ43^_j^($0?BDO@dEwedb1pVAu9OG*LzQP$ z$GNmK&Q9xmGT9B6x8vTS^rPYigc`s93}RLI*fq2^z->p=0Xr+cYi9%ZeZ^)YPV)i9 zEZJ~)EdcH+t`FxY@Zc=20(2I~^Nzu%v0}hQ3=pocvL90jV*h0+u6sB+8wqX|4bfOy zF7~Txct5Y*W}DlaGPO@0~9%FDq!iY~WmvVz;?mx5Mz{$>cV`Js+cQA8ZrsGp%I?R+XBX zfLOsJJUVmb&48ozgZY-ot2XC8DhK=RAX+lxe0fT7R~4^_1vvZpYT@<>Nye+PUOzz9%}cC)>(pc~})!9Y)kBz9_QIY1eOtrKtvSYv9T8}Yce^WVAY9Nhq% zd+wy?8|$aU7w3QNU-sfb%@ZFfH9y^9Ol&k9{GqU~lX?2;cxD@WIe+j;hxl{zSl{Bw z6u8Byohc!RkkK0r9(OFB~GnTNAL;4WEwsOO^t8jS8oms5udw z0P1H^6AVG3Zwv?z!E@m*Eszld0k*RF9fj7^O6~_b7}=F`QT{PXaNbhW4|UGr_(+^N zJ)!r<^>*mqull_N95V-pSz6}3jg$1+4*85(T$LAJiOzbn-vxEk{B{f3$Gm?ht_u31+P`%G?&4uQ<;nl}lS{fcFuH!*e0p%D1zu$jfr z1ziqZno)PM)%W0IYdY?g$;}d1s15r%T@#jXrO$rvkn65Pq5;=ijNLy*W=6SHB%7{O zU18${OK|PA^KcDtOY7r!j}=Pn>bn3=XAYSMYx+-`4Q0(R2Jz|8s54YtMup!gOl3)V zR*7mJb+7HT^BIZdd$GoR*UO7DoOVAin+QnKKV$0cDilS|)81&=W^#PNSU-Hk{stF! z@ziEk<8fn&pBE?o`zl{W+f}`uvyW_>KJ!kKO-z1kewRfjm`T{iquvP{1(k=kR1No4 z2lx&1?XpZl_SwbF#KA^L0b-Z{QXX6{9@2a}%~t~RYjaS!wMCFPJi zvt4P;>b?hJ_M9B>|FY)dw>aXj79U4Y33JYmBk;do<|83Ib%1!2^i=M2i~#}l?DDnJ z=UK770zoUFpZ*gdz(mbO0kk-{{IXTS*}%>}GW%==7l<{2t2|wPN&w$9AfV9%#~WHG zo2vtOWI&`Cq-GNMH+odnwgj4_2?^4HJ+ZYfK1nSr&i5rscvtWY3@Ltg9EbD>g!C^e z?t#i11!C9;v$og%S%!13HcR)&hnBqn1)cVHl?A_iA@Credw|c(mjmD{a10#B`yP0+ zoR^GF6D6T}vFH%)P`qtvPHwa}oS0Qv0ndeeJ zpR`n8-_pMn7h92WPNmT|gi3cE;npWem^t9waPFA0jxLoNx znHp2(wuS$adNOq@ap;$RJUwU=_5K@2WwO8S?c@ri#0)PW> zvvGAHc$XO*2K~FUyL_{kLcRM3zd@z*;6JbW>jKYRPrl(7$A)#h$&PPf^wZ!xa-L%? z<%6^?;4-%~oKw}aEB5r#SZn2(RLJ#jz;A-DO{D@e?7u=@DmZiir|V3&`3N=a{~dH&JSb4~yEFF3vN)&i6)Rcr`U>#ggiW)L z&x_-{s?{yUTOn&&$dV0S_pWfksGHpaRgIdAgm0%8tX?Tn<-f{#Pj$7fjl!Y_mU!`P zBsGtK?%4betdd7Z;8UuBgMTyG$B`}9)V)c;m$Hs&f9bBI4@_3!FuYH{br+&OAy5Mte5p#QZRJpAmkRt)6m;(siQ1$vw-|P@ z;zt_)r9Z0^fo({cnOiz(b5;UgfmPDR61T)*@w%LKB;^ha4_TU@#|M!vtY;4iA(1JzXF8P#W< z+f6Q9GxJ4?ZOh`50?}{@j$56M?DdNMp*c{MKNiLJSmw+wTv5?8GjQ5T$4A0;W;|?3 zn~xFyl1AKkggtp4VUiWvjALHPrI!V4x?HIHS8;0Iqcd{FQsr`dgEXbNfi2@{nvlzU zwge0`Av8eFn7P;wuYlHG&)hkD@$Fmv2mTVY#N?#!NvlbxP(Yg)9mCO{D(sW4z%TT9 zzv15H&`|D-(eoo0(p6(xa2P^}apRA7A)2w4;r&bD<;suH-dzo)Th>QoBg|Hd83Dfr zj*t%ClLxDeTD!xDUD3F7mGC*-lyCOei@!cyVOKwt)eu{Jd43f7b%LM7rl=-VdE@9% zsBVY9&9%SfN^0(xs6UfJ{k@654yImJai~)0s_A|O(Xx z5`WI+{bM)IFb&h;dDl?!5xgCWUDCeH`m10!m+1T1<;$fH6jxf<9W$iST)!P@k|w4g z)8+wh;>?3Xe`S8aAHDTMm0`vHY01`8007)iFa!=@11JCh;{blpIsgD?0YGpO^Zy<3 zWVD23sd;O~a5_dk&)?YkVT~ zG5^lu*DLVbzSrx(RqmtNOdu;djxPJQ2Bd{OV?b7%eR3&WN6g3LR`nxWO(&)+|P zVst%toE>~30$hA`DIPwXe^=w>k>gX^X^VDiwT{qMQ|!?4$M;m+aKUoG9J$h0bKV3# zOB1(yL5@uN7J$-thR?ND3GkJ$36r^Yw2}#sb6L*v+Lx8g`sucop*kvQF{L^J_?oWH zreK@|V1qLOg4(M`0%4vb@X|DSt**Cp>Xo3Us+9oRdd_%9k#)`_vrsHKYeg2RI_=5> z5HqFwPTrE9IrTm%f!~tXaa@syNx^HmJ2Ac#!SBZ{{L0DCvSuZ^+h_s#z94OZiw>O>-7nX?xw} zm%trCL8Qqw%gUsPT^pO-NO&Bz{rTZ?(sgS!D`2gS_9WRZfxiwf;eGYQi2RqH!}$we zdXF~hzw}b0bYwl)4%RlA-hUsgwvpwwm--Q3e+X%gcycpOMz8mu!FDV^vetYC$1&lZ zuI<)M-BhdarV+G*ylTP1O50?-C-*_?*rWN}nAaKh3EW{|;Dl^VEs=egZ6P~ZW}vj; zaMoJ6Y)b8!iaByR2JEM)^kwALm+HhTDMO1$9{C}nn7Ih$#Ag$(c6|cC>`zO(M!KSM|!-t^~`z1FT(s-ueZ}hMS0m@Kp(>R>KH^UhKm=2daW{(2n9b@Ut8d1kqqy!^2OG@^rR*0Rh&*!aP=(uumJI-~gg8$*zu#&C0P@XK1 z=k+pF-*Ja?XwZ0TZj;^9WRFijqf#W=Jl)}2g}~7A{D}sWBm?j&#v56Mg;|Udh1BTJ z%&Wu&y2qAz$8TH%Wu^4+Ab<3K$*D1X11FYfy@eM_$m85PGRY$0N6SkEUu2 ze~h!9$Nh4+dnYmxxew2fY>|V+w}50r+0KX#9F(JP9cRH1Gj0=V`PEgXfRu%FuG;gCvMDTaycgndd>)qe}T=33`1Ule;g+*3y}mD645*A9+X9_S(I4blUK z(6?H1n>s9z4URwRKS6;H*)?`L8m`Y`uN4}j4Y-iVcl-5Z)V2#me4wpZQ-+BiQ_j2s zlaO3-b2%c4Hn|&Ad>%hRh2Qc1G4ZPJ*SF@lUhuTzjD-Y+3|22(kd3<{7n%00m3|r? zAYAwkn91D6spJ+%$(^#f2*^5M0$d|+E1nBB4y|)AWMOBp zF)hZzW1CRz8#q+>W@A{g{?c2aA6-K>moBeR%xH`mPBR^dO4tlXv$J!Jwy0&Xz9zt6Aq?j>Hn{?Y3Fuf8AWlsuY6*7s;4huUy25=dwa z-#Q%9F7VMhOxMHSt3>apU-RuIG3<(5JQ~DX^R&g@aniT4=lfu5br2ETFkZgGcI#;` zNNkw`QS3TGXl)Mgcc}Oayg3?i54w`+)!;Ak;%HQJ1SryA*^~OV|3mT0<)O_MuP7OkA!n-X= zS`A7ztC4MY>g&A>ldnqfO1Cm#pDSse>WxCSk(MeGr6;V=;t8S}I=#BVm!M3(``119 z!;4_2-~_n7ED<3Y29bszHxhIn)H(bOcK+|z%a+Us4Kya$XwSC^I4&jH*~0EmDtHdA zy99`f=Qt(6#^Ev+&zXRC)ZcW+I_DF)?w!6ULHhlA;aO*A`^C?f1lZWM$ar9Fz@VZh zfzv5>`0mX8<*2(3SnDVYv^w`Q8d<9y_(?8ry?isSJz=o!ZEB_0I34YQp3RmvR}S6h zAQfI|GCwpHI0lM~tOH=|a6D%kIwAez@~X>7Jc?+0kW=z!-G%jz>U6neQa@50vwvqo zIq4>y^K}nx(78r9^Cslv4q(z;LxTG!Hbr@z4AV1z^!zF#v|9h~CsNiUPI%5?8pjG7 za)B`7LIz9J_WMz9tU!!U6js-!DbI)*A5FKK043Q0utXA_9)8NrIkKl|+j!vNrCP7EP zLr%Vm<*P~53WHg515SN4xjSf()|Ha6kP^*mQyZE#7(v5{Dj<0**nJrqtd`8X?>hI* z#vsToXPA4LH({~E#@IEXE(ra)AVE|stm#8StP21{_43>7(O9+t>bEcC)zcb2pXCZewCVlZ-)+yhNS96#6IScK3>V~DsvM=+q@9Wm*?+d8z{)NzrZE6c>Ch1*nvHW z=``db7R*1EXmo~s1W(i~Al!4wy>K5bwoZuZB2<0k{-lxhwTpXP2Q7I!>#SfAVkpRR z=H|6C_Giu06O!mB;>jGR-~oFerp{HRQ)n$L?A@m133GIiK%u5xUdzu6^#VeF%W=;T zW)W8KBn4E0N0tV~wWfMi2@t`pbbQfm(Q?ZAT?lXh`XQ-Q4bEunz$4wHzr>bLICZLh!j#Xx(|Y^1?%N9?(w)eu5j| zhGs3evyp<>?ea0LMUYcvTx`gKqGxHkU&KgYl&=Yfx7%uj|AaZP66C zkR=qDHS73kG)KGWRm9fve(k3Cgz&1!K$Ny%K4JGfkI`CTh#_(%$IQL``+Nq!E=518 zD`88A@cJzT=UZFWek*iKLs)0J7xx8$g76hGTh)@feD^Bu2Q0(n7bBS%0D*z{^)*T3 zKKkAS#e=QJU#g}dw$c7morQZjDdqB2JrDNLJM*zzD_~^0dyKgY+T|CdPmZrf`)zP7S^$+HNxe?j!)UxbkVSnEiF}Cp&!eX z3AX*q?AItzLq`4Mi6*xqp6eroTuZ(ucw=hr$*^d7kTfRgOh??hjFdSMoLOZ2JL-XzU%ankFp&eFc@oXx$ivf`3Q3^+1g24+r|`dEEE=aqn*q zhe5E#G?W7H%KjZ;Kg|)WlgyMSvQ6JTU;Fs>Bf=g#1JOl+v)$W>=DBh2Q5j3P52cz9 zooQTPPXu0jWMBJeXWKQ}kyuGKut#@;eL?mr4_x_HG4DU*JF>!By<{nBo3gY)OJuV$N_3T0|F3E3rUciE_)Z;_qqlQV3Kpbt$MRvKKmpkIT-QrE=e;_Dk7=hgJCQeZd}8V`Rb)8T8d<^|3#G%ND5Fm2 zK_2AE>W5QLO2+3s+J{4XR}>l_*7q)LXIyh`34GXoeS7@xMv%1*0k(hBK+?F>DQ!Lv z|0m*kyrqNk&IqhCY$GOP%hUFj=1oLY2K3rAMEIFtz$j4l$=F1sEB`G9tfn66Of8*S zTAHC z=bL5ZooA`veL4FZp}cscc0X>8@TG(hos)D@b6C|zZd)fpsv|`ht zPuMZ{Mi^`>3Vz1&n3C?PhFr|v@@%_z(T(tz+ka`C`1!Kw*3FOg(QPC}QC?&jEshF+ z9}5)1=$>I{Ph)4;g*`~`p%+vFB;Z$g{Waud;a8c^h~;?v z14q(JN0T$`1x#2(7|a<2&qD)Zud-W7IUSsSACu_F>SZqpV`mz(-@zI{`<4sv%bf4n z3rMOmBhX_(!u^e49W1y6uu?|11|6wS@~-wuTC-mLcVwdYTR?-sYuSXx1Enkn-;z2^ zIOeY6qYj^h93=&%5P|&$z?saDrv|~FbzexxkI<2MWUxIJ#ybcrdm88R2rA)k`shHh z+t0`OIR2iUGKvO4=(`BnI9a~0)4d$ow^BgVK6T&LoYI+ ztA@v^8tAhqh;`M@z&X$Oe~{=fpQ|lC;bCvT8u~=-K`xMBGG?mvJU$2KU<*xei7xM+ z*!qN%V8=A%eWfoTpPg~jf@MQbHWe6iS1pVQeVhmlnm(o{Lx>M$u1-Vj@i#7DVIVW; zTp2VN4^=n|6*3|REknatDqq9U?_wCAL$RJ=Opm9Zq4oZ-FcsQs^+?q7FE*D{3ByEE zKGlft`i*6n#u37++UTz9V6yyx4%_5?y^n&>=U+vZpg-^(0Ow8yBA)a<1P{H@!d{8x z=*OQ9QZyYRbClp!Lt3DD%T|~FLv9y-kecI&{|MXYV{dA49^HFIsZwK7f@6+RP*^Y7 zTs7xBWOGy5@`s1B((Z;z&1ks#e~3q`AKq~z8OrcphUr_NW+>!Jca*m!8AQY* zzp1N@9~%R(Feb(5Em3V;CBRzZM|KP{f^n~uC)rl5a14nIpm6-k9SgAf-k=ZrZS30$ zCV(VK@eF7e3-4M1wk!i%*6bl(d`8Iqv-qQ7U9bmvySwim2z&l-_e=f{qe0jeK0qZv z9x4hz#jyisf_Y_0Y-Www2U2L+vv=T^s0;TUD7Ikbi`f;B6GK*1gSbQUV~VelOA{kL z;&}g&6%X#_1#ecDYO)=RR{0bFD#z=SzdPToWJwjK@z5hde6Vu0O_^b$kkgh!x#e~5 z;l#+07stn=YHx*{cU;@fJ-uUE;{4gY^J4h~RoG?MvzskwvDeD#i+A76zq4)UYM9wqSWqog(_iCMbmY_<4fhYMw|0YlC>xtz-%ty{96ti`of zJaG2#9oBU5ivIAx#phv#d{gcBfo)~~A34Kj{dpQlUc*_uv6`Wt?r^?KShneq%VBJF z?hugN$VoG^`@rXtr*|$-;LOi<4#f_7GcFu%zjz~tq`tTKKSwEM$Yyo!?2Snn7#@v*PUzeE8>fjc>!7mq%$h3C6|9)k zP*VwHKa@UnNP?*kWL7dy&g0!sQjg3*na7Fpsaus;bSlHw2Wh?lRt<0XL!*J+Y2NUr2)O{pQ(|yxw@%)`_kIw znccBlS^AIgz*~Abk3a9Uw{xs>9~ZxgD4kt=sD75wrDwTTTSr6=g@xs{_g}?tf9gxq zW2?$kESwh4atLTuE5!Zx+RnLxu7|kU9EX~8{_*y_QQXguHBbI^P!qRY|Nc(nDkM{J zNecLEeYFK&!)5^V_U$}LsgpEJGkR!jDGWv`T@}c&pH==>QxyR4XYo)dug$z??#pov z{x<|SD^FQzxc{@C=gD4KvZwm|>@}a9@msO=s}Lvm*vr1Ww=|-vkTG&YY5S3btf{ph%zi zBpWpC22s~uWi>`p>}QpL55`m_a^2|k!4=u~nRLZ<6$E)t=H@8- zTH{B^POE>R;sCjy1u}gvAg5~C$R#B9GsiV{K+HOaHR}k-VCZt+ZaJ@?r*rRO!o5T- zK!t=@?#b7-gQa>MI6&c`F*bmUB2{i_P6&RP8M`hg`uRoN*`k-f!HC=c@y{_}rnT-H z6?uO(^Z3WPkxD_n0{|?NGoycie~z4-ov>cQiXEQ|iiRlCS2$V3ENrZLj+ebS`l30N zw{tHsmsnLeOB+kl>Q7c8mveY^StLWbRS?zYe0L}`-r}O<@LpoR$ZHb7etpiW3U@U+ z45BjS)OatG+hp;z$@US2nGBWB>4Yzb>`RC(LkgHk9?JH75yBUWk6K|>zW_p>cweg?|Cxv!uI63D|m zl@-lL@~q~^Cul-d4B}zSwX1g0bCoK^M56y6Kb}InK_b~aqik7S_W1C*?oTS|*stsC zWf64agT7C~yJ}a?zgFZ>Lb~_n41XQ(kPwNOqz9NR5O&oK|G2-z7No9&m>eZN#sS3G)yyyjop$o_`x!{q$(d89KKw7A%l{r zl^1#L+L+2>t(Ml~@k<6i3j_S-EC*Pho%CQ_`x}9K>Sft%O{mI658?S~?GrNnf!EtX zn7gYm=>FFf9<-=I6Ytv7_YKYuB6*y!OJwetaNxU>wOV`*YCiACb zcxsSo7}p75&-iry`{p?+X_Ac(&OkX<#dGKh>y0;i*|orA6r&~aXt~12a{;LI1e??h z>G#!%A@WcEgJj3~rb|d!U^*}mF}WM5E^~CuO^uxF-9qo1avz+&{Z74p!IboC{>{4| z^G@D-lLY}!)#c9&2=Ibjcvuu0N6cH!5#_13Z|%tEHRAV7+T^Xgd8NZzrFWj6d`(YA zd|Sn6ii83}We@uMDr|!3gVJd8L5OIo%&Cqw>7C^y4bm|zHznujP`D5P-&k&jKjS|- z{u}%$^y+thqN1njSy4MG$_I17!)I>pqFZ|ID;oU64&Knb2ad%S%Vs=4YNoY(Izbo31p-MFIVKWOuE zC#o2*hXc5hj&1H_*xADh2Sc^>(@&%OzA7fh9gJ9J?VbMb*Q>h%oQqA62AcqY5xL^ooIizwb~^pmQG2D=~OPj5kpuVnywP^V*Lj4Q|xkZ7A)>9{Y3 znvn3{gw)VzHZ6(%M`BQ7x#TD10*PiTEJ!y70-I&8o^B%7%0CZI+v@^~9L3ulbpZ-< z?vc4!ng(4nejtDxPAdTWxq`cNt<;~=3E{3Vw9fIz()6-(WDku`wQ{?=${UI(^`s3* zxk1m;X;~og9(NO|Y-2+Pc%!(%+?OWK1io1)n&B8$tWxlYQ=Z$4%Ob&=3^1Q1xBs-n z>48dCcMhKriok@(PDzx7>5?}gmmIjAm>`WHj8h?BKjv;AP0}N%liQOv3dnQWd*Uvf z&ABK^V$yVvfpX{syG?PB0(X>^^3V3W--Tp<8;?d>pLx=y+{J*1r*^i#NiYaIErADe z(P(-tsHR1sw}2B1-5?D*Rgz3qTowUu8*a2@QTM^`xGp$nXh!LTfK3bPkZ zkTz2`7l3aT>0Cv0yCV&%4x|PMF}gZ*-DEIXZQ2YEem#ZlusAu1$5E&+qfO8CI!=S&a~3(7&80{3i7AQX=~YJCWxT( zurYw)x+VI0p(xwpfeTu!I;GM{ms@#?N_N%hZK8~Vct#v$madsApsAy|wD~SW9XMqmSg2W*OHmd$S8k}e&@)CyjuB{g zb9yz7fTyO}PIXZW!|&W3DAgz|g_*YU_yc#dsX*Ysc-Zv38?BH{q`{(%S}HWrQe4GV zvIM8s)J}+u#Vd^!?FhHwN=kGWfC~7Mu6RzIe^J+>P~{c1Q!QmP@RNe3CEWfe@AaqX zwWwDWfy%gsl|C2B*Gd~(WvSYn_>6H#YcPLU-@&p9L(^8O|GWQ~Bn;bdXt)ljBT&&n8 zc%H0Tn~b1TNr(}I5=CD3YA$0)cM@oKmYA@F`o};lF-9dkcYTH+ zRt!7f%E|m98xdrX!nb!3n5`N4HTJ<*ClH{ zSffXFQ}vkwsfGH~<;Q1*d+ZpQUyl2URbvI_9d8$?dQ49I@=4R}#hoJzVUub{5LJVK zYZ#(*-Pe*A&eFT9cegP!!lyk#PJekb+VHba9IZFZYg&yz#+*(UQ$+l8GZajP;7*`V z9F&Z((j^`h4SbvA;2X)@-t<&+$y$pb0*!g|%@W8{Ek)#%{3$Vcl>UXb*6~}RJ<>g` za+!pZCFb*`aoR=;=$!*lg9$o2o##M!w!SVC!%5jyB0C@P+t&*6; zf8xzPd1k@ZS_gFLNO<%IBs5YiP zVJ$uIHwVk}Yl0ru439|+u6k6^FhZBC=GmcckqV%x=yPfq+Lh`rVQNmdT=j*-W?$As zrHi@wzBLUDczE<=+C=UC;)zj7X96Er?9((GS=3B6?UI7F>tQzQHNU6pF%vow`4}w_ z3khmxp0k!*JN?j`1Tkb}$f}tsEN1^P#h14Xxh#W*uh6tda-M}&A~Ga=DV?Y8fs0#c zic=GkGpShdm$vbyRj(HS*gVTB8Ezs@{!_w!#Kw4t#K7yovXo`knBW~kZVn2-+v(R- z^Nue3GJL#FE8o*Wn6A=xiBEhe>Y@;|nVq%abe{2BL8fQ^*RAaFoow0~=srRIV0_Li z>fvd}#N^Px>XfHIhf|H1D6rbU4 z(AhC|UN!RJC+7@Xug2+o=iv1=t?jlT=5P=So2S0zuilTM@XJ#rr-8ZV)RUElFW*qV zcvz^x0ctUCv|?^uUjlw2i%3tl@Oi!A`6^r=Pn+7LekK5=9@B3Byd@=}wh0$p^gW$; z3RsLt$Q&;tfdyZWfxwgHvn1dt_yCwAYX<9H)jQGRR`n) z#S>HTvKZ})FM4y`w58yN!*)iSKn^pI8(a#Fs|ElP717}O4dqnvIgiJ#ehcD{0YQn* zX{JcZIhD+;h)HF(Mi*Dwu$t*Kx8kF!FaAL^y>cDy?~^NaoG{BAz%hya2xy4Xcbuf9 z40F3DHR?JJNeMOu96^kN23{Rb_IVBw`;TQRMkH)r0*838caB+=4D8pF$=d!y)8s@!!slp%X@4sqLAmFm zQc10PkW@s4ci5^xZN*EMwELgTfw)vfAU6k2pVZFodo z-$8x+nujJ?vRAaBr<9(a7an$EUpwZat@yedp3!G}EpGQ6L1x%m> zmPTI`%;7|D9~H#krsC0s|KWPzf)*~}5mRd*v~P73i*7F`V6}Q*k)&(o$CdS<>OLqt z^W?GH4OHIa=gD&<5MQ-+S{ts{%BX_K2O`cSN=W=1VZCY$T}}yiu+Uk{H&PKj^G)s` z^T(0bHCgHx-Jmsgm+93pEKSi4LQ{A3XyK^x2%nmw8{mucTncz6v{tM6{@HW8X=RUk z|41?2$hXx#@lS`m>4U9GaQeIFqG?i%Z799RZfTB%$@qqM^7xT$N``bD+%7}pc#rX4 zq*~LE&M-p}6PRU2`VTK-Hvyg?!*Dl;_Ti~3V{;oG&cf6(kP><*`x zQ5PSkvIVE5uxGu%ypjw887`mcVlSz@|Lw`OP?nB=p|1bw_ciJoBoSt7;f5XXt$*lv zP#fYx=q-l}q1?jK=Y&=Ui^WWD!K_jwJxUCi#geEFTqQ~?s#TFr!|Oo4z8GxMT7UZI z=zBD)ql;tpZ?kO|N|R)0(3Q|Ii`DRUGy%drdMWJJAAHIzQ@jMW%Q4+?QTFHvS~)(s zWSY3O#X^q0S)xU?F73c8Os!oh-fdxaRp&U48N^*->^x>We0TK&mX@waDY!PLsh;QV zt!))h^{Y8(!9~D$Rmp7Lw!?hn!09xli)98*$w(2>2z3Q0{UFFLo%{Nt!Gol!YQO;Y z`-CNL;1nP*{=?fjQ@Rr=Y7Z>ydBk~_rK}fv1IM3xx!GUuzx}ry`vM=xOe&=Q)6W_= zjmnI_20x2O`C&L<`X{d`zl^);FS+b%F192|D55ELUKX;5Eq{3%PE|TpPWg zl6iKPx>EU0?$@Ml+d#jj%T;;;VIr&>du#}$cQ2!7FHS-#?wqP$Jq;;%x!+1uH9wIvDNC^X^EPJB6BTX)rsFGDVjL9npz;=Q&`@BTN&r4-C4 zpD^yH0N-b)l(*7Q0bt`9>w#l5vvtxH$3lGfMw)VAs zXxf{#))Bgi_2VC_@&N&t(BGTskcvkxb)8jg=E^P@E_u;CUx6!t_&HM-=h2=4GtrW7 z^&ysBb-&Wf3R>)7ax0OEp)zhRs*+NX6bD zRgCc2-ym?O6@-fak}ionSe0eea;~MVUW|u$RxTW*CCkQc;*tdG4kk>Y+4~Tof}Vr) zM4tPacBcFn1Gqen!<-{RR2@maY-fuHZt;P>^OMEB(C1=4i8i;+&y>176_fh!BoE(z zP5A4QVj-kA!)lu=cF8wciL~pOP`9;!=-EvYXsc3!7k2mVrtF_a@?$&S$)47m$Ps2&Ri>r;E zWFRTd^HUNJu87Q|FG&b;Ta0HbMO=s}J8oPh_uH*z#{*0NL%hm%8}TQyD-*<~u@LDX z0;i4oIomz#J(fPU>ULBuP2@GX=^`$k{Q{oG5B`{>$qYexMSu$D@JZ+1p<+X(sa!2B zkm1I1j`^j5W449O#lUusXk(DjqYIMiZQwrV)rEC(P%2&bj{_sFc2I!Mgc9I$p74IoKl6JufGiuja&CYRXs2UzM6j;z zsFgkKK4EWmiN~dOPzumbA7>X2uaZA$?f;0K6iU=M^(Z*qxyqp|JjJ+~F(eXLlU>g3 z#NSgt=B0xH_%Hc#Cb{1_Pjr=K34%B+RDi;Mg(rpHt#E^_b1(iMMd#wq|AT_iz(I`_S~PBaPt#vu;K zLDw8w?;V#se-@Z;*0Ll~y!6}|@$GV{+oTm2U>}IyhJ9hG1ElO`Y8$+@eC1c+Nn4pZ z0$Vj@Ts79=v6<-G3~l?4?ylDJw-MnbDR!ZNb+iOr=O+EKmSxm@5lY&@LFsgQu zA#oZDQlu1j9pelTfvhZY)O9QA8${_EPh0eETdmZMT>D$L#T%a2djQEqYwr=;4YwD0 z9+d{jbZT?)4nG?UrV3wxG89lSsMX}O<=)(AzrqIpo)pMK^n6lcWh-9c;S{IV^pR1~ zk0wbysz2M}-`9(;x#0f=fOOv7%8YUsuo?((Ty#wl&&cb-f zs$|ow4_e?Uh+gun{Y}@`8$qkWN8Hk;uY({3@(o#rlsa3j1#MblRnJk3ls5%$i~gLD zzrSLzy`R)|>yNHv0JBc?Qg!BLNvX~)_FU(U^640|?j~9C!F=HTJ6R#yk_&NR_m*}8 z1hN$P33`wSS`Kt z-ep7nF9U}cvwlTqtjV5q#QW}U*Sf2ld8-Cz9NxXwV6qry0D%BZw=FhA9B?c_E2T~` zOIM2qv1ay3UP+sx1v6A&Bfqp z+tytj+{@Xa|2$wRv9^cyUT{77y6@J+IvE?kZ+m7K1r!mr1<6;z{+DJW^L-cf*XB7J zqMiIiv=!?_@wUf>irsRie6<5CdTlOAKHf?Y)xB?FOV7<-=ymE!W(>bj2sPtNVvXpi9C4aI?+sdfqRqD3`i!v1J$+3xeSZOp)5 z=GU$QOudsPyUL4rVt=mzJj6gawiO(oq$?~+&G0>6?!ev3AVz>b^cJr%!_BRCctj@q zK9@Ec$J31>JR`gA-sZ!I1M~WCPprE@EXD1RAX(O>=+WXk<@s_MSN3B7$l6Ph7?2!O z@Yka7Z+7?;6MPCqrUCE*j-l)Fu-Z3mq;r|PE z?hwR#N8Fc*aP@ckJlWSm6Tor^ax*}6yt_9?u9fBf66;*t40FM=zSgMdG}V<=+CQif zP@f^7JAv}xzG{@Xt4~(IYFP9Wh}J$KBHC5y`sQMHu_=pHz19~UGhJ3Jn z!g~Ym$fLr-<3C5H@XZ1lBa`G+ntWxoL^DsTdE90L8%$lkjdz!W3OwdBUt*kJt~2#G zK=rX=yJ^+nNd|Uu;v$%g3=s@PX6iHmAvW1lEOAtHF^(x9p+%@%l6sUc=^WYO3gHMw8vS;mBwP3FH z;U zS7(K4UZl1+NRJ*9ETKs)PZs+RvXTdMCt1aOo_wXe1O*)85iyeH3X&C`VH}eeZM>a^ z9Z$%@&hs!&Rzd`)!;{sFqCD?>YKZ=z*k|O6r35+2y8T2!i7|riY4kZBFn@NHOzo?X zcM~dZXynk7)a=h&UUw1@Hrf@EbF+W&&QtW}Dn&d~w--HDZO392T%3oWSdR?i7i%(C zdRHgpmek$tvUGz~S}4S#5%A%PCr{`5wD>fm`#kmLzVU&*>~^sCo#2x$Wp!IpO=TV* z+MZlpCTYlN$+YNQHfk)j?gFkU59CJCWLrw4xyL+qo@*>gY~FuaEsj$38J5Q!mB13v z{%EWnqPn~?Z}3LSW{JXpr;`&+Tu)S~_p)BrjF!U9N-#i8Sm1*vQ5MG&?8tqcF3@0K zmEYh5Kvmv)$CIAmJ)eB~DZ?oX`_|7+q3iXSEyB${KrP~VmN!7boJ zGVv9JC}+-m;VF<6Ojk>hu=Phd{-|+yM_UCDl5*Aj#n{(L8BtS>+D!ZPrYVujodd!P`V1Y{L;n zHwo9j$7`Q_R(Hd=5$4eH3yr*ymyJ%%uV=J(1&l`T zaE^Wmzq#2M1YR2-(}U(DylRG+$Ebe`%F?6Kbs;XThrn)?$YB4ui=KtiGtV5s`AXFS zG7g@hKp{X}wZd=7+L^_jpKWprdwJ(Mbh&1r;t0KdW`a`qG1HGlqsU`fH1EhuCxWx4 zoSOog>-D3+&ysnv7<-K5tPHx`fkS8iypbnG6T$GbRz>q!3eD|Mx_wo_dYddq<7-*k;?~mP+f1k*%F;$S)Q~#2sw!dFK2FO%M2uQu}8iJ`qsvrjbs_NHb zGPp*PJM`4ocLw#B!d^OCOWbdVpz4cg7@4T+8EWhE#VnKcfGek18u8T+AnK}Yuj&p?klLcLWUL~)4 zvgQSpauxMzngn@?5|etlk6h(_DG@B1i9xhyMTP$yWTu72_JArPXt69GRvsi(})K?(W4uderuQfSDzTb1%uN+^y= zXd@o%d_vF9btUD8f)QFmVZ2% zuG`Kl-jK~gNICQ-V{*RTtfA|ALepLY!!D>9U|hoE#q1~t!L)vJjPM~a)dCE#VBEWz zgWDD^s7W4`Zzfm<)AiO_un-arguU1zY~-V{GNJOsX5it**uj9T-G^WTpMF?SR4zsE zeh^=7l<(`{fJ+lFvL89JncM3d!P*>boSBj35FdPfmnC-sw+fVD5{*qy-dD9U2-*|y zA%V1*cyJ3QZb}EL7Uf(2)&Ao?wYWl2dWPU zBJ(4V_p<|8_7^L&+7Rk2rm7N#C$(PbQY&LSPt$>d)B`edn;1$)BKi~K*2XTSS1Tq* zeGPZ&sO$mz0nPKNV3>VmG#H?j{6r(>$MB?idSq4z24v9dY*`~PGXd`ev40m!Uwp-2 z4W*(NPWU7UKG-1LtbTj?>$r9l1_%@TPd@)*{24$S=;rmlEQLJtmY&zclpW8H&+MMb zKO6MH9BDt7Xdqgzvr3ao^V8hH;s7?7UunC4i-Yddl}sU6=*lB6yLR;6p9@D`4Lr>2 zahDE7n!_dRd1pE`o$~!B*7LU&c}@^56uStydqixoh(k0^03FP=6$euRs3Fh*SLeK( z!4BO}FNnuU!&TFt6NV}fb{|Ur44?WXOVRrNr|K~n^vogaaq@$~FZL09AQnscm1J$S zMML6%O1V}C{B5x$E)>g?-$9E0d`FFJrYiPptq1#b7W`>P;CBVgSZsWF_vZ#+#Q6N3 zkjL^rOU#Rx2SS1J%l|vUtkg7*k(PkZxz_jRYN``6(v0wiig+T;Q1OM&i^ zu<=|V6@vVqZe=@wy_HN$IyvKB&Cysck)0*GUgPBopR*s`6TM=Y>hJ@Ws^^b8GQ99m zvd2%$visE1P`TBm_}~X;zOKzaxO6J?@ww2HzPo~AY%eZT-70cI+i185WL@E=M{OUx zV=(Fks+eyNH_sB*wX#fZn=H(Pd|DhYtuaXRNwn5L_-`z9jla>z4OD3b3`aoz=RG`o za-my@$mDq6=hk?J#s@r)oH@yS`d>%+ysk7J-nuJl0p(VpdRS#?aEIw;22Kv?YNH;mpSFP~A%5DSyez%{Pn?3^*ab4ZPT zv6@%z1FN~Ukiuiu@?Q2qx$P@3--;;*ISQv;F!Qg&-lR%*3EpSw0pgr;6B@smX799y z_jx)TLRDTXx1QnGkHU@Qk#>0uqcth(>9&=!mfjU@=XZ56#u(pSQf8q$rZ3v9yz1ki zbP$v5CPi5D@4wilRXQU5y=3*N^mA{}V3E~avn^}GLl}GeOv8@rw6pf@nQ2#}Cq7yl z$+)lrgGr}MrokgDsPMoHrN7W@!LwAv=XHXusP*Rrkf>QJav64T8*0b0{>%Z1S#JZt zEWCh`A2L+CcD2OS?B%M2XVu^jn3<);JCvt25K`vV`y;h1aa6%RFwQseUD>gy4-N1} zeDQwh)F*xL&AG2n(4py}$~Pnr%*=z)!RrX2ebG!chO0PNO>fM}E z%TXP}dfz5i!b@H@%Tn63Pm2Ei86FFEkzT2+w^YtfYq8#PT3hN+F?h06lO$=>ao`am zUmvT4FsdVkIA>yvA7;i_gtChQRGQ(v>Hz#Eu89bD?#U84)=U$;@;?EsVZpx)ov^az zm)TX)p>w4=F;eHXb*Kj5mmiJwD)lT%jywiX61$ zZCttm&}V(kn~)zAwb+2h8kKP#RgaF-lwGA%UbfY%?|ame?>}ib)xaFL_WE|~#QfCE zueUU@khG=eujfkR``zEXTDkaTKVaLl_lY54+R9n(!kg7rND#o$bALWvIv|a-8M%Jk z|L|v$Elh2W&U6&!ZTCFf{jXg2}5El(kttH`X= z*ji|!d5+~`{)JnzS*8_ak=R^Ym@o++l%J4)BJpD0>jz+Uo3FyrhdxSDCyAPmd|UM{ zdscU$ z0fTEeSgq4w;(EKwrg@IyfW8PS-pLm0eM$VrzDTe#eDZ9ST7f%@pj=N9m%k@ye%MIc z^d@`Y)@MMzM!J*gdOI{p%ecI5mnfBn%nxADbC(KBtKXSk-=Z5`f5jToW?MfyRYE9m zA5j)L!yeErNt9hIbBIg@pYXJn#F(>b5}j?#Pl^@g7nTuWMK|05C5idpzXI(GqP-Oo zR}>1(L~J@(5Pkgr@@Y(>NCec?Fl1?pKB~*q7g^En)G|oAPZK`(KQK!CtFRpvc!c3^ju3hy>3p+^Q{nKzP+MqHoOIcnw45CdqW* z%diQxn2QgY;RUq~o}wFvj_I+pU{Q zf!z8WsMH>!PR&+|k~d=^UQL1+atu1tjsVi~a6kEd(g%MJYJrQhIjPGBUC)Ubs%Er> zED-PGUyj{aO~{AAE7g@!jr!*16@?`GrLS<5l>C;%0-|!rl&|VpwjkJ_6uJ@GXxm1i zU%bZ1RJVL|%s4^(g@4+wl7ip!<%cT}`nnns53#GpY#MzUW`9^1kom+|!`aoN1T)Uf z#8xc5cCvIkcs9a6+Nnd4Ar2DT=O!7Rv1lU!&R*)AMC0aIIi%)~L7{G!bg}LRo@#YL zYqIt#y;;$AOu9%C0HV_K>u7{>9pZEv!~m*Y7~`2KSA)4L{c|kGvhAiwOv1<8*TZ82 z_WF4j9>#<2#O-8Tm674zfLj6Y+nmLVJZ~4Kw8)!j=lHun6-i-%q#q?fOsl(cIwQ-g zG|UOR%6=k$Or&Hwv0&|F0(>`|e?tJrJKDv28S1qpoC$#*PVf_UWA!U+w%J80>(0=r zbCOpM1fKK~K;6U)s`GI#4tVxWea_dMuwoj1(V+e zP)Sa<=vBTjs?g3uB7}AIddJnD1HUfEkn;5_vf-?oc2=jnF4|pv?i{cP6p7)0{krd7 z3JH6MqTu_<;7x^EPi@;%FBBnzCw5mk%i!tN)DTu5s=@!XKFM`w(ndDOc zn_G)s1P8I0@7|;j_Nkj^N6}!(DO|JcwyM&_ifxAz09k7A{SXgB(Qn(ndCypf3 zP(`)U-u3AJHR;sF>sPKyJpvT9)ZKR*J!P}{eU5H#MiXNwZ)Dh7WzeME2$)5KeLE0( z>NEO3BS4HY;4@ad2`+us2xBHL^I!iy5OS%n)db(vvnOwK!p#-qLW2ts&~5}Y=c}AM z5ItxlKiV$c(=KPi+m0bCM1PT3;7b(o)ND>k9X0%Mp#iI?p~a+0Z?Z+Slpnous>eA* z%8oru2$NhSxigeyFyTFFE2ee=J+P7@d60${Ph<^`q|lVFFpJ6%j}%qIt(#QdBT%`k zqSgfI3c@%g=Vysq33dZjL{Jm}C~VgXB^qm{Z0k=)UGnkJT{LRd8mkQfzGKrT=Rt+0 z0-7GmNXE9**s^uNjlZmtzKUsSOQ5JkoF{+XnmxHz^i=pirZjz3YL3bdA>Mxz;Z_Al zyJbp@;E~KQL>vvhaauZ!Cf%E8xUW*%>n%pd)6mHTobXYMCs~AvhqeLW-K70V1i-;jf<1V(F##<*20Fx1R6tnK^Rnf88R$~cPXDKSOYnYH)(K)QJ(5EBYdK=ws2k8SC zAA;y49_d3+Q)|I%*#>cpeA|8?87$1o%m&`U9Jcz9_8~HP2IAg`M|q8-wF8Yf_PH&R^m64D-@o?5uj*DxJz}U zH*M9bgZ_b^sF|vAghmLU@z8?Afb#CB%c;@zk-PX>xP!6`QW^Nu7T`jK*O5>h6-a@; z(X7Lf$0)a9Ka3j?(c^{t=5ypn8J6W|j|ZzN_DRp-rBcIO(o=Q9g{JoYH8@HO9sFOx z!=_uM*rCTvpy*Stqpyq5`7|_>fNDBbtacFSgonN1iXqA8`tb1Y-sqTG6qg&u_$n{{ zMXJY3E9{He8Quu~Ym~(X#vCkary7d>p|U<%wjM?*;sv|uudhu7IrAOE~}LU5s(4uNG9W_n}GAW_`$-@PwfP>7hy;(a+Se*65%^}>fre) z=dfA++aP5p?y6#3y?!fPAjd97%?5_a&7U$JoK_=WS=Y;|eRV73M!(KDaP}sCg>! zv)QRDp!h7Z=&tKILPK0HC$85Eb2`Vff97!{X@a2wOrWBWOCmdbkxn+^^hIpc65KzV z^4Hi+__^GlwY*c$9rBcs3w+nK2AAwLGvBWxKPjMk@Vd=ZzLAuQ-Liy)1afWNT5dS~ z*jLeF4>b?o;fu+(G8SZs99tx@5=;3?qI~3l2sTXY`?I9x@H%|<=EU#2L&>S#Q;KRkX&2WPcHTHDlruX}-;U2eeV`Tox-Pn`6L)%+wF)vb&F0)1>NC||~yL@yJtz3{% zHms(u;w%-PB}S?svcOmR0!sJpp3%FYtgHDRRW*>zG4LdPv+RyWO-E?&^UNz~ilp=k zWvh;FeWGe$v8Z)Vzo_i9x7$TO`YzvoK97gzbI-Q&;q&ap9hl%>Sewh353v#QobRis z>8~CCZ8aX#&-hLOk+x(y_ zUU5ZCnA9eweVe)4;NK#c&KQbqGEb5yAMmqEUB@Js15zFrUY$OW1Re>fO*jp z+E0fYg$q!NvQ_ln&o=3i8Fccq0q0Hh)5r-4l3*Pb&f)K08g8ee!tTR_)xynazZ8k@ z&8wv2c}Gswj{KdulxvS*@b1E=`O$U>-H6fbajb# z{>1G&U}vp~^6m%?@RC#!?=fyT|5>;mlPARq6RD!lENIpF}vdSOVLK-CGM@yh1n5M(KS+LMDt6A!U6>{7jD1MiibUQ zb&s$|?0u%9f&k4&sY9xk&@C$=0le@S+wZMCVhn(oV%_doY|*FBj&i0)(k!8``9-FRZVLBinHTaZOP{I#1`*EWuA3G zZIbM53#h(M2P^#nF27V+u}2v&M1J^?TKIuvjZW@{XKT&(hq}9Xj<(} zD_&WA=8#E7nS#V3Xhs=f^%qu)P>WpK`X`12k!@;u;J^Z{7u=*K0b&C( zDz98kp(?O_y)a=zT3!#c@C##IDjf;5L45g&J!+hV-GA+2lT<_kVE@}0vi`2}iG5&O zx=2**G&Mb_VIV3R3{h<1G*-KnS1$KpULnb8kG4 z6p=d+v&i}FZTCdMB4u;&zW*>^0e=CI4jvGCreH$@dr3rWH;lUKIYJip`i3N%-D@0Z zvRNkYwS2A5{V&iP?#@V)`qIXF5VM;_Q%I1t$q|E6cO8Yq`FEOPBw`U^#?jQP*Oz4>y_f7mgD zseqLcFSCQ9ch@GW51#vs_}|_2$p*(O28I9Y+?Z)O_8?y5PZwn#*y{1&fPU_#p9)+(cO}OrUH25} zp;r6lqIlKegq#I z+U*d;4(Cd_0l1TOu7C#Q-ErOA#bQs{xOtwCdh{yER&IFm#EZbk$a3Oi@# z($iokY}JKT$LrXyJV(Xao5f&R>Wo*8{LL{VA^CVN&p}S~$;PB?EPDzf8@=8WD;r9g zvPZiG(FUX+;!U%bfC3l8jn=Mh;K@(CsBztNiaagSW;PLYhd{cbs2mdYS$wzU-p}1s=7X|%BIW2)_AN-vjH}ow& zIH!AoQtO~OfRSYCKbSR3O5^-J6L`!bwp?C4W`4=#w2y**;?v+C*L?xvYi>-C~&EVHiK@DcZQ!MmOv`kD7vS3VV-tvd%D)>eE&-?RMB*Y`}w$JSrc2$}0zC$Fvt zrgQ534KnXpr6qOQqvcw`3F(1c`OE^8a|>ZqJ=Uof(m~-a<>4Ci`p3)sjHM?Gy4Xf8 z#%=OZGt2yF%#fbHNU zHRx#|a?EqGOvAT&8D)K$uYI}>c8sYa7O*aW^)Z5F=CzS>r_oq2uNc3hES95ttobub z$a=n3l+sozy?`x|srwj|+U6v7(!W?~jw~8S8p36_!_-7GrCcd0lGiX)^|O?GpO!kQ zJGp~;E-g0iM`hA4keMOP0zvT{yV+ct$(_9$*AE}N1zYRhE-?N<#MiJuay#t&9*n;3 ztw33{YIjdbFceAQWa=<#<=5=4M}Cm0S(q_*BrPt%ubXElRY}%%lDFfk8J>)yT9|Qi zUwrSkto@BpK7jv8x~F+?33}#AaSI_a3dzzePh!d_LgTyo2iNH2`y|*mUGV}LoKJ1G z0#7fJ*{}?J&Cer!&%Su)Zq0#vVHV^d6_LIz7hL8NOk;60hz-Nv_sD|wHcDW6*bu|T zyldAtiP9&KV59YLi`U6fkwqB`2W~GLTXAVP#Dcj0Swi`Od!%EKYt`9Ya)DJd0r_QI z#sKrZ=F8?g#N{&|mWZ6?d&0VWO((_Qn-U)BSE5 zPV48qRq8MRBA6{Et;>+Um_O5?lX61_bUCf!Xt(GMx>!6Or1((+QS;YC*CA8Q=)DaRxv4VbAZJ8boz(SO9Hd!B0Va{dS1EaffhuYB}8?x-n z|9toOhbgT^+?0~`NkXj85v+5zRMwaX5;kf(+w=R%w%*8%QfG)}HzC($u}MNU)j#Jl zY#CXQHgL3BBUx<`9zID#irnwl&h<0>XDt%zau=qyG&T&LeTT}Zl+~)5!P{q33gSdw zZWIxv-{aTwPA#7Z+8Y+@4-&@ZZU0;!FUnWY$;rCBR$OYln zj^lT9Ie96IZ~~`RqeHH+$b z9=A7{l{qK9>U~vAPGWtQ9P9pE_DZ;x%twl@Wn59(h;4k9QNE#;vM?p87IDJ-@{wlA z@;0Zgr1&Mc-+%5^5gZ22E!(X1j{7}y!Am2I+s6-1Rox1A$AWy?Yj%=L4+XxJWtgVo z@Bb!?r0j>V9|~;G`JK>vnD*(rmgcpBn?I!syX1`=+VcT+^nRu8d!J5S{L`SqdBj}@ zD^B9x_P8V+e!jZmCq|LtWBR2Rl>0UCVzaAvGH#g%)_lEm^sVb^4C==9rXTmlr0n}Y zeVMbo<;w|iyP0HsYpAkc*5C!aH)R9`Bn_#giBp4fyPiY_E?o(~EOeTi?8XWRvJZ(R z?U`Ac2ob2D!+fe}F38FAz+0gUOPYwAT=!0{l-RNKs+kln9~O&E>9V&+E}KL9PCigZ zP}@MxTyR2yImatC4FKC@9K_bS^Z*bQcOx%_dxm5Ra%U;#{myYKwBt#p=F@^1IJEFI zt!z$-mw>p$7EIxucQT1y7m8D?ll!4A-$4wOGfpGl%L;vGuJQx6Pmhe#%-~VaTG+qh)N`&>(aUO=A3htM#3|yHv!OyNkRJLVNz`X^v8L@V;R5Iz1c`WEDn<*?)Z_uS^Xpk*gu zR+T0S67ssJlkEeB_9T!Sz{}{UX}F(MCri+r3My>}l@^268V*wGW1lyN@DhY8EAq;J zN||meIHWNq1r_7@3eUQuC+rYZfDqZvo5%&b05U7pC4l=FF?M8?Bto?$CT=L^EkQYn z0gomfu}Jb1qbr51N*(-GXx#4zv=>}_VTP;E3eE{u8x&04f>oF@)U=9=o~!v(3er4} zDRrbo+ooYw;;d4Ix=#y}7*0hHhwEDiAP)Le z^BBoF<==N!__6eV%6|LEu&yDGutb;4F!-J9gZqC379eP1caqH|p%iYiOWWa)B*Y@Y z^d=Qz&Igs&f-e4MI-c>`G*X!PB?T>aJy40y`wnB{h0FH4`E!MrBGOxOLkCDghyBu< zMyq-nO?Wtqly>3$N&GWLVmQU1l!x-=SvE*Aw1_bqo3dZ>0)$R$$*ps;z0T z?3{|kUn&i>2`iS#A6YTIt6tOVpzx<&fuX9jQSAIGPmY;vmGTuPaiUlu?0jhjOIy=Y zMGC-f%Qi5R=CR>@xSTDAQu7bj_VUi9;|0&)U@^se=YzJd>g&MS_ z!+&(2k@1yHR?&Fc6hiU}z1}AH^q?tt$oH3cdC-BflPYjs9XNqpmsBhijD&6zl)#Rp zjB+KYS$@KEsS}y-P^!>qyJ~gP!3Hk;x(}l2u0;>kgolMbgi=%YZ6I4Ho-{NDr&`Yj zTkt_vZTksZhP9nT>68$UJ4?U?lOuzdL{ zIfS_MN%7b1%IF`AhS8MZdiukJJ!B`z)vhwC@Wlavl9C!EpwRY~>^}FmDfBoHu{9_Z zffZWJaa#Prk_4F)mYG?t8xQbdu=o0R@rcm`xys3FfU(=Jb;1HXg>vd`O}-m!oEEQJ z7FSCos@H0NlEq!YNz$=;5m;zVoA9-Ct!vJbHTzV(N#WgvI|pke%?SjXCCRF07-bTY zNyEzSpbRXHzoy%)nV4F1q31UQlkf<)umGmGx~;AHp$@i9A3G^g&b>rF0stN7ORaYu z-N`!`XCyPowo=?^csrexrP^r50*@#oIwv8m35YT*cznJw^d=}|qj9VfWWnupzs2;@ z?K(Q%ITi)-(CzZPvInw6CLfB)L#1U5afw+0w7UNKrgXm~&x34!lMBFh8+uP~Kq!z6 z_U3}Uk$Rz2h$9km%oB193!&+9Xy+iocs(NNo;MXj9Zz<@1hQv?V_A6GndVu|EE+EM z#&FetWBHp#=<6h**f!yi<_fLh`>P+YmUpc#@sS6dOzk)oPiS(N4nBA%?3r8(OU3K6 z0WhQE&{rF`dAhyF8({x*B=;8XT;WPQ`F8oqEeSx9!N{!b8NN_b8^mD?(orImFsb+Y zm0mYdzeD0t=Q8qDhtA@(zNpbYYE#g^ZT~)n1hO8z?$B>tM$Xb7cZcaB+I1uNkN?5- zL)!#Lv-iLOB%ybK;%_A+E{tl|ENg2`^^RK+fq|0sB(765L1qPuv&c@r6^VPWz2gvFUuN+_nh7;lzByQw}j%AgIe$vPA;Oj0%d9 z2OJq5Dk>O?-b{|xYcg#CjqO0P{ksY2e%H4kr>XL!*ltScu;n*Z6Z=E$oRprg4o8P> zcKkWeIU5>vOo$Z)Uq}r->QLecs?m0|?!>Hf`gA6SENQX3M)7xVa6GroTG*ON9N0}KZ(bJ@nIdd~>^DKg7N*JM z5Tf=+TM)Pb188}}}O&Ds6#1)Y|-sZiL!VI)}MQ{%^s?mhRt)a*OUlT#4ri6sf$ z+){lpP_c9-v(%6m7`HK&YJbst`7B_aVl_JyzaN3090eLwnM|)=talr*@ zvXs>}EZIRgY)Xmp$?RB5t*R?pB?Up_3bJvkcQR@{5#tYP(1$w^87(k@d#_afs1=d} z-YO<l!NxBDfITod64*6pjcQAm0Q*_6wLm;xlW41@A#`fn;y&oyA4rGAaa!m&jW- zyh%LDR=H>5-}+(O*5bSE=gp`1WJnxWXTexVR9W|K2Qs>CPxtjLLC!Sf7v&jm`!QTm zpV9`2V1b=+Gia|Fn==r^?b*}-u-FcW$fx>?G+B{mEdgEbC%ZfzOquNy(+wa`Y$XL( zgvj|0HCxy{Ec%v?Crk?(U)HZ4Ns_Qa?UDaIC{S zELbi6t5iz6YN6kOutu-*$)-DA8FU*Z16e7PnhD$XuwX32Ap!DP;3TJA(kxN()tful zsL(g9y<>sI3tS;;!ahS($bS-Yfn{(S`-s9uK8}3c-jVQJLic(2qt#gCA5kI6+I=di zU^-rR##lFw^kv6Ye_uAZRjr43!#|dKZ!6=(XQs~K8QbMeu8g7fQ}~Rk5AG6s`e+6u z5DBoFdX2UtpiEIZ&m`4$H%%Ybby&ixk$|Y8oYjD#briS*$Y_B~{UVVqF%e<(X4sQ^D3=jhe@KR;%)QHnr{ z;&*qDNrN-%eX++reW3THQ|0ex9@dtc%O|KGCrZcTU{4c1`b!-3s78A*ZSFk1h_F}U zVxfTm==p!!a+@&0z(244PCR3-{JS}Q-BZZBP4Fs`2q}G{6iO_m6IcHkx`ef&uIe9J zy%5T8N($!RqYEm-^tc^*zc(Mg4y~9CL$*8mSRVQJ?%9E7WY!IPzg6Q+up?P!pSN%< z^bScVxb3^-ulM2~*nG9ZI-cg8D_5M z@-W~b-epsYIbCC|kC>znHaY9P*wc9o~}!69u6fzyrlOY0BebFlLCH;+V=NcX+!!h@Iq`DXRYtu zt9xN1)uJK-szLKxM+1iT~?P|nRtmY8e?n9fdsD?Xoe3F zPkvrpNI6NaIr{8pwPk8Y_|4rm-nWf;quBu)IV(T8&e{TeSj@H&54sJYhJ>>QO zQZ`?9oqGQ!cV98WJVk zgg!U|$f~^hrZkoy*bhIV$vgX7z0!2i|Cu!V0__WdWgP>nboF#`Rk86OBjf;5C&~6o z6g&|*od9gAZN-$hsF8vQnYdqy0lAi9R&Gv@@f*z-`~TTw*uzy@aUb=p9S~TtKz7)O z!;YHERxN;0+*sgBoW|X}NM9^*{h)!$zG%q$9|X-%t8VY9;ruVF(rccyf_nGe8|Hj% z1A!vuZcBhg%&cq2q#fQ%+`y{!7nI_{y_eLe&alf3C2Cebz903pmFjvR^t7215_+Cc^5RxVLY~<(3lHVUdfkWT zJRg(HoL5>yvEPy$lI0lB&}0^jinJ9pitxF5?&t55?Aw2yhlfRo+Z`c95ZYdZ{DHg7 zhoTWUSa z@*zwzT{1~71sl=}XBLuf`~ z?&UbvOO2@Y`b!ti9tZZGHTK<{4=eOCha-u)H8SFh9=s5hvpC*D~$!NVtP0xZ-{;U>UYlmB%^Fh5)71{(DI~3Yg^IeE#X9 zrZl-hb-Vyo@9&E=@cx^sx(frFEm+f^n;9~*q zf-=;+jexvg4@=v8uYh=|64uSP%{u)H9#Hm4^;5X=F`YiG@cBCY9h{*4HdN~l(^)HD zK7S#hw)1Gi5?+w(c?9`EQWV%P31yBb?6%>hZa{@1SYB<5jwKu4!RS7KJz&1WXlOrk zB@iUtBS1oYUK&3sJ3T7RoXoN=vsc$KeWQNoTY=2|tso|Ne}fnaw`e0oV=SF2IYpS$}ZVx0Qf2>ObyoNK@#NTq8#{dpAba^l3ekMw=;g#~Y~j~K@B z8?IVA^L~0_bB6ypqe`;r?W5KW4W$`e0Z<}4^Dbv_UjQ*z-+FrdXNzfE5GYL1jK8?t`oQwPL!S2WF z2@?1tM;sAU!;JQV05D(jX|9v`bf6Lq9OxuQS$T<7cJWDM7vi!5w?ku&8T1H>8({c9ynmmKQNX1|Vso7x@ zNox#@rG$UrGPt-eYfR^6l&x=JySPFmTBS@TOLm4ObgUPBTc!P@eh-RzB25**-_f<4 z@G3fu@Z-Tn!-uzX4P82cB4s0A{->kTQp6iIlry;TAAh^q_aE`Z{{gc=OuuaCo`o|E z5^7?2ZSVMPfS83a#VtG3Ohte$=2-x z4sc+EK)^GW>RRa+9CbD#OLZ&30EHW1IOLLbiWq1xf^?&_IkcqEbD`>3FkbNmDW3mI z%iYO|jEI4UFQ|f?3c2xi+HAu$xIttjSU|$q#2Vm$6cJ)*FMc`ose62DRA;z}WMG3U zM99#Drh3ERD|C=9+%h<%p?EFLGTNd7j8oig$x#vn8EjyLODG4u=!I>WPFXlUuk9D7 zki+XFg=HdV2ij=Ji(ZCGs`*~R2yc_NL^$UWTY^eIIue72stOJ4PCDO2lO<2WvcHNIN+5rwrV|vpgC%LG8F^aI=A$R|6Ypk$M z-LaPoTQ64xMH`MXGGXCb=C+o(Z>^GtE>HqlyyAJ!T`m;g!pRtIaKlIWI9IuB(6vz) z(}SSBV?~iGSU5YdZ!W028h@d`H3;$qC~v(O*{j4pHm z5KvMw!1w?su=nR`IYPrS)BCgiq)}HLvt-?m`JItn0u6ZR1q{L6OrErdG?!Qd#&2m? zj!XLE`7C+qP2ZnY@!{d#&DUI7ZfjoE$=z#XR6%U-CmGF_4Q<$j$6#eDog1CjNbeXi z`qzfQQ3OMM;kjIL?Q&W3rrowi*FuiiY>yu)4V9E3d)#wDbib+agoJa~milQ^(i8(>fcv3VV=;u(Wr zH8eP?Vq&xRz>v~m6B;w4^V%VQdYbltj8lLEH}HepQ4Ur*JrqpA?Vto%2!L03!57pC zSaGFpq9F;1meJwxIZV0Z<+Ya2saJ_+H7g}9;}1GjQ2r)sh$gfI+bnvstx zrlmkXpddhoC<$3WgIRO8bfXb;int+x3u0)4{}IIe^N1~Z7aIR*3R<89N~8oq2n0Xy z13>VD-b1*Dsk}ezp2PDQU3-N#kb^F1y*Wb|U>GYosDn-b4MsG;YypsQdIdZ{19u{Z zV*rI^kOvhEMq%U%J8%Oy5J5MHra)5zHt0MyPy;kTgU+)rGU$RWu*NRKhZ2LNs4VskOV0Sm4vw?st9Z$L`OWB>bn*#nGjVV1CbfUYiYn# zn!on|hBfJe5`&#XyRnmrmh34j%Baam{1mG&lr;z$PjH9?8%Dt#%=VxKSvX8ufI-EC z!G?T=hDq_=0Hcyfo00E4YF$u!A<(y<|K_*-XYCoC9N&gCCTGIe1R! zoP%SWPGi&)H?TR`Y({PjG&V?rEwBR-giYDJ13v%Z6*(dbSE7ZgGo*j@Gz|;&2V(_zeR6joF|L&v=a;gpA984E>-4KEM~#NeGxx z%R*C2eB(1TsS{IEo1_p#x_S_9`>jSoul!Uibov^x84z9ql)wwilS~`Q8U-|fn~gxX zV#`aZm<}ANA&F_mw?r!rJf|J)rqV$xCaQ(yxF z5ss&bj3i8sC(J=!8lvO-f9u+WV>isJ+8ul=uHw)E;>hsXG}7v4z8w1xi}f$4m-aa7^_K z4@*@~gb)^r#D#zfrU2vvt-As?2qr!VrkKJ5a!gfsjK_Esgwe!ReB1<2@B~okRZ!>z zhxk6qJcY=7K~IpTiKJ6QdWDN{Fjs;U#Tguw1J_}n2x*+B%tLCTIxWcwn3;@DNQ2&h zxJPRw@e*d!%JWFFC^0IRV^PP^-hFTcRimqWG|c(M;}p zL06!KRvHCdfWa^X5(0~net&GU1+1RDo zEAp`bxCAx8gNM7Cl0cSj>WQ2f6CRz^jnxVDtXSkt-mUO0`+*1nF@`MFyU6I7ngq6} zp;0_wORNbRN@ANlNCRC-F-QN^H?@tYF1C{=4*9q0i>CtA z%3eTBaC@XYG6;gG1M7^RIhn&ZeAkRpEja)9pDn?#JIFSNI9W=rWUQ$lA)6h!2nIapuBSu@laK}Pk_tr5 z$p|JyW+UYSoTVy?(L(%*gFzyaOxdeq>LLUp zhu{pUjtJJJ>Zu+Xiztl!QD9J51JoVEDuzr~a0ttch+q9nU>)Y$E!0bl$5(w-f1Yb5 zEfpCFr2Ej_{kUkt35m98gEk2yjMZbno0ibIF#GwgzzQ~D+flZ;gDr4Y*(-@W35-mI z9*(#QxTzrc2?;(B#SGTymku}cgJ5fMnxgnRsW_}II0X?(yQd^xnd!Mk%CL*LgElcY z$J$BuMV{C?6J!D+W9YJw(H+k145@xUkPy(+2!Ocxjbu;-iKT1mM!`R7nOEQgGElkK zQBWojfcFSFi&Q z!pYGN@HwMJIe7>!%QFepQT}i|ss!$twq-N`gc$JI zYZeoa!ZC>Bt!@a7abyeeo$*pu%IICZCv3 zls-ML5e7Tx0*h!0i56Bd@|f%yRRKyBs6E`wlNuk`%1wmjHS|E-3;c-&g5I7+gTrs0R*JA*& z1v>xUf=xIE_1r0vU~#YFYcbl8mKjSmXedPb1y@)DB5yESh$1WLLtya1z_~sFPj#WX z(B+*&s(=}a;4%Z&w&RfwH8-1*AcjC7gR`R|T8y3WXp1IV6-xMpW0<>Nw{vA5If&K| zS^xw$@bC5Dm4{}OCQ3Hffs}`q!J65EQ3#|Pvs7UrwoPj><=}%Y00b7jq?%#3-JTvq zb6M64u2gY@P8j9#4K77ebph|D43QHDZYX1*QB???-Udrdx@`HwCgVac=xwKGMN5F2 z+d4)OPgBb}QyF)8}&oa5Vh{PQA zjRzv0ca`Onn~uMZXaR&Z7@JxAx1Y&%S(pPdaPAv5+K+#GoL80%W1C;tD%=^6FxpwT zlcu3>`6N+3V7L#9IB~8B236REK54N}0rbvtqq*Pt;GqN_=?Y_T*?tlRKe&Xpmm3=o z06?gN?s^kh<8c6=`usr>gir;xVD*n+n^EY3|1Mrt-X)PRJ~+Sw$^g6^{d!wxis9a7 zJ!^}vgnQ!er(hEa0qF%l=mI#nthM=~nFEHcx`fgZa(G`GVVDCp;3c->3K0M4u9g!l zeKjM*LW5ip!WZoYQ=EBz0t+|@@)~(5IS2#-l>Ib8b<P0D$BE6b1^7F|8K~;xbC? zm7h5QUOA?LWvt}T(Z$Gj^Sj7 zAo!)^;45wXlHf^30rLtacU&S%Fc*r5lW8x)7^7$RZRCn{$DIaX0J0H7+bJS(*4cH~ z`S#m!!~`Hm9e?2n+jh)lMAjW$*zt>f4gJQUmRoY!WmEtjhovpR2(yVAXn-Pa5~;>-W!Nins1Zmo3_(3)pE_QUWNk~xr$|Wwwyh4T`$E^7$O6vjRDka0NxM+}`^^_=E z3^sHZF0KeN2OM);qRKC~H9F)?s(?5Xx+?+W1}MSgRF^;z-oXbb@B!1-yg?akk!WlM zqlz7;tW_Pa{kk>PD76u@-^4=uI#g)Y8M@jRa|m;rwnYDiI*~0_sv?KVP=c&T1?$?OVSM1hQO+FNa*P|7Ac-oi+&cKnE1(F1$0euG z^08as**dtczq82}nY0Ar#wbXwR4maG8Kdk>OBYL0bwCx%mN3BB!Nw`ZWXavo1C6VS z8)o{)7!zv!-4(?coA`oSWHFJ`0V-6$ zki{qj5r|Ek!WCm$9CNw_ybJ!OW*-ZNEKWfQKFt5Y4tNNJCoog9M%~OsQ*pzF$o3aJ z_yH+CsaOD9u?au$ffAz_mQ!rz9j%ZF7oBiJAdW&Sl9=W(0XW8DY=axnI17o6+Z1UY z6Qf@k0~9PI#`DmZ!l1l{G{T??8r-muuKJ5+UUk~8K+fzVI46910Dn_hakW> zh9}TarSy13RPP~%QeGj9J4Pi$wph_CJP`;%K(Z5~c!g1fQ8kj}rDjI@#p3R=B3#ho z6{i5jCTe$wn5E?vbjnPAd~&}4>}PpS<4I(KF$z0qvM1f@#cfn^Lp}h)6RLOx<$4%A zoF#~IWKqQ>%?~ra#14s_E9Q6I9na*^S~7I1~f~)x$|cv8$=axl1oP z_(2W*=y@vHWH$?93uAPm3x(PmfVveCbvErL1Nn_H0x_H`>BddyB+}Bd5(qZ%0T;!o z6+{l{i~y`-pNd^9S5$EaHc+A$3|arv#4c!A;2qGd`I(qxK#>MY9D{=qJInvvv=UoL0@Wtvwhq1}F=%w6`tVge!pwJh92JVGjRd)7AJnKf}->4}G!Zde}G-cC;e^ z^k6K9JDd|TT;eE#!3~2TXX3}1_%~+xMH|dWt`wK%s4^uxRn+QZ8 z3KM`!j5Gidyv#$O@`}rtR26FOs32wvk=so$tJ>{})C{?_iWE4|%4^L-h;aur9RqGc zV-J8Dghf|OXcT0kPB1<(kqvt|)0(yjF@yo6-(1l(SZWaPRsy=R0Pj7Lr34xHu(&nJ z26UFKEL{qQ>QUdi*7S?w)7Gk@Ku`#mk`0Rt zt*~>}OKbr?UYVDm3qJo%sL95fXt)Cxy<(hje+g6)!9_4u;|4YNZ%tLUM>sa^@s9_f zysB`8D_-#mSIA;jwFcdLaE&PQE$(`Y!;6wFY4etJ`WUj<7%i4z44ebK(>AXf&5JH% z$gMoqw4g<-n=YFLejyM^i%ipT^$@K%UDlS>ItFQ-yEm(n>5tNiWvRQJOQazyU+fZ8 zdT|Up^hs_bk@!~NVnA2q%j9b!YI`Xdo;DF?3%21Ya$s!u7kzqEcbP*QUeTD{1o&~v zxz4kArkFLf;S|_X%wfmz5OaV$^o(VL8`_|TG^Ak-X!t@Gw&40Le1QyPKtmePfQB{T z9`~eo1Mhh+2Rr`&zYa0O1MyFphdkin_{qluFz=uQECeDC^d_@z0nyt_Y~r__U@7-W zTHaIS`^_~p`730>^oj{NJ}vqA7+WHYWAuUylvoCxs%G<|XHv+WEczISE_C~6Qjq1J z{!tKD1w$IBMsB#qt!15TEM3zr-2*n@1U?Eu{Y4(I+hv6gQE*FYG+Kwinq#sZ{ro(k6)ECJc&hK~l`fK@x01 z?YMy)%z^(Lz(E_zf!DY}9n3);xFH`kI1z6%?~VTMiPunGANHN%NOfN($0{Eu6W}F z-U=vufgM3a({+VIRhw!$SvU4qZE(a%6iKq-;5|x2TX9M-+`$)Y0z()_T-nb<0L=eC zRYN?814BM!a<&n~`2^NEhHRK$0H^}y%_A0uX8RahqI@Ie%$4w@A2U|r$B0A^t^sD? zAO0;SUi_aWiR3W`-AEE+F(Tst?uhx(f=l88eRx+&3D+!sAxn+IPkO=_zEmkvg1W&} zf{vnY1p*+1;!GhQ@xf&$0$=IX!53hG9H?IHr2!eVp6j)qhuWU)>0Tk`9$Wq%9^fG- zzNPfVOp8h=9=sd#<-tx~fjJm~7Tkdp98M|zR)SUpN5Z5mmRymRTua{Peta4)v1jXS zM3o&90OrLp+<_n@gJYs+e9+utE~EN&n)~4&0d{6LW{qYX1Px*aR7B*}c_aTUt!dUw zL`u@;Y0TAW{>600Q0u(h+BMjq@x+)ILxm{kpc1NFd`0dM10|?IKt09Zi4Fqg#)4>| zml;|`$<<$MWO7kXbz4k%Enn;Ax*QR0vmEI~eCgAL$-B`OKs1Rmm{9@3#%ie>!Z z9vaNvh&JNueL?Nfp6-by@9m-Rxj_;wT)yV2 z1bz-ybb>s38qir%d>Uh?oo7bgoJo4A!FHx6-CvL`4ngF_V`0TxtsVc=gvh5>1i#@5 z1zKG?fs40M+~<2_VfncvVD@Fc-Xwp< zVoavnD0oCEmEy39mmm0nec1sYR;yK_K_kju7mxw&)!tYZqTcqN9{R1{vL&^8%^Ylj z6pZEW?d_S|UK)I>B0lB9abmhUsP#F}yMk0m4d`!eLQK9Q_=RoxnOt>HLKo!0Oq8G4 zX>E1_+0ZVdss3aw6YQn_g@({=5Anw&`q7s=7rD{RQ-N)q>xA@;r0Zz1rY94Jf)0uJ%P zT;foKav~p2uvUsCS>_(Ne!&*BUWk5y6iC4qumKsU!L^PhwbsE`zHQ{D>nXYL3)9=H zFy9I%WxBF0U0Nr|tT16sq7B5KRnv$1kjb9bDb0n9VW3!3nZY)#8Vfi3Bg8 zLMU)S7ECYoT7wX50VQ<8D|G6uwARB^(HG?!uH;T9qyhiPuxSNSpvO{OseMLCEY3d$ zp!!-#0HncLjZ2flFV!yDT~Mu(<;DG7577xAV-8)-Et!2_(Iv3KC>R4Mb*)SK@5zB* z$UVeN0;Rh$a3I_;9{k=NzO5%lF1<-;YB>Wu{BSErVQ(6XENMvx#-@zI5}c0BFL0!j zlucWx!A6*iFZjYP>;f;8LMVhn7UV+!bi+BQ!zs)Ftc(J7X%=5OSGO1v8vp{d8JAukfsiQMYT0w+nSz9fX_=wNXNx!U4UbVxi0$ge=)y zG%x7FK?Xw+EW;m>WLu8!7Z;(WF%J&BAF511Y`gM4GMy%VaNxD%+SPO zkOV_~k9UT530w#epRkNSzT>~}0U3-*Si6uhw1HxMLEDXuFI==PM9MK>0UZ2;6d1uK z077B3RWE~zCor`7z{dbJH;AL)TLi{G<5%2EYcv~P=G5TjNk-vi-t*(8h_?1mf7 z;GPS{#h!~E0RtR-!SPskYhfy|%R6Ey+HnX6C7jUuI7FnR0Uk{98x4j+efwy?!WX2o z`ZSBGwE-SD&?t<0a{tBK{`miBPsJsW0WX=Bm!pv`M_nBm$h?Dmh%b>U(B69U3$||u zvK0Kl$n+DhcTr(=nc#tdV6`slW_4g!&ErBE5Yxj)@s1Ei7c7#ApY&JQ2e=#rP56As zGd)+ZizVg37sUFl$}+mVMTvC5gX_~^tU-N%$8u_g8&E=>==($%+8w|jbiE^F1VbQ< z1!Au~&j`YG2?M_@{XjYjodiM`unxQ2ebWOzPs~lgRMaG+{I)yGQL~{AI5nUwLIsQFaQD zX@M#X;pQs{dx64AC;0yx*%EslzNY`${$S0voVQ@K<{33=qZLbuXjM;@rU+ zoWg9ce)d~itNiX+1rqKPiB>4Zu>L3X`LzmqlC{Y4$Y8@R*!D0cbV!d9)xdVre`DL;6%8MqI|e zymAWlsMKGo(9jAd6RXLc7kk+vwrPu3TVTVI+=waPUdAcmj0&b2 zbjQGE@6;joIkv{YMtjjBcBxAMi@9Z24tD7apkp#&6L`od`FD*-t zDv&g=UuxhG`-R(k!e35LrN=CM)124M-4nzW%ugU<^%LTv-Ybn$z4!;WKaB*>OvD6zvBTYhXvDM8!_#>g9Yl7$#bzVOdT66+HUqWxOB5HI?U z{1Qy)NZkL47+cyvV-)jtYcRT)aFHb#S;)|jmIvAN4zA;T2aFNyKQjUv6Q z&!J%2@I=8wrBf_IVgw;0M$s?~3@&0u`GOB&exZdYN5dSI)V*fIMVL*xki#)sM2#*{ zRl2xD7+3F152H`JaOJ{V5q;$gxqPiJ7**CNt3)S*@nlcZe%vV~LArpm%3+C9OhP%> zkfm2^OZ^sHnj9iV7CXKe#n6FXb*?u}y8xw3#f}t)4N83Uw#@*7*@TU&!0hD}H(o*Z zS(t=z;}T<>R81I4x_}7O8!HorSw75LE8L7V_KC7!HoXHFCVxEftSvwZ2Gn)EBPI~Z zEIt2{AvY))6&J7E7=_Ox{Zr)&6u*R47(u=euE`C7mL-ieWKnSArkxJyp)%({&x_AYch>wg5*waSsjSW@&)tQ!K)}S>^GVi#fNPM4rODRCeSP$b3Ctm4`O?A(e_t(Pdt07RIsRfg`tW9|s{HM!dqX4bpFxZCEBqaaI_G-LsBH0yUsNS$VR}Ux4%jDQY>IkfQp)mxVUZky1|})7g&hPIs0<$Q zMtu0f=j4JKD-mcm!Fa{tj`5k{&8;lPxWgQZM5>sa0(LJdSXpxCm@CfhBDOfj9PS`H z1_nkLfq=t*p4E`DC}k6C5X5rU@;+|2khVSwUpe!N!U z`~bHLvMv~ZI-Aa7@+mZMt!;1lMIhV&3?mwiZp3hf8rpE5O9B#>#4!(PTy_5_x=AM` zujs-i2H6awDmHcL}GQQHOrAn5#xb8e;IFMgsYz(JpcxmdQbymz&t*JRv(t z#uA(+p+&@Ya=!;j1y8=X1ua0-1=qX+V=CJXyBM;gJVfrBv4P9O3`w(N1i}u(d>$@< zu?DNm^Gh&^ogn6Ly?idFGMXZT#kz*ja9(sTikSQi$fI<#7>Z$22auz#mvW{ngj$ytM;lEnXoEEsW>Yejlk z*B(*_ucX1NVEAgio%rG{wz373@?e^-Md+g-9pFjT#ij=(1+thrXH;f-kQ7mkIhB>9 zU@}6!(D#3eSd3F>xY6QCFcD6~6@Q+)Rnst~U#UQyoi z%0d?9_2^pyL!G&*1g>Sp-7=DK3}d8~828=Je%30Cxr%2r|7kC4AEGXVR0%E@5gtk5 zQecn@Fha&)L#Jecr_6LDB{u_Ismf_k)h>phr(lDENd*&B3BvylJ4Vhq1w5%;%U|5}+mrwHw5RK8&NrDC(Xvp5D^zic zQKZ7%+T|`HE|FtFFkuaw@Pi%da0fi(fyj8k1CifW@Y)2x4s)1u9qIswCgbkQYe<8Z zx4Z={1ZN8q4?vh9gS$1`+2C&*I3M^d2p|Vy&wJhk7VvOm>~^BNfe!R{$&2odrngQx zL2IS+d+AG?71L>T>!izC5&yndJnM0*c-l9LH7M*N6`|5yQ>s#EjSs?^X>fsEq~K6l zy|S)`$e);Y8BsMyvt*g!D+D+;6DP?Ill3ER8M7vs5JMGYIO^Y|-FJ_OS0IUSMF12L zfJ9^>5#LS4;03~V^Hw;GL`m-}W)Xn$8f2qY3V{DFd=Xd9_pltcEUp0sUz3vT>DsW;@`axqOiBo^#yi z>T;L6o{;${#!K^8J?<6+BAwc?&sUqL#|$LtQye1$ZF>*ZRkF&-14eJ9_yA| zBxoq2D8R0yY|jHj&_x()rNXYUiYKVN2Bo0LjwDMM{NONBYuAv%Lq@6>0@;TCQ|7r;jsc;O+A@CgHe z7fxXd_}~}HYZkZ-y=dVUtY?~l1U)XWn(#*^zHJ~vhJWovWvTB&i}M+ z00%24Dv;?y<}BQxiXKhe-YWv}%dGlKB`6ToLhXJIqAUooz*G&@21^zI#5EwyAymyt z)tstE3dqO;S;t%5NbgcqR{egjsR~#nmFsWc!IC&Lo`f`wdzn^NV4s) z&ZHCz7hE9+w+^Jhj;{g?uO6+g>`>Br(kCa)t%8!$s8Ow4r$csv7H+P*9&!Hy%@YEE zx^7Izkk7~Xzz>|u$MWFcJkhz}PvOpt$;iyOB96GWtQ55X{kCisM-d05fQV*sx%^Gw z{0+}eZpTti5Q5D9hL5@iZRTcf-OkIr5-TTyffx+)4`0s^{mZS6VHBJ(u1qPe!c8Y1 zjXGpcz-}_vfFv9fD;&S^JCy&59ht+`KH`VI=`Cty4WL0F?BO0?^C0};9tOf6{9zzs zK_5%O3n8xwbFV07VF)u}+p=vS2Ct)@5DEpN!nknvYQYbr01LKKPt6x#GSxp15=kL^$)74|0p@-YC4;S{co?T}PC z*=``%ju-M^3lgCj0^m_YK_F7$6N-WHnD8X#i95k#vPiOjHi8&n@HS>JG#HD->_d1` z3mEd?WZu(N!Ex(OO0rP0uij2DPEw&V^D^B)6_!yNrxECUt^xI{8YgqWV1g0RjX|&N z5x)!gMgitJ!4tTvy6Ua|>doY|01%8!EA0&X>c9=4O#RTn6elhXyevjV5e}}e4Xkfn z&x{rsF5zOa`P%;#;%LOq@<8O|FA(^Wx~j_)^iSpjMqtPbNh9PO`6>ZN1JW4wGD8Ng zc23-a6-tHf8vRQF5fQ-hYI-nYU!37hLslVbb0GGI@eJbfw#`qoAsg@k9|S^DN5Rkt z0`i>46;Oc};NT2=FaTJVWtE`_caJwWQ(T1SvAzS=AWJx8GC|(4Cvr_QiMAk0GMg%+ zD?&1Av-T!a>%t^UG}Q1tqt;E{?xYe(GeYn)cB4ibh> zs@5&@?8mG!$bPKHoU6I!^2nC#`l^o&wgBI@ zOv}>X3$*`03$RQLCXPkdj}7ENLvd00-ft@bE@fLK)J*6$Ec1F_j>OQxo=~c%c`1ffhFf0yoi1IVrLh!hjA!AsxP9 zHjDRV1KhK%rG&C7X1^QZS`}0tF>=OKZ2*?l|jz z2l!TzWIUs44rry12smr+*Hs@Ff+1uK)4&xxqrtq?Oe180=|(XG)DA22Z{tcJh*EEh zl>#Gk8SjS}G_>rDqK^g(-HJ34C6QW(Zz?&F$d-%E#`59dfQZ`cbr#MRVG$R-&&j55 z4eI}Kcty5&2O=8;BG3u~y^gRT@L@I;LU*gTBV*wec!3PWpc$0miUS}{p*H}=*dSiX zC(dX$hyf1*%6Zfn9u2H`^h0WY#@GPin5r%$+%tkbP)w~Zh>Rf*<{(~53R5`vj~^H& ztpvebH76LZR%&Th<1nwF@mGmbSR1hCD(%y@wl`yVyk0>N2EsL$_%-*zHa()kHZmca zcpz$FP%W!ilLVW;u{d6iAUk`_~Sgtz%^h?XI_mu zWT6dQ$Z3G#6v$x4IE+mAWinVQklS;SAK2>_`FfbFhfdn1RVt-SjKL`RKOQNc^%<30 z;ZZx{ipv<5@xc>PfxH?I7e-+V?!XiZ0+z!hMUH_D0t#FnELR3)4F(CBL+KY>Y#cMD z*v!HWHUa9O8EHE!f;qya%K{h@j(>{nrT>_nF}O_G)FV1Tau#M?cz&$_W?T;1n#o#Mu9o3?O19 z*ORg?Y$Qx-tZ8ZlPZg1O1N&NKncEt+T@`q5`mUGQd`n_BpEwnuO%-$jI6i?FKw%RE zVwLwH8>}E9u3@-|(>o^n3(N+cN=$%*M1?lSuY#fFhAmv&gc#t!l1OzXE=)DXguQ@4 z;qC%7OBq`!cq|4OWb+d&6-o$-3PHSX_Zix7$r(r_O|ddTuExRw`9P93jTEAPif+_1Tp@ z0v~Mii4kFcY@rUc;1zDc75Ws~_TY>S!U~=kjZxe?%t8>Vx=x%%$ld=ypfubp0Kqn# z1}U#8UN~$ejYGMH179)_#M!&DoHoU~+$RJ95nMqI#9$UQa`1LL0CaqzeOVx^*dPiI zpdV!|fW?K<7hI&mjr~Aj7`!i};)Y=7s%hpe$`ce6gwLS@st`0t>R=Ach|5P?>r(0p z{TS^?+siNgC=wwNzCaCX`Jq2S6as-Dpw}Oww;&Kf@T9{(Gy@F+;TTfp&{qp43TnkS z#yD_6X{`BC(&&-cU_eTY*HAJT?f?$vBP@U|&@o-vNkXvKU=~~f3UyE*5CI{6*&u4Y zda#NQG$$o9MzVOuSz>)J$|)G0+lRQCENX^c_DGJY$wd-b7>NI9KSXlb>-|Wypbo07 zqd3Bfm--U;Ll|7aG!o3o&4Lo}z{8&=HRS+j0;gs;nhcUXlu|SN%H)-h-6S<)s}aIq zUc%l#ULz<$3hv+)7*f4W7)UOGep5U?N$Q32bU&V$g}9%`6`2+uk|A+zzmS4@O}K7j&Fvfj13eDDq$o2;$$H`|eJm3u20* zzXhut)JJq3S5V~=+TdOkKB@#EsIs1Bs_s96Vft!?dENh>^Y;Q2;6Ms4;ky`;3tyoY z!p9)~9=ZS_0EVwVNJALXpd9a)t05vMc5I{_9(s^maI7at*1$DT--|*MQ_KQ&cYzl^ zq4Sr&EjB?AK*0^RAiKP)<|D2vq%llhj#oUU^d>#A!J$9V2~(( z_&aGdg2DQZLC5ESFNT8om3@BzP0M6%-5L)dWYMB!%T@qd0TL=)7@!lwhY%x5oJet@ ztze+O{KD0%SH+JYLyD~Eu@@~i7e}gG$#P;xT)^0j3Wlqt&6^=R2IvKojUZt)aS9!p zuq01hwq*T+BWKydU%qZJ^yQ0a!Z%j4YTe4UtJnXpHWA8Vs49S~S7^StI#u?SLbnBL zA_NPTXP22pgVNo*&?GTRZiwmSOE^GHq{7yK5>~h{uE$4Ju~FLitKOrxZqW+XX3erd zXadv`C1lXF(}Orc77QAv;D;ejM-g*LanMEg zVNNf3gvKiynRp^aMtOwGaDnmE3sqFPXp{dg_<3Z^i$De`BuKW*RghAud;thBu{9|m zfF|nrphx4;(uFI?4Y|@UXaOUomJ&S{%qeU<2PQ~|@dOMYZ4h%NMdwi`oE(7_Mb|EG z=BX!ty~Kswm|biV%qsv6G*EVX;(`z{Yy=|SQF~4#oFIO<87Z6`y^=;S>0JuZdE=#V z3NYh&y3l!j_96@$axiwGsj$ZSCV3_a1IiYoj#rQ^5hnEIkQ1&Un1izR=_Vh>{2D1o z2(f|XtFl7o5h!VpDyv~}8br(*bGS+Dwcv)kA8G;IVoXK>2tx}nRVfr-tijCE1ugLb zLz=kp&EX1u?Ot0|RKe772{F2mD{I1hz5sIzF>VARjKQA%OO-AN6Qc$k4?`^O#vHHK zr?!Hu!D2z!7A2#neG22oz`gv^aWF}G%dw)wH0LU~=&7m78gqp!t*UIeadXE+7fslr zd7uFdFtkWju0jRFN{cXgs9{Xg9A_pBC3cvZ_0)Mdr?ITJloo(>e5ear94>h$PZ2+UoKu$YNn%r-??aGQhZ>-rdYjnbN$C?SVNgYFrYv?SZ+Pk(?nIRMm z8+LeD_vb_h1OOrV1O*5H0RSuj0L}n60^a}t2>$>B2pmYTpuvL(6DnNDu%W|;5F<*Q z=unzKX&5PL+{m$`$B!UGiX2I@q{)*gQ>t9K5MxG`Fk{M`NwcQSn>cgobV!X_fSy2m z4#XJr=fR*zeNI%mvu0AJKcNbR$yDgnrdYFT-O4qg#fvV(TBH^hn%J{w)220O@oU$V zYKOWFAPuV8xf(52BPui_-hwXQ3LZ?jaKx{7dt$_fO&d3Bbze$MOZIF4XwWVi-Z=NJ z%gQguUL8rz+GS^r>4v3?@ULpmuw%=fO}qA5l44aW^lQ6!+|6t|N@nZ#r?qOxf$o*& zEEz5&Et1@Erp?-MwfbzI(F{VA@(~_hiLa!v;Bde9)es z>enxgSO90soB|4J(wMbcdI%<{pln{D=h{;HMM#iRqsdfWVG(Ai;eK>kgN-x99J9=b z%Q)jq0Lf@0O&|#bAbM7`;gcfS(p^8;=%qW7~!N(<|OzB?$%XnA^0|J1sNiP8$aoZs zTk0{;c!-TKc(h^1C9foN9j(}Ai)f%o!D)+Exh*K}xa5{=ZfvC;1IQeA+_%@zry(2F$6_A9EX$I#;L9Rb{Nhpw)ON7T6tBUqX=TNu$rAe)Rb3b1wvga;l0 zcp?ljAcq|Cyd;-AugEB;3^KjOj2HkeuOJZwA9o01ZLAIFtTS!v#fHtd{2Zn2&_ow) zG*B2VBZwV*xGNCNpa>I8Fu$}cgaoG?15A{^bnSK5QhqJ=*j`U9j4gn)`)&X<-vP%j z*i?4(+)3H%3>HRw!H24X(El6&9(e>_uqVCHVmK~{C$6~Sy)^DPE{;bYdE&O%0(mdQ zeC&)gLI}`;A9Z*ljhu9sZaRNIgS+$Uthe4UHnP~kalyi}t;#F7+wzJHS`agelfJql z{P4r8V*K&QC$Bsuv(sKMA8gpMoa@w|#Ud4VWr+0Uv=5fkWNRy0v^gC zu?0_D0)i0iga$XbK@58EgCK<91^KYCjSa+6aF9YWr~wVd7*Jc0p++*UfCMRAK?_@0 zgZK#cy}v!`5;ImT(Fp}+FoERBRZoQF@Q zo!K~CKGtHUmQy(3JqMOxvUq#XOgr_N<@C1boxEX2R;mK1>1YFK-@RUT zD6=_X8zoBE;$^d@jK_H>?FLB5*|4LpR5AP7V)t3LjdQ-ve*C_;UNKtMEdk%s{lBWBy zF*#uCCs+g!VR$`~2o~!6bux7|E7I$u(nr0Y(a$h)Ae5(|`8j|gUuU_=W~m&@fZ*@x z6z!-APLC~|{_mNbtoCYIn?N%bSAlXoh-P}B0`EcWijSa~ATq~k zX+@DdgVAL2doOo#p=%vPlp%B;Z>nW?O-k?9b{*ElfGYZ!U zSWR-CCiC5X9#y0NciZwx_k4wIv{H*bi#2gK-4q?Af5dP!Fcp4q@!nTTMwx>MoWELo;9o+hO@Cgq)a&5*oRGvn-Tcj? zMqG^~@UpmRozSOAjvGEV=mmcfoU==U#_x zo-38;cIT**P4W!W^Pj!rTH-yw@7UxFun2V^EK0F;7rMq7e|QseLN}j115;o)xHb{S zQ^ou+nWbvyAjN2Y(y_wnhkS<2PjR>xfG0r`I-99JppT%L&jEEyd{w;udn^- zK)x%AAbpU3lmnOG2Mhv8ZB7Y(I+Xq^NX08$F!NjAbpqc1j5(A+X2rz*|rgj0#;@o)q~ zmV}yN>BlmiG8jU!FlYf7)&V|G^l+7w_LkHJ+mV%YBH1xXrC)FM<>)$d-3U&JVX32J zoz%t2l49&Jsjoj$m{tR1bU4lH{9Ie9)^W%Sh&VP}YIYKaA`{S#Mx1+kI@=X>7s=W| zOepn<@XEV({EFx&c>}^p!N^L7EF@hkb__d3@sxW(KX~+1X}Ra6Gaaz#yv`t{$lRXO zQc8{tcp4+29^)^kEACCKKFZ8JM79(m?-o;CR#PWlAuHrU*nwFEMoEiTbUV-pkFbol z(aBgi^I%TWErEoy3)fnmVyG4A?78VMUF}XR>pddGQZ2)<+zXgPI7inXCa~CPaB5v4 zgJ+TxQZi#-&PXC#bW|rf|ND;r2?`zIlMzn|kz)c9rAUjX(X=wjG(Lm<58!6KGO~Ls% zE}iSQw?5qdD3CW*h}0YlMRFE?Il8%zxz(Di9dt^=!xuqu{&&L)?!-kb)kUONU898O zkade;sk%ig`7s2@S$QP41#EC7LpU(sER|g3n{LTej9!g-H(Ho?gmi!j`v-=U%ON9* z3dwv_CPv&h*?dIBZR7z9c^YOy1j7&WFj%Hj64bw~6#7#^>aV+Wd2OcaOsw+obmO~o zFFk+(tT}==C@un->jl})T*Gi`oi5kQH@7!mrB+-&{npojgp!q$u0q*g1?)i9d_3F~ zOMuzoNnr&Vb@?R0((f+!J?2=3(FoIWNJJRi97{O&=2q}NS;g!=CHxMeq)fUMQz{tP zR9|M(!TVOeghl*bj86V%xx$-FoTFw;vE`8Ef>N*@{yN~kEaqnKFTTUB%I|MjM$iZo zI^=JG7qsvOW(Ah5ONQy)n2|60UX z*7cU`#`+lOs+MkeI+JCLQb~Fzft84?iYCIHTZ-S(z+pL6vkNtsiz?L_8BRM@A^fRf zL1osz(?RML77f+hoQ2{CEJZo+b53`ClfaHU*PhA8ET1f7yO1KiT#FGwIZUZ=_1~th z(|KK2z%eb!0bKPF3U{uUGSoBNKl=SP9@F$HN8WDwBiYgVU7a`pWX| zM!!5{aU|R%2eM7O@#M{|IC|~qNTcsJzAH`*bFmF&76J*U6+qLH+A+@ebzFTdOtD1R z$rZx+vHGV94bHfn$Ic1QP^8oLKl(U?*|-Vr-_*Y!vDMJjYx!tnoGWj=X#v4Kv&cIa zpZfVq1^;hkX)0IRH< zx4AoftvV=4yy}9SniHYBagVisWg0CZuhri)L=+j_!StyyLyW3o1Hl;Ar>0As3YbKwu``T>hu=@JYR&0x;%}@`;4I5tZ~EKO z6^{a#2O%}A9!Bur(+&>M)0e&!aqbCtj>Rj;@YRMXchd8&W11IklB!i1uvX!rNDx|j|T04gtn^}sV$96xN zvqHYL=sjcAVrZF~I+v35so?V`xq$u0D|#NVfzObO<98n4tn7C-KcZ)kX#UKqHK=bgMW_#f8+-Xq6tXWR+`O>dc6(sxa|Ar39MbDnG{2 zy)HanIXUc73A>hI9*lcW3jfLGcpm@$<-j+W3=|WyzPM@hu zQWH)w7M|E~FP}4onUq7x8!#t4xE(IkjGB0M!cy-c) z(PhPu^rW=?!VsHFY2iOZ0)sK|fHZdHvP++*;R`9xhbdz23AZQJi5o^S`!mjfbg=|- zLfn(i(uh^-JA($=vMI9@#p&*OP0*luvS1`deqvHsTIH+oXZE8#w9xZc+C7)Y(PM#j0!39%QRhuI$o8LDsau)R1O??p#NFwXBv&u`ft{ zsWMqZ#hj{VO1;Cq^ju`g&M;mfa;cZ?MxOmr-(U6atJ=DJ8X!_im01LRdRcy*tjI0# zXxd2FSM7REvGz&W=~BOK>(!7x6aVz#vO?ZF38UqWn;Me78sEOkEBUg1d3gHdy}ab| z_S8FhUk!0Es|OyUW1|MJwInXKa5FN1#$NI zI(CCe`Gt<2=SF_H0!KB@^xnF`KdeMM(>(xl`3jQ-`{q45&K$DIH()Ggye`qcZtuCy zIfxUA+PsI}C<|i>pSKC}g=nLp{E{2IVCFL9=9R<`eu?YI4JQ6Gn^B%0Bld97Dw|P> zn}R%>)Dzn+r*}-Wds}JGw^GkBH-s_sIcyguZu5U*&dWN-C%IXixLpp|sj%HHPGoLC z?r@%2A%4>#Zoq3r0S)-=ihtW}iTc%{JKK4mb|dvmLe*>cn5(cmjL_|d73S)5pV~sV zx4to>xuvi7PX1w8__;LFVa+9RZcQq8@m+9itp$x-DBXwrba(%02>Mhv0Xv0Y2e<6) zs31eIFfX6wu7J^kLf(6GIL702^AI-f-MLI1%{m0=+{Fz4woCnD_V(VocJ zs7ShI3?1f%Yzn}`V~__iEeAqk0M7sLPH6QAJY4ELT;@DnKnxH~S7}RwI8DQV066f3 zZg=KCJMH(U1o^PGIU{JKnmGY%O4tw0IXFeN!#LnqbG|PQ%vrpj30{GPMioA5~$JOb`z_1^GJojDu4lgkMCv|ctEcR2V8S8%&?L!)GUWI1)db>b$uk;?< z!o=_Hp*C*FOUAAB`2dU!*ZKfW!DX;>Z}h=+4Yu{f^FOBza#gfWv&S~Nqk zOixu=C48h`U6LL{0v;g|iRhqmG)q5H>I28gt6Hrxx!wNRmA=gL!USQU`D6+(H0B~=4HE$4B zm@!LyvudPNWs*B4fO@>1`Vmi^$YT5|;H(vD^GxmKYM;$QyNsj=a=&7EtxBMu#Q*qB`*Rrj zt{1fXZ|d1**xFF0m`;|}uZRy*W#>m|?!Tkf+M2vZ?v=fYaRqkXf}gzQi*;$w2mg__ zUTCz7eI{UcT7f~GBSU~(#$*3#uyS9Ta{Cd#X6fr(e~%GV4(u_2nytG_G-8qL*dn9< zLJq(+21f`#Zp-6QaHiCw1v1+?R#t2dmdhxI%W{vr&MeiA2P6Mp@vAc5QRBe?vgU_MqQd}1Nz&8@9+7OGt<~5%-T&k5yxDk`KHk0wV zMCL_x8zHc_VW!>1_6z4NkHCZGI;t*|469wR<|Bh|^Jj9bz8-;2Y_QjR!t5+7=Y8xf zWZ!b6>s3ywI#_;^0;dbTZdbLjP_;8k1AOjJ@9YKqnlsX_K3cnNyW0~vsjj;0$F0*& z2W8vY0;ONu7yxUWFQkY-^8wwRhM6{|7Kf(*Tj-{fQ%X_s-9 zRy(2pf}^RVsQ@AWkF@9Yk2Oy{uh$R6>b>!!Jo36#Fro8)7bdD=K;d|2%jX^sOcEft zi^pcEE*1}D>g|rMXNfqjOAhG$zF3KnAMHHKGT48{;>-SvXq2g1j9g38vV5ePowh_6 z@IgFQu0$wDgjQwg@8%4!RlUve&C)mc14=!u;ecxmcI(zpeDoh>p|T@QVtm245x*~RkW z(W((+22wA9kFN`J_-vQ{A6nIv1kEJ$pGXa)>yPv5>Enj_V+VTqi6%INgz)% zVpyG;dzZF4?8(vYM6Y!aT3i0$#h;J`sXwFU(hfQC7PBsn4x3R+{;|eG#=8nl=TtkO zr!}h&nAB`ZZMp~_p3Z3|lf_Nm`$}MbB1Z7$sduSbfF?1l26IT65yf^gI2r;3e1)q7 z1EeT?swH5wJ16U~FgVrBeL}_{f}&D-Z$ct`xPS zoMeNh!Sg_X1Lw|uTKdIdK@(jT!&3D$z_H<(EO{FNZbMdG>W7SojWP9V@nk1~%d$4D z2-B?93^Nys!UN${O+7}kLgj4*enFZ@O1ODuv9#cDCz%uQ>vqx60XvysX_qx~2Mbuw zDaw#kx3z=ohDan=10{uT_6s%~Fn9}2NE??uDW*OvmE6|`z;f(s+`bSa0k7{qx)*Rv zyxptp<;CWJcQ5Hn8?`z=2R~lbG%t-i_{KlRSm`^I7eVsn^KAzDsfOS(2%T&A8Xq!W zcX^VR%qO?gboyxnl-Y8AmBo^72$;tw12R}#`*)0=8sJj(Lr6?+qaxA1V9`+2izN+*6^>MrBmHVk_Vd-J!m%Gd2G#)k8D05;^{5)N%*^7 z$JP+;*36^&LNrhaiX`7};sucBwh^e(x(#y#a{yp&ZyW6q^sD1Ge{oWyLws$phVS?`w+Ad%C#ee1>e8n7ST<7H&FjKVf(lWNw zQzHW(4}VAKy~|) zmEGl?iwX#=`X0Wu{dEPI)rfMO1_hNwSyc{I3 zkisKoSAsu@XYwhCLMnN*8Oq&2Uk!K%eH;73N3-{+bMI0dvnyo48PF zJHXT`4EXkXg=`O90J`+Tco3?Robt!D`xf0k>xBZjX`$br=kU*e&g_l|1kq251eKFZVDWfmVOK-PtY08;7n`6SH<$9%;D6uOz zY03AYLI@|T`&LmK^B_eU!(e=xzw&hT`UtKIy62~$0>)kx8Ggxyp z4;0Ck>08XfnzXc~<^-r*1yXGSG9~S^Gr$HhOi4DQ6zv@FIRG??ASXP?SVXA420$Nn zQEXeFB8D6@XC5FzihWyXND{@SvkLB41fT4T@#eqKQtA-K_G7^?MqU;hr@t1L+NIxq z;u)4XL&OrMF`3^~U%A4#n3IqfIr#h-`>0Icloa3nE)AuDwS5--)7yyDph-v(K(0#1 zZ_wmB%j%5*0JhR<(AZaiy$=D?2FTb*vB&7bPN!2B|2*^#R=;2_YeDt%R zGJzUNRlhlk@r7>V1BsM!)A7DPLRs%t`VtS$@1QvjD>E1H&{G1g!8FJrmwd|sqDMf3PFit)> zM%}fpx@&?on-$7+7OD>?pZ6X4+V7AaJELN?b_oF07E^do1v0>Jpri*U~2R5t{qp0`nyr^)Byl}3~lE7KG@*C>~bDEIZ6 z!Wq`jtd%;yf;CsHb&ySrS%qO?eq+*<@+jp)Rm$Q*W+KS!WCdb-EIBe<)tBH}Ox#8{ z{E>CRh|hR~H9PP64A8L%&HNRlC3fJ;SdG*cNSCf|u#gL3fTdQeZtzg~6nUla9X@v{ z26W`figaFmHn@i@l>^eIQ{*P{2KTdttWtjisHZg9oL_gQ!q|1riR- zal?+S%A?|;_!QNB2Iam&R}7G8F@TW@U^)tV%&TB=U(!fV(=dQJ$>XnpzT6lMWbj=e zGegoT4UuGI0oLiHI;af@Nf})ZF;%@yi|~Hv)G{1lKWyDI?2CM;IZBD{Vl`oHo{fZoK)I6M4My3nOu*klN&%KRvk7|Mi zT(FnULQCxy)H2hbpS(_g&N;iFYgeY*3HdYLnH1c)HK6J~-N_9S!|X#MnUj(n^l1_X z6v@g0ZirzGWYPS5|Agn_G~3cb7NE{h19{FDki;6vzOuj;UIQr|70~*A`oBZAi*s}y zs+cuKe-~lDwc5kpCg3ArHY<5{MW8~jlN##NVv5R&XUYQPP#hL8Q%ikYDOm%&Ne)M3 zL@odD#DnGmil&-DV_wCEdhYuj$pVb3W3ey=P&_>MjIB2FB{x+IJNVM7^TViqQn&!V zj-rWYjdfuk{v_LU#=xhpe@jX7Ztz)F2lj8om+qfwHb>dOPY??Byoue z92R#h7JT|iQp>FblL~60Z)(0XE6*0hf;qG=eBmIkRzhmK(oix zhtc~9dh-U9Ygzq*vs~)E0M(|gNW&B_JQUYb?8W7jTG(={|9lwF2-7p!A<52-Nq%FS zQ^@5-ZF7o}JV=R9_{UnI)Q<95&{2D8?)*!TR0_vgAU=8$XI6d|$)mF<{Bp3BbYvGya^y*xRXDG~(y7ty*K)`B7>QjR_UJZ1L)#LWK zyITJCD1ACv$AQ8(U>A_y@wJDdLLi^_0G~sZxIQic#NF*y7X(S~Y9d?MTuL1OwB6Rd zgKeP{&45zSYguoq*j6RKwYS1r!K0>R6**HUx!0zZ50;(%AFvlk@vQ!15%|)t`kqdU z?ScG~084#>xQw!a5B=q{ir5|cemUM36Nc(eIzqmMLlij{r=6X)s0PJyC%SQ!Y=7AL z72hrc-fjP;ai_Us!j|T${EmY>KVNO$4&KzB7F$YF`D_1hRj;XVdPrs8vj2wSGBa^3 zzR3we{Irl&okzJpbMSQ?{VB!I>=wyyNcb3aEC&u#&L<8UKtJBvW|J|xixl@nz zLH#~0hKYeH8e0P^uSgNPtXh>CUnxbO7jN_uZ+dO0)GT4cyh`D#w0;Ph3cKHA*9pGY zrZX2Gn-?)zqSt6su8oH*R>U)5>tJ}CE)Ue1*MUzuQ~X=YRvV!La!VU)G-SzKH$~gytQ4A zZVE5#V^pi1C=~2_mhyPhBDC0P9}<#^*mo_DyWZbI`E4M~=Cc2DE<-oz_JgJidhx3f z3;VhHE2mb?E7wtH&lz7iyjqXGm=*QpY_E%=@HEMGOGY>zdR`Zn*s*n%O5fJ#X{q@b zca!iZFC=OvpGXa0o`AjZ7r&=^pl+Ve=0`&&jUOW($L%k~^9+aqJ!KIx~ z4V1Fq>0dtXZ{a=etlI`HN~$HfbeoB0@0xFVmdEO@h~5AroEStX-NdR;$+aV1zS^YG zN!6R-xtU8znv%wMq(J{%RwOFBcbF!%M^E#$co2fwPMB6_q#Q-i> z^=dAqrTvoIn$BYr)3)B_6?C-WcpUn9@rkl`+4EA%7^c+Q+6nu`CO5R{a$}~Pa27zy zq_lSmTVCQ@)PgEuEFNg+`_Yj&i*yJ|77!`+_NLpu755!+XerKo~*bqoZ%dq&;Xe=<&O@jw2Z$mNOSS;G?rym@5?yF0l)gCp60&I^s(%6L94%u zYk_*wrQkr30uOh|ooI2j5vjaM^${ev!d4w+l#$t7YFHtXxKAQvsJ*M>Rv#8{smkr| z0ga0U9Fa!k7@ftF8OB`KH*&^%XH!pm5L=nDPE^L7t8L9Z1^v|;j&hSk@{hk(W(*Hv zKC1h330A2Yv~nU;#*}FtWIfjhrT(*P!>BZN-F5Y{<%5@= z#02jF_6PG_OoGj$82`-d#kddZq4)?^Y7z69;9S$i_{P$)9t|@M(}o6x@{yxerUD}B zhEncWhL2fUpWY2$jkfl1OIcI38B@{N?|k%Y4TDSp8bG=?TqS3*-T~mZ7<9RrT+M)I zIjyCs+|kqOwpRPjP`9l5`l5KRH9{23nisObSyR>yviwv^4~a+?4uyP8Qy+R!EJ_8y zx$hSbmiCW`ge+J`Ls?u$2K53~B+wh5Qn5 zFqEs5IF-w_ydp^`q?$C0x&SXfBj{*kv(4|tlR3y?kDP)D1@F5*c^Ob$0sBweX#u)q zjy|A`#&*uYgd#h`b%Y`x&kVl}9St`VvArff_+(wXEcSimA2#@U*!*geNDTHN4e8My zo-7h3#hxr28F$W1Br@t;@_L-6GL$=Hg){tPMEl;aPmcyxuV;f%BpUkqLWS~|#kB)B z*Wf3-5TV3Q5=1y|_l3S__s@R@UvfV(VBER?k*=SrRZn_EuIE(H#G=(s^ndkz4FC5l z0U=?ICLZA|_yh23aP*I*Tj&3s{OZf5i4@_v5Ylq3&w*SmL`V+=UA#||l47u3N8i6T z&4oCR03k{H_W{t>RGV@f6Y=Q27)ZRIGi#cRT3(USYsKLaJ}mZ~12U&^fK>>dCbv8& z9brCT1IghkFCP>>ZRrGrh9&D(LtxPfls!bHnbd;d*OrMC_O8hbA zk7$a=emn+J(o&bZ1~gQxn1e>mRSP;(v85bwK<5emFyg6y!JEZEYK8ZP+=c75cF3a9 z0p2*d3x=Yt_x5)yV9)6Ao9wsm!+yN~4XVTG^MO_ zY5C@qCo4J1p=IAnW47u57S87n9jDnWiK~F0*BMq9)v6Ll!GJR(5aku|SpPs#v7;5q z^UL`h+^j+P2Pw&V?&3_rTXN{c5%_oUg1R_F&^I}`l+kDg!ZoY_oe*_y>y3BA)C3qE zz^tn&b%JB|*vduMmORv(7mtW358j}@snV_UW(&bmguepP_|%!DQZ1OG4(rTbLE5rO z##Uy4OX}pe+-%V+6xms*B7xPUL7 z^AR%v-j8?o?vQbd+nH;ottGG3Oie9Mzia>Pd;8n1Um!ilz%O;BJ zQRovdU%&v{%G+zvnZOi%e4q!y(^&)Jt*pDBR2|esQ7nm;C)R)BNg>;XPfKK&hYPrz zL{vgWXLH~LB}otGw0ZSeUZQ}IBtR=`M%5s<%Vv7*LcDrj*(6UD0I?OCpF>N>7`|0V zedSsCkXuF08?G}?;^L{|a>j)CdQF*k3kyQUcCav~%u4>v`WU!5VCuP zr-t(&dwC9&9!9$2#=0p3#F~esc(XVm$brEv12TTOqS*l^@)B>X%};l|*Qk#RzwUyM z_WG7h@US|UE>yIC81C|2Vps~8S!?$;Jr^;+cdwiW?RSv=EUNBRs<)uJUpQQAg~1ow zWF1g4S5c1i<@Rc!7^A9rZXbhqrhGFVM4al7qrJkx`%H`fi-zY8^nC zhG%%O_DCj+clHP-vbrs-vXGrM2blIyU;K_u8`MNZu?OiEl)Ji3+bOkTwi%v8L-wFL z3OXeB9s!f0+3(5jU#G}|pJ!}F3k;dcT>YHIQ@S4Bm8)EM`HXSj8o$PGn*a1ejVM)Z z6S;ULS2=O`7(*O+Hw;R}RORGijHQf7w()ZI$=V4(|%GBRjIm4$`8`YYBbK_s0h}#Q0?UrynSFueI z+$f%DVZCf!VInjgmiCM)b$M@0Coj>-e!D^(eg;)=7h~y?X!P^m;=PmN3b3r;kSW!>ifFI*`h>{1jDHO51@Ana8Wb@iEv z*p|H6O^<#Q!Y~6sF}4=-+4Qy?yyrs57FhwFTK?D|{TgaCk@#1!oRy-vDTHcZA6@*~ z&7!yvuYYfxPv%!{pDixHj>;hVs|zYy<0=&uoYGfFV#~STNuqu9TnOJUKj|9KCCL8HJv1{}jGEy@ z1kv~5Hz4mV~na82zQk8Z$Z6zRvthK(L(n9#n z`)6e?v&*RL1BCz-!X+8s7=Pca6A|SmhP>J!PKp}nf4Q2LH2IeFL@C?F0Kc(JQpoW) z#89uktF@7$s)djl0jZY?Wt1VrtFH!aO3ecwGWhWzm3e{GWz<0~495dMuz{%~QR^Xw zw(X0CO^Y#)(DMgx6y+csqG?k^!?Ed-FwlEu1*r2VLOFxHT@4hjGZe9SFr#j^Jp^r% zDvNnzjZToxGEdsxUc$ia*FtOumu)=W@(QZqINcd2gpJU?sYn3(0(A;iheMUxB<)zE zj(CmKfn4qk{s0o+F>6v~rq_=G)OW|E?ycmnY(nNZP6Fd+0o1&DPcRGIg`_z zl=-i^@Sc205S!3G?k6Ot12K&<7veI`%uAHdev%TM9TWbftb(gEtTj9^B@5tvxM{(Ey zvtWq|bsa&Cdg$DKySd{n+CRC6%IP-;fTcYJ*<1bO40`?0jlK z!5ldcJIha`~UkR)QF=U=3@;SSxNkQJcmDw;2t*<9v?*UESq;5{JR*O)tmYme0 zxhM)v4252hb7-xaYmL|M8oR^Gaj=hy%cNO%!??;l$9sFehc${hDCHiI7?MpGFRB9g zfN$9IKfLU`w_(c+5=tPU)XKctYAm`h3js$gKp)P!4&I~>s`J3-A6nl?Fuw=E_G=`W zhlS!1VCA}g8E5K)@lfNHC0j02uND75_MzcUkX$=1>7RRuyGp=0(Znp{o6rZf%w&Zv zs=eIcI#5j|gf;J2PA=|!LpW+B$i!}WCD0inHr-!cwg^&fQC;p=hEP=J8T`ilOhTt+ zaKp~)|`7~+y~t~4ejAZ0+dsTJD_QwgXIJ!H|*P8P+}zj z4kY^gv-27f9Y7I5BxNz4kMConAj&xmxj|!bf8U;~zKuL21s||Z09XePh9R(^cDl?( zH`T%90ZutwhJZvW^NgcU=#cWY)ltQH2Fe|zR$Qcr^5GkS`b?$hJtBSlJ26@FUMQ(G z<$CFIHLhtjC6u&w=Ii|+w#l|?QLzleu8?cjET|Ews~Ty$Sz%eI4ThZa-eJk;{2f8L z!G)C4FW3c8(L4~<&XCz%KdfDhhuym*XKcCBKQf;z1OY6tu~zpcSMfrPl?E$43;``T zKo2BKWT@-rzM~wP7J?H+--&1!Rj+b2ygkf@0;?HFww9LWU0TgY5k?tfB=LIg5(lVPPmq= z1lRQ+NddwEqNr?d>r3C;Ikhco?8vY39q+tF%>ObA+_2Ed_~KdKTw4beTxQ6f5sq3p zO-zg_)vi%UuyRQM_;caSm%d!*t~{t&Y!Eyd#v&-PDT0Fg3`OUP%Q>Pg6&dEpLGy2< zO=5pjz+#lY(2WGRha{KSWC`)`aq#Zr{9Uq8KB<0}9L5rB_vNm)fQoi`D;rNcV3)>a zPWAtOCaQ@6v=TFJYH`12s&=X;$d8`iJ`|mT3L^)el721~4v#HE6O<**Px=)h{pw1T zGlNmsDhi)K6o5z!j(laN`u^FraYZlll(@FfneWMilJh|?WG3CkF2@cf8s~l|qv<%* zN^+cmt5NVsu+*!RtFfYWB;hFX&xgWMAIj~xz0w2*66iqdo%M@R#)j--S3W^hmq>F& zyZo@h_iKhnpqMG*6klO9b;ZQa?__A5X6%0Pqs;zG)I3Apc`wIF$(Tr8XehDZ`Kp=& z7Zk{#Uq0nU(|oG^?I0$ZH+ck)fba`LhD6<8D(3T7P2GD8hc-#dgT|+8zcJp zk4S{Ae(b)XB_a001=Dm4SQF5GrWy;90{9vLM1==Vr&L*SnKGHCFpvB8$g?3fIoUbs z#$>oPku1`Vvo0B@vz`p@m1zZMI5(=Nj=cDgsnp(4)Is4%Q^Kd1bTZ`R7M}_E>8lO9 z=TBUl8vO{e?3SAh;v749gIO)HY!+xMa32qNNRn4=8Y~2mRdOzmXobNy7vqu=Nrd zHoc#MASDdK{u{Wfx@&AP$A2pwZlDKW?q5=8y%^5Bt~fq4^G!*O&M+3ZBVb|jHILt zkejfp>^y(QfOg-B^2G65>Xzz;@xGkYfB}T4y9>2}PHP8pYk#w6FUu8}8R4ztI^C19 z@_8nUNVYdf<{D0+g6i=g25*msW65n5L9X9bb|#j$q&=!p4;iV6yAG(^Cf$7|X*0hc z*a6Bpv8DD}X_a=_OZxAn$>qh z6c$?jCK|4Dshz=20nR|H5me@v7AZU)y^C$~mz11ZZ3Uq_mb`OGY(@6%G}ydixp1rh z%Wka`#fQ52A>lVoCN8~kdpf>mpWf)Sl1$Ts}JUd=6ReergUQ?ruy-QBu)lgUku zE2pF&0Pb-um+#Y+N14wGzb-y*2ThmMC=y$pf?rKa9HvJF&H@u(TC=e_tG#Zz^@PTf zu^^8L)~*Q+UW@{a_Xdq8rl-dMEJI#}T+I9w6-WT4m~gDPI{yGPfra&9lia1Mu@{;2 zwMB~6wg#zP>@wDRzrWKHp_03IX3Mk_Rk|c#B0rj6&ArJ})%zI)8kT-<+EvZ2ye)%LlV#6j+Hyn7ul1reYdlEnRh*IKZyI(X!vq=hoiR&-Rv%@7Kki zw0}vHnm#hj)ZM2W4WP7^_xtregn`F&izks;x_fjZHtA|CB}2a@zsf>3v-)6wnGr%^ z!|W5*)0Ddj;B2Y4#Z_4n&z98&bU!v7uq#(1t1=Bf#Q6^B0B*MZ$NR;3X4;6Ym%@hC zZe&LpaM3Mh@0c$5uSD_s)9KuQd{O3e9e9TKY3a8yt(LevTje`V zFJHNZmlC`=kFmwnljhj=10HRthQ?`ea*&UG#HB?_y2F(NKq3nuEak$YZ7 z(0jwYBZrmi2^LJyc!ihDysr!E_N~BO0<+!zgkOJuS+uEMC?crAc4r4>eBrs@ZE;h+ zbGu;!?D!Dz-QtF^tgPO@FzX9Fm$NENkopTP>ji`ianrLqvu+o52(Avz*A{Q9`}5=h zw`qF>b6=Z-ueFc%o;>qNx8>D+RW~8v?L2o^fIy^7*ACtHoeFz)uqDB1&nIs3QUJa+@cXYX(kh$J4@;tHOZ4yvLt3+W%pN1M539s(XwC)+0cUP+DC z51*zSRI_^r)W7@fiFx`j{^_F;TCvqGB1w5A``l0$$?@6jKA^~7AciyVaO zfB%lqBzqX#&C^hI6|-W8{T1NtAl%7UryhWk4_OQ636)3C=eNmxSIe1I255F>VsLD zLkfB!8_@-B2mWW|Ktih0+q2cY@M|d=-g8I=QwrD(mQ~4AbEWL+? zX{>m2w=>*5L+rTSk67?^oHTqBhBU0P2dxYcb}otDL-E#| zZ3=-h!Kpi@o6&pxpVYJ;u!)H7|l<4sXJ=Xh60q zoK3W2tyW*#`Q{d#QR)5rmfgzrk}b4U0gF+XGvPGu8Er&~v1Vu%`{KqrC`}~MxR6n}xr*|m>LeA4B*Fs7dxV9X+OLILJv9bg zBe9l_N*QLDcqKj`gAxV(dE=s565b0`BsSitrbkRE?K9pcZbg-JO*iQRf1Myz$64Cy zRqlBvt|F`WYjLL)E~WSr)1WDA_0ObRWJK-Xfx)C985~0hzz#PGuR#uDnH>jq)X>Oz z-c71k%IzrzZhaxKhqfZ~`zpUeUkoyl3LtKFX8fYpaeeieNkQIjImjVX^Tm*%z7jXSDAsOM@k*JuIbVUG5OXbu@#n{_GoSNinEi~oX26B! zk2tvwte)BR$5Y>h9dl^dgWtTMCj*an(=V9+5G_c~hiSPy`O~GOSZUzT%cok~R zbuLYY>W}b-oF~8TeBCI=+gJGjhw}Bh{pS!vfA{G9)mh*4h5`E_=>Qap3?=Zgb$R2N z@j^K1d?avb@aOIGDEmqv_b6Ux;wmt5e5w~(&>QqZC!>b0~2}fu(mP81~PzLMIr#&Xp|k9bCDIZ!{AD&(M4tF0`hN&*IwNi;?YlH`@4r} zIcFs4pRaDo$|rMM);3tbHPYe?j&c5~{3Z0OL7qty>JtKX1N3dJ8FK-%Gj8)}2E^9j z7vkmrNBJXTNnzkXd9LAf_&9?jFDWHe1PZ1@tndIo0O|?pxPS&%K7`#RT*XQaaG?gu z?a_whjWo+m;nr6nB7Db``q*_0l6}YPfr3pAdU+HRmx8@Az!?+48!@YpOy-&)j9erC z!J=pxM40poNk2U69n$r10J3^)odV=O>8Ej4r)$R_a=$emut*WG6oV@S=07?A3?u*E zBci$(rHBpcT){W|sNEfB*Jyt(xsScQ0m5klb&AHru07uk$LvMQJ^IFkQb4?#M9dNc zqg%u4gKZlQ`8KZd;(c)4)hzRM zr;)G6c~~R4w#@3VXK?Cga({eMO!S}WwZHLWmsj&Vm+&a242wP#Ra&w~+ae@W?9p}# z&l~0E`e8duYdB3JdY{6RGcbvHVbt5M@ZRHtP(LPs;P0Pw^1(5lMRn+zWsA4!$DfH19Zr| zaR@U`=d{{Z=2cQ%T~}xXaV-NdS6vZ*hG}i+b)LK+V%`S?87p zs^2{LM3_D$bVIgehufTt`E(A$L@IO0y6v^X7uN(|tVR`y5OyxM{7t)LT(6Pbq20;q zSJV(T2ck7t(V81I1k;rhRyo82ID^O`-{#dv9qWZZ)`d6flVs;Lfl0q5FEz;46UG{6 zYBA#sF3m`Tg`u#M<}HH*TZ73jI(e&1&jdGG8>X7Xb@2{3ehiul;G~jHU#COwQd(9n zCAgXJ<|Oe8jp;WxZk|PdAc1gPAv_y+sMvz#AM4v&Ru`85W4)>$1|2_TV2p|B>fP$V z;1}v4HOL$qL{b9aLW4)sp~uWG3l_xy8IU;JUqpWk>i9M8phY$iBq?RlK|w>By;MM-L7i56>7K>i6RtdWpQid zTq?)OBs`}oxAjqs^uUx=WTd~m-KPslv8s7LxQUlK%~KROWJH@-+|^;tJM`O82m ziUhOXHTDJ(yc#9<>%vrE(wRibcQi>EN3++pA>xlhy!`Z!=;-R5N0P3QrA=YFucHtt zp*|v}%M=cN^~cG@irE32 zdGBg7$w2?8NAEB&SRk8bcf~$LU)K+(k>-^Gr%QB+k6j#>?XJbm|1I{J8fr+ z9jC!_7&iSh^bfjW@fgOw$8G~aG7d=B08^h0r$lJmEXE;i0=B(O-J(Z~NvST$ZpMs9 zK0nMbtprv;pjq{BZg5W`vxXlmjxM4gnoW~o=DzWASAn}ZUnTsDXP8hXf=RwV!J`#7 zHD&L{&C>n-pk$xX^9io#YTl6BA^@BS;5UOUWH83tJ*IwAqg{fJlEe|M#&&j9}fTkv481oEDX#M1rb7rkNah; zr9ZqjP!dKAm{_|SvdTj`!+QpPKH{bvWff^Y&>9x2BwQXy&JYXX$xkRjQw9Rb-I>~c zsokQocZ|KCk~qD9+{qc4c0gnn1$B&P`%AzA2I{`+V6BpPY={*cHC$dEqIRp?2{q_( zQl`~!8N#3!an-A)+~W+9=ZJvZ=<>Rkfd3SeGo#^lN>rTApHn`_DO<=^cE|g)h#R-D z`x_7U>#y7lfX%P*KH$}C0?^Gs)!+8!ghTq1CyWDacsP8NCx_Y?VxEHamVIA2)j)&=SmWL#9f&!5<23pOtsVzp&&KV=C)Gy-d74u=E_S&DvsnLr1I?mnQ=B@IMbHP0 zy;dogSfWZI8;wO$FD>CiToj^yPnkS88ej4eBml!dL2Qx<<~g;}QnYM*v*= zR>(5QpwT>ZGVoSzqb}SJ(IFXmwO2Cm?^uPqe%=7je-|-!ME&E!vCD~(4+WF<(lk5$ zxfCB^%!y-NCKGy(E+!+V@>jVovT!PsIhHFWel--TBO(G;wPgcDYS&L4wmx=mPn^4> zYwk)`Ofovyt}YhHl`bhsCUbt;{1|da%2jnP5oK&YQH9*a%rH1AUvR&i1wWM6wlFbp zuHhduVT4a}Wvt%3bGX7B6h9)cMn?;tvHO~{>bf|;sHik>+|K*cYa#=vY;K~3{kJ9D zG2?`z(EL@#q9Kt&l-RACcrfpmAQStOWq{MP0xFzX(a6O>r zN$4sLAaein;3QXlRN3Cx^N@+N+1jbA9Df&aD>^)S=}TP^iK;Q2?eH=FC>?>y_vl9esgQvrQ-TUwTAFe(RQxwS_G#UBP z`Q6{=KqFgYW}Rz~emy(HAjM8q4<@vFb*=>@zirOL6^*ucj`-mB=h`YyTEu|s`e5iC z4vYV0$Li_Aa*%g~O$F<9->whj>yNKEzK^TD;?o2w%#~11mxrDp-8nwKPyRGdK__SF z{yUrnic$zkeb@N@YACM``1Yjsm3NrGY6J8ous6FE`VHm^!h}(j>@u3-!;DoHs64$H zFl=$Sc5+XyPC2RcU;_~zg}*JQncB;wfq7d1bf2pZ5__)7etmZL9XA(B1B6iowzo9Om+bZ#AGde@;$uUBQK#dn#3Q))(tXfq2m zwRJ(t%Zo_9Q5@)blxcf;;#Pa8kWx1gb;TrgBVzt zXH1iaZ)RXGE@Ug0ZUBp&2Wl+q&Dz-|Yy^to{vOI6d$d&cLCN5Q&V&KG#i5YJTx$2l?t0+vLwbCJOLit`^zv`%aQd1u=T z6}rJ43o=m+vs8RNm|kTMZ21_LeKaT+raaid0vEXGWjv)~{8{S~U4eDvqhxTi%4FDD zyXz}^2bP{D7g$LHtKcJH|G;#GNt~orZ26BS6<{Y>X}tfFAFEnx!JKvd28J(3%6#jt zIFB~GP^KG>Xos5h;W#s}ntxkOX7$u{Cfi~Zb0tj%a{ORUoFBS&A3pnKvtuqaIR|Z5 zYjH0(8|X0}wM1R0G2yrZH2x$Mdq7TieYO`_rZ{5HOUZ{+^*&Omy*ry}xtcU`Gu}1b z)}f;!s4!iHZqNNbM`hGS*1Ud#1Tyyan1ZbjYrJ3O9(n8DW92IIjD~)>fKvSXksZFh=MjY+=ELE`jY|r1X z(a?J;--NpPY@|Y3iJ2-kI&7ss{S=@1;V*!~< z7FX+JRaj75pa(WaYQqO*TF+(s_WB_uwsQp%DIg&*9cDOQggwG{VKeVti`7XJ0@U2! z;vP=)9dI$fCN}uGcT4=-mBN2v(zVSFskm!pLn_Hf5TQ@!(3EiyIXpQXFg&f%(=d{j z0KDNjGnmOlKzsR*SXJSJzP@B<-Zy?GbM`H~!`f6q(RLn}ldE>YZFd|_r}?AY4~S7u z+W6bGHTmJ888XQ@9tmwNap`-OXIrjV+wVE!^qL3I#o=bEJt;_!gMIZaBHL+ZMN4yK zfcsg4?Ul-p{JFDds0vwm3U(>kglG{!F@9YMuyx7-^E_&0C?i^bAWa9q$=eCX%6}L! z$WVDe4iJR!#o{K_%;aw^d-`1B_sdpaAv!^cnTnsFoK{IzGInoMeT&2k^Z>?413t5+ z9AcVvYZ{LyqlggQngU>uU`aTRF9}-OuUDLKayvFk@}P7loQaHY&4?Tgnr_`NsP{|U z>j!^U9f?UHuu&U+%$&VB3kH$r9Y8b|I@B;j{Ur1Bq=}Fh*>JHH%JWn^P38E$Btht{eXN;zLa-S85>Yyr)4e<=;TRBna!ia{S!a2oRaU*o#o~Zepn&9XTyzh z-XNnRItnk9ZFl4hH=cEN$f&yMm%aT!q^6xTO-zl*`f8Ibme}*2@P)%B$=ksT`P4c( zh-mId5k>oso6HscwC-b#GUh^9h3b;q?gEE+I+Z1Sm9D(;@ZqwW88+b!Tdq0?iY;?f zSvk_@$#K;#Ib-^7Bmi5Rz4vdIx3mXTRD^pW@g2;?t&?_Y@xakux+ckRDG9@nc`3w2 zgaZp$c<$n<;>?$2GwEbP79FfWaAmbQv9Dlnlmm;9h)CC-WUgX>k065%BNB}3=FVyd zsN^zF+cb*J(>IfaH{%*V@u@5wfFvlz%#C^*OAr9A*RVdZe=DslIX=l3P>l0lZfcw;)(LC(_Oae^ zJK9y7TlM2CyK4$Cm3+%vG%4Cw&aQlrl5PEb038Pq4i0S30-y%50uhU2HnnTiVVsDG zBWnyx4ODxh=D`HAwoHkiXOL=&TZ=LoOlGh8>+(R2S>?UtV_D(U3}ibKn1NoGpz+OX z7rPM=kHg6**AO7r1h(|#0^5;H9m1b8ruDP=F`dqwXwztmrOy{Rt2$~bN0{>HHJislBReHLgY*=k zJdt#~G!P-8u|NnDh07c-L;EqYnDN~G==!IxHMN&ffrNe1dBoDk(IlS661NLZ-DN@A zD#kz7X~WCg#NY3+3R^)ie>t_A@g?29Bh&)b<^$558b*g+2k=vue4-<5pd{w-G_5Om_rq)>Vtc+at z&3R*<_1|Vvn3HZq){@}Ivk#xVdT{OACv2+7&l;-00!_969}xF&YCV;q5t|Q}PVWSc z@cJ}!QN4E0MSl@e^b3TAr*ST5S(mA(nxeGDe^woUV_Pph@DafIynd>w*u4E9<+7C_ z%9esK$x>{SdFH*2}lz*=2+t=n_y}Q0_f0nNQhwFT3AP_K{ zDH`$=ef1YIjJ*;(`Gt~VBz+B=H8rp*b^DkIA7raM+4%??SR_jGU&)Szc)c>@>-y6F zGk@UUzJNcURD$g151iKyU%tmFN^)9AUcSDW@}1 z$AK{G@l@Lk!B9Lb`~YHuhs2U#JZi8QCQ_vg^U{VzD#P4+sAP*YasxFM5A$lE`ohyV z0%5**$i;A27)gaaFg*^QcFrx$1BdJWegzl~OXLM#D1dpkLN3$69xP`@zhCT^1e;U9 zADq2EoCB8xWxk?jmf?IVa6UTp%+(n6?bu*PEID>2{i-y~Gd{~@JnKOajOj*t6r7|b z9cFc(%L?%E1O%sh0hbJ1V4_fH zyHN0cVJQI-Qvi+BKrrS`C61g@yBX6B;P@?~*xo84{xdDsoW0oDJ$}UXd>pT(RN^6x_X@t@k%hJfptjUb@XK_qZ((YR{!aE#cL6afE%@il^vEC*}V?;3)9v%*g~*Gz%SeDR-32uaRzFV?Zq!XE!dGZduYG7f)#5EOC%-{@3x_0(?{t5;zC| zPYM^mCgS+$J1?xUhMymPWk%tuJ-l7SxQwY4`<-(x${*jx&z^e3p6_rcY>U8+&o#yf*)1$=&nt|nYROHHjdQd0A8nA zo!A@hvAZc=xrI$^g?xr;#1qO)IRRzoK}2QPmWiN~N8BZkIJJ9@69=p@2LX}G*FQhH z_n_4A-_PsyTL?`2xhqx;RMsoahma@r;P7zMgi=@!zJa<^|4{0>R1p+~OZxKB@o?;Z zRRZcE;T)ZCz3aT;RoVM#<&KY&Ng@!`1TEp-&dK%m*Vj45g(Qv7$Id{L0rwv#*EhyB z0*)_F*hd2C@G?^Kzr$0cBfP+XaIv#UJ&hDfI%l#P4*Xhl(#AJWMEKfAn6xYFyFZwa z6F$$O~o!*9p*NVU}Rp1&d zV2;{^Zi6uZ+_00cJHWl|uJMeT2V>{d9t&$EjjtxDRUp_pj*Kd`&#`1cFXM67%V0+A z{uLU^2ga!40w_`xxkqeUT{eHt&p|nWlmdt`k*$O+HGnbKFpZU|;U&#T_6@hecZGV@ zSmQ`?T;I9Tdi<{6RbCP=09#p`7$*?u*AatvhmdRGs0wzS>rdOb*ipXcZ$QBsoaq50Af!j*~U2`T$bCDjU^w8c0C8QNT7# zo^LnQGQhJFiy|36`OeQ#brAcD-K52u%jh?sqPw67{6dDDc}sBYJ!65+R_A0AGEdB? zMnz}XTDO~C5FCzBobXWnCa5sP0c143C0XzTZz#LF@5ixTo`D3>J%6nh#aQ?LW0$BP z$^{*CD|PYxZEOCCyaBjz@?`kVQxea4kJ=t5?jDCZH{-XE;)1qwi@l@{k$MuR<+m$I z1n6Lz7ymbqCLOG#Daew@&D{n?&OMcU&h9+h6G|JDdp;2BBG7gyeL)Z(b2-8|x1AVsTK{EV$ZxI8?Pe7%(LD#`7Vk zQ->cHs-aenvUkE$M}(Rao_0SSqKw0e#A|;OCXLsei7c$wBcw-n3OKRn@4VepMM_mXX(rF&* zxiTf8KjbUY8QO}F`^>MOacUVEs1hB9uP)Yx5OaUaIv9s;l3p#za*d#gZ3;g0a+jp;*N2P%Z!39wBE%|s2(Ktaa zJkae$EbLXS?8AUDc8>8W{@LIaksd+7mm$H+X)`}K1zs$VNRv${UfgEDH&=tEf+;7L z3#Gu31zend(<~wUeKXJuQR7Dnf{iq2TFNqa%`!7#g}N51p!-mwYGh+==V_P=SG zvVz=TuY&%Nr-R@#iRm~E6=BQ_UqnwS!0*h6;!4y)fH-#Edohrm%jAL*4c{H1CghBy ztMv-kZ(tWXbmo&fS@m0TS5CD7=^_!Vp5d^Y4({IGA6^`;oL86`FXSj6`B2w3tyxG| z(N7$50VmVBTuq;2S;T1m-0t5Y&97e3QkJEYpwF)?-TCLM6#_ebl%6Dwd^Y$|QeS}1 zfW{Jp0td%i{_=^4Aj2up`h!s~A*&qBM*ShHxBS@(ACDG!O>R}za6-ndxfABA?32*B z^@Y$y7IvZi)5zokXpXw2w-1kN*d5@??yk!FniicNmKVWu?_Ux%Bv+wFdYqJdJv{f$ z_q|6_%uqoDUJjPIZ!51N?{4|-Kwp%C%vupK?6azQ+8*=RqXq= z6x<>l^7&V~#=p12Q&_7ASmcZdKk}`lK7Y;kwg3w3@36h%!WTRFnRfh+QHNd)S{|B@ zMMw0kR0_Tlu&@?OIKc0M4&B_Y!s=VOE_h2g=QW@0SJ|)%|2!bI=?$wKvIY;lZmDQy zA%B)`uk7V|9qZ_#|9jJLL>O}jNu=?uhQ1A3cnoB~u54ckcLIx6o~WN#PXrIn{Uf8o zu-b{)`%ijJAc$o*o9%&Ch)u!j$uVync8Kizkj(_e+AVstK7aNKM;|?^-k$dwRI(1k zv3_(vlE6G>EOn!n!jMZIu3GvGGS+qexN-UjO#xXHOd~%s&cMs--|KOBGxvwl~^;j8o#0+<-OO%#@>j7Wn`i9WCuQ zcx|?w+Ei+m4VL?{7SH~AEbo+A-UhrqK*_)5h}QOXa>*=N*tUAltz*lgQYYdK2T#tK zQUX2Mp;)H~KjCXxqG;<;aNqHkzFy3>>GM0M^Q;8^V=d_1HGW7gjosv@izyJV{RJEi z!Dim-#Rpk}p*Q8{(=JbJeTJZx<^h9e-|@vCZIg#HIj@83tX?>H#XZ)26&(9zvAx6^ z${7vAo|?IQz?fM7=nU}kkbAh;l%S#LSGv%{aq~&D>*C`WrM;kRH;VoRJ0UUc*hgV2 zO;-?NTRShxX~Q9rw%7h@pY{ZT!~AN^3*?h{sYzCDC+@h`s#9`n@)P}icE_huG#=GL z^A*oIZ&H&!cc1^7r8EC$!+Ej|xY0nwJ z$V6dro>uBp-98}*XxCtvb&kkG^^o!IvT|MX0zlrI2C8vAeS>GB64&yxZ;E80_^F6thzaAN7cHQ>WGGFM?(dl6iPld7o0(l+d z^DSFTmWgArk=|BC|Px5x-OVmYB0MOav8##l>ynxBgo6EtZ>Xb#~D;DdjB-? z$Z+s4CWY(H%=rFgjTs6mtVAv6<9;`__?QID4PkznF1-qtLORfu%ztI$Q+zjfNu)M( zh?j<@2-HB_U~gVGRnBQg2?OZ>p^dhNidH48-%sC6L~rEfMiSjE1p5MNHqYOlzh`z+ zHoLCq6HRR1nWye*odhNNy2>bzcK>*ah4%v|{;uQpqbVhnUgJW)Pu^<5n28>TERMV! ztB31;7np~8vMZV9_&GzTE>EXuK=0DYwshbpqe1ui@BrJ_C`Rz8fR?KKH;ccUxJkMC z$}$Z~+X`+n_waAji~_Gv^qdZFU*ya0{Q;cMtWV+>lZVx_14mz0xJ^9#>fA2l`uNpc zPd&eHMnuo5o%bcbqJeYhd}{fhu&1@9{rf6><^TQm506;Kka7zD{ONXG*nOn(P|Ha4 zb6!MeZez}`;QeYAY2p3qtw$&St-bE{ZSV*8`eU>${Dn)BQUo^u1g+;u=rCmxNa&aj zdO^lOQ&R*O;Y6LYSWKKn3bVHl(K=X7#-)-F0@}u0cV^IX0jrRAGijPVWV_%c7S8U2 z25y%Es@}#bl6Pt7)KLLClw@+kp4*cq+JZ$|HKd?&$I~=cYIu!mMY$_t&Ex~yF7QU) z%&!c%HIA~)b`|uPElA6Dq5(6_LqLK&4XLMgTGI_|YFIy(4e7eHVqzOWu%{H5-qI@O zG5~#QpOBd#Gc6~oQ(Bxj+8Nb1c>W=leH5M%4!t5=?4{}y9&Pi#mT6;mA%7(<5&6>-Z*7nI9J*FvKe*vsM z#`B!CGD&q}gl({*>G|d1K&`%Cwiov!xf%hfJgwLahe{T%?XzZj@7~zCHuzQ6)1(ZX zSF@rQJE{*W>kYr0T+WKtS7W=XPIY=@nockd#`56zWaJd zU^D2nQu$1Jx6|$4f+Ny|h%^zAseM1F7b{VXfo zNyzkQDJn^#flt{HOWOmeTH9|XGI`oL!DLhSKS?*eyII7hpF7`gK%{!SUrQ$djIqgd zV_q8d{$8tggsNN*(x zeZhi-2Yi8eg0fOh2`@`A*^nO6$O%smC9Da`_n1gy*wa|OMlaGe^+&&FG<+HuNembm zASgE~&TlHlxt7%Z-Il}YMh+Di@)SN={c_EKuPot<>!bDU2fRT`sXtrd3Kj)lX?QPu z5uKQOxAHDbr>e(9_4j!#vV1M3*kbhSi=QO8i5o6TdgkkLogvXiUgrAY-I(IyQa0XU z>x?X(z=N|qH8T%FXZ6eh8`z8hc&g4S(&jBsyXeoY_-kADkt$%K@1()YgpJ^g+(WrX zRNR|T4d|)2`?0Kiv1_{vFlwWH{dJ zs-r~Vxblgk!TIW_#6fDHJHP~&h#!&wi)KGyw|3bxj;eYo&-bBn4f*}vh}rWHzx9Hi zXE$7Iy6EaETI2ao?58jaJB+M^d)Y5)7t!V!z;tV{nBEQ%t*jW4mHBzo?#&wd!OI^a zxmVBGRz6wkLd7Y+bpsc}+*1TmolQ;PoMBc_VfkZolzTJT!bIll_{}QmO)pc+XaO_+ z-@TPh;qY@q$U>N12s*@2@UKf0V)6rZ<;hi~gA zh@3p6o5a*4UrNefd8evX*$;N%?RK9DflQ%eNG+v4IX^iFhd#E3@~tDl<6y}@bFa%f z5X>NL+;O?~fwr;X)xTb9dXKRct~~J11lvFlsgBk&XX|~Q*C3g@&vf7QQyjr_3`0p! zgOk(NgG_DTUdbyTu3s&bLx`a-TIgKd=Z`+KG$1QDIB`)Gar-u>KWFNpJ-vq`XQHXW zL;dHKkNKQp?{v0tiQy*wH+5r8Yx+Mn4Vqa^{>j>_5`J6#bAzrAV^zNk6y?}1$?3EU zc%UW7o9ajvTBO64w12mR)&I+UA(Z1#Fo5|Qu@rHz(~@kEsunTqhO^Yk z_2Khlf*N-3J{O9N3O3Fic%RmN#sM3ZTRJ%0VI*=!(jfmmUPuHipdKew*5aW?ZYi`5 zblIP0607K%6ihd}W`AwpGfM7~8{U$5Be{Yeyq@0wCnNKiy2VuK7%B0Vg@EVX*$jkN zLCWO`wing|P1r2%A~-W)ppG>&MCMtenie$kkt;q$ua$Kxr9AsaamOu8hFqT2t`d3x zqE5TjHjbKzN?|E%!fiZMAk(=PvY*U|D`z6Id)PG^3Yum#M%)e5L+HJDsE2ZkgK`@G zwz1*;u8dEqegcrBpw53sPgRDrPCK!awW&H5pjIcNj@qGXnOatOkP$X(@1(46m%_K} z3HPKIspAHn3r*j*LR=Z;MK!v@3lHT5D~o2-h%+pP*xOGp!pjRG|IN2Lh>v)1LiH#a z5+PYug(+wM^oWW-=H2EnTey)F4v{>ITgb>&w19wW%2EoS0rslxj#-EeE%(+4%TJ$> zJ~7>?lt&4OY60^_3(XcR)Rh8K$AUjdk8EXkG+lvc;EKF{jgW2lya?PKtHU1F5{pq! zy(-O4)jU>xTd?Y{c1e#q!dV$q$f_yLMY%hIR!Jj_gZ#(gSx-%!?t`2UMtU8)gAnEs z>VoqiS$3y9e~RvBtjaxNg<`KpQ)`M6F7L}EN64OD#2=g$Ddo(G9@G~#RuD3hjZ<=M zNYQ98Cua=bu4Mm(0AFlIC!8H#n8|ZEX0Zx48Jf>^4aep;<4!%tNePZUePXJ^^xMWk zj_$IH@U-sZ-1O9Osxs6n9Mr-7SRR;W8w9c%=Pdv|;awd}_^ap~Pjz$3`!9;Bcu;n6 z0yRl9Dg6dk4+oV_72RFnReuatpBc|5VxJWg^RcYXWhv1%mUnF?SJ?}=S@N62ZSQ54 zI?S+S#Fwwbp{@sI9qZ*=Qw1%Fxzj;;C9THjvle|gLmgV_^sd$VH{!r*21&VORnAU0 zLftq5V$_gg3)fvl>a2L-7N({d$R|y6&mEDdp>Jh5C!ctIL4;QgoaqEm#&OT*rhdS; z$MS{n|J#Ap=KKqK=DDkX?@c+!uN%4+W1AHIIrR?h8!3tzLoA!wRmxCegC6p-6*WoL z`AYu6o_=g)AqAn;BV(vq21@OHv|^E~*fYAW@9=PsbJH{>H`dwVSH z@{1g1oQDY1a0&b~=W(1kh}eL}R3NV2?Q6#=IUlp=QF5nIgd2En5)G`;07~^@7rw9Y z?CqIfc&KwYNF5HYCiUJHcWTpv+J9nxco_1};{E_g!{VkG`UMr6s&=2}YK2qW*Rfpd z!SE*djsO)flEUiH^$+Jj!cn)aO%+0{ADm=#jANmy1!dP)o_6TvJ1F0^4u`Zl7zP8! zZ|_1*ae{wV($Nn}HE82&7DEZWx_-yf?rNtUQSIb$7&=5g{T z!T^MtSqh)gMwOxZY+IQVj^mXR1v9-Cxvl{4nNJ1b*2ZRBeD-@tqz;5oAYueyJ6_3M z>;M@mV$HBfZDJV-J`fS_-M5c7}{fe$#?0`lY zXzd_F$;t{toQH^VS-*7|9eQfLN3{+D>4a1L@r6fsU(r4KHHHjS0br?fr7Y7$Oe5c! z>vopyo7F!M%})yFy}IufKt@hz;AbCV*T^Q7 zfs85^9V(XV`kF`wV9oLB!YjSOG9CGx(uVdAoLXH|fNpW#+%*SaZ2(xl&Ef%HHHico zX)1MxxIddO{mM`){-Y=~-Br!V)3Jx>fQQcAb82w!aIjBN>H%+M6j{i7J>x_uIj3lb zL)0(Kdt~Q`k`YZaPD8+K(@hW&=h>I4m$+M=_)FXMAeEqu*T+$l-Pm0m3{?M6U2z=a zeV8(VekXg7NhmtB54ZUj;=BZAJ`tE|Co#Z`U8nIqlDjafK>b3++8=dwa!D#sx1!ZR zKOCet%T+khwRQ5g$UhwN7{Zn^?QJ@ct+Z-MToShYr5(gR`;Nr1#dxGXKJ~$()FpbU z|Cp-prmpVZrODl`{F{aF$?N4+t#6;e1UUFiIMrG{=Z?i-U=yylf_QL;d1Vk{14z38 zM3`~!dHf>Lv+{nk{r3kSZf|DL-wku-y#v@&?cC%EOR035Ty7oKug%W&Giq<&rRt7@ z>?sxK)Y0RLo3kb$gW8;;VdQ8hd~4h?KjP(xywlJh+qJ=451#70@e=*c%5;ED>!2ekT5I}SHs(Fp0+Z@h#8`S`xamJ5zgO~AxyK2c zs&B8bRN|}D_(5nhMO~ZtA!&`vR6x^{#sWleN>1O^&ad2%d2)#LJy!OG1FR90*khBV zRV~$})cs$BYNHwTzaZKrT=BL3rZpS70bSNhEU8>i6*RPeCGk5Gnua~LZoSl&4>jlR z2PDW7m%#SgRJy4|$CBc2;JX{Mw?z+mE+^lcGp>KU^r}zpSw|*X{nNR)&{w*LDvdet zjuZd05nS9$;TpN0*RFl02H2^l!C`&&De4Ea_DHQH$+ix5s8vtR&ZJ>-iq~>33X{oe zB|Tf4I!F1HEj=J*McH7w<|FO*UTuTfex$y-ALJ@}*O(*KZahfN@`mX5z%so@Ri#ojN`UYuvZBJ5cu2v*ac4x}60bK4G)-iS;xie;cXHJ{t6w)k6eBDDYh3 zgnHAs(@5!W!{8)B_fMP!^KQ8xS{k!$M23Sa3p4WmvhBTSEn7fa(Fsm{W7dehP>Weq>a}UNS#|8`IYr?5F=cYk}%t` zHb7M4_TdUGFkEHz)23<=ET)GGAp6dav)n;9K$_v1ZlI!9!oslGJl_*|>XiPCWw(rT zL9kdiSPTvprJSAsLHu+p5HM16$Sxv!fwT^CbH@>%F-PL*`aZx&%mvVhb)nr)wyOPd z@&w`o1yroY-a9|zX4LsQ9G-bUEX-w+&}5oFoI>4&>{RM1pAtl{B(wZVdk6Nmp3$$xrkl|Dc9r*yc`|@2r#U_L9?=6 zuTR%FA?A78E-v$@B9t?O#$A>@7S&oXWl0)yx*`cO{Bgv=i~9NrMG9B@V@aT zPHgUQ0MP;jx_o?H>GBP&U*CF)6yhOnMwd$;4dc(lIoUP1PDX(e0IGj0NdGu@^u}df zb#@l-QeSO|>cPnEbKN1Yf1qorMelTI=;pg$CYgK8UdsJykE>d1hCO0N-Ay!Sv=r*`67t|Qv#0%RD=ZnTRs0!&Irm3 z>;*VIktsc@ZvFdh@Dw^&(6NnLcaptzO7{D*;yowb2PfD8TMOq!9?p+0`wg#gdw*`# zdSz--n5{-w=OwsK1E_yh0HBJ8mY*2ND$L)xPH7Me#}6b!cb6=+)AK8o9Q!vcBlRsWok=_jOhs*CEpE#VNPfAO2wjN?8#L+oVN(nFD+Tggb(<8rCmo=6yHY=f$m6t7Cm~>GfIT}tad#*_LqFdq)Guh15bv z#)M+VRmKG266!O>F!HT?Hw9N~ApFiCEs?5hu?iE!EC?s`*o3YV7fpQ zy@n}p7VM!2dGiUG&S|=(=Dp#zr~$eq`OV2A#3)`O;R}@?^KYspZNb9Au;V zuwZ9Wi1397gfq#a<<9=$It=l5I7^+F`@OWQcVR29{PHHF!j4q?^t58 z8DMSW#w6=SCNT@(6adkNhC5$}U3qpws_I(wjGB(QytX!nRP4dcLxo3|{HB&xb3^xg zJW8c*uaKJhy5Gg+duu7QW7nYqeWs<}(J>uW-K)U@)jez3YVUhi+f(CC11i7-!AnaM zgOytqQSUEbYPVlQ>3>LjW$o5o@SpE;yhDSn3omlP?a||!vC%Hc%A4SrGaq5 z+hkC!wak^E!k0SlTGuC-Nu{cja?{tX4dd%>y!6^05&$BD2;J1skf3-owDt#Ohfii490rC#OJ;5)j!jEf|sj`V|33)248cPE_!*qzslh{G- zHRZ6+Rxg!u4u#^2*JF$YMcJttPXLuH=&*PybFj8W)L13Uakxr(iIG+foQZZ?@!R=( z+H~O^5EHa6%9ou%=&gCdb{Rhko*Fj;rj79SOMAOn9iI9Hp$UBJF~uAcGM!SXi9VL`^p0dH2Rv1ZpT(w);qZK!EsnNM;dchF?APY*{e6DozZ~jU5JXNoi zJ#VTq5bw;3vghK|KS{YOsTC)cqhXJ^@h-7;+w|~uLgkR)RvDG!8YP|JWz7BJ{+9L! zx0a9Jp0m;8*F@MeEyB+^rT`!>A4$(r0dTRKZlD<%ZuciFvn{h~ej?dTe$Pw^cbP}>-v%ye5xHSn+= zZvYFiL#&7=E13kEaVvlOO~omOSxE%wvTLl&IR;OBmX6}}XnDZC&gIz1xAV7t@wG-= zjoshR*C`?>B5gI+U`Qd(TKBPHjwqnLA>?wl1QaM=VFM9ct$zj+ z5kF}$`LivUGfj4Z4t2(@^R`=TC4>07{q65W{*R*jil_Sj;{bm4IgWK4dmpmrv9~z( zj8b-vRfmvd7COV;E1Qlzl9ipxF|z9zSxE?K{zQpX{{ENe?sIV--;4MA^?tr+DA)8w zM+LVYT$SFpN+KACEEEB=j_9WzLcxfb=T zeO;Ls(55o!6*07|mzg+z@Km*f#`yyKmf^`2uYJ||RFUmQc0WU5{b&+;6!1zZ#?^bD z?LA9{4dKn;pEst1w662D-?M1!X$qwvo{VQry*oV`Uh_bPw+4eu3LA+AX`40Yh1!?M z*>Ls9&e_n_vf8(JxD)c$+`G*^mnR8yd^HE^N5w&s$;V56hbxPHS0rFGPIvASco^^3 z?^bO{rVID4FWkRY&7=tY{O4lvO1VQkf33T>mPFK`1@^40-r$W@|KMuV3n+HUfWcGK z?sb!dn9>p^u}ml|hHLoEz4`vr&Z@(~$`FGgDX%YGPPaqH@V?d9{nmu6#tRFiKhUSQ z+7fh_?kulza?AIvrvy8$v={Uk;negET>3?M31=Gnogc^$KivRYFqChBKe!-KmM0{b zf?d~sX}xkW_1~HPpkN5o|5Lfk^0k%5+U(_x9{LzjST?C-ann`zExnyf?CA_DiMO(U zRymF$oUt*`eB+=n<}*k&B=4MqVPzl4!Ruu);}ekXCQcp&(?m( zr?&Hxvr0giFCkSu6v$!E9(6rRfXgx3Q~74%6Ru1Vzn8bW1A{b8CjSblJ4bUfKaPrj zHu~@Ro#)D5H)|_|?8uU&@McZu zXo`^hYv27jLj3tAWABN+$UVcL!=%HLA22B2*r}cC-Ur5xqw0fho1v@yE}S~D+qcc6 zXP7nx?0?eFP&r724Vv$Es1df0S*}}(>C~+!D=Enje$bKU`<4xT3-57zG_53Zr0-N~6h_^H@w?U<} z2R}a+u>V|}zJ*`h82r9O%8Kz=6Ql@k6|%7uMRw4n1e`g%(no!ZPaZL2(?GnMYv`R) z#0FWgnk30Hq?F8f>hV_?3Z*I@UjVe>6^*%h|JZ!iTd(lt;?pcRDaw$c8Y*%WGwJ8| z@__mKb55ku3ek)4TAO-6Bgwrhzc<`J4!n~Jph@8i$$=$CyhGAiG=b=47CtvU5nJ$E zAYUYitu~W0zW{MOow1Aup@o&qS+9$TI!0l7(}j+E)0ON%0zK}EAud?@YU$67{##jC zo(Ga%yldMw{i}xD0XY6j7Kz#nmvM|d5Tz6f;tOyGM_q;ED&<3gLao_Ly#mJwN?t(X zuj~g{-B}(R(N}3W_1>x%G4qUvZ;?B1!<%T=NS7tF*_1j8`7sXIXD^L=vkBv~Ow5`8 z#=Y()UpZZ4Ui@B>J`;v_ismwO--`CjW*Q%1(%N)eK6}|&8%s4)Ac(&nqx{=TkwcI_ zfXn-MsXy6H@yKxZyQfNy13=I16#$nrJjwQ2=%J_0H-q=wKIe)VM6m)621rrs8k*Ep z1r}Gy-;cIg@LBsyKC^7?a@KnC;96d6%QNrEotIYxD6&V$cZ9juX9uOdgDp-z`gc%L z1k(GTRp;|3sc&gJHDU~Ym!H{q!P&q-<3r>!$|Z++(EeN5y9ir9#o9NC8%j zYn4WRzWVtr%$!jDSqW_YAa|*=zJ3-Y2&ejJ{my1ZWkuqC*$xzqHnAu30YKO6H9}o+d;7t&9%&YfemrnNDAhf0+gM zrFdpb1S1F6;|YU-kObgIxmueaXa*(vnbkajGE-}wA1h|FB%?`D$Sp~E zJfG&(2jQ5@A7^j*`{(CXrtvN$g-gC{|>oO5z2Q#Fq$USB*SgbER;nP?-;$PU3sozkrX6l z*f7XNfAb86?(Cx#0_7s7gb`$^zy(ePj!*ipAAG*$b|r>{ks>6iSDY4Vy9=$`K4xJ% zd3%{W=zxsEDto-3lBzjK$>l}7iDf;y|i?0*PXj(0M-d0`=HqJHs zAx>~e;K*<$N}djS8QB9=6`UK&aDRi(QcBwpOlsJlDZmobJCvmxrkt^yU!>)(toRrC zASwI-xSO*93y)}2V8ENLm)!N_XR}RUwxODS`Be!?`Von*6tseQl&%#3QIZ}7QskNp zh1}`{QyQDf2)8)ph^njzbkH1bQ@RPbjr>qOLl@s_cF6dAnrXPnw*=(Z^8@{Rm7Y$1 z{ykkz+kP$VM$PnKc(fsg$0!`2$kyxEEJ6Ta;@-b#en0|+5EOV~FWN~5?U~~F?V9{% zYaKaRg$Veyzq!9@H~Y6}kTphmr*~3@c2(IA(>)(uD6_>Pf}Ba5;VgTv`t5$dR;VK- zDt$5T0Lghz0R6bWcsw2C(o8&YX?j^>f|w1cijv{w!BnB`xz9W@_pH#DIm|0I1|z%O zy7VEx5?0R@CcoluV}YW+c5lotdifikOX>To(;p4&R;X;gQZfl5EdPDE_5RB(jL!ZFmK{Bp`^!*SjFJfNHADu< z5b4r=vxAIeMuC6A78mWXZn*EWt;|LZ2qos$Shl^X%5>=|i7e7THGk0BbZ{?;uYXWV z&d6zLsN3#7|KZ*n9>TNgRBTh~5Wrgb+~a{@rWh0xO#m!ZZ-`w@jd4p;Hd2Y*W28wP zC^JrLo-n>@HPh@KU2GkFS#QW+o2td1t5tVU_SRXt!K|!kN#Deg&-mdPVHv`e{q5Mp zBML1oBo)FYyqA=@8F0bK)$A~i^|YKkzAboa?E1r`J0o;2T_!RS+5D1CK6KMuV6zY| z+)5HWGW$e?2z?6*CDS{EOA*3TCT@SsFP^mn7LGZ0j3kXA(z49$PR1mX zfWCjsvmm&%sWCgFPP?Hb?*N={C`gKEe&xo`D>uRjgak*~F)4E{Od9zbWZ)VEK%Pn< zwuZSr`RO{O=Ej=%Av8n&h$eVs3fK7&s+nnYfqut$7ScKT5ppXEL0^dEe*TBdKhLC@ zco6Bt9HW_*Yh(S=DSWb!X_Rm<=47p`YoeTFeeFitwcKz&GwWvr^#K9Om2{lC3X{q` z6|JF3t;z7f^D5d;QVY>wOttDqrnpnVej0xqji(=Y3$9TlH*U5^vyF}`M-115T87?5 z)*^=Ky_OF(EyJG}@;4dsqEb<%K>j=$cM^>ckjmF&*z_gjPKzO5wc#CZtLP^h(RIkC z{)tEH5wWiJp$}6+pG*jd(F~ol8zBY{t#>P}cf(c0Y9Rx)nnx6k$XaWS`rwpM*Q2w} zq(|;F?kO6*2AM$7yyx*N>7gb6nC0ENl;j6Tce_(khEiI3dSXYBT%o|G)`&YN6X~Ci zTB+Spij&-cs4T|gEcU2uxE60cEqoNoKVT@>su}T^lzg*0{Rxnrs&S_zva!dKKMPV5 z*?T`=*s^}y8rxkMFmfeyd}+r@J1^w&K$pcTz+s|?(vhX zn}j(s6THW$IE)KFlP=YUDm9FhhCzz;IC=Bm3RKtEQ??o(%w9l-6oT*6dHfEnIvida z{UXP7BB3&mpHeTG@-3Jei0%sty~j_(Uk(Bs5ct%;=Abh_7% zBc2RXZ`*d+C+(vwQ@tda=!-i}Ebf<{+yt1Bn9PImPh=2g0Q^ZOBm7qXPw6pSUJsc> zy&JIgB48lFpGbb9V%|S_;^^`7GV6;6i#pdsUwFHziQ{PmK(t?+c{v_&LgLblKjkYzI2f4NaX?4j{CIIYdh`ThON<_)^w+p)+{Zxpt3$D1^E*%j zl{lzAWI$t`qU>|_Pc;%vBa4a+%4#y-tk1Y}Z2H9~Lp07rq8=x~VYZEOY@cHa|1$lr z2P7X{DLhY>k;2JTcncBM#V|QMeJprUMY8g504t?$z)LV)L ztp3yRF#^QlPMw19-a-`|5MIe0{gE~AlN}zcI7pD8;^ZL2iko`jf6PJw2szAIRtP8m zMOUVfEFFBhUCq3BFt2W*93pY)@4wfvQCnhnh5yj_x}WVq4C(XP^CoD!kI_Y#DZ>%a z-T)AyKmrGzRa*w*aq*12GE69H#o*PJopsQHte0szzgD;pA(acOT0&e#N1}Wu$Q@4Y zO!R$`M+NdWcRH5$xRuny;+By_w#8S}^LKy#KF+G2skADP@cqr5I!_JM-6lWooh#tIlm?hLxPL zy!vaGPpxVm$y()GS6ikBG4D<8Do$Nycj=TteWbt2Pt_m3JTED%s&~OP{4Za4!17}w zc#TQG%LaUx%v{FXD5@`=dY-ilSWGN!(}*QqmSyOxtSY#3$S)=-$~5G|DFRT?hqc_6|ywB4=BI=S){9+ zao|4SBHK1!^|NEsB0#Z4OA-~R7K)fT%Hk47jZWI~}XWO@=? zp?x}Cr}GVyppme1uKAqO+q_SzUSFJy3OyqE|7+O$;b7Y+70)ohy9i(kwgbS8Wl8|n zQBpXVaPhX5qiwQXQENY%-gE`DZZZh)0p7~bznWdct=?s>1n^a09vDbGOtGgG1ohT* z{j9fq+4EcKZc9gP<<^wU$-h-G9@k`Du4Ngm6JHJ;RZ7x?PeY@exnFNTTNVBYu*Jid z8N=?Tn2g@#cA?YdpB_ov$aK^k;(Xlm24wH8_j5m*`<*m95|(EGrhn*+saL-7Fw~gz z^*(}4%?iKBwe>@!8*>iKbV&w6mn93&@-)E3A9HOru5MPb%;EHxyC)#ZNN(4p@l$UW z)rTfUJMSRq9kgafL(%o+tjVriwWQ^#$F6tPzmB^EIwbMD4$Ad=RnM=TArhMna_VY7 z+=!H0#)qZ9FXZ^c(Qs}#a(f-Xx90z~>O!-1;iW$OvQPI7edYo-i@;+}uWzVf9`CQ= zCCYAO-jQ^#0)f>aWlApZ2n=vGz{I;qfROw)v?{^0NG;??`@vwMGiz^$(v|5)gC z84Fc2-?!(e-R5+2Sl-NV;b621v>IsE-MUIg0C;F5)~Nc5Ld*B>-@g?a)7H2uy>|S; zG2b`cF}C5^^;)x!UU^>9=k=q6vR~wkb@`p}N&oDg{dD76=NS0KVfHNLB$rZr3eFff zSbS$j|80VGASL8>@T#ojam%DTrr+Z)@lZ4dTvs0@ zc{h=qn4Q1rILr8aKzg`&F+M09k@5;nzloJoU!)`B#`0-?dSW_*N%^daq3C|-fG=@< z=)ns!V-enQo=EC2xUAkVUVy@!hcV^M?xcB);dr3)mDUMkCMp-91|tZ7OekBDJeADd zpg9uTH;c7ef2H=(&Y1F&fX*i3LTq&3XW+nW1&<6-1ir1dW-rDs^PU=Hx9Z>~FGhSn znMtH{Yj*d&xpTA#>L2Ceb~RX;Q$p6>?;%v+>;UpA6~tLbM+zdkPP?wG-?A%7a{_$A z!|gxqC-aboq`SaVqT*W|K1=CJF%$t;9tvxaotTQ}fr?zr#Z-gJ+VnwFv4t>Z;pHQU zl$}U|;vSis4QE1j@WHffU1WXs-bqwKI?blZl$z>$I#_ zGIcjhTJ%$6;11Ew)n|3#>*u}96V{4nD2td+El+D?t{Tp=GvjIn?DE+~4$1EBb2F_F z*ePNOm{}Cli{D|sC^i_cX@%JHZ@bqD)+xq7K8GY_I5z=c(wF6Lx`heUQFv^`ulhcB zjqhtF@#;V`#wBsm?@WW zD>>`8qdH!FN2pi?Q9V4Xk!LW>gUW^*=K&cDsGc%hTluJ`39P_%uv@mWw?eroPshs~s0-%OFgzzXY)99V}++ff5`*^H+8_eTTgs(*JOQ}N?1u!tk?Zwh4tUyAD7HI?g z*Kphh8w`)c2o6~ZEjJ`??C2KqvMq0W`6kW4;L2lT@xDc2eMDi?d$8+4OUvF$Up3W_ z46iwNS>C$~gsfI(S9uxknF zD~xy|hy|w`e#;h^=wWe((iJ?y?O>ntAMQWy&UzE2{r&_EKr`VafmzCQBU!$cRJQh$ zqdFJHfBpfRsuFU%Un4Emd)_ly?B1i8NXo4_i9&{QKPiy;WXdBeBsfejWN2-6Mw|w+vdCMl(Aej1wBxKpQdFaR4t~%~>aVka!-Ws>LgZ}t+vRuSSXS`;kv}XBF(Sw$X~sri=S$w8|Ptoj`!jnmo_=it!P@s zihcb5)OPTj7}+p6-(r(mM9YE_aXQC~8< zu2ylYqNJBH|6*WUc9h7iQ_L+wg&H+6NWIBvX&rh4tQW8mVEo?_2Z-kjo})G32Q@MB z3zenP21GHss%t&uA9sadGCw6XPo{CtV_170J^y{<`5`0EA-(0#jpqc~zc}FP)jh7b z3U;sB=ZAr;F&qD-iLio5JX}h{d^2oDUs10CSyJDh{Gqdj(b#U1cnl1g2IQ%Gh40c_HYN;ETnXASZ!0fK-32mO%Bx%3gv_ zH9mYK^y<4fo!V*l{mIIAu27Qr;21NPJOu;-h#W(p3;-ZN4gjD7G(c|w0K_Q(j1Vwy zrP3$}b{V&^){3D-)H%yi^R`W6KQ0yjRVn*ovkbQLWC4rz>hWBuOO0;h?HE&kU_C8B z+HS?VSkq!+m3N@ZJWj{gHt%Eh?yFMsTp9O?4(Zv-`6j=|64T2TX>gOZ(24t08;S-c zg;P8DhLPXv@ZVd@osZsh2fq*bVZrVH+Go&#q3Xr-ic=SxXY5xCN2*Fwh!s+T>5;-l zXMCnilU1+sTmRRkTCNMZCF*|Z?5RRFeW4dC?H@HX!=iXi-L%oFPBYtuogH3EpV!Xj zCu$R~gC2G*^tf0*u2m#A*D@d6eBk%U^CWP!J*?iarR6?@JW^}x+;<=S(Ubl#EuG_OOtCZ6-~P~%d=Za!3rVXry7}&;z z4<@~p6=cs|h9yJriGq<3P>Ry=G7nL`j));LcNz@wTKwcyK?+0cHz(qqfEGTu=YC)& zv`H3eR2)o(eyK*yX4wjD*>TH4vLpbSQMAtn(JrwYg;YK))}|x9LFUeK^zYUP;L>r+K_6S3TJ0@bU@pjYTt1HjwkgjW^MVif(PE{5G1Z3g!OErKYHv613$321VE= zVq&iRcWB)t!uYvC*r?b#2B3++F+ncI0e07OwZ}*fb(XIiU4AxRVjkcGY&0w^1DT_V z2~PY6bM5~)_*PKHY&ixAqFVqsjsV7(N9h@aZajK0_3&!;#A1~Y=R@M7MnmWTQB;=* zJZ}Kvg^(HBe$TaqjW;+;x*7l*YpRu%GH#dpiS5nj3B!3a2sIRD0Y4-D6X~yhof}09 z?fLwz>5l@gTfJF1T{-OPnSK-$G5Kcg_hEO(NP-NG6RRaA0teAVwoKP4qG{|6T69uq zoz>e$kmF%m!6ISmvTy7Ln~N^L#9i!+DNwE8IPv#0TXUN-H6?$~HOE-*feL zjqIpDIX;~ZHg)XTvHqa_ruPaB3lrB|hFzElftzHJBQE^ECKwlpkr;M}Hu z)Veltmq^tc2Cq|ur_emW0j{CnWk0IMq_6V;8Rs*a-TTMPw%yMNzZ-=nx?Uz4j73t&y$e3+InTKzHA%bp0J3^KEtvxpVEd$CwNXW5`8Obcr*e+3IloGgk?vu z^ay<}Ab+|Z`(-o`Zm0xeW0F=1{Y1LQPYaQ<4*{7I$HIsMmxMJ;(F%u=T$-r0>u}Pw zv#$|&n+tGpn-qm-s?^}K85II7a-bs76B1(DPHc)1=w;K`-Cv9)7`Uk&5vPfIY#hg- zCDZ~BnrM> z1+x)y>d5xg5%o0@RfdOKWTDjY@L^0edv;6+Au(BsDGWu3T8H8AcH{95WYn!%kwj>2 z%*R{F;Oyk!jesxN_XLy@#DKx_nu*Wp3=tS8!U?4l95FngzG8OC+ZVP=~RMy`Y?5lD@_-1r^qplYa{9UVtghKpzI93!uU=Rz&9{b z8fKaA7enjJ)2+;yD#f6Y0Jx1>kQSW*XpodgjWon&DpIo~ zy_ra9?wEMECpcg|^En{vNs3cQEF1=Zm63U3alkIR_D!Ffp-GP zn_dpO81GO%5Lp0<tAXXj~Xsu<&v#b-kF3Ij1fCMppg-IM$N8rWw&bKA^E)FO*z z!@DvO1|&j3Ll7jl2dItV3W98XF1x=_Kk$U!5k<1j{gvztBzwrVoC8U*? zLl-x|BRKp*L7`Uzs=K$Wn~SM$S$d;3f9&*UN#-IE7p16jE$@?IK|y7ygp!v`9eS(? z-56|TnT2x4$D25zJ`@QlTja$^Gx_5ot^@GsR+5BteA#-wB_ValLJZeX-s@DHUwMb2 zEty@ZxTJyYpaEUiDt(cj0P+lTr5B@QeC9_BWr0k?)ROXcXalc@4xkj*PH(G{o z>00)psdNQz+Ew-kcX{utey=!lrbPJw_E##eUo07d=i1OJeejSc7G<{+iRXintVQyp z-QLolV*Xl`cJmbUU+3GeC)bb);IwSM?;#5?H0MF=B3C%UlKtsA66TUamPT2nBzaln z2YcRhH=s6AV7P&F^UDwymvGdn9||C&hA$`&E)wuEQ&M&c1)>6_+d_(dt2Jw&jT<@6 zcrttr%qhQG(xEQi+*|gT8f1udMFHB1;kEumb6-dcF^-v3GAE@L;>`D>zA?n}wq!+t zJSlLmkX=-(vD^!O*AgWO$*ZAxe{9QXbIG~8dnJefsiHn)ZOc(FF3RT1S^C(R;*5G& zckjQ3g24$kjtP!X^Tsl-#s}3NpbE%OV98CTlGH-)&%lTCyx0gjw8cC~oeF8jFo{XA zZ6F)EBjY~sv6(q0LxFd2mc?(l>QMGdJ1)`Cs;Jvbq17wO9(ag86?~c7*D}j%jgOS# zl*s%2{t3h5cV;PHPf6r6Ow66G6xj-Og2g)$8JB14`DPl`t|_W~&cXAxF)Fp8zN_8T z_L55o@pY=5)(YpORLq(`MrJo9TSTvGh@5UJ22i0F*Uf$vd%fVUJy}KvPDUJY)glZ# zkQ)(fBr?jP`;2*WG$;PBPqG?g3qvg6Q zVTDiPSHn|;8QDG__lP`68vc-jz3Y9B5&ODbEHe1Puj5W3*Jckt)Jl&0Uk2|$*F5Y( zM0{#@xK%WyDoFwnImjO=z7)|S>+SO~Lj5SWa~9=+Q$kxg@gC#ve$05Y z2LsjCk)PK=<2jrmU8z25{L!cNadD%ZtR>IRy)S3mXi%qw$aHJUc5Ci2 z4jTj{zrHg3N8`4$PTl?DUhadT)9_)Vv?eZabDa*#F&7Sz3s;oLb&vKr?8*r}YQ5uF z3Z-}xH9BGw!=ta$x{n976K)dWG#=g2H3Xi|>42%npy}!mCK2m0FikeVh+!pqVoXlqFbPhp4i}ws^9nSl7hG}|+EruZvgW&rLXR(=K`b&?+APT6n9H-2) zZ*I@=3hI#dr25|bb{R30VUe8_LhEC~WV>8>s}lUy0~0FYrKnEg4k0g?P+~_gcAqy* zpPlj|I5YcQb$@;NErXZ*HJ`U~-Z6x%D+@kP<)#MZ?9&NlcKRXA$TE!NHv3|^-Rs*= z7k$;wWI%{%)@T#EjQo4JJG*d|oqm!E@`<{-+a>kef}(X)q#GFNd$=UhzL>AKoGb{y zfRN>wh3)qY<@n{e6B)=5(e$M6y5#sSV_$B4^T}c$aC)5W_KP>0$dcfhpjK$Gfu)c) zRn%RFgoXRGLWz%{K`89JksAz&5I%r9o-u_3uz4fL&=EM-G(3C{N!yL09E*LmWW>s7eAj+&0M1)?%z`67^VgBz9m=V%nH7wIdVgVku zKJYNC<8@i==k&KrF{+lWt1}^1R-lb)AGrS|YUw6CdSLZHa5HlYCR`2|`X)Vme=`c> z;Ij^Yu)ittZ&SH>H4jgHfZmj2o&(y!UBwY{=`+!Ex}^R)ART(_gIj094x2aw&kIJ<25wIRq{aam&1Zh&fL;}mF=L{pJDYZ%ymS_yR{Zx5;3 zjv3tx{2RhR+rubtVj?#ffB-~K`Dex)rm_K8!((kQ5V02z8Kz=d)?o!GRaNwtmj;Xk zEC#tR+Fs7|ycIS;#Jp>cgywu1r!xkk&Z%rN4P)Vr;os_mFfaFzQAFXfe_tnqRT)IT zDB_s7VvwT!POxlvIGq9R#i;WG2`7L1nISBh25)VSyqEJy7tUnH4k*De<;H&hMUrBR zKw6;{YyW+pE0yfplRKkKNmQg5`qr;gIgz`+#;j)=`CUSDPF^W24#`gYfX60a)NV?EX8$KmgpD_0V$fNIvr@_~y~go5vA$$JQ8#$AFm2kdiDrVviHx zehS6Wq2UI{qQkJ;29`QLa7!vohk1u5VqZoIMpRUkR%m|bf{y@m5&54tcW4(Few~R!7Y_KE3{l7z`idu8I3s~ z4Y|4!ntXPBWt|t@d;1eN)_ah+G5Ff*dW*+X&>yCC_FcP5lXM}q#)HKRr8Z@v@h%*W z4vjz`_mN^w*~>0KLJYLz{uM>fLGn)!beF|SIsDrmn^*`&+>+Z6+DF+*<<|P^hp`EC$Rb%M16Be zc-r@aOZ?*LPPE)u;suNIPs8{-C?*yKiM@ASzqw!35Z8CjY3)TMv6kx?H-Np+RC8{z z+hWa!;H2uCZ+rB~AXHU!-2>Uh504 zY9{SHtT+6Kc{0di2@y4a4jf^GwCYx8QF`|dtrU!Vj_d{zY8it=)j+d-aQcU>l!po* zH=opJ=yceLre}hrQTpdAONLmaujcGMd27iRSbf%dYJ`+{Mtm=l147C7pX?K>Sn|L1 z7~j8|)Yec?3OcH>R-SH>u~8$L2u#q)Rzi0|-t3h7A{c@ucWQG$+lO&sjhpkYP6 zY1uXGTI)z-uFJV>oQrn3&JsoVtKTWDws$`MTyVR!t;UNti29o2aVLhu`Le6twLC!R zW2lRd`!<)OV=k~}$h#*@g4c2nvCi^omKlJO2B8L7uL!^9nkQW59A+{9x?S+j=T3w7 zyI8nTM22HN!_TXJH8mOve*Ny6n`RZf+bnUs`8`X%SKF$%2|4oNj(2mj#R2S@?cVI( zw_`@0U!vMX;^X4&<1_Pa(bO*53BKi+FaCh{=J3X=Clp3q7O%agvx?ffUy%#EG*>Px z{^B(M(zmRtbRC1JnoHhmTYj}Q^rpuF>Jk2zrXIw(%t>}lXEZ+4{R#Q}vL#q#hr870 z`!K8ekuoS%aix%wX(cA}QKUrv48oGn!EQ3D?IFaT_C@yZ?j`Pfff(dwd%#&)rhIg& z&F;jn4zXuFk83nt(hKWo(>{(gs{`$$--9ek64lsdGQ=_&t<`KUpEYBj zsdt$7si%_hyuq^I&rkD@SfnC486g~t&~wlK*qVL>F_$U^;I8)%AXKO$^ zfA8-v;SqLKb>5MGke=t4);*cykW|U7Zi8d#R`$kSoZy!a&uk+H$=m_!(hw3XFVUBr9PT$F2PX zS&Ra6d&yq95Q&rM8IjKLxr;3Q)HB*U&Meoplq(+$WO4n*0Xun80BUM2xz@5|A}y7Ckh`Vecara%h-)=?`s2Vg)yy{AC(QswO^0jR^D|=qR)X3IbW>$RLfhBAY?6rjvP(KUBpNnZQcl}+cMy;^0 z*d+@}v7eP!chuY_Z28Q$Lg(Dj%opROEw=YA71g#eyW25~_g!Isx^0{h-BeXLyd}}| zq9G{!Bt?z@G%45_a)Ldgy94hPgq`r>@)8^3NJ{Ml~4nRnftNSPLb>v=YMKKf%Mm zmdueuO#$&b8w_u@c*=u^l!_TWV2VpT0|wueQn=D|@;_dvJ7VB>%WbBM$pF5o`H+-c zUA%j|{Hn6#6_lU6E6*Fx5``sT7N`lAqAi~Yylkm@dAiAfU)kUoKq>iOkAAa!xXBS4 z4CdVjAYB9~T_Jf711O%1_~{Vl`*-6DZW%JV9W@O5JiOr$O=j;XlYeQt%t6bizeIs8~7C|ACWYhc#Gzh?Qv7!uxN7AR&za-`Q^SMB%IQvNF9%l6f8Ty{`?z4iy z|5y_E96Y~8EV}lL5{LS0x};-&y?Ix5(IM!o`_0qGV%{uyd&;l=JU!zuCUUb}BI}xd z3RL~89*Jr->g9d5XZLilzHVKk`ta>zb9o9+Q=k!s%JjWKeAT{rFkX_(v10D$`sR_S zsiJAyylrR-o+`tw28_LU4OzBETdb3M)RZELoBCAbm{73Zk9 zbEDpffJ>QQJZq%z2=-UZwR?*1dXanX{&m7CF+r`v5NXbn;UBrhccERGHFgY)S;yO` zu9rOwZb*|5HY($YuVd-(Dfd9#bg=1zmhbsd_-9)Wtu5iK$~7zsC$SGqlv@}-kJoI! z_Ju#wc*abyBXdch?IQE_)cp+$>^q1QL5@>xBfZ}?{DpQ_w^JmldZ)nRUF$O(z<0+_ zdhHJ$u>Ki%csA;$PG#dd{-PS_mT7#*Y& z%=%|c|EMr+pbDaCUWIm67dTKx->uT%=dY#6Rzzyo&sEj3i?yR*E_U%Y07$xdr^9|6 zpjgC?@Bq0lazBfr+5;;2lm)|M zvM&C?VO06s-Z&xa0@Yv!^Zt%HO0Z?o zNs(X{m2ux9(+Vr9PX|d4P;3B$l-(hibP@?KUWp$TSORKlmhOrq*%(mdiPf8X!xuw^ z)R)M%S!G{5N3NtX`ra+Ok~i|D7osyvOOYCJ>yP7Si+it9C&bXNh9_%d8_Am#b*J;L zt_3%(xci>ee4I<4*h|kp0_8?B4xBtmozS0LXVYB*iP@bq>=Ab(Gq>GMwfbJ2K0s!t z>DzcoH(gZItp{KG%`a?Dmbar6lEE50by0DYHY8f7km4|>z4!^DtVJsce%Q@`EX&f? zMgr>ZjsYT}mv`e%wJ~z)7_dUNYC9m|>0mNWM&9!X>O5B2W=UZ=?wCdAt?cKX|CsmK zKum)O9-I(yr8gI8G7jV9zM_@f?4Sn0XHTaHc;y-W&K)Uk|0W7^(S+(OjT&Sz0ME5a zr(z%I!rXe|MBY=ZX$m=Vsmr1X0Box1akF~8@WHGil%no;lIMNIstSM_D0O*(6{%O_c&D)?D9sp&u*L;kA5}6P@jjpr^A{J%;_?gWIx8cQabIu8?S57 z3|PN^y1Z3X$}g(f11>e>Y2+=mCGpj5fxRH{b8fKf^l1Q3p~v#s&>y_G66c6WsAOYj zzxz1ZtwcSUwjU>(SKI_2gt9$kz|)g)`zi*0q9ul4)gy#m7SvXn4`0YIys5DEBQ6jp z{b8I#@iBweV3WG5l_wAM69KI5md7rp^l$%Fd76SyMU9oYO1;Rq;0gOB9c5Q)T<;T# zJ>kOKti@@u(#}MQ+$@{pp7N>Og`V+Tc{@2R59j5W z!O&O^h)Yk?oTc0oUG>>v@c0Iu)u^OAvI;h0mAmTTN_q6c|6y6uxq0mbj~?2KwzK_D z+*Pc`kwZ$kCcBDrib}HVk2uC1b+#+#K0&eoP`xfL5GZ?UI=ULXOZ@$KE4z!%h)RsivZrdw_^$2Q z;yEQJKBZ};v8=Ko2I^98BG3+1z8&AA_og8XdO0}0{VBvLgmOvhO<$)gHpkU5GCswp zl2!vrck6mG65syFoF=$BT2rA`1-;M;PA>(s#J?JSeb(-@`fe~@VpdoA2xPGShVZ#f zqqs^Zr>~bx)4NDf<7s~{TIwuHiQfahz);l8!KzEPq$%@Lbv#9N>E*pNdOixo1X)u| zk|PONR=QErruy4vb)``taSUZWtkLDh+SL2eugn0Fu9OHKH1nFQhzF~o zY4W?EwXpSHVe5=9@PDV@j?l@gBa-@mI~B)BfPvA)GI6c-48_8lgBbUvuniF_%GC*}!mZet@pY|K1QW^%7Dz{~^qCu+c&=VYB#8-9)^q zDgq#p1-^N^&6p7PzkrvT%{p;1(tu@VrC#om` zxDO>Njecuo)ZxwOP8fJxnfWMeK#j^Gzf3D7j|zsSY8z1Yy}=up4ku3OrW{Hmy5U|& zcBi?pYLcBLzVdjYH-7#ySDMN}TA!vTXRQPD{#dGZPn>;lyka)?Xja{wRBYc9Hycd( z?0N2jR`-#zSeajuL7}+*ZX8~x8^e68_aGJ?24tvl0`RqzN0tNO1?b>?~wWa8lwSNXx^Vf+efvnJtRY`_`wu?rV9niPyJamD3*h__8884ebb_HjE7%>8 zFZIav$5}fvYN;&E zDu7*66u;k3F{Ee{_^_l`rFi#77;-8HdhH`wbpUKR!2kD->jE>tpgo>52C6M47p4WZ zWAAKOPu4z3b`R4|Oha-qA(PW`9Sy|vk3bLxoo1!BelNEcr#I?zy>Z2O&7M^w6)`1e zSC`0D{qM4u&8t__(U*^)vo5Poe<+ukeNR@q!Qz zIj8)wFA5OY5qRNO9r$>9Qt<8^?>80hD1|v&Us^`>lgenJ0hGeGiPgB=-vT0*ER67z3*hPk9oVWP8NP z>7uR0xBp<9Rry2m24}_Kz6wu*T6I%rt%cgqhjgC+5eru)!49(S#97a@;ps%P6I7Ij zRH`jL2`*^QE@iKSgg7@bX~6ciWcS>!CAG=?(9ynXv$gY4G)CxCv3dGOJAXiF1-+3?Pqq?yF2m5ISExG&lecSVdq%T{(4}`b>#y^ zAuI`>7d7$UuhmBx^uPDqi7uM4uP_l}s@GFA9>Sid2J7*z66QV$Z8O=F1-_R2^cp2j zs0DYgBv0Rt?|2ZR2W+UENKyzZvCRy2C6+wu);e#K^kvb))v?0!{sn=?Xb0v~^<%m| zrH9?m9>Nsrxs$BHzPEDF&cPDxBL&g3nK!@jqXvDUa>PP|x^Uyd#mX;53mr+KNA8L- zdpdc{Kfxcvg;Lb1U=!efirEz=oy_N@r@}+EehzM*tl4#RC2~6{?`QpCZkarW-L>5o z2-KlfTl)9>%lg}1bT7O=x>lgkX^XeAW3~hFv_h@6wYkbRO~H~LtNksVN8LxZJuuY} zmYBRzJ8il&(3oUL`B=-QP$p2&Vy4-Y)G6zg2!@`GfponRO_@ZiI`&SKGnt^Ov{53% zagMXd%Cj*a8~W=S;N^1uoAaF;cd{$bV$TfQ7W!uMoe5e7`$rm?V{(J6y3D>6AS=)4 z`wVl#in6N|EC&4hhaoqn$_gvyb>au7XGuTIN)If zLWO=vfh!IjgDe2FV@{fq()t;(>@&}o;W;uZ{`Cr769*Z&ebASg^7S?#E`I-0?o+;R z)U+YD_i(3P-frbI=IYJjO!H149hfVfNJ5BD%S3;u-YJs#r=O+LM=E%7Ba|e1L3#90 z)hE|`1=LVvpZaS`IyB8VUH&mtO`_N~$81Y3+x^#+gz_7LZ;9V zf8$_NV-b)VE8Egn))JuHwOk949&U=qwD{#jU?SCicc!9%X(ndME#lg(#g*G;lGT*f z{R_pT=s)t^QEj#6B{R;~6{;(jYd`e7KwW6%FJjo;R%pHx?^m(B!b8nUj`2yDhnvtS*RYG&n3Hx2-C|dZIWc-Qc{YA`r{B zr*h=gwQ)>rR9%MhIKV4&rJK>Tp7FRU?Lu{pU4%(N5y=ytF503U-JkQm&sUiiYj@M8 zXpnN);tR9dp1b>7FiW|8lVHqW1CB)8yZDY7p?rhsTW@9`z$;5WE-L(q+!JtpOD35G zrL*5Lg56drjS@*y?y7N0*mr%O!SemuUgtPU3#XFNINA+8x2w7?p_g+rF+4o;F_BfL z2A=9^z!&YwXwLx`;LZf+G7{DioCr z-HsHtZhy~yJN3R3f!iOhYN@6wXn2(4=W~;C?@Q#=sGs3UNyqk!F$u;0d`KL(4WoHi zWTe$*6e`b_JO}$K^`QX+47%c?mqGg?G3zp|sXT0S`<-1>RzAl_j3txg0>fX72f~r? zW3Vw3)B(9X&volx*6GGC?50=i#I3RGg8PAX$#OQimD3(5w+2U>>veNHe?X~U?MFqE z*9!wiwNm9asSpAKbaVgp&cB>STQsjMwrwxTwXbvvTRu@<%O#LyQT$*IxGtN3Wk$U7 zHE(`q7om(G$$>p?X4&ZTJT~>&ee_ear52j{KQ4f%fXnMR6m&QYz3O8 zqpdk6rq)g(XQ0~Fvri``gZDgb)f2EcBBzMn( zt8~l7(~rm^F;IuOlC>o-Q?AH;jtAS)#Kgy#VKq?cb(HS9Eib|{V%w<3WdU`9; z`lVwM?z<@g_ERpDSz2;QxaZi1vwYlIL-99{tj2_0@^m!|``YcRHev$z+M^>!sYZks ztZ&|Ry)c?oRwN|(*?d9gVq+LWaVcgl36Jg}sbO`5^apzDok6wi(N=D$pUgqpKdZvT zU6nzncrz~BLeSx>&MR?O)m31sb%n!%cB!-3mt1OTnLN&Q-^g>IDX^$YwtUgsNcXe{ z`=m}bU%~U58w>*TO+ z?!~U=mNBFtT4|DLb@~Ob?ThNWO?{m=h0&yVsk;7g~3rvo}f*t=+J8IV4@bZ8jar*Q1MB9M;J3(xxR z(XGE=o$-rNB5cFU5$V`vkIT!qQPDI599YDr0*psJ-}?qQ$?870)Ju*3R>W7KInG0O zo(-uIK`LCoX$#;;yQ+(>QrAF1=Y7jpb}9ec_@fzZbt z`Q$wj_P7ovp}$48+Ow`GmI3hJ+89+Ce%w_?Clk3@}q3>Ri!o;2D9JA znx`>Y-r@_$Yq4Kj1NuUoN}GZwwZ`SZbcjyET&8%%_xAidSJf1c2dMtv1*KK$oGz}u zxnY&6mbR8*IZ>ORpw7Trzkau8)Mvb2DHfzZQqh#mEFbD`%GW(pDJKq;Vhey8GbjZe zra#2P$V}_qG{FNcpDt`ZTwqm|=kB-7wvdk8xyQt0@dltwsIrbLg~IcrYIJ_0pUJBm zP^%5)Mn(Fk4ZgQ2AWyvRV^Zl6c=Q1xLnNRQ^3v8cMOh{_8m1glO&w2gsw}#FweW8u z`?FiP-?N48hkUb2!WtrQf;b%-1hsAN#zFCWB5ad!7@@!$*Wd5_Lp@?KBm?#pqh7na z548WM`Cog&J1Jo{=e%oQ9-19}D0KNb_HO9=3N>Z>+uBhA0E|0k-277b_;~BGJ4RYW zY5)G?zuQtbg!(oW^<0O20+;n9j&Ny~Pzood?7u%fS8!>O4HtFgOa3ik zfIiNU2#ygxav5en0ALbPLcGCr!Mv=e z6VuXJ!_N;ro*vcmKcXl!fu#2cbN>;945xE@qxAH!F94Wuh6TU8=>T8J5JpY6R*gB{1-(f-ZS052;{%_7Wm{=rDJv zzEp6%RPeBL6rHbXSTnSqJ${2HzMg%&UN;mZ%{U=oNFc38b@HHkxvmYZe;Zm>BGMhW zbB{!M5^=0TwNS+dXpBB)nt)Kwhe5+YE^z{X z!wOTEFf2#dKIYxgJ~?s|_?fp9z1y(CsvquP^BGzCRj|}RcXW30wLu5rl41(qvuy8I z^mk_r&2a9HhRI*e3|+Y0a8<){Ay^gQ^E2O91mxen5Q-cK!qhe%6J> zgmZaVk5$1P9%G-%-p_Z2{>$&F1@dQ2z{e^^LtcZ{^i@yO->4BKaX_{|iE|o=G7>=c z@Xy&>sWyT5vhx3SuOdEFMz>j6C%V#$8{;UA(GZ%zVGd&Jb)4vG99ke74!U5%O6D8>B=;TKn3RgE zfFka>WN;Jh%#O*VO=27W-0`qv86R0;gpDp0o9dt1_Bz2+K!{4_2M;$Y7(8;2e(152 zk}5qn0g^6C77iXxb9H@$JgG{V@+(kn;)w>8n(jz?KT91e6ewP(1{bQFzHX9$=_6RL z47XLYiag7>Gh^;jYnIhCtnsQzFp7fNDqJbb6mgm?i*-sze8}A=%Q0-OG^aOfy>bgK zxzjo+CqTsP5x&x_nzc&G@0j-|%*%8T-Z-L_RnXc#fn^MRAu8~y!}BXY1hku{_}yS zh`Ts<_VUF{?oXZTWI=(X7MzP3Gl0bjlkK0R)lJI^Ca4}#ly)eE4I*9DX=;-hW+V_H zVB2_YUfK2;Z_PuUclRPk7eSU~Ywc^%)G~Tc%6W*aviTnp>9xzRTv= zy8xgR(|h#l?Af7hkx{*Y-T}IZdUkF_wi&6&k^{RNeug)gjM5eczUD+z)d!BZ-_LE91hyI307xYxJkzG2L11Cri~G)& zN5>q-Lm>W5a@j}d{N_bRks|JDkLo^s!91YZnOx)Vmse}nvILNkADH=VC}oO;kEiZc zp3QE-Ar%^ST%f#j)KBHKm*uW9S^m#tRtZu)nR4u}Ht;Wh4>;Cpmra_s3Mem2Yb{{h z3iDRSwCABJ!NcD9bbDrOq_d0fOj+~Cl=uN* zf2KIS%)$bBWZ7*M4uzcaZ41El7Xhu6Qpe^GR0{8W=}=rnDa;disTAcM5C@k^EBd5U zk@m4qG@RoKMnx-0&HgkQHh_zhA{U`(ER(`2h=XZ_^I9k8iyS2=lV}qiBeBo^Ngt4P zmz!+ev@+L~Pe%XTLf!cCtdCw&5PEGZSBafTwgbr2pNqN9_84yiuutN?)*uL_WpxAc zk13o#JCrtG{KK_L{OnMMQm{6ZuYDI69OXV`Oaz|0D%e!1)~|G=nEjG5@e!IN+t(_{ zu#{%aa%>in{Z^LeK33_BCft4@E7d*^4y+bWlDi1nCccux!g%kXw=#<72Tk9)VkBA! z{Nh5doQprl>H{VW0E0}~v@bH#R?mlK4WC^OA@i)UkH|oW1rx}E0Fbo!NrlbUN168d zYzO{vAn2LA*{deUepqggHWz}|fU3OwuieiWjTQgsw^^ zKO6J0!);inPq^mjkNhLy=UYiK$``6vt($JE7tZE#@vxu!Q+mb;{kdoIiefjdFFb}I z&u9WSruvs#cQv%oj;zRd;cca9PHmCbsVA!`H1j zauZ`gzao>jplZ2+8F8?xV0h%Od$4P5^83#+VqwCjV-ho<5B??K#?0bmvk%h6eDidP zrq_8B9rcem2Jpd3!JxOdfw?ypXAuI?i`7&;3Ex*iKCuI@&_yQtu`gr$0*p&j%w+!dzLc zMVQ+3@SsC|pU5aa>#2A#F-t#pB5`{Dpa0LqueTm3?vZs^0BWaT0s9Srza6`qPE(9KyO3=sA$Q)UCkSQKEiia~u?8hV|Zg{`({NddjzYFz;?w|ZN zc&sRXYTg0~M~FTZua|70;JShMD(y4oL_!jaiG;ltj9WUjhOecfK2=0I4a4tiQPwms zYS*9(fdV2n>+*qUBaxJd+h%#f))DkhA0*YP(Y2p5&BQzd%x2tuMECQVEilf{aE&|g zp0y?QM!ixGytrUlt?hKL!r>(7^4(I6v)y7_7pNC2Y4P{sWfWF=DPU%hc-ougpI%r!LmeqFd>|BM7B#$bG$oc zUO90p<31Uz)N%fh6Ye`@-m>0z%6tsX$YeHotjA3y3wfp-oiBMK*$SXCk$j)5PMcAH zJYrkRt#4H{|GW06D*n4X0zZN}qZ?_!o@6$jtCRC<%s}Bo>&2(2g{NxPx(hnS#b@kR zFIu0|TphEy68I|Rf?~j$5ymk}B_-P#=Vp(w>q}0-I_AV}03ldFV6v?V4G34Bk{-#{ zom%!p=|!>9icI5VZWlRQu8kGBg}+%?aIFfyth`3n+F*uv)6@|?)VV@auC3cM&>z*M4Df5h~eHh{<@a(nS zV4R9Co1!N}A0RX`Q;8#O z03_o?S%QRDa8QB(e|V>q8N;$I#i8j+E!P=z79 z1;5t>tENV`_G%x>d=Bb(X~mSS0@IuTI=QY3C?jseJpf-LDqL}9_wOx!s#S!Zc< zyR-u%0D{LVJm*`&5WHqdKI*0t(bDhSr!Aceko)d?KqPtMGP)mXozdCo5!cPcw;jgH z(uvahRaDElh7tU}?}2=2m!e;uMg=U+;ssmgWI(esI>DZnd-ttg#J;-lYuArUKiNRY zxvUm2v+n)q!`6#1kxanp$3U69DQy6yEKiK z=SfxA+e^8du9$AI`aF8LWTExISWo%SnBV{)!z;nc7PG=%3Q51zgHpYBJ%~ww(4W0CL&gh-G_*K zA0|^^k6MZhh?G~(seN*GMl|;4uck}axis1a3bE~sk?t(4zM}ch{$-AP7uM=)0a2pu zMS#3CV!X~Z(L-l6Xe?T31GagZ-_M=#zs^wWhMD_u$DO*_8DS^s=sP?3x4-U~mWUKY zmW>EJtWA+S=zyF##ZlRiGcyG{y0{osGyI>N9;IIYYad8ZfC%ITQ*buntNyZM5D1 zvnfrHZhFz`Fazn{tUDh~C9ni>Bk9v~#a>3KM~t4!NKHxHzNLraM8xrKMYQhE=k5YY zY!uo@htjD9aC$P9(kJwJ+mEU}Y^62YH_ErSbpIF8^nwvda?F>S0tj2{Ey{Zyl}2Dy zmCw`mjBN9@MGEiw`}mY%E(U0G6IHJ*R}`KVr-nhgiERTg3(Npm(8JT%{vV!KCps(D8`e-% z67O|AM}1CJ1)pI$b0m{E{CqbV5xblm9+9oeIo!R{doeH7p96ZUo8=3drX31wI|&7RbP@0Oj9E{pf#SaKeoBWja_c_ zK(@1|M$#c}9XE@*$McMgzwKpI84cpgc%J*74V5gg1(8Wqqnl;e?-%`|AO4E2Rfz{? z=rqyG3SO*Obz1#yn|eYR!ZJ%N(n1MUm!obiXKTNuSKib>oWG{`DcE-Bdgpz%XoBac-;17;xFhbE(<=x(2kytR(jkZ2%%Yj~@582HluJjFg0}a^!pfME zkWjUfWRWyQXr2D}jk@ZR^pcVfT2N(!oeiwj8sfRpg;PCJ1_f@62VhS-QO%(gJhYn_ zF6%o*^6O0YK=(3uA{4OCZ%*#88BlZdPHN0i1CkLXR}Vdv?glnvw(($(jw356$j}DQ zJaJ`FGD7t$4+wBNItZ#Y1BKwBVL9+JGIxeZNSMcX%O|)l85?W*sn_)GloFw7WFnc& z`G~~U1^FZ1MzeqBS0h`$2QZp`c0ApI7~9si2ePd&P<&QKQ#OCJcHhp`W3=giRv4Ul z%*~tk7{o>`)jLV<1a@>A60qj#Dnfr`jDza)$j|b~t8gi)NV%@@Xzg3CQPhndONW!MYRHmT?COO+0=a*d$wYdN_}hE!xhO zC*VEzDhY9b>nO;_`s9zFGta?s|?SQ!GLDapaV3Hb{rs?bS}+cD%lF-D}q&IYK|eG zN7Jp)CL9oYQIB8%>s5O%ye0?mR{@0Rdwa;^ftC)5Hg zP5e5j&=nGA0}jGR1p88*=KIz17PU*_Oawa5C(C^^beT_b z85ZL$5y75V)gnOvl*Sqc1aSeSI603xO(ZLkfjl3n$hSmP>KZSI!~v~kn@1wmxsdaC zmRQSND-=t8(uTbML1Kx{=hem2#zo-#X zhD8#zQ7 zIdL1U(NJw9#5T?S_~K}9v(ZIv)UJ<-TalsBJaQWkkGDmAq?%^VqY%d7h9JcQ2J#~V zS(eQ9g^23IaiGa?#5k&(n{Ab*^^1tgvA>XSZ!yAchDtl;PA1xp zX#pj=U^C0jChB0twSnr!v$g@qKZ@86h$vL5nHG;V+qjbJg8etr#lJ-5JtA@dFOCIr zDc5qwcva;D45Dx%z~&1!Mu;G~KTt3gJ9f&<5W{#nhG z7>b_L65l>zNIvx9aSHTPRQh53G^S!IMX~l>ck(#(4&n*wyq&M1_^zfW9qsFZHl}b} ztfBoyv=EYPLJS+?ca3%9R<-mq~h5LJ;v%>uVF;{+m=aJX&@(I6kJ0I=Pi77hZ zu>o?q0eN&)q|{Y>9AbRb_IX_A&^DKNlx=;T7CFzU_?QrUBG-BB*WhO0;6|_8gU~Vaao1}jo>32)!C>wc0P+iQg+jg!3dtsZ{EtLmU&gZ^ zdfo1ty{7i*VPZBVjE;p^Bkk$fSn0bv$^V9*SAP@>nx~*zcJ_JEI_tpm_4PAAUa@y!>Y-TDm80Id2$3?{r){1*q;4jj?qZY~7ITwvUhWIiq)35+?EN zrjk{y23TL_I6c-H&X^U$y8hrbY~DO<@&#i~vgrB8LcD57_s?8HE$URC7F#ZuUM_fp zfL?n1B_?{?^+^CSlSf7fUX#QRf;)o))U3|$89<1IlI&|%nV#8uv^dzCL zAPQ{Pe`+ay;aoKEXNV28JgE8XbUqCD^T<@&%BuSF&b3!*={ct>Vq4V}+B^Vzm9XL2 z*90%!KBybvK`0>EB{BIKxAD?{*c&24f!N@*=rhxJAw`UXH`gWuzJg;H&%F_1GSer0 zJ_ZwPF`kl0m*8*V8fHo@DZR^S9Z2)y-u=e8IZ8&vHTpCK6|8XwVzk%I_OqN{ac^@c zEMoO!5-rKR6?HB~o?L_ zm-D+YG7o!V-}tKFbMs^0ClfT5*ItIk9@C3dP17T;J!A2{|bc(jil>KG?YJ(ZRk$>8JEHN8Juxy-x^=&T<2GLGF*&TsvF)R%#y#3da^m`hA2at_Z<9EZ7? zC#wI!Gjg5Jf6IrPFGcLtPieY&Krp*Bq^^hSa~_CPT)OzjYX+8Z3zyFzs*s82W$YjQ zX)yOdzvho9TnZjc*clmM)GCVq!zTAUlV03?HX5;yYMG&`y7W};V87tlx5FPjhI}k( z@;(u;MD<;a;3WTc6 zXV4%Z0L!2di;WwPe$Yg*l0C&zQX`{2XoQ;Y*hn@#flL zUs2w&DBj<@xeBwfzwySSN}oyJHEKOLohNFvYv;YV+;`#9Yuwx|czg33Oe9qnvghaq z&mKuF_j2rvNdfS8woEFiLDJ87P1n}kK#P}pj_ZvCgN^OpL0P9cXT!u&szsO=Y zbA|O{c9z3Wk8A1Na?XSPnI+1)B=MDDpHCPSFY#SNajQa)WKr4Piqfq5+!_{^Wg zJM8jgEq4~u!=4>4sO?z04*T~LBBz!Y%flU}PWh>AbD~=MEa&_okBUd=bE?`SGAS8vNrqnosYR-qBM(QR9$kG_|7xRV~uuOWAjmNG_VP8Gx7@7;S_{b-pZ z03AWB(Y-kLb@B{J!J}&?YThVQao`Aq@a_RKE>P$l-8g3|WB=qL&Kb-;D(#F+F_y~A zrZA(lY28dIm1PaC>5?^Rbt;((1`etceBWRav8x_W1j$+Y7Roj)Y89kqGIu&r`YM)J4s^Ha7%#ua&*aD|=x4+Mdw|et!SZ!pi zsGafZ-Qk|Vm?g9(b32-bkB#BHbkEG2Lv6!f+DUsP(=;}1MrYdnog<&u z<^Nf->D|j8m!PH?f9dmmp-@pkgLaJzXcbh~Jk48}R;Z4?D={q@O{L$Ie*!hYK8<=Q z2v8n~@nqo(CDk37HaB>m-iXjP>nxo5H|><~yu5Ity?U6Pd6iJ`nBu~pa2R3X0_K@0 zwEU%)^Chee4ZkUC<$Q)?RqI{jpSp;QM5nog!yhFZ2h~!qi0Y-UGnIgQo(O4whAB>Y zK)&Lf;v_?^9Tsy>PKK zA1b{`gPi4-=jl>Swzg8qFqGxYuLl^3S_91-Oy_u7!cyeiJti;vAMkYTFe{+$rz$kn za)su5OK7G~*|$U#w~UU-ffgZfpG~n_MJe)-gGtGcUFo-`CE6ERIGwR0Jl-}VC5c?} zdAkwi54*C`tGoyN&A+KuIwpA<7S#K1n^)3iB-N8<`Cm^@NF6){N@s~6RAWIHw`BrK zk6RS5J#+K0Rq9+MBTp2)pZaxvjVY3tq|mfedB@9@5ZUwWoansSOv{MU5AgGwy@9pd z_nM3_u;=GE4UqLzL-QgW3smsgi9gAdf=nR25Lj0eIf{ag+W&rja|eH0Re}l<=1j)f zDDyBE+)?NF_|pGJYV8whvi7Tpffp8sbrx^7Ya$l-Ke&3HB7kFN;-zb7XHC>BJs7?}K030=G1XNX}voGSIP=Z>|HPamwVG_fgOdI43RTOPv{Sg1uic9LKsmy3-Wy1#sxBoay#J z1)mxVx@S^!NHNHOrq5oyl@Rq!G}3$L-qjm$S9R#p12-EcUTUh-Ti8->fK5`^E%=+A z#9Fuu^$WT!^Ubc^WtiCs=^nZ*=*{kM31V%i4c)E$=4%(3O*xqrH$Y{VZy>W?UZ$`I zcMP*L<8JBWDVz<-$pE+(tJ#qfi8+gSqDrUfD}y)%EQn&<1SofC7)RTwwO0MX{p@V{ zz*jS=&$41hap+e52CDPO0HGsH>t5y+#0Fb#EXtdxkI5i{B`4_Sy~9b|Ve()B7Of{- zij@3Z`Arf2{$Z^>da~SZlIU|P$ynN6aGSIx@6~S%ESnX4w5x;}mS>M34x@J&EPV7m z8LQ@k$~W>Dy**%J?4ALjmz1J$I)0ug?QA}JELA)a_gp5OR~Sr?mQWS}gq%u(=j845 zjy&d)P=+To|Mi=A|M-_xi`_WI&U8Qn;Zn-pWE14&v$XY~-0z}k_k%e|^CZvC7#kz! z)-zn2v@Khed^0t256|C2kaL1*u_r12UhXm9S*z}}uItUgs=lLYm1&>j{plBiPwbMX zy?vFo8IT7P!>UXw7mW2-$1WdluP#HzB?EvNim#{Gyu+45mjM}~jLVO8mdQwp%>v>d zUv@wgTzQ!|R!ssIR&-~{`GikeyyYw`YTXo9a0++8M{sxfzm^ki-oIEDu_><9KWUk0 z=DG}o+j;5>c7Y$;4vKE(wf>s4{bp^RyzYZ)tej9B~Jom}_9k@v+|GP10eK4jEECC>-UvLG@ z7BxM5^EKz^;8OJ$GCR1AAeg40Oh6`t{dxVziuJKv;{IuZF9bpUny_|ekEP0q1TF*# zv!*cU=I~w7>*;?jZo25yy*kj)%Ky%8z!QyQ5+aU_szoFw{g(Ng;_A?EJO4%L<@Ki* z1h~pg@5L`@%;qRB=iTg*m#){AH8mgLJ!?r9uYb%&5=^w)y|(SqZJbx8^Am0(wnxY2 zY4;q)URL_a>*eT7{(i^tGv_5XNR`{Y^Nzm&8Dm>b_~y39C;i$9%=(BcICaHq>gwbZ zL-y}CemuZE4ny3RvzGJ8#buZ8Oy=HNF=TL3FS>;B{KK6#Si+;cd&)M6Lv| zv_C)x@<=K{lT`XHy*T8R+J`}tSX#mmlT?h7Dn)JLl1Ble82|^;pfdZ=|2&2H42An} z@KO#$DGlNcfVzk(b}I{zIQ@$|g-1_iS_~nt5yQc*lt^GuM+rd*h%lB=dsIspQxSOS zrA8}N1Cl~g$q;Y4$<}2Jg$>OD4>XO)zkCyd5@UXIlj-+uydI9Zh8>~j#Yc z4TA*&U^)6G&(x)uG5VDSgp_a0u``xEvFOBzcoS9bA(Cd8GRz9ZNllCIy3AgZ&lfua zp(txSCWS0c7}2^^JAbfF+X$x5B}XOmwUA^>#p0{d1bwhvKRkr`umJBcmJyJ^Q?c9# zU{J(*ia!m~m4^shlgS#ExubG(K2q&c11uoSYC|g*PY~3bbw9BSX5$8&We1#iF`0F+ zs;wn{pUr*ogfkid3)xSP*5~5+B{j?r2m}-knPlH@4M3kcl@AaTS{#iqD#j;$J3M^uVIRVGHaVb9f1J?)$kwAr1;t|>+ zHzVqlNCZLS0P&1;_;?trHx)KXLTiI$351gSM}EO2oYxpEfq7~CAMF14Fgep?2Q|-` zlq+4KVT!`l)af#JN{SWAi{CCoJh2IbBb5h0qf@=69g&3v$`gmnT<9#%Cl`(UP$c6K zgPeR4P8xT`vYf&Z)ue<;6^>2O>Kawdc$j9v8Q4w{LD4A{(k%VP8*!Qt${Dl%A!zjQ z`fGCnb^)k0A}X>|Y{ZuR!HAN-4U343;uG7_C)btxYn@>6`KNKcUtu0e%DQ2z}94EUb{X<@MQk*opxxi@4QLi0HeyI2F* zq4MMu>TfB3FMFeQH4dSBrhUme}N6x~;)I41nQcSo;eUS(@vG*A%bhRmSJH9ky`( z*@wAN+m}T7)LO)9%(#MPPS^$0nJ(uQI0bY;`Omf!E$1*D=PEh7@Q~oR-Z#8}pgi!| zS3W;}!{{XqPYtm7{sqa(AbK^5jr6tsF>z%~XsE0S*&goq)6 z?Ph$>hgU7h73YQbkK>^J%G{3PL$0s*i}D~v9j!UF4{scB-gIg^N-h3xqjB?qcgRM5 zZyk1vUajyErEGhG(%-ik>R=7&$d0}%b8_T-Rz;`!T0~uYp zX{ofQn97f4Z|*Z+t!w^tzxl1H|93t>Bo6#H_58W6EC_3vvj~C`7BHtXl;T^aG2Jew z0<&alunDii%U5rSrkmQ!dlm8=PqqGd36CLK3M_Lq-K`bV709%06XWj>=Ni-jU22;t z3S+Pu@SJ1eN66oWM0Bv0gL1(YW7pR>3*&AVTohm*Ou>!{2j@YCM{cRlHrdJ+htBq0 z2`kolh(TwPEAi-{1E{pv4Y`|n)QiWqC*yjh%g#B7|nA7BC^Oo z`UeQ}Rz9iO`P0$S&pB?>7BR!W{-OM5F4}g3cJ$`iWcBb9MW0nO^*<$WZL) z*yl>`z1nHRo>^w=4}k!;miz#CC?4{QMF#DLrL%VjF<2cxsG{$3-J<6N>y$xGRfFGruc>JxC?hO_h+#mM zVo&Dl=PIM6U-WfERRdr)OVO1K7@VTbo~33QCnQTi+!f)V@jw1s#?ytH`M0YX7*g}O zRd^+y)zU8}W{LHkd3(WHN(i+*Ja$qQE_VbKPA`8f3oNXjaijuhIkw`6kic&2S!I3J z`UPHT6?q^7p_2i3?6bHwDnCkK=gqfxl^Sv!&hnBXW>eHQ5zB#_FPZ3+DJ-759U`!? z|N4QOP)udq4G(NU9?SeknG)AR@#emxb;~ zCr|Fm_%n^axcuLZd{t(*{({25MXs~qf2B4YaZw)d01`_Dr)~J~$hzo!=zYP1b0_a^ zz`8?i%5HU5FWfIr&JzD@f(b%EQz&vUKER$0O+6nyqfWt?+D?(lZ^Svaf>^rq5U_9d z0#>&0ql+(#iiOY^BzMYSS9RG=vmEgX&BN1 z;f;Lcg)Ko+{Dy2a*A0EEEr-yp5lNOc)vczNVtIB-L4uW0O-gm5FS@if`^ESUMG;{{ z7G|KE24?|oFASUuxO^$eU5_di8v8P?R_hw-suFk%2HG&dYQC;{M+E z=hk8)$$Jksw8mr-nz{&>rS(;gEGR4-0E&A)UaFVe16BB{$As&yYBUjuWKQJ>~Bkj?v*xt?RiCe?v|N{s?dKk`p+=- z2V-FbBpeGLzRXw?6m3?{-Y35I=JKAd(7O&-llM;wLPX$m4JQ34cqJw{PaNJ+Y~&DR zwDQEHLw9d)fB!p6K(D6>NCfu!x=Gg^lQt|8toX2&nQ*n;oVdXlz6zZKaOVBGmsUjo1OQ9d_es6*BjvxF$u>LT5fGaoudEwC%)bB7 zdrco^PS5`6we{`upH@#_`$A#180GsZ^w*!#T3LU&UHfJI9V*h{E~9TR7Hyj!OmANd zCQ;lYB$^77_xsAAp=m0~*4qP!r z30`RWNlHlFg-suQpAtkv~OEZj{%mbOzCJbfqs=nW-76I@xB`;h#(F?K97O-8S#I_w;C( z7mzJy*TycKwIFjX`+B35*^|%4nKCww${t^q-yh$aDOT7hohMCyzFu>+UT9(Ir{7|; z*Xt*bCo(T6IqVnkK_;&InGalwJlY#S2{O-*7FOGT#1Z^uSj%att(pUUnQk>U)LSM( z?mIkSwv_AqWy#WhKe?~F6`CyL(LZo;_@|BAa^8dI19Mk{I$kok;d z5WFSBklmNn;=%0jBvoSY`^<;Qx&qA~=Hh?woQIby*mw1i+VWD~BJG4oG5Mi+#@jl4 ze&x+2#b@?4N!L%0CNV9Bk4B1xqpT(sD)372L*;4Gbwg~{j0~0KzRKv5Lh0Q&IS={Y z>zN)wJ|WeqElgicmHXY}b7mdxe$!z*S0sNZV`%KaxA_?cyPKmh~6}(nOZZ< zbvdl>%<8^SdOr4G0!LqnnC72o9Ez~}ens2Uj;$Z9qw=jM61ziTiGLzsEO*0!>*qu} zF?cBPoIs;OSviI#viEyv2aDxM@c{L?)%@wcye+xRv|Ggo!aPqhNx-QBTxn&ANb7WW zYip;dh0KQjeamh6RC38C+=g5NG35Vn_rI0XkCq!Ojzoq=>+s_RwNLlVlns#{`fg$o zCIq&om-jh7HZ^i{v}`%VB+UQF(0JJy#qC;2$`J`ZyuO=bvy0lu@Q7%JTrXMXYUfD^ zZnn*l{Jwr~Ini(Q=casnn1lp3$wDGAAGImtE_{2Ki^t;(CN7=yha!gU@XtD3AT^l6 zL}*dsvUHEPg-e(FQQc*5bK}boZaQZEd@JqVJ zv<lr+#-4avEYb8&P@LSo;X) zlc5ScDE}?4_HOLv4UsvAl#W8RqJ@|9{3Ir|B`Ejl*7u83$ZIbThLJJaH>{-wKD=J| z&X`={3AavZ5FfJzp{;=GwTJQnZH922ybOfnVgt&3;@LlxWb3C?abJ212rpVBVZA;v z^eUcR_napCS#T3z=sh54uLlG_{Xx6h_|?@PG^N zAH*?~2K)96=y@2w%P3FKV+jSgaeS_-v?-=z(Hi>1m}p=SRj|$yxD8&@?QGr?G&2Q> z>R))<6y0flH7VNSn$H;^^=|C7rwGweftiSS*F{S5-QYBtkQd{bYn9Glb_oI*KoLPD zFlQiuN0tMhz$x+dPQc=@B}3yg5ZJ7{yQ9ZC3y7T+q)mgJA+M5oi zE;0F<_mrev^F-QN9lR5CGsm;o7~OQi-iomhWW^7f>j{3tQWI_{>*C@1$!T|y?wf1R zw0pjMDbVfGDyQRwNTq5%T4U2|iS)zy@9cX@F}XXIG6!N%_^Z!fy^Kg<^#g!!e2JYO zqH$YchxRSNl-J}$BO@cr{KW8gZ=7p%GZh3#0^JC*3s^_TAd=TM(SQlmfcDDh(G@&v zYV~NoTCNU+qCF$0zN?!cd~7GD06mH!v9ZYfMgBDMkNN5L87+?5D1Pl=jtBU+m1bun z67w_AYx9%YT=sSP5f5!wnoW_E4bU6BF8neR1L1D0Iis;Ep+Iz2CBwlHr$DHO_ zyge_j-oud-#}d!XySCz1z^jd$qC+Q-6!DS{o{u&l$0pGtFvr^ zzf{{a8h7&Pq{S@+d^X2b1TzQ*Y{Z}R-D7+DLp&Z$Yj zRNZNNcbY(9`MBeg+D(iWDlzSyXSC%zNU5Q$Vhlfqg80F+@Gidl9=b~U7<6RxA5~Jg zH)pA->Yy1pA!oAeXqa2yP2u-tvVG;jkW>VZx%|g-Ml0}5mvkZyZmrzToZ1O(emmOKzM(4+2$ICX8`04$ChS(L#iilIM|eaxF*_iYE4&&y+?l zl(+pO>t_92c4KKVYc;2FDdf#d-?y%a8()o#PDE~0RX60K8FbUG4>xd3*CK@Ol7#vb z_sl>lY=r@Dg?yE=qU z;2O@2a#+?G!z}6JWEkZWR(}j`$Y_hev=8Vw8`aqi<2c`z*~;0DniX3z{bE#`4Wh^; z-m?rSiGIud{X@4{^qSSMWp1Wd(!JcuBF8o7F6K_(o?W;RtqJcst@_0z+v9_F@As;K z2k|i)vwZtAoH8Mb`Zl2?lzlzpf%N!d3HztiQYe#sFOYNgZj=C6G45fZMP}9qnIWyQ zQkPBw^H z08h5(&hj$tCs82){YcuPcV?^>cuqyL&#^oxh(Wf5^$I}gwbS5K7Ecbx8NX(& z*sYSNDQdN1y?MMj(@_;JfF3s4XZk-7;meF!!6b`qFb+XnDI;D*lIE#Q(=!S1R7hL~ z(*hF0_9H56I7&aiyFEu|q;-I2oyH}s@5@uB;qNp~NOdV?`INMF4AeRTq|!-r&S4O) zW+k2nK_9usc$kg`%MN)Q;;eOIu`qSYPUo3V7V$_JV3{puB@uNZZ>gQM+etLZ0m%(C z5M{@9kx36d<7F%qO5O|l_U6BC1_`P?J=8Cl#u6aRB1| zP0$qt(F{9glR|oMT;FQSO9B)EsIc2cro%^Yy0s`}a+bBOShJ_Fb3xRNDBV?!Hd1lH zt<4L$C(7E}$&a;@A4_3iY|sf^iRxgPvnExpURI@u3)RcR8Q54UH&H56rb!bhV7d0S zTU1a%q)TT)KBfMXXBN7EU5qz*W(cBYJ3e}VonF(Gq9ss6vn;SYUqM`@ZM-Juf8@(k z2Q-laKY=>cvscs1AOxd)Kv%`rg-Mxm~3BDMUVjM3345LG}+0(&+pwTJ$C&S*(} zUlpsJ9Vm<3eio*B221`OmbL4bAi8-in<@F4$@E`fvZpIZ>x5nj0W@9&Tf4sGDC?-0Tfd{A*8rGzzE`Uiku=^JptJl68wIN90=XfRPD?Hc&Y2$$x~5*RYf|`*oU9XD@GMcw(IqE|g03L1l8QMC z7GvAua+Su@dSO(SwU8l4@C5(V)HSaAuH)2m!NmdZ0=r)zJ#-xwtIKSi>zaj@xY7o5%W8j5ZJr8G@m`2 z*n>DSGJ}B_UHFIIA49JUBXF$b;@&fox8uArZ}@g`#Ptom49l`_$7xfVSgqbBV>wE4 z;y;9>B^VZd)UcBt6l>p ze%NWba%AZ`lcRQ1FW?|*blUy}vqKWo6n4?^)!yIw(CT&TG?ydl+{uc|5u)~Gt!K_dnKrDxW>?sx5$mJ!HvIR zEgDAbzANSh2S`>8S8X_m2)T>OyNlg`yM8D$ z_m+n1K?;)ge-HI0AAhK3b|@hW{z-8d9YNRsbl38Zx@1dGrPBN7K>dp8m2x5#u)?(O zH4Mp%ZXU_@9tm^qI+s0lqCx8DOT6bbAmvWNb0?UZH%RZ5yY5R*(;E!xFo2Ic=-RJM zqZ?$CG|4~iQ6{@~*Z+B1vj867A*;XuDm1`tk(YggmqXEKWmk|~3PA=HWg`@)unlzE zC%DSrbiaJlH&^lnH>Go=5`X9R1DELse-98 z6m{9$xw_?BPazhAA3M6Pqjw8f}vT6f>ln8II)FFeEQ5*1nemx2Gyp zKB9 zlo{Yq>^89Q28MOv*%?=~*$v;i+7iB&cA_Yfs0)~L=pC4X2w%T{Bc-;1PA z?<^~P=Xf9`tUZXliQIW5C-b32h$Dt{4GonC5TC9>gBOY1Cj>0Q-552{ZC`vGqUUBTR|z*^By<(w5`gwE#He5i1#r`A1LiKG zRTr&wo(M2xI2Fidv_W_*?9x=voP$nRWd%MjUAwgF*j9X+^67c7!08j7z9rAEqE+rN zhzKjh5)E}m5In1*MOUM0w!usR!POQZ8_W*J^|X5XYor6^z!hOvFFQB7=&RT$lN1$p zk$w653#{#z)oh)fYw7;LNbx+=UOX#bO$u$j(|N=Ia7IBcD@0qOqdjPZfYoS$6A{&N z%|&M(H-5`BClA`8S;3ErScCiBkNL#J~&nG zVRdM*&vUz9^5^k#|6NCaO;wH%6S2H|R1^n5fjriJ4X~x#z^s&Ql*DR4?xvE#4+2|O zAz`oY%J@amG(BxwfAhs_sg{|D3qPyvc?m0TRGgM5e6f55+|^s5|z zpEEFEF6rJ7LjHH}&}AU!SU*_HAUjmJM7rdsV@%3*RFrdA*R)=rn1=6nYSIAW_99EH z>Uj!?O$!zMF0(g6C|I}$za#KL#L*U{J|Gx;&PQa6)?Teh zk9~L~8LJvrSN77c6;TAKV@aOBZA)QwvyH0IV6TfoIx;3p=IfZo`uhkg?@N(2T|r#A zUu|A||8u~CV4Rty3(Edc;0hDZ{`hAw75n7TT@L`bsw(uJO`KM-$Vf57x9l+SJk9q) zP<{_c`G7xp7XFd%;p}ag2%mrr7NkKXw{KOJb;oK0Qpz2J+OtV%y995a$N3K`lovbt zK3#W<;HGOnZaH8{aui*8#%JsuC2aKXhN%=q={47K@`cj05;&I_J9MZ^usyFb<^0wG zBU^OF9njdlU`eGc6F`$z=#vh$gw-+h;H~>ZDIqhQzXrRATEzvbcY`$cTdhF(IJPE6m!zY|r#Vq=M1tm}*swKf3jkmX*{=*b&{E_9f*Gjyn= zSyZ3otDTl{Tf_O~ZI<5rw#b%!G>(lZ7*;o-pB6)k}_05}HEeu|I)~ZO#xsCyS z*ub(#%FDPYeTgi3vqo1}ITxsLTKT9#nR7H)@S&8vJ7FJoy~p04>gt;$d0uqs#<9SP zolbO{p2=dhd{GjY)n7KA<1eprU+kg#Y@DKIVm|n8jAkm%Ej*5w{3XqtXEAJRN#8&J z)>F;@WWw^?Atzs3;mzc;34O%dGdt4YTCCf|?+e#&`8tL;N8&2D5@dW}1Wvt@9qTnG zuJ=c9OwgK00_JIZTd~==T}*s*_8m5uVg}uX^$<~rhY8R9D$mmRi*yE4621l5ONr`7 zkQnKKvl9+l*QA?istQS&k?)(F)EfoI*)*uIF}`v!)Zy}0O6VXJXz*aTbJH?oyxCw1 z?L)=EtrSJ>-Nbi-k0*E{1UxqGhe$@x%Fy)!r_8|<*nW#yT`;ISlg$Y z(c}`7MpseMar1qipbzIwsVcp|SStle)!ZmwPff`W3Xr$`&sY#cl}Qk2=CRw?7y*KWDv#; z2A3#@{k!H#H{iIGz*X?7w-g?+Z2=d&$6=mA$I=g2w12C|WL+%cr-Gl}n=37oO8}aF z9J*ncBtp;k`0K+fe6i9Lo1q#uBD?VNvslg9XxE=jhRtOVUf^t@ayQj_AZ3Ur=lKZH zk!VOd)ZrQKY}Deex{$X+c)NUK4# zo(fZNs1k`of8)a}&p^-F4kS2+^-xPeu>f83`17tu5P?@ft{*4fcJn(-{M{t@aY@Qm z;GqeVwR+q~NIG|iA*d|}X_kgCV8(ze$eLpGTCT%c>jEhGBsZ*@>s8e&CAvI|?>dj& zCNn%E5{m+3YqbX=FASO{$t~?~C%GZV-c}Q zP6oMzHSuHr3>hv*kT6C)BR6bR;kNbpH9z@gh)n_gRkU`rpwQ37LHAa8O_g6NHWlh| z^0P4rv-1&rfj!F>;-nh4W-bY&SJw?zwv5XP)j!n?_K9X{A@l1ik7r&Dn)1)+Eu>nl zL06!mL5;3MK}MWIS&IZFoudrNU~2)p-*2PmeK`5{58^!%pm|~6^8U<7UvOEb@C>Ku z@J&Ipwy$zEKV)W61S--S3UcW;i&8C&EH#ulH(SwDP6qcEI}e;0@6)A>2(DAoY08?- zzL=cD%b#$SdAdOHIe3^m4J?d|V%8##dp1|fyVK-F!!`L0yyc>%zi8mjJina34l=6^ z`A9AjxmWyXB|i+$EF=M?oF6GxI#g7cq*>>DtQo41iAuDfJ0K}2DGjo|G34o1zhHT@ z;B(4P#!25Bt=Z-vK}QAxQ>^dzPIdp(s2p3#8D0i{+eQ0{b??3q2Op1j4qLrJudo~C zB>5}uCGZurL6hh)kDa!l;*K-#FHD zN`8sZcV}))NZ2G|EZ*?2i{EtWWf$iu5w1;3%kmJ@dQZ*TYQ81#EgD8&*hejqc~X+) z+Vh`{^$xJ*P47*qTKY?2Mlg(i2^4r?^mRczn?hz zN_1}9=eK#5St2KW`$JeDN z22I_3G4yw@bLQ6ar&qsv8vFJie$x7sE6e1Lj6y#B-t#e8F~{SF;P*He?Tv+`Ut@lk zcnP*Tn5u?5lM0uP^IW=TwLY;u?-v)V{$kREU4#0_idXvE4)M*;L@QU}nEkv#dz0hP zC9Tk(fi!#T?WcdV`cJ&gqd0R?qUFMI z2Xrn+^^tqLt8}8SKxq{Jz@WfDqyW~Hri_9uT_N~YflWHV`kixTt{2u#RGP7hzwYXm)J-i=P^&$WW69 zrHB*31=47|q;08a4nee>AYD$FXfK$0Tp&9`K>u4dPH>+QaTj}qpHg(lNF>UI3&<;r z%1ziwKu`a(<%etbdhmy3IlB%ev=Eg-$+Ll7$#%{<| z5yaO;gnq55hIpub5gC$lRFB(GPxH`7^XQAf4+l^r{3*QM8(M*QjtMb#J`pxXAZy1e z<8xObFdlG9Cv<=lI*6oS$1&}SF@D4eqBrqMo;sSFv}d2o^$>#nT8{%PyPWG&ocY>l zbXXefFqIEHus<%uO0#M8KD)3`<4xFwRGriW1?FU~rfEp3{udtUW5;4vK39UnB+ zTs5K&3QW<_UIIkCETttZJ3OyzN*G^W6_}3%y&Amsk(*X#x=Z52yDp=}@c<%4h5T8C zh`(qnAe{h|E~ZQ@lxi!+$kAYz!;TIu>tm$l$;ZnIa}qS{VCX#FX?I!g6-lPfeQLzZ zk+Cd@X(P-{x8Xt2*5_3HVm?ns5MKlyH?ZW~mRIA(p&Ib66OG6*lJ;-XZ_FFaApJm4?OEMqEfY8u+5X-Gq!6-$i!3jv5tP-F)j0rPk{0n%t6UXGI} zHSZ3X@xl!Ykhq8CdMUhZgK||BGF1|jT)MB!78ScoyP2lKq*7kcZZ%3@G7dP4x?%-A ztu8U>=>QDkcej)Ft1vK%PcE(2c>9Ik2PHlqnVPNM07F6Ln`xRm>5@J&Ev4!Bcp377 zMsDehib1N7PxjTFES8Ow{cUg|kdG-oc0SP=@u6;ybbjyhmoP=aJPJ5cLsu0XaRoeZ z`2qUGGtV_pRDZoK3$FmM<@`P+Slclg;nUfO?9$a6hr>9ag= zVvK7$gT*5-+`!5^wL5owECKFY#lUwG7lO49Y4WMNyi_t?CDi#x@0E~o*&*!h{>}nb&i@fqnNkzxri-zDRL7;7fbuPwy zp&-})n&}KfChJ-`e!3NaxQ0eQ-_Q8b&5pyX1`o0 zf?{P0fPtvtXGo&-Fr{mKNX=8{Ey3$z4p5p(>HW2=@I(Lurtp%1BmaB=!!iS-jMC!Z zQRsUsERSLpvRS~ocAX&Ig!4tuwfvLqp9Tv7SZ1NNrqu+#`8N%5@T^O(73L!akkG{U z#1_jyQd`wS5#pRs{TER=JXluxjs@OOZp^5@=cCk{-7S?2JT6Rh>hJioA3%9Y{6)@T zwYu6X+dFFD2uaSWh*5(VdhzGiJY$!s)7LhuURdj|t};p#(+$)OKUw3o9AAv-^{=-w z7sT3X(nX=Dbk|1$j&`AkzGM)cBlCN^;?$84so|w{Q12J1H+;itt3$j0z)yB}9!u{r z^*Pd(J-KfLLrIFw$DJLPpm}bh^tRu?Usw(e8c^ks$mK&Ai4k0+3kkoSn!&GH_?bmNpdn1bYD{Er|z%w!y3)rMf}=+CNh88wEXo3$VI{RM3^y-s_b&4(8PnG#7g3Ki`atiQY_6 zKw}IUboiD97>695-<^cU1i4#fsYNywEC%DeDJsN3Y1FV!(2;34#mAE%O*^3aN1}cZ zWY7fM>W+l4t_&EBt*bFyGWI^_9ISuD1$qMi=uL(N+^? zC79fh(MkN0p7N-aKkkA+)bDVsi(f}a`Y7B*c$?zSK8{g)H34{A%91lkv?;KBIY&@j zXRA2q+!q|h-+Nu+wnf+7L4Zc{RuIZ5x6Z=NT3%#E26vRJ9f}Wcu_RJ@Tj;D0DHZ}F zUPpm4VniWu#J;}OkCaFZ6>qE%8`_?ye-0Zgm=aTL>Hd-HCfoi|*@W*P@XE_SHyAPf=N5R;=3@;#c2wux zOtvV&Z|!&MWkabHL_1yj%@n6b{o6)*f4+PNYy={og3o}5v+F*Z*g^h?s)#vYpyTuN z$M@v%RbO!^yeRePdneR#CHu-ooS=S^!<%u*93E@_>)YcC@*2TyNle1zO`;sk3zo&H zKA;Xyl4b){6P(F^$_1yyF_W!(Hbd* z=_v9yJ8Voyp1l*HUwjdcGrxZiN2T2Q6sb5IV?JgPDQW!xHCD9)J=(_KuiLh#-ZT5Q zbM^QZH<2Rg`22(Yw(PcFC5=ry(1>z;)7EJuG!>~>e)rE| z^bn~qdup;EUzFu-tA9s~jcAe*ksxVECxLxnv>2A7kREAPMqs{Jz6R7cxRH2;gxVa` zy`vhWtT%$R(|fTLltAGl14ZZYhew@(GlMtyhiPzB9T)}4IgE51w)e;%SB6Yl)yLhD>e#pL#2ub6qq=Uc1=7{NSfR~aS}N1wNT^wJaNt7gqv+j zah?uU%-tAodi_@K5Nbivaq}4@$0R2iv$$23LH7qXVUh|~-~|6YZI#}n<5;B|qU#=g z+;c5Ox3e;%JvaJ&`J?3jfPsk?iT@Gu@99wa?~4Ey+BIyC~AJdD=*kD&D-;Ff{OJ`8&Pr6p`11{C;_BgYo2Fi%AH z((!*HC@75QyK#J7qf9`$NpXIWB9JxOy1jq@VsiFPF#i3!&P?u~vt$4CU{L~0aJ`hL zk;wdCjx0{qqYW~{pY|xYZF~s^YLtQ#8XkQHAj;Z<0w6H#q${2T=T*IPf^gT3?L;tM zZ;iFZIkIcq`*FhN3GndLX85`w<4Lo6icJuXcX?=Ge4X{B6BBMe>wd<$AHUy-$U9K< z@6zcda8Jaj^1q#fSV>Z%RRbV!EHt^<=0bpxmo%5}V#e^vfJXG!a@%$#3*aM2%#Eo; zzn$l8yi-XR-0%L5{^kYGDOP!u`AbD0HLK~m=ea7wMO#}Ddn)wyPWN4PFMGSexFkk> zlPbAchAsCm`B^kgbYNyw`LE`hi(B@xC-JdXiCjzgul1K^ipYFy$77E#eBZcuafb0R zk85NOpUame%pP&A9?9)pd%V;AvEa)aKsU7(Co#o?If!n&@-uX7vHttlKfCN-q>?v& z|9JP1bv2$_<)%;amG*A2*Dvid#Pqde!rwPyV;&BYa=uLe^xDykQ_M8qdM(e4XB{Y~=-v-Sdi8QN7MrBa$V4{}W>;AU z_7VwRg3>E;pj}zH%%2P&RV{&y(3#ALYEZ^&_DrMfP3H%9B(zD*Wh^rJa2P=3Hy8o~ z&;eutfEfTcXaxX(odZBH0mG)^!6+Dqv?H~tWGDt9W?ZnH!lx34q<5a8HkXZ&xz(P8 zdk2?~r=zdeIF7eeOlD&|CJKx$R(Nb#`5&EKwTMYQDm4d?KII={if2q z%$W0GtF&pMMup^vW=f4s3AhUi$vduk+v@$M#%Z#n{zJ45$?{m^zuJ`^t3)C3KOMJl z%}~1jI=FJ+ry(+jjPumV-bhM{utC<%)CR-E)Qf&B#a*Erak&~g+-BXaJ86(>F|soC zOFnbYJSL0GdO8B8MC5dyo7(WJ`OOvVJ+F1R`(?dXZ0My^Zp+QB-a`Io4S5ZIl;_!> zKGJ5x|9w|HoH(z)!MxPs*@%W5JDF+zeDm(BfyfXa{f|l7MLBlKTAChAimzNlr}*p())SO@+_%<==K4~fGm?0{W)&;V zLm1E<0-+xjN5wsuRm%)f5dgVP5mP1qj-4<0L8G}-ig)BarqJ2uN^zL_!>r7J1+eRs z!T^GUNpVs(lu5oUOld+U);LrsKlX<2PDRem8Y#to%s8`JA_xuad(8I;IWJfkzPlCs(oQf;-%P-o5=a<48= zjR^vOAKrFu_c=CUUtwG~x{v{2KNJkxRP;l2BKf9fbdm*_FuELxcgBT;3)|+%&`>6o z;s^kc_dZxuAUOE%*4-NV7`c1;zZ2^-E)tr)wPIN}6yxL?haa1=Ys1PWWLl`~_dkY@ zo$vkkDT4l=nuILt=0)KUuxOoyi`xFlMhaZw;tStJ-v+_3Rknd8V1Q`63?WATbelFV zh{rfDr4ayPo`LZyvxv%fhOVt6nUCFa>$MEt$^Xc?*YgH!3drM7m=R?Cuxv!DPoEUf1Idvim!8T6&ax3 zZZ)3&JNvKyOtP^FB1b%o;{>nL*{nugi16T@E#6k?U|>F#MD{YCvWWBzP2W`V#wGig z^D#~qV88u`DN^zG3bcLCAb6vnyZeBI@mypWGeEFCS>vKSEM~b+9eU?F#BBrdj4ypdvB&m5AYo1WbnNN+8_l{(8*#>f?L=fdqaERlQ1Q4zz@4|yhasI=p z@0#8nN~MR1mlDbZwhYHKmzu@jBBJ53m0jAMbj-e39lo|=h)RkGvkyX?k9(Y|uX&W3 zY&FF9b|Bh&_F8CeZK+&H*x1##ih#v15?h)%SYQ)HAFw(E7rYT;)PQ4dN~n;%Wi)BO zWXbH~I@HLHir|#3V?O$zi@dahy~cMO3A8g)dbTN=8kCX8ep{vP1!Ic`(vjJ>jBz|2#SrgmLL?n?wV?rH*8979 zvR8;-29w6;vbuj%e0O7)OR1c=eX|};NAqSr!O;9SSVlVa3fz6HmEb0p-q5VZGJC?R ze1DZ*-5js>;qArC{y0PdvHFHq*<}kQH@N0Bj_t&2{Pt-iGY(Z_|8C-KNB7TqzXcq^ zejs9@#3v)LNe5-9n^}L_Ua`HgX6DZZcv6+&`qZq>okvTs#CC{lM$-*7g8-L(S*5>e zk7FaQf}(Z-^y*k&7OctAT;8v?%D+-=vOe_6i)(m*yT3_~=7jP&cpyVP1uw|=Wm&HZuZ*ERrEBg=stC+2}z+i)8 zRIAn)uOJLrh%-Ps@dz+}u?`W^6eW%pAselhKKXC*)4$#9o60hH9#s+86@VzBvT8E? zPG&Emg1V+Jw5 z#P7W@!K5vnjHv6pvk#bOlMxpdJ{wF{(^#CfdRSoah2r^8$RYqN9j>(2_8($ z7MG2zQXT6y78%G3rr{`T4a1`am$G7CYo4Q#Q@b%mV=n7zIK#@VX4Q1z7twnuV zmV0wy)`~1`#hkj;hFY91`lkas-f-82nR! zEc3qR!i%mP6kuA7&GhaKhbsQ@PF*2wwggYtC_cC^bA`;sZRhWZp2?HY+Fz#M-1!}} z7t}`u(^lW36iz$*P7+Bc9Of*++l!0)ZRpg2Xqg22Huaeu3GA+yx9yPH;(&f+DF^S- z*~JeB+&ipMa{kyqryozAyi)y*@)hJHR?+(5RSSam1p2i;s*R3H9n?ThMO6Sa?jE{j z*QQax;PUTRVIEsfw;%bPZA1l{DV?kal(7)2aOX`p9?lH06yXb_yIOi|X{ea!@7QV% zA(E=&tI$MH&qfWtb0$V;E&z&$mq@@StY3wc+Jx2u^O$mP2FA#%FMrZ#k9<|O@uOj= zNB8}v`b_2gam#(1O~N*1h=CB5@sy7L?_sy{p87NutHWQ0Ca`bLkn&}$D;?B&R==LC zFLQoWANX~=c%dz@OY7gE^V%1lx%j(!=YWz0RA;-|>))>){X2fP#ky^9?erDgX|6Cw zLtq|3EIZ|&wddj9yw!M%3NRW3D=~+t?X1k+;#YLy4d;h*NfMG_a8m|^ZtJHx$q2%Sk5|3FZB+n8u$9&ub%V22g&_s zu~#1N^gKO%yQ=^3zmHH6&V_3AAjV~Lv16MEXjlX+CxWpv0@nFtOf8(RR5;is?7rgd zxUENsv_PU;z}UT@wihB5JOqIpv&o$x5#I@DAPsa)e~a=7L%nq$;y^=BaCF5L$dcK z1;0Rzy?D%E`FJ#2q;frwZJWbACX$^%OZ2HV05pS6qC?bU%CE=VJ5ehRjd|D^6OPt= zuox2oBS)Ik>tk-lb$~8cKn79pHY_~+{Ft1Aj7?LIO*Mpf2F2#&#O77ScFe>UdBZzb z$!Uw^XSQ+A!{SPF)Y^jL3Kz)@Cvm{}xS%L_1jaaI)q^F5ytBYSafSB<#rB`XQPdNL zZ4*Yr5~w)|6JZGtImoYI8Q>mftA|hSZDt%0L=STWxI62SZ>TYLpq!x)nqNU9F1*2$A-O0&|!#8B*O(-WyUd#o9ZIlCo}>A zTZVe3m0f0;VM2l-;wvn|F9VtZR2EDix{e4%kje*OR83y_4Y?k+Iiodgxe&?hxWV7LHUF>qR zc4GfqjHO#mr@%7WQV@kw*nt@aGbs`C-w8;!%$lye%&-J#b7pyGE`4xr7B8T2mHvJZ zWcpr6Xf(VJk^UQ*OR-C48fVw6Mrh;~Omr1YF{JlPrE9*24-e3bYtY{x0Dt;&TMGp) zOUY5JE)a^$?mt&A*t9FkuR^rt7VUK9I&~$`9pu8L5XI(sY$17f$?SEx&u%c}pZ!kX z{rwDBZtM_2&gAh_jeramr}+C6<)e#6V%Z-{A*MA-Xw#fmJ1Mv!`ipAxVJP1x23E_t zIsIJ)^lT-_!+4g{6sGRdobBu_DFlG8YHD%WD*119LIt%n z8y0t@j(8G5|9I>Eg@%_*NdevKY8W6^h z427J&>}cZ(|E1@F-B}EF2wQuEKQ;Q9VL69J`Q6h@3}ad0cB<+wO8t~kY^^MMqAZ-F zJZ|@y()n(tR&{A40^nk9WxQ3+5LXeF7mJCkxV=G~Zay$Qao@!_W_?$kNV-!qx zE`t#ALl|f#acHtJN>?)4H{eYgC^JpejgnF>KvhkSj$eb&Y^!`ttny(i#4q`dZ>6kE znW$FFi_|jZ;FiT!x2y_~YBBhwA>yZPcF;q_mH1Zm$>;4KQq2Aock-taOH-f9)Z9(c zxEBGbSF=}dy0DSc^DM79bhlFg-qrfP>zi>`45{l8iB!mja5nT!`#G9gi}|Gut^82 zTO9LlmY+=JA^K%ZD7_!xig8o-OZ8HJ9|Vs>|Eh66!=ru{CN`XDKm6Me9jb*+76Ru` zl(}d`Gm|$4W&ewRt}ojUW^4HCP^!~AzzApecyE>7-W7CbGTXeSx6VJia3XugH@$@x zSCy?XZqsGs0L0Wy)Gtp4cBeBc4i?Mi3N|;~G#%$~@5}2QEfC1N&p29`6H752>_AOy zfUZ6WnlQw|n|i4q3)24}CtI~&Z6>7ln@<{>;-fwCSI(yQr>LvHM~1Xhn`(>mq}X;I zPEnbJCj7@Id#6TW4&`Ykj2*>RS8I#tmpZO8vg zc)12*WsF^L?vhFN*m&}w#_Ps>wqMItr@gON1_vh{Gp8LB0?s?*0(&Xw`q+#h1arkS z`P(E`uBh+PtZu+;f6uI_IQ}~Wlg>&i58u4`Uh(hUevQZF0;#P9ez|gcbM0$oz6H-N zn!PDTPR}gY{868}u-Ed^2+qiLc}(niRRUGCZ>-;L{$9Ylt-9H4qR~jJqM1|rp7uLY zxgJK1>0{GM>B0rHKzm2ig5w_d+pn)}#*?PcipFhcpmG%!g>TWm71;wy#%9{ggajxKg-_pjJG6_hphk`s}Ucx+7-juC34Ops7Y+~0Ofyqt3JnP!xWBZj8`{vK$ zGq(5P9B`xrWf@ zI`_GhYwmD=0%jRr(p{1H z#l7G<5jav}E?=x!np?j7t{|+kR_^)XxQe{r@9@LzRil+RWV&{Vi{|(9F33E6P{KVe z4>%eLw&%h}6UM&(ZC%rShx+@{vA)#feyK}Qsprj7u?(TDr*CzA%yhi(`UICBy}t$y z`(RjeB`9t^P-Z6Z@r0BM=NNo}Sug5Um&<0XYTs|#mm9e0_kL`$>&qnl{M5Sb@dqK+ zmLILA==<)*YE2tzDk7@h#*1jcI9~s|vPd~npSr6D>D4Z?RvpJ|E@BO@f7xJ%3Q_w6 z7{|@BmZ8)3g7OhtRSH{u|2A8#w_pTA`7vWxl}(S#kV&Z|l2%%C28p)3qplK(;X4tm6(% zLg%i;T1}_A* zOlD6c|6M=+vpD`sihGxY_YT-5$9r&h+o2Aa*TfXdcRpu#-t)zCoh!bMpE^J_@u0pW zr|NgVV)1+hnMCRWl$ZeR%{*X}{VvQT(!WE$e211l;0wh4*YELP0N}rOhVc0%1Bp+4 zPp(~wxjE>q!0ba0eR^U{fOT6Mws^IR8?@+(}o-iyQ zzYY3d5{`e)u*zupuPe!18)9(k-Otr=zJLU1`Xjz106$kh^QZ8?vpn2c1|OiI^!h0JyaSA zs6Drr!txw1u2VgU{RNc3Vlj<&6cD_}sZgTXSkrU(yH8x3d!1gPv(bqP4G*8uOVE6W z*$&SrkE`}B1KaK1z{L?z<+0NNM{ms!mbN^8(KUMO&+yi#PQ7;BiuhlD1^o=TzJ0+% zp5VMHU1R%ZO#RSKks=}T6}jvz=a$ZVbL`5NTKs~X={cVRtgWjbjx)X={tTu5q`2Oc z94ugj+V;H_(o-mXIJE%Pa#-!qD7-3YI3@fcxll_}gWTrJjDNznn7@~>`eEX_-MY|p(OaPi?qkw}R^Yt?nB@G_%T zM_)aIog!m^IrPeE{O!-xkwv}kk}|(SX=T0{5JO^Eng6U7Ws5xIp8MR?qFAtRIueBGEA#~cX7c!*28wMf; z`Km+6EMv6W1tBildYu_%>ZU!>zaXq@l06B?`~;N>49+q+7MSiiQRtHMglFS-umCI^ z-V4z2V{XZ`{4aJNjntW|YVEK&j?{%m z2v)cchTrXU!%Jt0nKjSah_vGy>`L03)8Q2^U+^>m-FRx8H~}Q8x{~>ABBD^Ypag`- z6j=wW9YiLkicE%y)Li{-&YH1$uAs+Ah`WP%RHbipO;qir6_1f$oTj1mpD|+32v^Uo z51qJvna^Saq^UZ*5oC~}(;o~PtUw1kY{HPb1;o|;JiUbkn(&dmSs4-2&v-DxbeRbf zP;1_xA`TB^=bpS-=o6u&X|V`Gn3IObkfWljw1T`@5@=PQ+s-MnSR+Ri9bU)R3+b93 zW2>2NnUyA*aTCDE$158)`FeO|;+d>PKU>7}IZ{)h#pIxkpnAm~6=6zj8~thWsyYIp z(_gX*H<`zS_qtEjcQn@}z{t5KvwPG6{cC6L=j*m!zn`pHR{bwXxBngW!k1o>jiBKy z`bhk@XNN)%Z(raa{N=tZxrkKnue_@C-`6v?se3O%sR;AvTi4gunS~HB1vJQ-|dGhwT*58V`f<4gynHPf&rUP?@V66Z-xAF$_#~>-Dh=YExL7p1~ zB>YS}RO~af^5Up=*0~t4Oj0}4bZte&V2Nf*f&0-lkVAdtvIgL>-}nB|hc% z@l>SIv-1u)h&I1$oVAavIzf{(PDf%KN(FAdF%?D0l(8aQ{qrt1uSrftRm0i^K>rlC|_*+7#ScG;WsvE z+*kIo;DpJ0*%!md1_oZ-_*eRVE@q|r7g1blV98V8LDc>bj}J-V*d6~Oqq-(H<~1JE zdTkfSf23el@?6&Ze*7hgW}b05BCQ?VkmBR#e4gLA%EDgZnr2So-&V&_yhiJ#=4YN5 zv6I>$hZ15`=hi{@XnHufEFGw_u<-FH?M2r=)5Mp-VO*r$m)Jq?hb2+(!Ir@YOEW+I~IIWJciz) z@v<-E-^~rdvmBMnwwrp+!K)Hy2W>DGi2{7LPL>J1ed(=7;8O`wQd@XK1ne?z5&ks` z+GA*n*ty&c(Wp!nij%@#=nIpPFMVmSOu|8*i6y{Bq%n#re3N_Rklb2AQi&~)mLX!+ z941J_fmEXQefbZZ;3=m)Z2>xE*)wkA5oz3+<6+GTy{SV_%nl0&OmttrTeUQO!r|L& zLALRHkf-;c*@XHZGQSBCB5+Lw9D8Paz+5p?=yKJVRQtL?cLxVk@f!AWjgj5eOA&A& zfwr~*bQ%YknD<}R*nP6C3XUQaXGCAYoipcq)gb7%mkf=#Yi1QTt}Hx<77us?>5tO8 z%qu^B^JR(oq4*VeNC~y=BS4y4Dts}LXe+yjza@8RnDaT1CKoBD_=#^NXyKmek9Pi8 z-HZmoFc;e9HTlztO~9mB%-zj}8>i5BnJ z|GFBpfA=78bhF7$!EEe=^%;bS@a>+0v7==TkPn)I?`fsgm@2nFc3Pq{Qt-o~6~>qb z!BjHtfgW)1xj@9( zF0h*W4m$8ZLld)KQ9V*P8#L8#pUOvTXzgArfRxu*}u5MYLRU9 z6p?v+fxwW8ONTm11Txt}UzUOTmO#JK3olvl)pD99hC~mH(^9#JSJj1Uvl{zHORi-0 z(6-~m&<4nz3!*_xtYHSSsg)gC5OwznDeCP};`*D-oq^xyXRs>zEs1a$e zq#J0)cY=$DtLm5w@C8oN?mxbdH%D5SW0wF~tNF!sJwPQA^j~@5*HD>ovn)LTObD~}G>ua`AR&DRG94@V{%g<{h zqGj{*+BX=wSdcnX#u}!K+@&>fWNyw~K}Uc!MX0)XaCc`t$PfeGJtXTySH&H4MuTO- ziHq6Ywg|t1js>M*G=$u?}tL${K>7SnxGnu=Q40VA+X2NKISx{gA%^Y)QLO``{uvD*v z>i(JvNT}C~nWe!1()PxT5{7QIER_T{^aG2o%E%@%9M%qpb}=+*v{G~j`}S%26Iu2ENRR{L0Us5#BI`a|L)uz!kD5~7F}w&$RO?zcTmE6N7T3-H!CDnmo_f$bHtod z=Isab0Psn#S$m2~T3R3jNfM@9+Oaj}=7kBVUs=8YNa0+bs4F48Q{y0m5W=jo_tx^5 z#s2G(@QST9Zq9PYF^(jw9_1DB$dcaxU3w}tJYvl^`fznnZB2iTxCw`Lw#xz|?>Ju? zHD7V+hngZq`os!&KPb@4IcCzIQuwaPDv(~}ZtQ%RM6)2#dl>>87~ft`mzhEKDS0S; z@48%RmWAC7PwC1RY$yp}sQwLdLkp|E(zYkAwfSnvE$xWsGB(GeBNV?l{rU(N$ox$c zGdAWsEDgmZXI&P15bnluA<@oJX6*`#@feyMlj7Nq=WINP=m8(XW&7$JJI_XhC4gJS zDm@!CMxF+S6K5=KD$@IwnDUZ}xnuAkN!AC$vtrr4gKhUDmmkR^UlU<~HEWY?lnzm# zw>^J(HOV-vZhee*f7 zu~)NnCq!?}jo~ zfBN-eYxaZ6Syo9 z&Vb@Yavj%RGyeuInfbpE%XZrX;W-by7naut!FUW~3yWwJc?pzLtTg9gP76B~VX zPK{mRcFTu==#o3_g2(f2YcGR*>h8{`L;n{pl_o%LhCq*m(%um6nsXqY$9vq`;lt10 z`zZ(ZD}fIIEXT@Kkzi%pVaSo{+S6TNP#_u>(bNCm5PlGpUP^Nz-Mm+xM-zZI;Hxol zeP>bm7>jCR)d|9f1J;_GDVnL;sCM~nt$m_wHK!IIL7h&nTLsPoLVfn-I245obg+Z0 zB_1>87Mb<}#{@0%GYT1`k|ZeMkpOy>`vDIq&HMcjF@> zdEm#gdq7A+>(}u~_*~D2#{=6Av4NW5Ad3GrslQZ0zkuaIbIzFD zs8gpsSm17Czb?mE^s(%CFU%?y{GWvXpe%i7lX_g6VP1V`KYvm&<$~h+_#B3ORn^2J z%1ALK@R|ux4s#ghYD!gZr|VBNk1H|wU%*y(YR#)_^%(V%E?R{>ULzC(>BdMrnWoL5 z$`-+$*FO^7^Y}kyruEjkkgo83qE9n&@5C<1#aOzW0_$u*j;394HA#4MVZ@h{=@C^$ zI#m_vUuBY3?%TqGfhAe6k0-}L9J~NR_cgvgaI<@^8if8WKHx=O%KlEtl zra&7S`86R+?P)+buVjhMRs3Fh_cLT(6rwm4GHc(~Dq!nTB9A9!bzTfys65WYND5U# z55n~$o0)IY#aDt$wbr~qgc`*$PEmMS`u8qYd~{gW*FMxSxX_` z*XSC_3d-Ud`u<2F&14YH?FzZ`!u~~{_=}!gTw-zSZkvwu1H~2m_(|}g#4L^$Aye#u zo8`DfeDa||NNf19`!9aHfwrrm_#AEoVkqIinsRB40$*VOXFM1$^5&IDws*f*ImcDL z6+#{cn*$QxCGTpZR)2mL4Gje=yuC4YXKA0I(c}!?8sk1Y`@bA3KIex!^2MpqEiYx37acS%EijWUGic`I7)|Jz>bQmGAP3MZbCw zNAb;Zg@|34cKI*SqdeN{j>QT@v5^)sj06=MT94C}PBqq(a71uOJWH~oj(pZnE9rY> zl0n3!ci*HASKoa~%5p9(Y%{8vaR1d$by9U*ij3i}Z3q1$<=F6FxSHvs9S}8#M#Ne; z?KHNSSGzqH(2wi#k*dXEAkD?5KMgJyJ8st;Iq_u{*0+&@$vkl0RuiML z{9gnzEh*@@#LG`#ANaT6;0X1e`$9Di=CS90 z(E{1crEPXSVE=CWC*BzffH}u+k0_^ZqkA*Q3k>2pv)n$~Exo4{Blt^$2$-bI`)ZzF z4{eHGC^jDbRP87m8ND!B*777`sto#V?ciR{dp34mLXCuaN*8oYu({1?n`10 zI_RE|!F0FJKR#(Kc0Xue?R^&8UT1o8LRH z^h7?S{)IaTwX;LJY5td>kKN@DQzHp>=x=HX5zK_+W#0VmfQTo`scW2|m6L_z!O$d? z6W)^%HVtF$?S6ibd{a5RhAffl=%uZwCST$B+b564EkZCqpP>A1jyk+y(KMdP4=%Cz zWz4uFN100^wt~8QlqeV40Fn4a`_`ngpsv*Y-6v|1-0-k0wBaNpTe3E7Rl8p(#wF|K zU|M6o!Eigg&}6s~E^X3j_+HcM_nt~gTfr_|E^^TDF_w|m*Q~)X`=wgpuD6t{btOLW z5jIeQGU0YEZHixEKXqA&SniZQ?*ynLhqs`}%sT>VK$79ddLT@Bvi{1XG!bwGV8bUK z17SW=qwrXd7&*$FSVbUTb&g^(qZA^3YH}r8F=N`mQT}RbUY%@1UahQb2+lJTb+Vh_ zAfKG6B_kVCvID(wr_4Z6`Z!SuA|4puFoDu&Db4PjxM^^`^E8C}P$o7$%uXz@L}^Kz z83}RKUy8mbdF=I8+o^%*+{0h|fvUF84pTes>D~K0{GZ;)&cm})YFAU{n@gOjtB+(t zhz;YYSPpPfy)MW`;2P}R`H%H{f=O7pR+-XH*$k#83{$fUBw{E4c22b{f0?6vQn!-5 z=m7+kUvXdIL>#{YCLhi(*T6Q&kvD$Qpe7zUNy+ItyA3iV~dpe0cl`RvArr68k zq})>Gfa|IJFNREpx1J{~uXM^KPZ|u!8P}cq#<6+V;2;%1EX|RxM_K*g1oP3870xLH zaFM?4VL5VsFLh+(;_(mpx;y)N_f}7v9p82;$mjdy6eo1y*N2#H3Pd_)x{YsRZ2c8< zv*ldx#Ae5toh&im49ah*tFng=uW88N%a-*e0&Ci1az-_I%;M3GD}fu<29ptRkfXvC zfV`1n4TuwhsaWg%B?ALD_FyP`r5%cL7lN$V6=_L08P^O^x<~KFl%=Y^)aBZ=VV6_QIKYj8B%EH^l{J1>RV`eVxV7P_a7ps;;R3eg zEfTaW-HxUBdBX;?X8V2(pX(d5ZsIj}%%^i+vMbU)FnDg!Z_*ys-)a#Y&GyfqF#FC3aFhF zfg=oppfmXudGIc__*8)yh4<{r9}L|*V+GzG=l{PyOYqi{46u9zhmBxj8~_sKB_}~2 zF~~5YO%)JEAcE`Ox=tRF?-My|*o?SILRgfS&zw*9R;d`IiZ=JKBZy-%0Zb-xHX-k& zj;hMM@ucQrD1T6aDqwDV(o*Sn#o5(WWQ@qTHd48ccGLSBe2QooxS8z|>2r94;zlCX zDolJ|#okozNXhI~s5$M}3Z0m^zeeVJ({7{Ar}Xf`!tIi_ltZ_@bAlt+Y0^&|u z+*5cO^jz}5O?jwU6byu6fJVF~B$n{BYm)CS`^QOKN0N}6JPj2q+G^AUml}#wGp{3q z4bnv`LxZ8{v!cEL_Z7Y~Q%5@k1oST?DhVA;VM(&v^#?)mk_o5O0FP$bl3u++r(#q9 zt7vGlI1gNVU&IJH05=7TzV;=FOR?7)E|{yVirzb?wm&EW*{}c#MP&T%{`Tk@BE11_ zndvOjNu>K#n4_YyKS*`T+Xv`E;enP=DKYjl@0{4mb_+FhU-h=r769&xJBmKuJ8_g@ zF?}=gx#5Ezgu6R6$5ZuTv%|Hp{G9WWzz`E1q}!8#ajlQ$&xd9%Y%VM7(yyuTAB5%0 z?DO=#=g$nUBCEDQ;2fVdm9|M##7=VNtT@0Iz(&U6X%oSvPlLH1Co|R!^?q;5gdMP& zdy~f84Q*ZsNK4NXt4KEP2K*-7UmtRW@-ugv6a}K5Xm*lmA02vY<>u{~uh`EFf(hN; zXqpyR=B0KSD>M;C9RiV`z$+4RS2CiqXX5vNl-`OL46UaMfd_cUqGLkB^3tppUvUg9 z3#4b34?S^?P6jOS;5Fg-+U)N9QJS=Ccn}*g&g|b<+na8u$`-j4@GZ}i*MJQ18q={ziz24NSI5S@_WfwO9w)SI8ou#LWx~lI4Kl7c!PGW<3373qw3DTm5mpewAt0!JuoHRu;n945 zO@t=+OuLneRD%NbR2bun*RL%xM$C0%C?5LXuTF~;zZ*7|bha&8$u2#V&BPJCHDuP+0ER7qV;isme*2<9{_RRg5Z{Gm-wUb`-Fh319^ed7+S?%1QKHh= zB*)>;OKp;ke2lXOuF_-3PB|dkJE$r_$k_{G4J01ORTDkhF!UD^Mue< zX@4TobdIW#L6F*BX63%77fk9*vvsH0$Z)#eG*u5k!^8vScvO8eCBwK{L-mNf`fMYj z?ReN2Ton(R&O$KQx(ED*??kOR80ymdk`hW^LPL4Cm>IPRr8lJ>1jMF*P!=T>#!lr} z%-@B5mA?RKnF1TD$IsZ`n~wZbQR4wo8+=U?k%VmFN#awP?bn88G!s9tsSnK}o^l6@ z2c-ZbgYsluXV!2tGW`Vk6oRPSweDH?W_6_0WTQ@NGsFBLs^^ck6RijZf{j( zgr3Os5CBBv{E)K@mL#(+EE^N~6^3{!7uDWFSSrjx#Q>#4SyBihdAjgu@P~zEmK#PC zHAs*`6Bw${gJ*|ae_oqh;qv!K@^;fw5-nz_Y|TH5-o^^&V_k-=>Pi#sapUrq5P%#T zYE}SNK&pqK*5&2k&BpNNP**aKBAX&Aorcr)r;`YPEk#M97pNnQL}7NqNza-If3z z0D7VP+Ck=%CDZOPJ=-d`5$!cUoj3qrViFQpf#_`yX>40eysF~>%hM34AU9@+2b+Z2 z0tx`&l#n1C8P!igw^O=HC>P(JxY5&mi%yaFJ}s4o+{kbzQ<0yyo70YcObY@ojw6oE zAZCo6MStaF{&s8%a+3V}=ty+T5eH8RRxxTs3?MnJQGm@2W^2S#)szIZjNfU8+8G+J zjV03L{a)W`A%k1kruW~QH-fZMs1kG*mSF>fc4!t*HRB_++V{Pnzvx)8J6bMX`FVg6aiv(`4%u&TBpsMcoptx&DUW&)u4 zNy2LqT#ieT1F+RngfSTfdnpASsX~ubr`0$>=@_6`5aqP0&_g-rhmk^iJOX>xiM1>z zgD#eVP{DUR#_&@B$&>$?&1(AOybcu*%bPX7)THs52xzy#xmBSCDO$Kmev_~ObeMiF z?BHP4k*hg?n#iUQH1Symmz2}{wQ<{2{cY;V^P>Koq47!j4J0> za&mIq)ef9F7Xt!-JU6I%@!8Ytqi3i1Y)MqPARFAQog)E#w@-+dH;{6uVid1)viYh2wHRi=qdEylv1>1)Ujr z61z~~UBYq+;#59KdP1RtA}b;!DC)EPD%i+#LU4s0%!hCG>ReGcef8oo!ye+-tU0-D zyWA!IXdhqGmIa67<#BX*41?emzt7I2l>avu93AFuDs6{r2dQDM$>Ux-@anJstW3|y zcGIO@ttgC_9#3!KH#+|Ld&|TDN2HWXaL^69SEG0~${Q!wq&Ewic91`yGVDpyM)=0Q zAN#6D(#P>Y`V}??6;#a%ss>=<;F74Q3V1LdBb0DPGv-$B3iT(7_VX20X7Vlhsl!Rw zbMn&5chr2{$#-gUwik?_`*Z|e2-A)J4m!v?*LK(3q~z=GQE&gS(PiprPE$2EsG8Lv zgJqx;jHc<+qY1(DeFAC5oYAacE32}V6M&j_EE$ZA)*wi?-Ivf|1Lt+2O4!OJHk!O1 z;id$Dj*ZCwaPa@};Eww&c^$SggQv{10Z7>5IvaX>>u>_#l_5&7f%x4N7sQJwUq3b|MN;BPZ0ULTdu9Ldpzto8H;^U|cR(L9zKqkXW-Dj#kRi#&XOe~g!)a#NV5&iBa(1$=Di72F-~;z* zMzV2v53Xe2#`00Jv7?cZDphg8NZ`S3>qp)Cem4LovY2mxXQs116rms7shhu_qcP2j zvxA_Y#*=-71jsS0F3hgn4VH8m;3$e^pPN0gNF*wb!G)` zi{urZ8DBqp9xzBVYqk#o4_tj`9x};pH6TX4m+^fK${wk)b`XjT0>$0tV;q{))w5`N z@M3dUP`Zb3?Xd*ooBwt5S5YT^=XJ2vN05r~^oxLCjfhm-YvpXee4Y3&2LA6x)#|sb zc#xMM(l!u1J|+H$MD~1{-k%*`on`=|$>Yd9-c1NHOSV34r5A{TQG{d8Joo`B7&B{| z0_knoxSY_}rw`I^-5U60^VH$Gt>z7bc#wkX7~@n0FiGOHG`Q+d{Pmmr<&*y;Tn7I$ zsJ1ak6;B(#9xHFFY>BtO|53D>trmGzJ|3uy0~_GL;GdZuI7_1p#z_7zelL*ppRb0- zRfM7c_NRP)l-kLc05N}#g>|2ePu|u25-Q#}aq9b)`ZP{&7FM7WMz5xeD>v{1WiD5| zmE!o_PV&+)|Ab9@uUYY4GLzg0s@s_719iXzzJBS_5BI$Q`Nj;_9Q8ypuuuHd2;~o-pu;&4eG1 zt-DOs`wr5Ne6snBg!>JOUZ!epYbOr@FbO~`jQz5kaudQ7&Y<8HsLSwr955Xh=`lLP z*4_x$+qKavI;jJYVO$ic^wQMjMdo8xZU-MJv&+?}r^Z0yEKY|hWgStTp4xln#O`;M zs$h*px_-~_*c%i=eR!DU78>*ips5OyGDD)s$lHTJe1)i43AfhpB&VMOc3feb25png z`?B2R51(G1ETxGS$(qR!sP!uRGxbG^pEB4+V|D>qLS9DK2 z9Pv*+F>~E2htDb?C3e2et<7OHzy$jeXgN{!dFn^I_bvSKz9##rDw9-G%I?CZSc}V} zVsEkjdh=v!N`<0S%17rjCg%YkSjjmT&V8lqWPVjpc$RD})e^Kxbu3Y|KEF49O|8SbFtCskCViu@5giUIFx49;jR_jX(-9`i z8_G~1F{L3B`?kxru%iNN15;c$c~VfPpE2j4+rJ;`BA_|Uq25ruAhheKNE7i9m6Km6Gs8?zE0yt?a$QlIe6#u>^u3Dnc5^6R#cmNrnb|2pWiQ?D3jS1r!O%PFn z$WWw&nHZ+j?jia)MNrRqr4gpO4VVyi9&fgrvzM;CU2bRXv^MAAyc1brN0NqC=-=#7 zsr1H6+b?)J>7HHic2E2u;d#8lUebD)Xj|eNOgJieH0G&^uYcs+ith1=HTPMN#qQe?Ti z#Zu+~$>glt=^;0Hd&wZYXGFf8t3gYJm&30>-hH=~mNR1l9`#p_Ul>vmGKCPCc6^!S zru>d-oH9V_u9-SI{zBr!OW$Y#X0^-sti9B{@71VJ{b ze7Z$+o4<#)II17{_t4?)iSLU53wLhN5F(c$LVS0qVM0M9>Ve@4 zg0noN8|zj=m23{hHQNh?!rn`!0p`?#DMvza*#SUIu>OI(80VQ!)wJX4#~9>U#D73C zNLd5u=ZD4r=>Y~4PLE`BqPs#yTGDJP4AK>4)lGgW6dyfuu%Zjgl9Ym>x`J zK$oBW6cg=WP*hqFW&B?HR|-?x>x^GQwUUAm`B^X@P>C+fqMtrp8@RtOS5Q>|D_3$u9n?wDf?;XT>$TU)^>L4@ z3+BDfvS5ILZYbS^3zQPS(fBnx$0i}}c^>}H8=yy+7=DBub;q0~IV?fnkbz#_ z!fBuW`z7yN^9lGqD|RB}yE0`oZ9>fw#P2*Qdij{8miv|Ag?DZ)fe#WU)V`3={-di> zKOT1;jU|lVUR^~E@}LIJtlTgWsz^5e{qdbz-_b9Uw|x2|1}qH5^mzo4HZsPbdrzkh z?nyU&dR2$~BHw#iDdsFdiSOdzVXRiw?fM@pDwMQbixdi?4uF#MtP6ONT6H^CGF$u0 zY?ehmDCPNloR?=>V7=ChJT{I`ZGg!i67#ik!sLtg`NW|2GgR7d!-sk(0$ge%H)%qG zDw@dy%PlLR@3v#^;A9E{M8**3i4XORb8p=KOyGUrxWd5mxl#`|}BSPE_cCeJqu+2U6>Uasd%{T8=h1o;fN?*5j}w_hcJ)qch%J{r#dX18)nk z*zxV+t9iJ0XVLppPnN|Vt7q@OtP3?6Ari;FO0_XE<%yqi+$PyY>_J04*dM`yaG&~T zFtVz;D8SW+dh6`Kx2roNzTsR45rXU$4dk9%S8(Yl6WpjvK3AZ!tE9u!?7-FESyKFY zbJWXKN7CwCu1Q81lIjIhKz1p* z@_ckZI;oKGZzLorT>HFP)|uo$`zy~lvrL==E+G+anUE#iwvjcYF!Bu`E8}7S_v$+PRyxLH>m}O<`-)v>`SDE zffXlze|tMr>*3XH?0FU|M0%&Bb7@e?z`)t&i^Su}wRVl;ChU_Dcj-_OI<{9!>L0ZSdprZosTPIR{SbFL49XH+IJk(G7 z@~L#y{dtjER_ljdiP_nk?GI}mQCOv|FHA`c42|sp(H!Zp$C<&Dx%p7Uz6IgstUg4$ zq^*0hiK>(hdxlsHJw}EePjSDJ36wBX0&EDuMvJ!TJ+MO3Ei6G276;JG&U2k?0SNQZ z;GAG35iSNQ`04!WOzYlw9yYs|%8y<<9hlvMyw62CGz8LF{uu4Wl*!D8@S(<`6rg@r-|NMMV($*Vw`G>J7d1b zROONhyG%qTfPWXT5krs)nyMu3+?XW~w3g7(IsrJXfcwHN!?Q0k2-jaRq}pQ^Hk_!2 z?rmJnxn;80A_-#TzT-o$3kD)0fg1@FiI7cH%nB-q0N>B!3jSdrck$*`D#B#&D7gV0 zOpzjniBiLm_d`+9B(XQnX?Yq?(6;EJ6|tETRFTp(pFE%w-6P@g>iS08GT>{sny80P zAmgKmHmvy7hi}-hf2IvvJy9jtsQ~M|vJra}o+8|el;Db1z+#j&oXBrKpo1I4NjH&u z0Eq-v&=$XfH^pH1^h^;>Jt|4v$zdY$4zsMm+tQ7oe_2{)M%K^?6X(+ zz(k33<)zT6wP%Di`FIJe>jfHsNF~H}sPuj`O9CB%Qg~JyL=g@RcX>O8TxTFML-_~0 z@`#C57LU>E%#qrUHMq$p(#Cn*ZKFV}^dG!P5%3SU<2(ebyz|l6TU_C?mb7(TBPqFT zQ7xFGCOtAAusRWxkso-8BJ%(v@+H(IR2eWRDzO0#{g)+C-7x0dfCvtg7U2tRPPTY| z;&OO$;}%qegBRg?2F$t^>+n8bdgLF|a^8m}bXOP>yCS*xT+)XnY4_-ClD(um#d`C$ zbqGPS|C``_yoe70<)d_ZJsSTp`_zKNsS?}MdaR@Y@&Ovx%yh*JnPOAk324REP&aVjg2dBTK$@=|rbQ>9vP4CMrmiTc-a96l9T+kZ*y;qk3UDSMOX zNESAM63m?w(e5z1C~Q0ey8XD6)Ad^phK5r4R-(=FasXOC{F`((X87583j z0CRd?-R5<)jen)hC`6>n_9O@>qPGH{1axz45A(pn?WIB>iY491_cIq^+^cE~BE7}K zivS2AWvBWV+VdFbzG%31`<;LrXSH?05fuQ(&_<=7;rb~c=f*83L+X)sWycKsA$m-y($A0Y>YlabNdu+xYECajF+hn0??!mDlC=w<*7%Kb|e?lkRWk40T3kZJ(uIUFL z_e^v^p@RE)c*Hy&VGTiyGzu+{6Gm5c0@#ic=MtsP>6JhbJ$NBDHDQ18%p6lcQd!kl zN)>f1TvSynB;2|FSd7yl>pytcSKwnOUbr%BMJ!l{OqE3Rlx#|EJ>OD=eu9NDrhpVF zVNjU3h*BEukQoU0N~}TRJ|1CXe>&RMl*~n6gklAFPl6lmIa!M-N$_ zvri3mOikz&_bL(A(g!d$Zd2QDufd2HD~t}cUve+`7pN8D#b%`}}HGL5_18v6$$yj>Z$h7Vf6#Jyl5$;V>e zthp_ZyDm4Mn#T*Qk;VRCaBpeCsuJCQ!2s!64uT7vL-Bu+(rR zR7{KSs_nU7nHt+nSOOE7U6B{=h`Pi|pY!PIhc{jGEb%ci-T8Jwil>UEUTx6rz;O_aye*T}x1?L=meNxxN&A>kAmxH%49j#Jbd;V@IMVl+w8dfJ-7`hI{pM{GH5W8c7mZp}Zi06@m% zPsHahklJs2D$B`KlFlSZu3->dfW)%ldG3?ya|e#y_JG9%@~>5~r0IYW(&GJM`6ihl z^jQ7#U;Une1p!BH zL7yIvMb2}P^R<7kVKua)d(mBjOI`O12&;?S?4sdF=H_mELyZqXNRRR&AxtX0jZ@~r zpc4JKv~$|6$RHV{#OKT}ViLoQ|AcfGGOz&&E|8|#JbD9Z_Spl2GpIt*h{zQ|NN$cZ z_LgHSlOBe9E3g*7GF-zA1`<5Lj93tNJ@e5ITxTWugXBI3f9~FyzAg{o4+F)qP04Kr z!gS?)8h=ND|0c*a3$q~wq4*!B1X|`jOb-0GyOW8u+$@_wnF8A_!U7lQnOY*q>oO=O zEXAQl7^^Idr@S>b`c1C~3f6fn$BPW>iFw_demW9?Ec9J4%m#(&#nBl^;ul=@WHJ_6 zc;Z2^goh|~=#IUR?ZeMSTJ?9JtW=%MaZ(HNzm9haGl`$j3BZGEh`8m6d-~C7=)a>$ zAJJq%NqPgyXIo#o=^)f+Xyx3Z+ltH!rU6j#kDW4y}8%QjC<{wRW{cuJ2NVk>$=7@x@Kf#L`K<3GVZ-(r9zaVvJ#S1>MIRD zzdzxe$K!k+=e*DR^?V6YcJ&{i9W#9;g$5b??mNF;zM*P87r%cV-5SxPBw9ar@80R; zi%0+R=d<7w5CVHn3R0s2zg(JVlw3a-*)$cA9?v<`jePa@OKY*%_mq!uCfuC*QE9s~ zJ;6MaH?CyxDhMgmgegkOlJm^(A!ZW$o@_nrWJk=Z5xAxS+!p?p#Y#^D@UN8@IgHO) z)t!AfAhgy0>+T=!3QtAANitp>$cK~UH7vo4_^&_zv+g8H3z75+V)8ARoL$0>)xKt@ zU@Gu`-*WuU!e$D1pOiEtPkeZ$mfL6kg8OL^wd57RV;VA(HaH!W^HDsPdwltt)v0$e zlPtgebw7UjF32&kQHzp;GyvtXRx7@2LjAT9=}1V2+vioc-smrRCB<0caJLh zHobSZzO-BswBVY%`LR@`JgTDM3uA_C^!1A^wdlXeG$1OT1Zxyad?Ky;@r=Pg;irEV zM#)s6WfRUzcHi$u%r-x-t$h=avKfa$a)%(muxsDX?g&|LUbOJv+`*=)s4ow3AKEB9 zr5_4fd;xzB$m)4~_%iZA(BZQ-6^}H6fIgFJD&Wi{ZCw6ov2)la~oB%d7K49pQ z@D8;FOY}yHu5SNO4qyU+TuR5DtPuWm=ybpS&rdbO=_uKohFRaL2?5OMUiPD9jF?A=fv0rJAg!5Y{=Q{Up6N(L&=lF4P4bOLkj5;k+_Bqr{`?QOK7a~%#WSL zN7uNG2mk!q|Fk%C-FWEV-^1^WU%UX>Hk33nt~*86$sJ}iCqfyR{&tj&8?E4l3kU5H zvZEQ(#B3|XRd}uH09<-XIWc)f$hJ2#DWAe6GD45@lU=a&jHCk*Sv_Vl1=;MsECNks zYm;(teFsv=Q`%+30DHXA#dVdd3Ox&#tR6B&REKMrOX`ev9sn2c05!sGyopM~+FzV- zEoXL5$W_?!2jz$r-JZ8CAHfWN#E$}`#pv>quG1pTV7|)g_IqG>$-sC3n9Ev-3=IGR z9+!&UQHitDNS0d*y;YmnH>G|dVpg$nLM6~vzC1p5!jk2Fd(*TFIt@`^w*SP?TV)TP zw6f+JMrB(P*eh!l31&I?fuz(ift#yR-sgv!*FTiEN!~tkBG)YgEyKzeVv+c%6*dLa z(PZa2nLYE=Ea^W_ZO;$Qg#sePCuuI&>!L#Q~K zSac4N9)!C9P2OW^F4UQ-kXO@1QjwVZp{H0-|@2)@vNlxY7}HgFN-?WZ?2D zZ&Wlztbw-zkn}Cwj<6wbp7k`s`Gq}j6RoN*2|F?k*_@A25!3@N`dDpqQ5>quo^iP!D4qxDaFj9vd|hu97?P* zQ&dDdrP=}C=<(tWUmU>vHW6QFd1ZAz6)|sf#=gmEipg~q1=g?*GdV8%#=)GYP8Won zYHK&uNC`!fniGmgg^IoY2IU0z2XHdoDO^SLG%f6C!zce#myQPQ+ZqY&r{cFsxi_s_ z!k*H|x{npTfv?AHexmCd?*^-Td7N%!ak?`oX9+;WR300;YA>xtpZsPnD&T%O9E|nl z@G>5M$(@WEk=?0=$k8Rai%@1*@8636IO{DmU~!#mCf0NXRQwGEx9KIY+eL#! zm*_CbH%zXCqxNC3L9dKGT4Mi7B?xmf>)qL&8qVlaQ?Z3;h_v?#hkGwkWERDF9t;rP z-)Xyc#6dbV3o_yXx+Vr(;02k=>y0HrWVPhs{Qs^?Mbk1B+Ai8ha=j>KF3m@LTedrm zTD$A(^Pw>$YxTh(zu;B(VFlgCXFQ=@r6b8M-0aB8hME%|c?F9&g6+TwZ zG3;^cU6n7b9Zv+cYiTXB_`GzfN{wgk-#PmPg8+RaORl(x|-w!ui(X=nO}hjiBoK23kB zxPowAARO_2Q+j9%f#fGHq@w7KVCnc7_-!3F-lCLkS4}dzGo7tDp8>X!_lLPL*jmc4 z;6{Wb+z#F*x(wJM!MwOe)OtET;4-51U-)~{Q!$S083FQM6=SVGF(RMaBOWk07o+4v zm-qM#BFO9tydz@$pWaS9ec78d+J#jBen}cGe>zM}l(%@quH{|B5nF8*O!%sFDn|-X z#IJhxwB+lw@R$7EaE7Wc6ZWhgC<1iM(0|9XoD-hBw&!XKpeL`(WG6?oPT!q4%@b>L zm%tIWFrpB&vhYOz!bTD2=OIFN+^Lk8d{HI;$pPNA%aDLv!yhOSzjO9ao|8u=cT zu}bVI}+6+;!_ujkd zNCHRZxr>Rnp6!n;{Cf5ox*P2$3U`c`&aLLn~6j^@O1op1MnZIT7-zFPi5g@I6qq%cuGmUd1?H3v3KHz7kMvg_=nfv z>GS2)P@5EJ+pJe>B6~UGte5-c-jCE{!cpr)Trd@Khr|It5gS?>6h15&xscw2<*++r zh9-kGO`xWkFhUB5u;*$(2kFqk)zeogR+;j_4wt2Dm3q!(k7u&z$Z`@av>wBlI~`^o zc*DvLOhkt6UA96c+riMeU!DGduhx%?M>?Y!IF%rVfe_w)al~|&a3uEqE58U{@KWKK z=YhB@BiYZolu;QcrOx2QIt3nW64b$%@qGk2+UW5K6r){gnV<|Ab-ubrSX)8vwv!jf zbKeR{EJ*RZ|0oMx@o&YNF356_s60=31g4p2jSq5*miE50_Kazq+UPaT#_Nyc{cFep ze=U*ENE{J#8`~9sz{4}8?tu$hXCSf2I26AvfmZMC4{5mWlOMXngSMc9oZBI8B#=G| zaJAH0ry3&FBgH?TUCiXiXp5Hc7!HI;APF2HSSe_Sv9u(zjt;gWfz$VWPNyErpoj!K ziH{;7NpKtkApD})N29STnS#33>M#L8)--$2G_;Lzq&q{=fZ^4Zr6hq2SQs6ODi)0c zV_X$U<||sPYQ$B#AzP>N+Zq8xs^Hfc(#5UZD_b|NZCO$aQ4n5iu0@duQ;^S`2UA`4R zgWB+DsLv4@1df8PP-{K_MlY%4b}->S0V|dJWGV9L$dnYi01}GfNH#jzWi}NR4Xp9wZrsnfBn3rqq1H6Q9=zbP=Frx`3}! zov>2fPQJVa#VRY!ipHaudLqf40y1BQJtaDJWvY*n2!-+Du7kSY9VKBkJe7M8HYeOcAP1SAc$$c| zB56xc+_nKY!Dd_bE+V~fh;sdV2hxHG3=!S3dj~{hf=OjKpw50HC_~CbvsuD-mGE}v z){SatRf_yg*Nm9>h<_&*9)+!y z>OsFloJ66U1+zQ;tXaZpa*~&!!Xu{@AC~>puw*#Oj8mXD=#qaAD~kP*J?+p40OFdI z6yBvc3V3${01v`pf17fQdp4Lek7?d=X+3MtWdv(F`ogcqeGRF$W$2BXO8XXLQ+=4H z2FbPMNWFy&Te}&0B0&M(d5e2Q5Ox7sN4f?6dWYOBA)>D#P2qUtEE$XCI0Esc6exIx zOT_odkJ&&YOxSt98|_}KJHQi=I*723Q1Tw)Z<9vUikPtS!@?&L^3o@(%tWK2CG}V$ zd_V5(&k$CnPgXEtLG92=T+1xYxNe*FAPf3wLU$rnJqnn6o(&cW(B!Xqu+P?=g$5LA zb`NG*8(@P+Ov-*0VrJ{@j8iK{7*KOz;$Kavl7=ze+`6Jzb$=2y zX~u5Qquh5{FyBiZ)}h=ReLWS0tOV!DcU0{oN7v<_=yxkUgZmrp>C7G~SJ0*>) z>>He5id06Qd~(si<>HM1f(YBx*cERcFdmWF11$$ghI!rn5r*g3Hre@l)7MF`F4~BU zt4_=s|IwK}s442#4h3~eNsaUj(oj}esIh27P&<1LNcytfFq(YV6n|7?dJ&d9tzQbh z$9Jac=eBr4J>miHfNz*`b2}8wqp(A`zY^ZNc%m|5T1bbVRz+2C+h$%Q`b#gdPp)Gu zk{`d@CY*Z|d1ue~ZQbOf@ZOzpWOKCC1$y^g;Gjn~soE~DOA?+{0^^Y$dI1+3!9`!a z`&=lSqvWCO9Xc}YV&QpZ32;|+G5+=q9zc0Jw5?oHsAE7Z2cIvAY{kM-e#?o_a$nj!j2#H;*0Dfe|UKB+3D$gfZ35ideH@7rDvC0WN}IrT#gbR zbkqH&7bE?cIxJ-UX4I1(e4rC^niD8qGDmb4G}V!T4$_dP9jQNJL#Tb_nI1n;eD}uA zj<{u(U1vLcHq_}FZ?T}0F8E3v-kt=iK}>Z+uhO5@n@K;+&;3313eg9RP3e2GVlbYW z6WAdQzQms0BRpWbkXvb)!h-pr&=$f9ldGb&pKJ!OuppGmCBv7g&eIC^dbAao83%U$ z&ZEhK8pR6i!DZM+!Q}bK*VSUWMawFke_!UkdGb5-dITVZToTo&Jagc}8# zogdm`UHhht92^m(@mvVfd!lXTlG^~cSos;j+Z&C1CVNYUutMwPy}^LZpHQgiTg(ls zu16r{++rbjE{`>~5Bzy+$u2EjP-VVlNc`MZf|>83!+u(e^;sFVZlelnNKXnZku{iR z5)5=%VPm!`MQXhezrZm_GOCiVz$3muV3nk*fL{UMQ18Rv<=PVre_nY%FivVc<}yuE z%=tdrIp8mkBui@`xTvDssXVj5)k{Dr4(R+;Ey5?79jt_#>|EyUmJHWDk^dDjkq5dDLnE{J|TZWQua#T-FqW!&9JZ^dUle@7=# z?XCuhg||blGAb^!S?)15wpz(Qe3tJ1B6{x%%LFurV<)<5muqd8(QCqr50lkmv9n@; zn;b*ODkpHgIr^EvNT8EF*O#$9(yOpNKJq8WK|%SOqwmK|=X)_#JIZ}VJgq5ea!&S9 z-w{ci$3Z>`(H?P@Z`La=*sOh)yV}cD_Z76o)Zz*GFB9!fRjnvj;VRm6WDF`=H}+fz zW(eRB_(Cw>oF`y&UneTMSo?AZ3=yAv1PO{}2Rxu22aP>@e|T}9w{^eN8k}Z*0^L>& z^GX5dTEyFr`Ai5V7L-Tte)+tGL?GU~@8{2sYBL9_^ zKRnfr9ZB|1UuT3R_KmzHkzs=H2`ApKA%R~SQ}D*N&#SIoorba) zipjHQY<9%pPiK4_iZ>=c_6}j+%GV*JO!7UmrEk~Vin&sBQl|%p@F8)uqGGK}qMx@R z>ON3Qe^75zJ$>8GR_?v3Vw^2EVYh(6FGjNuId&xhaZ$aP<9}CiE_>RSNfodE_2}~` zvvfiVYc)kqoC^%`Xiogd^~czI97GbZ#0;^&joVj6xG zOb*9ZZvcY~;g<7W*z+IB;#WVrwD2`>JYUvWz+&oKZ~!Yca%1WB_m58*n}|=cR=MR) zqj@|aC^G(>e=#*nXGu9l)vNm*S8~EnG~tw2Pf7tqXGgIqXiQFGe&R)(<4pbK?e0)M zmmTs!#K*Od4o=xA2aeq?M`MzWq=BpV9{dn+11zQ_Jdjlo5^DX$7I~j*NjcHmD?00W zk8g;-?E|-WpW049`MM*Gj#e*0N)7t3Yb>qVgW7D>Zc^&7YTstSFwe~Ro*DYMStnP= zV%EA=Z-*XZA@Z3a&5ikr3d&UlPf)H)K-kTi41$_CBoEj|?2V{kWgO$c>{GptiE8vw0T+en%^Y5xw0%m`9F#IAjDl~N{vms;x z;@5JV&tV_oJXK)5afpxx$1qN1oyLf1L4-JtwkLuGN&pj^GI$Y&YrERit>CBm! za-t_tc(aH{(`+27-631V=n0d+*U|oAS)66N?$TK(YN~18^>>vZsqZ1T1r?IXthzh5 zF7@$@8SVnWTrx|0c<1 zI;UpeMDD}&*eTyUJ#$V+F1FFt{2LZ`Z91Rm{N7QDxqQ9UW!ox{FCf*Uz^1#yY%zj0 zS)oyLkftXGI65Y%1B*yG>L&-{p;(tMTteJa~|TY;d^ z(aN_~d%3l5ySG3o#mUu)TEO#Jh)THct@q>yX#O??y{#WZeE`iav{6}o!ZI)Q`?i^X zU-NlD^wZ^3Ozce70fRvQGgWPcAqzIRfqiUAH@)UXBJLPv)!&vDt_OqKOX_^C#?l zX6GR*FF0C?*>T&}1-J+@R5#wn8 z80Qn?${T0b1?k^nd>TT(Be8 z!RtV+f;N@+S2I`gw-ud26KJ;4%K2JMO+b>9-%%z|Aq|<*H|V8{o5+Fl<;r~=qLJI za5UfFwbUBjqDkQD!%p9`ng7pj!iJnoU0lE+o@i~9(VN!4iV)N7lR7F+Mg*;5_3_@# zA8&M<3{OPpu^y#Q#jGWN8lFs(SWoch^n0;Yma_#TU?^#;GG!`D*z5`#J*cOYBBB35 zLRD|t+HfH38bael+QP=kh~I1yY2@roNr!6K>k7$NDNx5=i(Kwi3|WUS<;dPJ2u+^z zQZV@KwG4gL{8Pp&_-+&QWPj@E2W7Rdw+k}V99IQnzxy2?BHTj4io0)=lDI74H8%g8 zDnNggK_9<8Q12y|sm?3n_7#!M%^5-$QWgWgG@^_d{^*+%&Xqc!7F%X>ul)tvg*T4e z)N8NNR-TeQcUi<)x0{e!D|y!`!MxrC3POil4a)bDrv)qpIs;*iO6+9*BrNN+Cw88X^#OdGReGXs7jfO?zk~KkAsIn~Qo>t`H>>TFL+#GJ!8hJ3kTd{h zT=*t1<=VWZFlS=?cs6XzP|Y*Bc|ZFvrj9c#nltAP`zN_6Tj%8 zuFrI6Km3U0<<7xx)2)A|#~Jz1?^r&t$%$NKa@UncE#MlhVA(E0ccxucF2DWmcAHTD zUsfY}ID#W*`1A9YNdFS9Z|8zKnS2&z_k2CdqkG4E-nb$hgBu;7CmUCVy4WwhjxiNE z8BajL*B_3FBAxnsCiqj0NB^R`Zn^Y!eO9}Z{K0D%CkLbmq?mw&74pl9UO|Q8LTZW3 zrfSmC%J)X?JF^YHX|@Yw?s6P&p8<6GLB@;uk!Y%@cTDe+^u~?jx6QGZ1gOrz z>#s#SzZi5k?R zHM;%KwiJZP9&~%r?}7pwm<+*UyWY|Iu4^>-^`^D;alawvY{lgo9I&~W^axEVlC{eg(H1p7Tev42++M2%_mBZ~8=42`6DSr#f52cZ$ zBx62aoin0lM49%qO&QM=`pfTUc!0&+~EZV?~YXfmf}kdD*rEGHC?vN(dCGooX9(rG-d{s^Gj)yv8rILp?huqGbjYMQLH9 zF3XfW63B*5oh()KixBc(NHfH8Hf9fJZ?!Pn3rGh_m+$7fHS?Z|F*_DrO#tA#bO=qK zx8$b0uVKf3duTmjsv(Ke{jFBL@L^p|_VKjTps}g#;&}9-<_X52AS+j<4|g)G)Z`Fi zW5Rxhmb-0(8Q#1JSmq#2S@#}w6~F>S4J$w*&gQ`pYDc;l8wMOq99E#6kk^BHI8qFj z%j(%X(%B@-he0+WN+%wP_T%ru?Q&WptX@TPdMtnq8!5+5r9%?r8A-1h*?1BG(Cq~u zT(V6D>+N??N#mg6$#Jc_BA%Is#>-D^0T4HUR-T7Km2$(MaJx8K!C5505s;=|Y8!cY zJ1M>?4VA9v4k{q)kFrSy_Htw|A)~@7_PS&j$8%g#w2XDB1BG1{MYo;Y)8%i%DyQu2 zMVT(q6tz90myYzQrdv4gUA3m5w)449gYV z7T0l?TYuQK{s`mDA>&4;sP}?IXexg0B7TnM=Kwhut6^`KW_Saobb4tfv;C~{+8`OI z2c4q5nT8daR6<|_8{q>HirY>7FRQ6eLXO4@;I5D%tD5ei+Rm>kBB%4q$>Ru{UWz^n zK`1qI{3>8D^eY$ayKX6lg7h#POxf2RXKh`=8$8WkxYqkBZ_FV60zUC8cx|0QV3&#)UNr^@`{S0c_-Cn zGmWW2V@sgxu%y(@IrM@h*}-1{;1~$l#{IDg2~>+pV}EubG84R+g zM+DvU4lT?}({bl}wj5p)Zkvg1eqiGMvdzh1N?7OVvd+$LYG6_qX%FH9$O%3g&xr1| z_WJy~<;}f)D^aCB(O0JP8a`WFjx1e{9Mu~4^X2r}I5ci=s@Ciq%KKgKLc*UpBCE?tictP?dtHsyhB`VwZMo;^-AjvJ`iV^WMBq^m3WQu z?}G7B*ut<}LwAsIqxSq{0f-h*=;_bK_8jQ!dhF@`w|9#Vx`acP<2VDW?8@`E*xI+% z70-zJrU!Ms_N&@Y(`TsQbgFHnK0Yer^-DVEJq_`7hib!9j>jVx8b1OUG>haq;$>-d zHcq>$G9w^*eq7taBiBhh*hy}4O1BsoQHO83xizP#{OdWO8dBC+;1%MTunl{uhD2=hxn)Lf85$J zmWX|sKkj^M_e7&lmIq#V@{QfS5%aqDDOSq7H`>%!)~Rr(b@ z=$C|$DOAMRg^1C2LeA{z!66`B05UQYrn3M%S)KMCy9JG@T;<7jvI^a5%qzJN`VCT9 zw@kU^sJ{XrWd8u|_D1?KBe9B$$xVWRcmZL(FghKsr^{aC$WxReph!wpJ!YY;K%o=# z7$DC|Fz`@CfSUS0$P!50mQ}BF!bEe1zMd88 zrrQ@j`SPXV#iG5H!Y6y>E>;u=cPQ#wgk5?>5zh*z9PG zm}TBShrIUr^M4!i=6mvr&(IDVzI@U}EDEHlFMRyG2U5t0HDQ1ZP&v2YfINC8eLAaP zKUB&Y6egL^DICWG6x@V<*9@UZ0zg+9k4=*FB$Hz|J5`lLnT*IkUSI>z^O*_)-x_&n zLINiLWnIe8C#sj|HBtaajc`@>c$3WI?62L)r1Lu{M;peMk~5JKH@J?}IK;*($w}Ed zD~^dA?vc5oudQNE`z5&i;zO8ezhqQ#$!}6yfABr1VvX_@I~4~BLC(=(akvby#80ko zExzioJ8(@EILhx5uSt^}^&M zMIV^2UL94*jFX@82YDtD}l zX%aW0*#+0tlJea(D|NW5H}e#X7Y!L~1gqHRp)|>Jp%KQBKea<&2t*c?KwOupZlzQ= z6KViF#Rv}Ye+6|tay&lO@&F6Y0Lk!fe=n|Ah2y)0fsREr5|;u}C~ml~1jQmx!6L5= zv}=CRiP*Zk_%(x4PHiGaruIGb{d>VT;1i9M;DWEsyN8dcLFc;c1N?q_;o~c-ZoJpw zUa<(HyR%=iyrFdr4FWs?mD`>qL#TOa)04vSj;nRN}wo3h29ow1)M z=-9Z7`Xi7geRME?mFxM@pH2A1u%md)iHijS=@$?=52x$$^Q{aYB3<(SF31Pps<~40 zfT~scx>_RQiB$|E@6vS2p5Q9g84kczuSJcY)&O9r{3M4f2B~asS+nDF&QpwO+tcpe ze$N6o&5=Au;U5+GPy@(xJu74QAGOKTYhKk^V3 zJGFd1MM&0hxyhxOOUiJQCSdB>=}SmEUh7oz2C^+&`tfO1M5i@}9VB4q-d?~=sX>SG z)=!j3Q<*u!--B#QWP_h!tW|E~1EM#;@E#YTj#`WBQnD6ZaxZQUIY#v>B!oR~K7AQN z|Iqae@9hL~zpvlnZ|Wr|Uu$o`6ZobHc!^23JdeHDOd?jKqKDYUtLDWwXPk zV64|+C8Pv@ygg9j$ssrHmM$7QzGB|Hz=l)^1$4P(@H@GlrioO!pT5L^&@JRg4){ec zJ=cR3o4;Xx7gP{g5xPz9nITSLVo|0%?yk8y>vZRN0U__6ePWKhADl=cCns!_6#79^ zX1y3F%}Go|P5=@&7W`jT`FWP`or<_wk2{yc%lOZ!hYZ9zrxby)NOy?M>A=|7zrlgE z=|@tu#v+5%PKd%ta^}o=+6BwfhVs}qiqQiR-Bjhlnpdmoo6OTQB6lLXODD<0EJp02ogw-Cyo|N~K|L)!As)DM80^I1!U>PR;bUJqSs*~(_I#UU`=5nG=wcAR`ts@}KBYoaK~-xUk+ z%kl1<3aqM4S7Bx@-JN=7-LiYf|0gS5q+1IaF+wK%@F*REv!D{asNwp)cZf^f^KM6h zmG>Wo3+SZ;;IA%tC7TtaG$bsqTZsH4s&=8w#Z zV*~4|nTK14|AK#Y5qfxZX?HJWmxEavN!s8pBjtR`&n<{r$ah z;u*5J;_>N^JzLlP)+aZla+6Iq$B73Vrh0ndfTi$mbjS!O%~?*a?&s~|*wQ|d1IYg_ z64S>cPDXrD?OSp96}2X$@sP~>s|8K+3@JZ)`&1yD0XkP?R=(8#>B>$0skf78fL7%b zx0>=dm*0FGk|*M6TIfpEt6#M>+Q|Z=CJX1iVa*Sg>N)NRz302mOgF?x(*~*`A||7P zT{B8fza*jJ+o)m$i`(UnXC9{@NctHah-O4{q#Y{Uez+qm1ngVviAvHkCguvQbq*^V z9?P-T_`;h@GM9;KWxkj-bmZ|UsAqFx{qLw$th;G|Zb*-|h$-rl={r7ZOqPB-7cDpd z#FH>49*}^ry!voaVQ`Puvo%G3u82C!jA7Sk3`o9_!;!bTKX_(TN$W^!)l`&ih6DC( z!?^+@ulM9vqo2@6E+l#m^nOAAq2q)=DBX0pDkOh3l3APp%ERxZ+%x>uCdG6&y+scd zcahD!-unxcnaKk`;XRe=;&fK~$7A)K4+J5nvZvfN+VWOE<%GuCk2h17v)Bh7yHjWG z=y`3=!dKN$L5-%xjU#q{`K|f=mWQp@J`NdOso`VoT{kiff;sNryT)HLciS~dd#4oY zG$)lV%7%B&aVo6s?cfQ(jHl~Vj5NjR$y8Xq;P^ALU0w%RP$&bsj64%(qMq4InNSz2) z7Vt_o&dTG|gy%1=#7q(Y#|FN7sp&$DXbR>kP+XH@9mKduQ(mU0cLX1tGkm9ctDgAi zrX-L5ul&sf*cAcgniXDYS#{fcJ<|G<_bN|8`PG)&g^8a|sXcj=CbrOI;T@vPSzgW4 z;L(V|g^sx;|C+<^Fre^6_Gc%|p2^Rgb8DX`@Hc>^B!2IN$I+l_))y!ua>eINFMrh( zkQ}|{lfQE5?|!Y1u5!(eN4?8k;JKUNyf0cRZ@cza`Oz4eifSc0mcm*0tzqXmz)d?3 zj<_aPHCS|qRC(}E|NX|&nc|d~4DAE5f(UQ8|8v@rrgEo0XD{P*UjOG1{(q?ge!7r{ zEf@uxZvPp9YaF5``A^`BKX_$2PkSgLkjjgxoQcucZ?}&N%{)GMUn{s?upb%ckg8-h z0@uL!#vlVd60d!oeW#iO=E(p;O{{BT2bZiZTexStTEb>h||qmM~6y=wm)d$s#iKu-BMbTL)4S_aO;&0^uG??y&qVP6UzK+U*3p0Tj&|FxAo@TsY1Pl*iE zdh5k4pD1FQ?>Vkv;BiY^*(HFZ__Gw#iM|MLPlv1)w}pKm#G zjbt%PM|phEio8gmk*GXmSZ;ybqwO2g%~VKole=GtOF8bVql85GY<t{O~=yMji?NSb>!PFa^G1Ps%)Ay=D;7C)jdIkE=<>@#ADn z`>UQSg<{Kum-&UbJ+j#C89DY*{4!Y-IaR2dwTmohnP8A&nf|_#FurdQE63-I&3~BmPbff|wR!k;8#-;r&%N0mq2{uZsdMtWjiq}JDM*QG^WNWQDmzvhZ8`L^kE?&XPO}5QqXT~n zr3*E`m2G$f`oWgu&4$^pkkwmL2&lV=0?FPci@9cdR9_c?pu|x{z9UlT*KFVFnX>eJ z-l}($wAp)QUXxLA8DgQ zlu5jO41zis2u~~Za2=h?nf3UEMjeh|g2ZO=*h?$q*wbZePAm*b9JMMglH!LSB+cam zBfd&&p7rm0OpRY4iw1cJjXt)q2y*mIa}0KWLXfmTPbkxY;?tQIBWFj}YYOuVRc`0! z78m9W5PQC^{fjO#XOL+#sV^gikK@L&$pja%9D*~t$b%!MQJ4j&ceDs9=q*%xW-EA! z4Me@|>L8BOEmcMd>H%S<(GH|MKCRk`F>5EcR2vNuIgqb;!DsZt*MXUwwtZq2$z}64 z_46Mej*1;%&WzN1pREg%Ts%dv$Er*%dC&HEJ z(MPs@_Ov9zIe!l*dB`jOcl22k!9aZDZNxEEIpNQR7|P*D?0H6wwx>C!;oxpDIgo34 z$HP|`xraJXI?rD+GEq}#yKI)mGIN5PYY0(3=MXh2h>6e-iDxPiob%3A+2`>^x>07h z9HO9Zj5bt|_ zs&Xdwoc$#0NW>lhB~n@>mdRpCrM$RGu>~@w7l_dc742n;(3yhqHn!AA0%yM)0F zWzk;3(BY>cHWh7ziuTWH3|xirFI@C4;ZdHmXf<=VmN3`=6t)7@oUJ=jzp{-MMv&Uk zM4Jh}17fXjs*o^6l>HQOz;?I;Hq;0dM+wqoLZ>EGUa3r?%F?ftf(;%5i?Y(}_QTq2 z6zsG@p5=`=FPTwBZEQ-x+F9UV`DVr2{1Ux8W`^Ld(WVNEmhN|3veA*RcAKyvE!a#| zY)bg+yl^pe#G9AQH=U8kSF%VeD;>CJT=Pk+m&`l2h}pdNPGpDST=xc`HrUKu=8fvV zKoE=ou8OM(8%BsAqeN6xSd&b#?$4Mdf_RZ?Z$K0_I_je{OD?EIzWSH~B+4i6R-Fl# zhqL71sm5=C67i|>>!DS=W|abI%37Z~r9OG!M%;^`WipVXvXU*0<$NRey9$GBrr1xu z-eYIf6!ZT*o|0

    2DP2O;w*_Q&%|Osgo95;GU35bFpi>JE?@j49lVdo(Vi|JKTOQ z2WfrNT-w>z*0=3)yN-P3bLVK&=d+&`8dI^EoK=@tfJCBvbW4v^`$B5u0+j76fQW^s zJ~+GkARtP7%^uZn`Vd9lb22QvUk+ zyX{EmBJSX{Da^~dcqN{#ReHgDI zYC!`;6)-HPJNz|o_3!S4a)@m*AuvJY8An3Q^HG?sS%_#?%)O1~))GZ>FOWAi%}(WU zf(hiR76u?3at8ZJL0Y+-6)ETbvfFMR<3hV?uT2&S`i4f6k6*1c#VlhAX?s41t zsAj9m?u7ycqqm<$DGQFETiAAWl&^I&6?d{cyy48U#en6V;=#5(TBwXX#38-|hXG+p z9OtIZ4w|8NtaA31LicA?bDrOZ8T8IGD zNTq|a!cr4JbPpJ=49?b+*pGhg9L22@CpJY!0il`gW86F$Qk>8BYiC382r;6#)~dXIzI@jFkL$!A=S^D^jeDab>N1p4vEjSB zVCNAt|8R|8#E`)MRP0qWidkW2X{Bfj3%TtCcPT4#l{PZ%@!xmn#VK$P(l{;o9PaFR zgO&S>D>TBTgN(Xy!JyYH$XZ7EK_=A-#~|qC^?)l6vMHk$&o2mzn<-Tgr7BXTHj@A{ z$7Jt_>l906PSW3S+TTPvWXIw~1K43_#A=6SB?OXaBxLrMwX;Ul($egw!6rAy#<2d z`hCFv^m0V?t3S>6cKcUJT&fE{&~aG0iSDbTBt<;eMKq-5*0IdBC|-?hN)@aI7+}SF z{mBmQDX4#2W`Kq;1rceo*v5YhvzfB z0hEFd%rxXny{MXR)xWdG56m}*>u=N;FAbY7o9c%U0k_#0erd`h`f-OaBfj~2ek003 zL_krz+z3$xY;qKYl~rA0sg4{5O{J=ju#T~NwTjM3aDU5M>$Uw|O3{suR}Ly?AUz|9-NA>#|&IK_F)pT`3 zpe@%f>+C)vYrQ>?snnO@G8p;{>A#?7r+~`X-!vhQsh;8$zE6g&#;$TdsPEMm z?i%=(_o^xOAXS9_c&+%?lnU62=#jqux?g@7QYOtg#l{tX99Q!qa_zKj8NQzL269~r|Q`O2%VJp+oh8;8;#;?o5URTJYsJUJ!J3QypCsZc@y zJ*_SdPW4INkO?Nc{5uxCO<`Kke7{p;aRwfCr{AdUf(ytXWncN=-sWvAP7^aLqPVqu z<@7ePYP%t+4HB!fd+q2X>|OvFuK86DHB{2{4BRtUuXm(^7Iv@y<^kQV2Gu*>&sN9! zfZRJnzin3mzNT4XW;fMb3C`4WkK(iVjV7Empsbk5Qg1HK2V@rhv&i#*iM#Yv)#E* zsNYB5L~odZE8E|G^M+FT6VSX)T}=(L%!9+-B?G$54(B0c$oQju6w~f#0F=83nqt(y1D|YOgUmZT?5* z7ByqC%|kpCnp$ABZ2Qb;V8T4PKwS}CJ<_u~eW&8yjg_@jhx#4-n0TH?>%%|Y0~c;z z`zKb%6uiPAS#I=9Nf8up} zeQ?oQCn6=M-uZR(JH^vxY2!C39zR#PDHPRq>&2Vpfjwm!1U-c z@~tzCIzNfn87}CvQ_dbae?}p;hwJSz^C*xn}v9tboY`U+GY?v?cj!L+1*2FJ3 zmqxsd%er5PMTKrPSslM7=!2nWpExU9v~#!DdRtj%v#WyV%-NXX0S7{yGpDrJ1l^DM za7?n&TC%9)ab~dHeXMKz7Ixh#VEbL3LjC^S@@=$p#T4trr%fsMZmnV6_J1!whM89g z8nKyY{Cu}FX>|M~Ro;-_$jR+&p#;^zlDvM#MaEGQRJ8R?Rnq6-uE)&>S3|n$?dF@m z?Fc3p`f$<{E`HCqo1ORnX_b^Mk*-T6mwf%uQS+tr6Yqc&GoiT%_c39)N^AgSFuf-3 zyl-rA)8`WjNdO^rb(vX%54%}g zu~zNM0Ao>7m=Vo?Pak78X<7m!*oE3DE0$Zi%-R~1aNCIV*%}Gl;M94FhH4)Va@&|7 zq&X|4L=#gTO1xDMIlcdQv(2{URRRkZ=fa20w)%+D#w#l0wYyvuO6a40m67^Z8eiPO zq%lRS&v0y%&;EgkOCmX0oo_A2XwU`3Afu~X?`A$NLMtZ5nUBB?q#xzJ*E4HHc9YFS zB7fr~PI(zQ4~c?Y6MZjO+K-9%)A(u*^eweiOg3@DZ216UD`Nwrk?2rT*hW)crXU5> zpUOYnHBw4k!P0;=LQb2=N!RTsW^{di4J=i%s2^$QF~G?(rID0HvDv7B)LXw$n@sho z#@C^t0wTt|j&UT1A_ye${Vs{|5wZ#~dr zVR6XnkQs;e;)99;SxLo=4Htkpxx!OHlLNXD)Irl%i*8c!5H=UkkOa)m-8|Tv zlQYW_6x%x27UCzK4@&+AA)!|k>v-Rl_*sp-P$!jfu`dWM4X&5BchDQ_bIlbcrgt?n zhxXm~_tNlzcGwsC?|J$ed;*SMj&lz+ubrC|xOgHA{rajm7k9s)!oe%fx1~c}k*lxX z+}-h5JIejQa^$OgTcjij4S^W+6QOlm;XZ{1v5rle@^==~=SWZ6J*lXzI|aAFVGke5 zY!u0bf>RV`!cO@$wlnbu%sjX>uC&L742L&;-Z-t~@qF z53-k{jMab7bL}4`!AhmEd5?y%J}_<`(KC!Q>3b>a^WYwhmAI6JiOSoks$$PB!xPq7 zmi)-R+tCgT8x2D4uIxAV%OJZ5t1Z0i{3^Cr>3MvNewyCQ?&y4asPCi68A!smSUnmf zFu967tXjWxq=&$8izaH^)-ij)o%|Ofo2C~WmvBMX$cSt8A@z;hK>o&zaiR!H1qjzJ ze_>^L)W@nu{r2u0^%A`MgL2NbpIFYZZ2Riiob0RHy)7GUmt~sux6EpC8n=!EQ+|WyVBWBMuW^CvFQxx@}?xm_MgZTyuXo{8=;SKIJ zO#2*%6kBUm}~qm zE1B!x?v+0sMkUvqcH(*7o=E=o-`oF+Lo4n4B=Gw$Ag4X13?e%u|IU-K!+Vl?BGKlXkGqPw> zow~v`L|V~Dax^GnO~^Qbq@eic>bsYCYL&#Bjd410*xt!)2m~bZ69z|tz#w@L=p~3B zIu8P&4na_qkZCikKLN!l>oM9~Hkbs6nU|pO?jV13o!#rvmWs!jF!lIY>F~<29BGGo zkFnOOC;3V~<0WQol1g#2fK$U*Tg~&^qy&txd3)_tg=vn?>n$cZRp*&`pnP4stWkjD zxno$00)H{6zA;7EqO)oCY z3|k;Hq*oHToczmN$(wzK7kHyKSCWV-wFV$EPTUZ58kL)nBIVi7VpH}6R@2mGH=QwX zc$p!=d|u;iESJa>@w$Gg_<9zYh#x{}Xl$+L_3*p&Lz-4#GlW;r(Or` z_H#j|jpMJ)Rt`$j2v>vK1+3C`hsi4%H;^vNNXwOvnF-?>>;2>Xb;?xgmYPN7(t37-E_J}^grvfq!lcdv zJ%W-ef++Ru#~zMP0o-V*Vc)bKmPF9P8GR#PlH$5Yc5XUawS>G1HJcL>Ikd7pp?YP$ zb(Xl**eZV|;px)TsD1of#`MM{`fZA)TJ&<>g}Xm(wSx6yEU(>?|20-t+WT{>_D8z` zd+Cqdu8Al@>8}s%P3^zdJ9vGgKK1-ypJvyg?rVR1@cZJQJ&rBbAbSNa^Us$_UBjyz zcNdqFzf4_d>YY%Amfq*k@_6+3U>yrP_$sAr_wUySxf`n~t@lnG{&}5ErvJJ+)pYo8 zF;JQ5cX{nL2q|5U`kPKgSrT(`wS5Sk-8dkP1=GBegmyb>L`|>|nxp;fS3{LT4_GJ@ zzQQiEvUqXJGR%8IKBy#=rj#b)`q~yIV~e<^GO=R#dXV&$DRHW}ZZP<8R16^6(-m|q zS50^%@nR6s6aNg*k2N5yIF}@q5K{w?UiI+Pp&Cwe+?v6vcbdx0F!753ia_4yudx$P zzZ>TQ>IA5E%zji(SQ>BYSb{%vH9$vp>}RP0Yr9gBYq7+QukV3W=J&jf2#865PPMZ`a554TMx$;#rjqv8odXVUA+=aU0R*8LWyt%`9z#wy|B z{I|&)7a_~$ZNZRouoAr_W3MBAwExsI$5H*``z;l&Gbcn6p(^Ld*rD72q5_T$&##Yr zPg4S=>5e#{ryT@WBuoFh?|x$SG0@k6OM+$5MA__Z%UvWnZVMe*v%*qxWfO}z%mR*e z0>iBcBGu%th08!VCP@I+XmH+C7!qjopeT~FxCr-qDHCTuSH=p$^HXNYZ$ZshoW&rdpcP`h{wZ6v|8sUtL9--;n95^p{A zmq%eiVpNJ><=Ml+OT_AZlytE2*(7OX@2lU#7j~QJzu4DRhg|aY)y%m-V(Yx&>s87^ z9?VPMu82kfqK@tdZ(4|weB0uT_#Nq!GlqtILhOrTHu@_`kv|4#=)h;05sP9lZvz1Ict6CY^EU3k^iJI;AQ4J_kon>UaBlBN8|+g(x#6+|C`4W5@6# z6e0=QM<;Qvr^#$>`;Fs|@L}e?PN4Yw-KY*-lrwSf!MnqfTl{h2nxgDa2ZjEC*7Gf2 zsb=~P`hI5P4B$-2aVPH>aQC2nKnZ%veyF)wmJoPNSG0!m;T)rXiP1PG?f+EZI#`#G z_bzk%%);I|&wjh0A3VHzhuGJ{Yik}E6V<%;XS*yvkW6g+C08KI!jI8}nFP=ppXA3F z@*fi7oq8rNf=Hj_p2qsj^pmvCp$gvm;>Ni@gjcOh6Vt-mHk<5 z{1Oy{h|ht8WbHnRMe9>8+z0*&&0f6ua7)sVZ-XYtDm7{ex|}j}YKX(Lz0+_sYA=0$ zb%}gm-JoO*{o3Da{J3`nNL(?hLW`@>a}@hHcW`}7K>X#7K1BFGSv%#qB#tPpD?XyI zpDjf26J%k+rz;#t)170}SE8=RS}QOwbK}@HJ^}F*UFM`tUHnb__~s<<6W!zM>~SC% zQD0jyeKoFs65VeDAq*MJz$u6w+aGlHjSQmyEOsGL%2>oiA=Gpq zYUd1*28=W?eTEuS&cH%ArkHpQ9tSPV1JuQ^*H%sjMv}-Y$T%wgcp2u&@)cCrC5^;u zus!IGiAV&?$l)=kXa%puJ^d4WAR>wl~$lg%=5>BDmXAo)>eGBJ0Wq%9xPm2u?dbh8Gt0jsp_@L*lM5dH?Wm4h-=OiUYkXjvRCNck`TgrSSi}*|w=bjFd<{ zz~k)$xX%)T{ngsPYAj3Zdujo9wE(IHMl&o^trj?Prd<4*!C~hrw8#A_EE$;$?5R5W zs$;3F2qhYZio?sRfq+~` zFbMhN3P1rFnrjn$ci|UZ`7VwHaO@KUsHbJTa^oTc;~cNalF6ANro4xm^MuJI=&WL}lIvXn3-c;Q zPVsNL6p9q2#%E>u?E^VKDVRO}2d=T+fv_I0}XPcM+-FSy~6xTLk?`Gp5(6uKvBc_T;xhusVav>JW0BOm=%g>MZD+H6#Er6 zH=1<(iYD~F5u-oxxM3I-sjGGvr{bSQM@-%FO)>O2x)gMyEK{mscsNIvgmOxRLhfy7 ze>v}*x?(+GE(n|53 zH(K$OWCdP62}fOK+U43_LdDhIDlC)-NAv+j=2-|9z0qE_Dn$Sk*N1Jm%GvDiSnJ=& zmL)2V#`RFKJ+`<#^SeDHY#T|#qYvxfQ6F%CtypP7?5S%`(L6?JIIrgZ7+h2+hOhvH zo8UM#fYxn=`4I;&^UB07`eGSSJc%a1fEU~HJ_*fa^D>5bRTt0E7dP-$`57`^XJLKCwO8_% z>)`t*Ritv%-FD7GR*pXet{;=p&~Z>bzJ*CtrwWW~`4wkkq^TFL1xdhNZ-IQ>9SGd5L|FdB@39Q0e-Y>nT-jJW2y*rs#lQD45Yp$@nM!bLhIc=B(5(wt z?!x_n9&aMTm(+9nT8}RkG4{YUxY@P%vfHE_kou}8go2zc_G-@SU35pzrFy*0NB(y> zf(%&K0uu#aj{>(uP}}Ybqjr380P05b_0La4vd>@56$FK}RbHUL%yto6E9m4&bn-5` zYS~s@5HvZ8ui3?PDiwhta@&D`Yxf!G6e4Y=*#mwi#NYR5Yu-d^J=UW1f$9GN0DZR2 zlnNe@_Q*`HX8#O;6!idQy}=WfgGwHQTCsyV9|pFm>>7UtwQ)nbLPLgnL&ow$rXE9P zu|wuZp8G#T7DB`7jRPle_@Zcnr& z`r(cYXtgBCXPuIexDa%lbAyqg+$+HK2>V&a1UGlHCPp0^2(7l{P}@6*`+!l-czQ6l zhBYk3gKNvp6YR$gD&e?VFz9{^6nu0K1%~t{z_t_M(20>hz(mi)n5Asr1dzXsK!qc3 z5tB)A{i^*>(E@d@vI3?3>ev)(C^@_D*XghbT*Fnsh~)FL!0MkBfM1UusL0gI%>apflz#ojzjZmDfCXDPR5Ta!?)QokAsHdLk2p^!UDfFLM zIUa5ah_FSR)Pyd-Gq)5#QCN4dVY9EfJEY=jJ{sf8l)baf0p}Oz5TY~o4YwtgF(p)7 zUNgRN5=En;<@#UL4tmZcg%$T9(DFPZ&F3E~y{Hhu_0?nhK#OhK#e;(l2y$h0b08Qb z#+Fsq)Z=!ZDREhcFkql5+;TSl`u!a`Ffgf7?+HX#+EpqQ0}<#QQ?6)*Ct}Ki3=H1z zRadb;p&uyEu)-%0fph?rLj+zakdzPqa<+k&eDynT`6}V627kX2rgv&-Ndcb$ zwAaM|)s3Df;^rdsfJ@M$PY!I<-}>I=#qVX_CRq|`F6GC=)I*tOw3J(5CgP^u>h^VP zYCr4}y`Fs=dzpx6BI15*bH0%UoF$q$!@@>LZxXT=UMm1Eh4JaPme}LacK--8C3FsR z{`ZSvS}&k{v0TLmC&Zg_{+pLvKJHsRtJsP*XaqztjrV&2$E7(`f7Ov!@oq5TDI4LP zf7P%F@ZT&DuCMV%9)Ix=*0Q*OFUwcxRkE=B1Z17!>-&Ss3w;OJp;A0obP^4zlssu= zWGp}L^@jl0h8{1Efc)7vE%&iyceX-oa!M|hHyw`e)?|OoS0wZ*V{eXYrJLZPcew!Edm4ZXr|XlOxjW;5IhOj{fGB# zKC$xEDxys2OUJ!@QWm}i6{npeqr7z-Jlf^!64S@mx2zhcs(SKX0^07Aw->Sm04@CE zv|*wEC4$2t@MR~VF#kG%8b#DMV{m^hKDr(cdIYtzFAYUU=-y*?eEo&Qgu^f) zm?LKq;vBQP|LC~e11uYrXtu;lg?$JJ!y>kW`}$1?;6|4k!s|L9p=ORZ-{~&6C0p^03BZ`Y;8Gcr_)Ua2cfe6z@X>3Rwzo*$DE1?+Gmqn79(bvNNElOF`k1 z9Pb_D3MAfjV7Gb_9yE_`FLozA6!M>Zg(%y*QC0sk9#P*!=o`hi+;&J9t&!Usy8xa@ zo5cTj0&hdnTU$t87r|CN1lo78e%T7H0obxZf?Gw0t3zDd?bk$d>Bfu5yDUocJT~g^ z?;Wt2I-?&M6Z)`&o$t|dgQC}cE|Eo~m)hkMLeWp?(qUmkztD1Tf9v(5^0t4ohbn@= zvVElZp+xu~H;b1{XA?e!qkPCap45L#F|ojI&DcYjlkn$TkeHzlyFm&rV1L~_o)7xR zJi0Dbjs~VKb#qg5@5DWf{e>aQgKlRTr5`gYQd`sa4zdPE)H!a?lpjZ~5*C#tURH|U z4}^X1@Gk`o4IMjU^v#t@zEC$!84Vzc)j1$WlsSpn?hmj3{dcP#@r>lnbLU3Kw zx|@tnhd@xWL2YxP6Wyw!C}utgd^ZPS9oSxvFRQ%HXIHQCRTB&jP5zj~9 zwb0pv8)+o?+&G&hyJYMaf=uE z+;DD0D7QY_7@u3)#8euWe?-0iRNee1K~hc|LWMf`Bw`$U74FOW5;>LY5={)g*Q+^u zs&4ycU`}t-q|)@4F84M=VlqXV^olv8Ir!Z+C+L5IY6rZlrYCIz!B4zc7ehirS*G`k z#7?e_jt_b~ng~>&S|MKX^o=}I8M$ear@;n5d-n8%C|wt4F|rgjFL4`IzwXq zLD=BBJoUg(R^Fb0E*~uu(}st$)G*~uOot_TJyrgec{->P23Ui4OR#;&*?l9k%9O9qc_mi2W zh<-^^nN@F0oOx<$?hfEsFX`Ruas_tCz_})02(gegl2wyd;4=_>(tE8B4Z0N;{Qlv! zyRYXp>InDDZqgYccT3gTLCDnv3 zj$o>^hjCVPWLVVSVg^gSy;SMNz1&w-IfCtlR2b+w1Ry;Q}%N~{4- zSB6c&MYcxdj(uf6wof#*hWFn9$UdXba!oZ;LW7H?DZ+Ic1IA9_$s(3cg=uTUsPCfU zUTzgv3|rA;k;JT-4Vxm2OF~sS5!j7 z$hcCbm%$J?Q;>qR5q0%b=~6-vUaATfCz_yVa5icU#wE1M{{L3Ag|!dA=!I#_*x=x{ z^?eCgcSCdbGx5pN{NBiH^jF=6J!$8(`^UT);+5WDc2eFZw_6{3YPUAWr@l4r8#*)9 z4%u+6M>)Xpg)b-2F+B3WvwMmK-k-$cw_TTS4&_9Llc8vd=!x*jTPi0&3$lSu{cQ-n zT5l_Q+=|ZQBUR7!8NOFKbx!$P!YEHwmSOfJVXfY&8(~^_y0^jo&o1p|^p}duo35U! z`E$tXGtEgxjrxt=^Hgtfm1BETho-I5h~>W*L|$41gNA){%T#8s-Cg$cGtw1*{>e0Z zJhCB!wJG)7ShWrWsXkZtJ$1T!&u_%^z5nH)g-2gk#cqz>af!_*j{b8J%Z=W;m^bju zqwrl_$*n5O-xbR5obDA3zrz{@v^;B&G)iIL60q?nV`ctM_Z$_^vmGK?%1gM(zaFl&~+D%tV|ADX$n9W_8tx-P-%%!>rx%}w;dE{?|G+Q8yDMBm>~SY z7CF&9@>p6vVss+Bcn&ctcj?)v#{;CzK({9SwQ#G`39sb_?{D&+(Z{ULHsV`)2PWxJ zqjLUJuKGG@g|iP`xKw>vFQBkHpV9kqDF z#~Q(mILaM)Fnf}OY<7wo0(O96h3Jf+Nk| zKha6#mq9}u(J}VVEK=`{Jc8CGN4&cq`tdzUIx949uEZp>%;z8~LZOoU^;e9PPVbt=qg{lPH~nL^Xg_>mBAta8x(ljiG>5tbsrm-B(FD$-lylMC`xOo6n6z457Ht=HS}W74FJ)DP?iEzq*w#j< zl+a>!HfBGH(?YD-W8muw#a96&mlkbBy^_Vyn}?mDGRt*S5u#)X44nxgiB=X_g+iqp zTHIFa61E_RxL^8Q-Ve2}Rq?+-y_HL0E_cNN%}D@?@pFL2Fc@+Z<`o}2A=)!!4%J}f zD$5Tw5%1^k*49E3zjMNL#ToSx9ZFvtG#xdqJ!EWx4NrRw8S4;U0gW^i!tw*BS98;~ z?539q(ix$WUIht7`xx7_5(|2PGU5_2(hy}*A}bz>5wL%Hl0pgb2eQvV2r%U4 zZbOj|3--`WZz#Oy+>Ei#!0-XOn_G~};)n}v>tNGqIv1`VHK@8#m^q|Fzxdi%#X~cF z{%#i0_>+vLE%V_ws>x@UQo2%EmJ&Tq$aF56OUCt4V|{{N=)>rVMjCL;S;=?_b)xj( z)?qrpBMKgn!PA>bLQAcpX)-F2KSw{;-U6AP?9ic+B1gL+l?ZLPK8^_t+=<&1$)wF0rJ`$i90nvuczDy-Jbtg~^)=K@4-S=U48`4+{sTz4V|S%{ zrUo;0p~$%J=do54i4deo^-^P5n|# zXzLS{(L?Q`EIjX<6q_gHzsmbO_++HLVN}*)X|QClXVAHYcB3-otWql9M4PsYIeAQa zB64ENkV6(@wkN3afGc-}0#y*VQYwc}#acZUr(1yt<2We|6wIgZ=}hgw!g|VKvN%Bo z_Dt_dvxq7}&vcCJ1vQkh{wzul7UILlK0{R``VMHQQ7k=Ipk(0Lw&BAd?PuE)UH511 zoYS%zY(IAGODW8fBpu0UZq^{%^*k4UjP?p)_vE`>Sxsz<~Y+rn_@I;IJ{V<7_m@?Kk$HPz4m4N;G zlY~25T$iW#zU6$qiq60$Du5D^d3Nn!gdXUzFxy-B6TGHLmxM`33X$oEm zfcv!c5~``0ktkvz1>VXYQNVnqE>L&o^9FZ@;ycGF9mjeRsF}gc zslTaR9s-)tLbp?1o`W-I{S!uo_%sVLPfl>(E`qiU%@C7~DCbc|wAnTwMVshQRYt>a z7ghC(sDS8}dCFm4MFq<>R=s_Hq2mF6Q;rP_xho+&&kI~Jf3ZsfJT7DNS=OH5xuAtP z@=x2#XHrU)otLy4T+a)f_AQFN!&Q1P7gxx3?Om#uTTupV{_tV65QD8In|M2}R|MJC zy=4K_{K)C!|0pFyoVnuCZH}@bCgiHK``9Lsx~8uu+`6Ie8p1`t+UpwMOj`gJ(q1JN zE-mOsE_Am(r~h0?b4VyD7w|?uFQd8nq`KYtQtDe?TQ|Je_|k1Tc9Hy(aa@7ydrMWI zS0ma8^UrP=wA^rl2<_~hy#s$3W5t%`FkK|Zk=%PUv6@~Ys48EZEjPWXeVLbS3pTx? z+VwKew9QpiWR`9>ukZ0}N#$60y*tHJ`04qDKeY7T7f>^s-elW(d5q@ZPQJVb8a^*no88;)?eU%8ZLXL@t7`>fky_Scu` zG|H3DPxB&avmYfm^Mp||(t5Ab%R#287PPmAx1{3%?e0kHPj%8DW6H6GSLePe*yx*n zufmB~E~D8qn~BiBOLtbN6pUYYtE(uk6z6J+V#{(uNHT)6-0!YYhD4#7N8^Z}G{Uoz zKXPL&;+c;J%(~LO;q^46h}S2FEKdLw=)0jtlmY#SQN+(fbYFK_Q!n9SdC6vhCY?x z(*!VppKo{kdQcJE@xZrMn7*(0X@-797fQVi{`oBdFdL=|86X&f1fLeXe-ONUW0u>#9LA@H zF>DUDE?Wt=glx0*(n_#Y)#m!zkwEIlH1$#Fm1lt${{?oe4m3O6!xT$+0luxJRczzv zjtp)3rdQexB6b6p8x>^Hx^wT}_R;o&-g8vsKH4Zax=pWNdV|y5)axsCOPv?;^51#z z-TpKHb>0m;^BqRJVXZwHGiQ_Z+J#S*{~y+^`f0IN#P;hkRmtwq&8z=k)=k!P+)<{RWmRE* z%eezu7+_&?Sy*yZlYsdR@LMbiD4kK=H@3!QhD9z=iHUcxF1J&yqQ zaR*;XZdw^+aLS#vbbQxX{B6BIM?SOV-ID^uBOO$Zmu3R45inO zSU3N*bghlrwG6%Qn`@aQgv>hAkSAb0%T%&%J=?yF1=W17)W4qVxS_?y15Q*;AQ2q5 z-sOvRJ1_+(Hv=STjd-=i!r;!WjpEP|nfFJmTfqBU(HnK|OJl!pz5gHUw#iE53EV7W zNY?+4b=%&oU>eJARpvVVU)F7_x+H3QtA_PI)~)hp;C5YYb^UgIW9RmEL-WX?>`r6* zY~aqFu8se(Zr`_en)(oOADV}FfCDZLR2&eC^urjf`$w)i10t zw%vw?oYgUG;&4n?zrXWMN8_Z#+I^BcjHJ6`0#-HmLI*h53KJy^fG^kVB5+FmO5%Sk zYJw`BO4>JrQxrzs;pyr(aO;1R#g^gB}uZ%r8`%5LC-3uy&3V&et z%$Hwus9&5-1tN?RLFxC|>)#|l4RrfbG^QEmZF+Ecm${f5pbUKOv|CpOY*1NAU0_deELBkLq%D)&j;jh$`)ih$m&t8 zHIy=+O0l1bL?|%SVbj)2-yBMn(YLaLwPeY1j;!5^`!Rgn2LyM zt>FMa$jC5RmGyhqDu#O9v z+^t70kR4l!_yS;}d3ybH8FcGxLhZLZq1?&p8v@jHKf@?oOHd}GTXS*jYZF!2-(Cvx zB3gf~S(**4RUyk3{m;Q9;$&@~Q#6?`^D)CrwD$wd)ZG5&oYYLHK}( zEUo=WDsabd8%uQ96@Cnn6J5G}J+#Asyb=_n%egZ<)PomMjQZ;{nA)@2yLvwF-&d)! z^8!Y_^PZop!i(|leHwh^Dwp6e!M7ml6`7yuK+L=Z{44jhfYEtB;+12>v^C z%|DB&S)V2Fot*TxHqTa`^9?A)i~5q5CE#K{sY&dU_;atz`4WtV#j0Bjck4usnZWtD zpN*%z-B@H#|E51=wndI((Wmu3Td9b)&U8`k7#>N_iUNz1c$9*mdJv<#p0|60+O&5nns$ z6J^9eOb1lZ8_y@4E=`0&ld?6`s&Wzr=llV_-o8kXz~4Mwxx1OyW+I6ghjp6eWOkgX zHy4tyLz-VC#uN&QYX}qiP#Ha3j3NdqpxlcE0V=?_a2ME#|T=TLjbn64PdR4y#ebjlK`bkw1vY_CZN&bXlNg2Rpsyok1Q$4ozX9wWJeybG>S6L8nO(tL#~UI>UA zAF=)`2))RE!~@k!!jV?YlH=>VHKPe*f()jQUaUyCqUm#PQO~{a70l)ZGiAX;zMc=5jN&Z-e3{4$B<=A^qC#(o zgu$IB4YDsJ#8QLxzy{9h3CI=wj~c)grLf{=Dh8hb&pP)gUt!Dy=-e~@7KJ`Jq-RtU zgl-2|lh=xELp|E5HK7=U7EsDORhI}4AQ?tW02%jy+xanI76u+hGCM@!&r#trqnux_ z0PUJwKcub;n}lt#Gcm%FX$G9 z{Dc&XvP)*SJKgAl|9Ov7PK^d_3D=9uK!V-*_OP8w(L>9EU?;#!BU;^`FcOVVJBW#H zKJoxvhP3Ekmj-BBLM|+LXbsRQg1WMta3@S3mKFMDHR`Ai3y1?$ihxTfeCh%d7RJDG zgM3j2N<(_3ljz(@D%|cOe9FLE8rXdSY`rjuRk{p51W=#W5(WD+0Oe#tf3QPs&>)$< zC&sDlgfu*e2Tvl#XAx6UvFu(c5D^Jq{V0fCLM8)<>N^iXb2|Q{LhX=)_$Xr+;2Y27 zSR#tE5+RbG`CL`sbSUHw4^GlCW7ZxS3S9PC03>Vj9p-3YAdw)F2eqS-XA(_(Q{0pB zp-M>R*bU*hD}Y_55*Wkrlkl4lBpMJZqyY@|8R@Y}ie76@jPlhG~Zy5OQd%)>A zyM8sHu4V1FH8ChW3Hun)JzEIzia>fHMb*gBm&0T`6?kA7<}=3PhNm8}t|dA%z_z~K zQWr$Wf-g&^An=#(Gl0TcE+cnJHtQr?BI0Y! zHGk510GX@jb!}e;h_|IIn*w50n3Wjd*cDf?uWsMJ+@6F)=SzAjGxVPy{jSmJ6)Z#N znZOs{BEfwg{ZxZuKpz@b3Rz+Ckx%)~hkwrJ90D2K*#bnQNh&{X9rNeJs}*ThUc0q% zBXAe{HUOC6KF6Z!i*y2p2Qd&n!e?%f#|%8)mbs{P65OYk3j_=g>ZO?gxqW3qEk!R0 zL4Y<;jK=sa3Z&I$Q4$gURM&uU=C%e|l^=9ks*1Zm8@6(KrL#&Lj~XPOKl=+%9lMR{ z&*8B{sxorKz((f|e*(^2H@V{^Y-NCIJD3|Ok*tQ?S51uS%a`!FGMEVS3?-!x`K`tP zfxB72g;`bu*XnjchASa85QcnV=oU%1+b)?(DnzXmL-0Arj{qGiG)4)dSP2LF)gbn& z16?>vS+~$}`6}Dtu&}F-z8B*XPiF@-3E)Xj7%a^ppyfyK26wr1VDt2aWN`C;PFa}i z@vhx|SzYhlVP53kWlF$e-9T1`mSb`+70Z_-FhEL$Rg%9-9lca!cpoyFy8=0t&aHeM zbckT>nc?GIo8b?dA&#dX1p;q>UI0^|B{8^1eK%?glEE+>Y$y#(y2}cFxwsRw)a;Y|vobGSVxf=SoI;;| zk6is#e0QhKR5>FS;@c$!%n!#0EuRW{MS9`)0J4H+dmr5&ifau>g@8L`4%Ke8&H+*P z(b;3CmVAMl2Uq7gGyWg)-Ycl-2L8KDNH4%I^iJpeL`~|L9AAQnm08TWkARK?wTVXg^ zKSop>Fb1xqt2YqMEbdwGuf|^o8elmQvCd~ZJ!;WJ(xujs^W;EJCVgY!BqB&G<9%c7 zRQ~W!V3VJ;fW~<*z!NG87sQIW_V>2f!%xIOdIfMr^#WLB=+lLiJb9QOvnbXWh^S~- ztVq9>ZSzowO8-f2D|8N0fptA(Gyga7PYzC3XMaJ1APdWa5jZ>r)lUC z^Df`8snnff-j%G5JLQjKjc-zpOeMzNzAvoEMx5Ip)pg$;8-btJl4uyO;>j`9wq(6Y z#I2kH%8#BZWFBU-(qDXx(@$$bY9~VPdrx}-ox<&3?+hvwUY>d~PzmN%6!e(xXdAVU zbqMv1U}BYnNYjbls2_@yFg5@79ZQYjd#7K8{F z2%P`sFTt(m@Mkc8?|N@BCjJg0`NAopu&|%F@W~bhpR=vZgSMuQiTQ^f90xTg?04{X z^#dH}VozR_!(@DgbkgvDhj@me0U@M&$AKX-$;_7EuJ8Tt?GtT>Zeij$ZiVc3a@O$T z9j?k_Pz%7)?h&Fb$nloQqy_f7{)ulM=~0K(ZnFk-S5HETeW~$?B*PS*lMj^y2wCw6 zcPmuP3!sPT-AynPPAcRf5{6iaP!@b!4qJV?<-?f8w89NmZ|_q2z}F2xg(E&{0;vBY z2!8JzDsG>!15VoGM(`a6tkbZ zm}~o|t1S_zHs%iDcrqx58IHTnnNkqTiT(5Zlr0Xc&i~J>ftyIWJwq^1;C|x*#4sQ6 z&NhgF8_lEH=1F5?)yrHik;f!(22ZOb>z?GdcYrz63#S?cD#Hxg;^INYUix<|gI1zI z*CJT(<9|%f&%h)bsRqqJxPbXXfE&y)!BobFeF8-P0C5QZWR7@bQJ#w$a05gs+(NnA znloY%Xwa$rR6mMsv* z|H$K=moVJ2zD$4n)6*>CksqVg-vhCoh%N}-j9?7#sl9|~uW-4%?@{rAh~+I>rH`3XCM>5EyKGle))V~RJFrHKw{`i?Z59K*#g}1Q&mzkEowJnkL;kdf5;pF zLILEB3Uq-faE?&4zmT79-CwPvcYScsQm<1XHJc0h`<28KnFwo7MBzW6TzUW7KD@eh z$>_%1oJoMy8RfdamAaKJ_S*inPTd7?EdL|#8kSUW3()KLy_NzXE+Im1v$>MFxN@A` z4S`;1(BuIilYqYe2xf)Dx<&%61oQy;Z=dt$rHD1y>Jm7s~ zbU)dwy7mi~U)RA!_-Y4c*K4^4pX!w8E!xHe{tkk0cux=�~HM0TSXMW7Yc7Be|4 z&CW_jgtkkCByO*d25*(K6mM&N7w92bi-e=i;uo@yxtvz>wKFl z^r(1k(04Q*T&o;Or^Em0`Jqd(CfmU%~z&+c;jGv7kh0UkA zbQIU0acr`b`L0TUL|VzdiQkq4 z$-KcW1MIU?fjq-E!`vA=6 zPO_W^^F@@IHS;8uhDTsXvJ~}a_z-T4Hs22BU5Q%A^dX3HfHjOa269!+Y$T_`a9oEW z`R)5^htrWg?1mB5@yqIVUbXr>@41%>j z`zv|!^91wsyxvkpZoSE4H3qNv@7!;AV#L^!S_mIEC`=$(>C{Ngs~5Yt5>wppdn8nYqj zv`Nqf9b1>Y;+I91J4CrKE?Qp>nooGgq2oLZKyh60R+0<_MdjD&2f7Uc({;z=1JBM7 z7vEg9TI&hQaZvmjbnWO#(cr>kmwJPXP8Em-rl>?THn(#bxb>9fzBu~qi1BQM(#q|` zT7jcTuZjFxNX1xw!=%Fc-o|krG0Zfx&pPt~Xy1z`(ztDG=?jJ|)>MJe>LI3gmW3E< z$=L0wh8q{2-K-ftLu$rHKjmCCrA=WdA^}-MljuO6A!V64_~+jhqbY``QwvTubXMqZ z_5>AY{z=)89UZe|RJR)}*}NFJ53zVzdI@*3qGBe>jM=(jx^9Y%?mYl{`9%?4=<*)O zGdzZs{y-{`=TjWfmvpTarkr};E$dGJ4=Q?id(~Ea>Q`D%{0spd0eu;*-$>e-bn3kL z!))nNoqp5NM_)F~4(y+reSSVX$7drva}?VyIJ`j;ft&9el{zx()~noPaHQ*KR|J_e zqC9DAt)*4N|Ie*uPYvecygWe4Z-EB#V17!bBCVKrx@OdNerA|ECd0k4?6c5~Y)@ z_5C;6e;UW;j+C{JI1?by_H&#k3OJe(CCneN9wGwU82#;?YjybhZ1&4uv#fYh=IY8Y zw_lWii((M7>TH^e^kYmwH&nd2RYQJ&lcJz+&g2puGn`x`+bu!$JeQexKSQ|qr7lc> z){J81M;}sdkOd!{b#A;B55FeNPhM}ws~ikIMpnv`Z5|e=p-dll*2evWc7#VJzD6YG z9RBH?qr}=9wo%SrlrZ*Ai_@L0vva#+DUq6or>sLYlt(0E`D%=wYtbFGv>(~f-|?Ck zD;?hJaXQRpb~e)_TQ8b81p0_g>jWt~{Oag&+^;kUR4EulD)pYT&o)ivJcA3VMCh%6@C^_V3k4Y7gczGo7#Swt&=}>_ulc^Y1Coc&~U`+PYG=hEH`F zAotFn)S|me`ln^R9wj6h^*9K1m#j?Qyd2X0jKg9pS0>T&rbC>6?(bVA(P8H|@7>y` zq|-#YYH`e?*f#;moDl&8mY~AJMm(Qh;Ys2^YRC%wt<&5pe??Qo zsV>CNfL_L`F5?lFmB~z-v|)brZj5~S2}R7>BTCfR zP6&zUO?>8&y=}*=K)DFrD3Z{ z*JnXlI@mMn(wnS?Gyr;b8V^(EM0MrWd{rLem_^E|;gr*AgcI6mXU?WOlsaFqGcmP} z$GHK{iz_|44^a(~?Py6_8t%C`w9fr+ndJvHz{@zrJXZ$0#4d=GJdLyuJDgXc%xKN* zkFdLBm#HQ=uGkH?JP_rN2?V|#@k~z9JSSsrD=nXM;Pm!+sVSwZ+AE4NSXBDmR@9%= z8g=W5?{=${*INeW!6(NH)UFuqq>EXK|$Mc&M za}fpn0e*T5Zwfx?pC5H5GxS>Lz*iL=1H*ucO!6q|k_&Jz8O4a|pc6`Wnd##$5*<|2 zB4p|x=j$}SBHd5CRfQ5fkz&O`+2GM)0Iws3qQa?8R2^0=ZO7`U!W#9m zW`+?f{NC$BRL_1U5-p#I3WlWSSwnOQJbTsa6_$yk5jIkOTN!zt=qnT1KRva^bJJh_ z;^Km2x3G*q@1|>hy!vmKc>r{{X#K#?26=C1IYIf1PqH#L({)Tv2g6!f<`9W$fV%p- zLghWLO_<&#uN3pebVbkr4Rk}QBH5sI#Iu=E(JJ}eOQI1pT(Vw}$$@;9lidRG^L->a zzF>fu5H}f?VPAS?c@ClTIy*w+7Agov8!L$3f7;HT24&g%S3t2An{)@ zD=gEpEiIYR6w*pM6Wv4&q4|N}B)(h2O%Sc(x@5}u^&Vayv=nthm~EgzZDsq6kZ288 zBdhkMS}@1OR8Uk?F%vx4(6skW4Y?%)Ee+wKYC$}MNK`VEfua0{bZzHZNQFWUdP1HP z3YF#1SkXMo?aa+X*>xd?pW{1|TWPvE;y!p-dOX^%Vw~5usZy3OA?u@m9|+1y&5JNdw6)vGyN@R zNC`i0E3+_nA~P2WvVWa&M&7ond3?lJp%Vp?U?CN?%r{1O%+v3GUW8IAhyA9H7y_CB z%_uTHl`N97$1|B5;iC6>YpQUUE+|g7V$rP$HnbikQWV!ABxtAxwN^q;JV;BlwJ&4b zxbxbMIw5E3I_bn z11yjV9A;E3UN>1EEMR3g8QeAlx{8=|+jvb+@7o{|`w~x><@)TVxs6%t!)%K){C$Hp*GoF6U z)VqdqZmKsmu=iMZ{EW1byyYUPOSe;CSaarO9}M}(p#uPcE!&39L!)J_%zQJK{)1?O zGA$3CF7I0Psbh-fiLUm9-0YE-jF+}rZW~zCD{}5D0o)3=z##6qO(snX%8S}**%V24 z^yIVrboE(Sx@~y6%(Zkg187l$wg~@IP=iwVHR$M{`LA-wv#=+U_wRn*zh+dLclQJ7 zO!E=3Bbp}cUPG9oJMX6RzUwRFQIRx>_s^g%X z=@((p#q_&dPb9XUFwdqRGVYKB9j6*B(14i}UFk+f?qOGT>AKd_BXOX0UWlgY)50>oes-)?zU;!zVF?*gUzkeaO@WV$7;N zL2kzUsrc9GNfpU3v7Vt41f8doB^JR~|6WBpJY%+kjc=id91{W(`W#H}{L3R?)>kBp z)Zm~>H5k$?t`QBS^j31q=@%gD$Jdz<1AIA(&!`5(uNSiavF9IM=6Bj1T-nNun6(cv z5J~M-JL~N8I4&c+&Q3T zvBD3D_F~aA$SYsg6)p?%dK%sd>{=Oq;6K;{@o!yt+UPE`dG&x6)$C{9`49X_IHdVM zo{Q!IWvnVHKsXSyy1#6z(?zBs;k*L8XLA+Ya{Rt6r)#UKQMYKv7Mi{fLl&06ekmuo z&SJw}nhK^{ecOc*^|EKUc>_WWZSS(RWN^n9GS$D(w8Gr6Rl~nk#B@#9F7dd35>d-A zaJ)u$A zyOJVibIjXit?XlzYjTzXrXZ`!1*iXhCLpcyr#4O^(u7rb`ahfO5txPW*iE9OqF*nk4#V~goM{g6A!p@7X*#^*EohoGADQ9x>}14`m7Kj< z{O04#b4HlwoyVSDO@I46&&88}`J8jD5BddPu+PEwm#-Bznr5%q39ywtzP?ll$&z4h zZLZaQev1OFi1hv|`drvhzW0s4WQ70Y+JSP&?2lpaLe>Vhn|W^mm2kXw``lc5pH(1F zYP;xqX{&4gdbLK<>t7yTdPTGk#$jCQ6WRL7>fsdEn!_A3Y;&{lbuUns$^^X** zg8lX-B=w7W*@Jq#iCPHSOj=rT^zvYY`Il&I^-ss@ka`V)-|%mbT#)&3DIJyK(5Lv= zi@X0K`sB5R)vK9`0+COn@eI5^axYprW_j#OK|HLoWV&=wD6TGM!*N)BF8nz2*wJ(NlLs{vF*mGYcP zVfp|#n@(x}s~G{R`te8JG z+z59Wsm>u-U$?k~Dv|$$re0NkmmW(gN^AReBJydl@7mPebTU3ie}&=j^l7DtvD0}} z7%zypzsAD9InriM8VNkU&b=r6GF*oU(Q$^{*q};s`4uzn#2i82dwKUK4E@DY;DWqF z`l7mRKclyMWJ<3oXYt9AjasWrr=b~sZ1)eW6esU z$4|TqN=K%)zS5Y8mp*_%2J~LFYB5jtAVrFV`MbXk1=-pJI24QjUh8_{6>_ z5)H7|jBZUGWV)w{qaLFPiXTS&VCm2J=HZo|t!Lzn%oeY{TIz{;mtk(J?{Af1{F$U1 zGQG0Uua$m9Ha?5ovd5xIpY!^-=hqIu8BkIv{d}+R&3*up_-6<Ghg@ zXY4N82-XHdB!x~D8;1+n2WX*pl!&L9@^(215pMUa^iAn5OtOMvR@$izWKMKaQi^Xq z)nBzhGH4YnWc*UZjY33YtC31Si{@N$=vy@B1aK)!bwC{@mnRmaRTSoZS;gQ(*j=xA z(c2UXpM6y?->Ftoy2^moC|0;r%j|a1wO3a4VT_h`@YlzAZG!G_MSHkd&qk_Xc>YS{ z5V9R6u_tvd>FGVkVrvRmN`MX`9$b{5@c$Z!^8$ql$v-st5W){SycB;AOMK1#{q^Vx z^y?-i`8jt#;%Jx0X^`tTw@@=|)!P%1gW7I-OQ-84LC8k6knK|6Mm$>>BumuM(y?gt*{!)r z{8=MFFs&sG_L(vsnOrAKXTlerpxH}OQkQRF6QJ!c#T zRrA8!UuieL=D0P?6OU(j8m!~?7>=~)N(Nf39X+2=?e>lHLd)^ph~yNEN0+z~sV)M# zbW8CVHILgftg@Fra7zvsh7aiDIw&P(&ePI?{EV$CGKamUVTpM2Ze9GI;40}B+NO*r zm#BI*=wN8jgvrMo-p7-?m!Z!bL2(n~hv60?<4oBY_ICSHg|kR;^l^{#Y`JF2)ob6zZTk(U#hi?gT4Rb`ZPzBPkSYEU+Er}jW2ybtX(Nv0q8 zX2UCok&TmLj~C&IML%R>n4^Io2~1X-W!d|Wlgi9?x4!8sgL{f=m0EsP=q%vAjne6w zz>gIi5V;4h`(BK=@9>20#ACb~N}bo7(`2NfJW&nW7nEfN@0A7#^>b5FF;!?qk=3za zHw{-mQr0D-@g@XLd(BaOO}mB7;}W6m*%!(*lIhWX>pr3QTK$wE0wi$0@>8S{Y_$tO zW!1`0X!1PHj}S56|LbjMl#frJ)n3;g_(iQsZn+`|&I%Anv9aRW5v!0tMcq5A^HKf` zvu`ckFxk;sD#qc$i~xZ}hScou;F{y5F!Q4r;yM;5Y5aU3}Bjul`C+#7hWvE0x_zA$ zr}(zxG!0*_8H+!c@*y^Q;Dy}hyxn!^cCJ!vz+TVvCY2qx1Ku5Zni;Y$DfqWtS6JFV z`|#8gwclU+yAC~(&eNyvdfA=*h57K)-u&s#C50x1_~cF zSGrSD#j6GKl!kuExrhSy;}hN|Qq>op{(G6&dGmVn@bOAN?8PjFv^AsKLwiq ztskt~4fU7*yo?gpDZQ*$o#Z|;c;hz_X33P;(w#WUEtR$SDqvmm0@AGao1~k8-wS`b zeMs`2ayclXf*7(mD~WPTIbMp#ZM!cYcP58caKgxRRX4{y4NJdyIwYpz#WLFgN-K+I z&vjlen6CJMqlr6<-D2B0k&7;Blbss`v`hD(Vyk%W?=Mr>xfdsGz@jr%0~J|OA# zP}RCZWjkn88%iq6ub4_7gT7~rnUgiEJp9NrR}b4C_yx6C7qKAwR}YdfvlV8`6AJC) zgc{e)Mp$nC^D>dZHf^XyNap1)dp^1c-HbnZ#LW{w-Lg%bp19fb!U&zJ?hM@ylapDR zB6!^w6k}^Ur=;OmZD&YQ^UxnJs=bI7Vy8KCrE;M!kR@0A{KEXRW~lblU@Oy=>X{L3 z5sb>YXA_caQb5qaJW*`;O~BVT?`x7TG4KeZzzbPVZ)zbK(=|uK*v%8f2zwcamve-# zT-%)0KmekwnQd+a6D5c>nad7Lj2yU~p|wi3776xnrn7VvNH)A}(7?%W=nr4%+Drwu zO|~~R#dm`0rkTo5boZ$W{w8YX>uSk>Dq^K*&kb$F#Kzojr{Eigx7*O#10{ZrCrRsL z%aQ?}?|HQ=z(3upwL15PkAACl4jWTo@Ho3FBB+6%C&xoKvaLM)1gq-8UcMPWy%zRT zF=Fjx%p#Zn&9sR2DT4K*)91?02)_HQJsYWbsxjI;HRR>ti2G5RK7JXByc@9K4L0`s zoS#8`Ou5wA+jPw+wu7^r7te`O${XRq>Bm+P_v1=*4>)=!C6c_ncIKW3cqR8k?b z_XgIid%Uff%BfX*Y5%^7lJEuTM)G7S^R8)3fQ<7#2&iO`?c9Dfwans@EL418Dn&-r zCZ5XQ$G&t^=-Hs`*D>L6Im#Wy&gFy4iZu7$u6T>%r7bUP~vWklN zJe}$7wgqmLK?dw|mO|&J;*)o<_v zsVlY;G-=P(!ZGfEPv%V{(~8Z>X)jc7^G)y^-iTCo0mTsyAmszb@1Hpf-q*snKCZ}v zf$&cRH752(ZjO;8EzMQOxJaNBfd?b~ns}|KbojD4p7J3w|3hKB^SRrEHs^kqH$NXo72SB=r6=34{+P4lF9Kj<*S!kB?;TZw3RJ7aYiJ ziRPm5s8Bv0x^&k2_fWVpt5G;6{2|p{T|!N4?fqRi<*weSt_XB&T$MCI_30t0){HEr z?myldj96w=HMvTf`<+&pAK({XseLxWzE&Q-`g2LWXCx-rOpjxxhunAvBWP!h%<=7+ z>%ABy_KetUQNuXup(f%9@Ss}{>jmGRJnDS&&A4W0^QVWKqeKCSYS`SQ5H$B1mB=w8 zg^(VfLFI0(|Jx$cUan0}YVM3+oad=!x-iSQmk(8;&Z`j@wk94bH2)h2JG#K0*K64| zf@vso9T*@LK)sGoHAx?7pSU6qfx=_f#h`svaM;Jz_ba=bkuh0ZV+#|O&S9!LG@H_q zr77#y?ODavfc{*KJ=0c_NbCA8)u;@rT1r(mrytaDl?9EdDSwKbQ0J|cy&RDuk);5w z-#RlvSDUX?Ji=_Z=!kIyyZFSMSCRmQgeUr zQGJftw}a+J$nban#xr#zV%Aq%`BZR`(dM87MEU*as81@8i0sx;S=hBL+|#XD1#|TQ z3RO%*Q}|Jvt#=TRfitD7Qz&rV!odyalUGEekSn7(p4JfAXzNV-71G&H3?AQMBgv z1D4;5b_iFp&lWvLk_&nWdIYgr#6UVd~_6sito5&WFZo1PfF zJS6=Y?@oyG7KyYpwzT?4(k72JF(gS6N8NdLtWV_%&4VY;Qk9S^ccjRQHYtKbI>HMh z>J)3y)+@GhP_g-BM>a)yOWbLPsorzi2}wP8?48E2yIAs9S6+JFPh#qfmD#|EE{wvh zuFLCF;3|^2U$IlW6Y5oy;y$EfxjvG)^?*dSB?_2jX6SEzpME6TiLE) z-0bf+dxw(u5OVLD^u`r5;$Pa!TpJp?cVn4CWu-R-ZAxQs$pj$U*%fA$`#2P(LSZBjQduoBk)xu@5YlJM?#ddfpTJ;pKz=JD*?eOQQDU9RC5!d1`(S z2YUZ^oa4s-0LvYrulC~{=lj0j&D@iA@|EFDcAskUYcU;bR|79}0TaoCe}6xECFo5X z8oIo?^hb$9feQTxEdTE~hu%7e2K)ys@5ed*KLD2P|BG`tTdKUxck?*?_L}F(#l)x>94O_tyy&}KbNq7?s!R+;_s3Rsz#=umUt zlwTU$Ih@P6`j#`wgK4ZBu!+FyqLJNS9U}2kp-hUd^t6K~4Z3 zyv{M>Ib!fhFFY1>xtB09$F>AjWe&OM+7vo5d66n3JaJm$tV&)bPZ5Up*B`h!K{f)a zGx3ZI56#^gPD+*GJX<2C-4~TnJP|^ZfR5}zC&Pfzp@1SmzC*FGHtyM>ZUY3mXMpY`4)CNPi{(H*~(@rW8c;f zi4IgzsiE@-nO|#acHZS`J?uFiqq1|t?|T?Z{O;iA0`D(GK)Hdmv|7o->a;xo&9UdX z=!)M7RZJ;YalksXmn=@#>D`%p5D}1e))h(lI#7%cr0iT+HJLd;#bqU1gUdEL?OtN} z^smnEs15_c2KPkw9?`ZQ@LnP-nt^hL?0}ex*I3Z6s>z&9Vn>oN)*K|?mvbD>szm#T zIB>M|sQ8sKZQ=-FxB5sByaFRzD{c0%H8tuWly~hY&01RocM|OeaFsO>^paCSt8PHm zbGkDG7%e;JBAYHgX2xTkCxouyFXm_19pK6$PtVEtiu;4S{hx$bJkh$up*`6wW==ow zrw3U~928oI>$96>*+8oIXG13wmVfMNNu<`6A~SH+T_!5z)PcJtfS0nMvd-HHqU7U( zRunYqEGwjaTbP34GjA8R@b+4YN;95!k~tw_EpD30+;VWoAFj22&9%R<3R%IR%->qy zW~Dya)1-IS9L5|`ia|uBcFTwf3d+Msn30&<)mRl(yG|qA?&^1$d~S-WL=4*d>+2HO zvq|4#wJdU2j4X>IXN=;@;?wlNv#k%jTr>3f$}`^1?f=?5W(xSZrW!jdX+7Ow!|eH4 znQ$)3OzP?q@DN^+fIMAKd_kT~h6c8vz+&R2#$D8`ry^+04}{hxfM<@*f<(V3>@TH* zE_lkPJ;?}ElRc5nT1g;0U)~WKNi}5cTtX0OKM!Wrf94AkSPz8Q!l*CqD|X{u*SWs@ z(gTi64|hX;j^y&k487EV4x=`fcUnz=yxibK?$hC+u_V{hEpUh8GiZqnsZS&S_@3NP z1#7V)wfZv8WBCZ8q7=o8Y0%+6S#wC4^ziq|Gzzs5Z2c)4vel=V>nY=SQRm&=))XD* zd6_zKaeQ6qi|Xlb3ggIcT$tB0O_x&RZ+Mea_+?!Tp`_kWT>y$2}KHtFnJ3{2|lkdp1bJeRW)-7+_3>cS?!LJC*CVP3ep~r(X(7ai@>RMAvW_4 zd~R{xIgP_dXJ2Az6E&kfYrDtdtPV$l7M&64-A|L9g5&5a(aygdC4fVFj-8~dS;vhf zqIi7k7?zR|{6XVMy)hHLMC&CEElW@CG#*lLzqDt*s&WR=YxerW(-c{!pecZO0d(^8 zTTqz)d03^7POWB+QBAngn@zqVh*p}RXXm?Y$qAuuEmCTo#4JR#!>l|rb89)`b|5Dg6XGCoh- zbO8P-o{&H9X*P9y8*SQ}%=`^YnzJd<* z751RoC1M7CNGO(a^khv+a6ipH7JnY414Q5v+G&9y6u4Cgu5%9Vs05s6#u}vo2b6JM z*UoEz(OH3jgb2g-EczzP;C6+#5RuNelE^cg1nhkwhs~I5rU3*w><~FzVc0Q?fkQOl zRtkW#6!_m`@gDZ&w5cDb#kYi*pM;uw<$CnyW^#bo0xLw498Vk;Apb7d`c|AnPZdGhxZ z;oye+{hs^;2vWWQm}G|A%35QI+1y}s6iZrr(Jx6CXgcZI_+vjcf|_6lk29Gs*U17n zq+d$5JT4+$J`tSG5X4zg_6VL|EicPP8=mLHT<4%>>kpqGTsTiW9egk!rJakZq&0hZ z8Nj8H<7p1XK#bO9Nc1)8Q(OcK@!SeHp~APHwu)lLA{R^^OaS2(jNu(1v=u(pVR9gu zcD@0Z%t9PJ&P-q;EKiGAeM|Fv99we~x}OjToAIh{IA8SbFigf-YYdS5##zmGTudXF%tqd;2zH34~a;soVFFr5!XhL@Fk_s46f{0XVY_#L=+pa>LL3u zf1OUbo&64zl~&8fSPp0C;w)c|H;qUAB&t%fttu6T%nj?5Y~ z)it4Ip!^B^qbg^(aQcDo(;wGmqE^ZmJ^T|{2C6DXBjgBL34jr3;a;id&nXfm)CCHXa4npErHuxsKhQkVm{CYVA}U)NOHgVbTh8d zp48~Lp!XXqP#gw4RZSG{%ydTE^mp2dgGk~a#(piO6}SB}R1h2nPqqTqISz)@qs z8vv2e<5dgRUUX z-{q|X%B9^ z0z+bs(edQE44^5)_?9X_9X*TL(@u+Azlr!hVPh5M79Tq+C=^Y)CY+PvA!O*8(DTOy z&JqJvNHoWL11?F&kt+~aa&Ub!-vdZ{S{M4?IU#e-gZuZxL*zm{n=j{tii@n! zbKK);oTpZ^(28!xxrPSdQ5}WFm2U!sKt!W?8l-o z@1EnLTFZtO+C+1Xxm4E<733;OoJ%<20u9Bf^oGd=Bci;HhR&FHL52`tFoP9j8A)bu z`j}fm`PJA5=$z23J)tye6nd!jjM^1nHV4((%H71mH`e;*f34mcJ?vdP_-WQCEoI#?(u_2*xu4pNUOS4jV z4g#lN1x1EN1qEFJ1_@Y`ZvL=vU}D^xoB@2g?js;$yP*c;J0mm zORwMaB|Jz+eA6P zRemGi9?{{l1(qfV8XW9BbY{P1kl8zVt%K6uH`5Jin_&S@b`HPFsmI)L_5?FQ`-&Z< zkD{mFbhun=bfw&!5b3KK1dO#O1YBMk%sO&6q1USGP~Y+XpE7zA((fdg3MdO?AItS2 z2S3Vxfp`e8qMqX_b^qOhkY-Af&4{SCqJO}%rWQf^+CD{pfjn~*Pq|PxfqM9=%n2;= zK}QnG-}-9&gCJ0fsEq9q+t)G|mbCoQ(@>oYQ~OarZ`Pb)*hi+YX)iqI%~7m?j<2Vl zq3pi>0;!0+G>CJ7pdV@^NY3s{?A=C`*I>!;^GuGLJCMM6#54rXZ~08leh&3z>gB*Y1*f+&bRTWQZOeHLA-BAY|Q7N^8NuSThfDDXevuORtp_(j!krT z7nxnTeCw4ZH{a1YxV-M7e*|ubgT6#DdK#;jE{e@}Z-Edo8)pP7qEM%NaaCsUn$sMN zVwdN$3Cm>1vM#}>sE6Fz8I+?(vN`x*{zLNcY<3q8k1(l!i#rFz7A4{2$LyCL0%uz{ zKa`jARW>7%A)bVlh9{};mDG7(Ay*?n+uZd^EpGiNI-P>P*3I`Ci+gnqewwML<2$yJ z2?*Wd`*8JS-*P$E@Mpw!fn;OI$zw-Uln@_yo>qu}Scmy;VQ~~-M|3IkcKOu#aQA=PO-$2Yy^W@wAFrSxj zO~DJU(>U$?nC0fMi|^|p{q@2w2CM}~wBCFP_-&+7mgov*I`R3PRzjUJ-}L-fp)WSX zmwfYa4v+)5Y8Gk~^i9#93(P`sfg$(&6K_WuMge9*7x%>%FRMadcXS8su-_qY*pZp! zM_=E%`2LccbsXP9ryu&RcHu#k6VNmBMP%ita8tPbAONgk`fj{Z#}(}V3dAJO*x~*c zYxmjJ#2>zkejo{{z=US#0qH0Nq!$gnW9S_LL5hH&fT*Ymp@dKjNEa~_k=~K2gx(bd zrHK9jK>AroNY54dd9wKp!2zWp^#faQP~B z0;lS$>?1mc>p5IuR`zDaZLwEO=%XjOJ;zR<=#UIpCudbxjoWx`l)_?%*T(PZoVnSVuJ`C%49_Vf-kdA#iag=ZD;VVCpHJsLLB1I?k7|vKxoRb%S*tCEgiwClPfxB^UQ;3_3 zh1e?NvF31}#&E!^*Grrb$VNl7G6t`@HpjBj;0*iniRpE9@xD?{g8cc^Ut+&Z2yXsc z0W1c}elr!=j({0G7>~D9P?OnaFH^eViAa8uRy(03%I08OI|~@oh8sAl5^_3JO9?!v zy!FrhGQGbT56|dW90g7Vty;IKhVi~B@v-#3pd=i#AOTNHAdDh1cPGuCDyh)zaH=}1 z$5PT5eCUJZUvUe*CN1?;YU8QiCF2Z@4-ETbf?Lm~N(_E&&PjA~s17phWKGncCx*(? zaMfBoN;uzAh&AVM!f*SB+J^mXGn5aLK_)(;zYLtxvKH$VXgX>WGlL&*mz9a6-~Wz3 zW?QY{5f=6vCgq~g^{s0uBlEbR+`Bcd(kw@XnLIDmI;-Sg+vi)A&Pb@LRTBZEF$0*N zM7$`=M&LE#v8Xk?Jo^HrJ_yn{(EnDlBDIzBeH@|E614R2?5#&vha_%7I@5L64YrKc#aL2=-fpT={;;_}1vn@}PXb%!2wilJMQw9WfD(UK#zTKnJ8CkkX zM^#yuW&}1*wgtSm+N6x<>P8N2{pxPg;=XYDLzl+iFORzi@9vbUUG!R3e)2RND=~#B zZBz2Ca54g2q~?zdA#QQ0UcBTh@4XkVzm9ZJadO-)@6WLFSLRSF11Y#>dS=Bp;wR3G_=747i->pG zvz}%LCz85-4vVtOmDP;#!h8}wAM^S*A`>~ytnktctb8BZ`W8o+YDsqe^SFZrHohYzp1f@|iFx4G3F~D)=ZHqb*NHQs zV;;qpGBl82x}m&r;;e{;W+o67M83#3A*AR}{pHFxnfr%AZP z4&ZO>mf<1BC!ScJ&T5#QJ>oAd_}mzidG|a*4Emxt6<3+I{XRih$naE4R3amVGJs_# z+`0rMisY5AkRv29zFJ`3xxN9>T|iA0YKVW(I`P_DzWt2Pv8>D!&LO#Dr4;KLu7(5L zQ`z)DiEAS3xxEGb)J}|6UWlfKE+_R3v8;`w%DL0XlmWH@*Fc%Gd@=5f6s;ThK2i1iYQ?*2!V>Ce%b9LvL z5YE#YcNeTo%)6eYv0Bb<*ILooSCECa4|vfw%c((SNvikRd|ZPeA_+Q0NU`+C}_jP`3I7L8oh>kLzhmh;vzW2U)dIMlc}6S*iLYRY=O5fmSq$3~2&Jqbv>~ z)MJxKhX#hRb3ZVw{JCqU>EGvj1A;;9WwXy4S{>AZwIKFYiCaTLgQ8y;W(V%P@mh?p zZH8AYLe2Y|XVU-KH4lv43%p~F=|A`WLO-Agd+7^~)_-piMcbSn)NGqyGOZ$W0>a_H zjr?3SVsBK{IXqNhT$vmY&GZV>i|_V)>n)8l!yJA1TC=J-gG39B!=spo2kqJzF}BSS z;=h^YxMW+-AUO(X#u(q)dBysGp;KQo^Kn{l@GIsaS4DX+3|A5h z{;x!wePsrH-ymSE1vHoBFcj6MU|%!g`a-u83%HB}5$8~fZ3{=#d*(w2nT@~rYC9aD zM;RRTB!6I!_jmjdp7@3bhFLRT+_xGSW#5aB3`VOOw+;{g+8QxGkX(m;G#Q*L9hZ(T zVqD{=3dg7dau^vCB6|U z(hvss*zlF>v@c(B??O}->E*|cs)vO`SZ_navJzkWm;qY8cXky@#5h(BbkC7ABXApP!X|GYH(t|LQkt&1YSP+qk&jo{DWrSnzx&tDf>0s+Qx7!sRB;cymtut1B5IZ-sq1##2V!UG4LKjIK&K zam$B$P;6(R!QjKp)JEY?%1dWjwbKc^sAOovUvG1Kaj?JvyIjK46t~dG)m8U-A!9L4 zS@{r1#K%)R_c;x!+FZYe2n%lgR(im!`Mj^6m-#9&Zv;cka767UuvTlMeFqKjPcAk@ zNxFx6Wpy}zl(u~#qjNKdj`ug!MG1XZGD+P^e{cSU+L5$*t_iNc844a&n{ByT7@5#Y z0@r{?h5?j4uj0{_TJZXMjCT5rN^83aUWoAh$tXP?QC1T;B>0^cWxlKeM$cc5yqSru zf5{sb#R=WwUcHsAt8(|QuK!AkL|oe6V%C>7h{)>bZ^LPc4>7y3pXm^e>X%3N7qb&S zp!zzENd9-?J#Tf29q1X>iv5Nz_2W7g6!M6lVfwZQ+p;};k3zfFqE~BE7K4X0zo;2s zSejSHv0}Z4-}+ioxD7{*f@HCBmgr-NuAgx;qol3vB@a;efr?qsv6(f*Wi zsuDnrQTX{v4yY7WU?HA@>nweSJ-OSA-a}TosVZ4OG)XXj34&umFSMsin*=%D*eBfD z2kiHD$L6=(;XAnt(VJ#B2-2fgBHG#0Tw)X5rsbVB(S6F%wH|49 zGalo!rtNwwgQ(i1#Fg89jh4;QGx1iHw1YV+ZNLiC&w!nfD)m8dc;)v4jrkY0g$)`F z51JSqivnxsxefIOjQEhg3;a5Kyq~+v|Ey5O$wy$k3;$X_h_$70Q+SB!TarAqHQOFireO!KR{nh7-BJs1uI|Y4L~&>9L7C%OW4zm{K21K+j_A%fzr_167W;L;Qs<1= z5V+}?rR+wMbb2No@JuH9S;YDy*_>zcIjBt`S%slz$I^uoTxV8&P9KNOirp1^wl+q9 zsT@_GJ@YK_;KynjqesUHXCId00BgoQV?r%`#?`zOfGztn1zY{U`P!T_#O_2xb;k-C z&W&M*7OYwS!&@zxq06w!Jly$@?d+_C%>I$~Gv}o+Pb>9X64Ozq^~a}mig?BlYGG+M zuG$kHM2_V<(rCF7Iw)sRgv&Sjj8wx({^uF1w`%jL+GNO^SV(3*)%y9IG^P627-T_@ z=BtK&;yRZ=;J{AOq;{UaZQ(c9uS_s^&SW@R>>!BytONu!@heU+(otgLIjS=wddm5= zqv4VqmSUbnBthI)a7HI`9gYe*=|2M&(BuuCw9KcmckMgvX&#km_k7qVi3N*2s-Cpi z0WR1j;qFMNE5ebMSVk_irokAAw5USZ8AQST71$*@>@vm{=5^1*_)h)4a~h}J&D~^R z0Zv5-<_;kaA34^sFc-pM`$VEhRbrpk;T20i?7W0y023|P^07&yL$_feC-uIY?c`#j zd18i5XBkn=PA(Do**$>?^WDueMgUGYSh0x*E-wC&}@5GueN?qCk>jiwbnT1>#b zY*V3~KI9`@J@14q3pf?iIGgqM9VefcMiITbI&Qh`zAWJc0!A0>L?0YX9y3@RLWJ_Y zj_dcR-F-#f^`uVY0y-9ZIDt6CtEi#EwH#Dvn|I3|e6tRHdG0wNmqbDUA4O>w5X(>R zEJD-L+$LTpge0Decv?fc>*z`|4occ+@;tVKJ|A|5d@Zpg9p*$z0GQNuFOkl_Jq|$- z-W~C-!{2xN{u(|y0i_edgYsTm#g&7 z>oAq^^16Gf{ATlEYjGE6XNwT@q5sgoo*fIf7q`{k?9V@*A@f1S`Rsf3)n5j0)&y^1 zOojdSXVss`Dl3TzQ(W$QzSOVR^=yQ}ZTSbDTj|!z`R#if$w%FL*@0l@XXz%XrHo zzm*>IO&i(>J!enqCi>up{}TWc0q~H_|5pIa)@rn|WFQ$lYFYIEEmqu?bEvl7S0d*J zDxMuLvS|6=Vnxe?r}y|H5$lc(i0Lx(+lOLBYt`%nQrUQ|4B<7)-@fHA0M=GBe<)Tc zsKcM$U1$lKt@fIDSog9$;?4gKfE|hz6YUNE^^zgz{}llHzr~9GUjkrGg(qYgMVBs) zm08`p5z~2Td!gn0nGn%m-#@JkOdNQ=_Bs?RHVrb+WF_EI`~^%*zL4H1-7W8B;79^kSAJu1haebQn|QA z*_5E8Amv1-9RtUf)}KlwK@XjT9R!~>S>{lz@O_8)Y5_dmt>ks~_#nYJ_7dUG?aWqr zl%ekOCuk#w95(yf_BE80bdAl&h#~5`K;0+^`j}&Gu?Ji6GBo3B<-kKWTuIvSibJvD z{07`I^Jvb1qyZh@YE6LjnUk!b26?jg7^d4!bg7aPD@;fj*2dr&qSeIE9CYN;v9~-F zEA07^zRY-@1@2Rv8wY0@C)uU3EL!E;YDI_D+QKZY3u01FwDJXvpXhdctp3ofozsLi{472Nb}MK(t$?J$USPry!paMNo(K%cJYB-Jzq^RIA!5C5 z@|X4Di_6gwK{B8IO#w?lOO3=c!sfI4W!6pmD5%CkZI;!8wa2gSrTSpXa3ki!s)c)L zLDpqL^P|HWU3=*fX-9cSR5GH$QO}E$BFk@mOZ3iV+~V6V6IU4-0T34%*|UC6C)G@h zZ9g(Hii-4g2D$Bwn=iT$c7@fkE) z;KG)Sg@R>axGk442hob}{ zV2LfJR;Nk9Ad1c-!w0R2?W0VwGfosOpc;rx@;>@G5bC}YT+;5n&pHFH+v-%Su3`xs zqr2WA4e+ZDDG0_esG>My#Hpa#z-c1r!Jk{|o_@%(k|9$E+ifjsY^Jj81cE%22ruVk zH%!RNiro%Chp&VJ46yo6$69g6R0;?!b*BF zT0tYm(!)$ry3mWtVJ>yU^j}Lq9#2P)hjaR+|NAxHd(=1h`qS>bsJHEeA2tL_jP=U6 zlxrX23gO00_9rNhj=nJq<-@XEAIvo^YV}UM?tMw$-!g;!avyh-^K#ZuRvXbi38PTVbAeetH`ZJUzdc7{>FG;;9MfeYbqT^I;8<485}w zM++Isww12Yl6`_`$se(Pt9rXYk@$U0ai0KB^0Yosd`N34+6ZO*fszGcpR^S3EMxWH zD^)yf9LICD7}~7~@Q^UrWlZ4@7(V9wv1_`q&(*Y>p6j`)cbYs0NKwJDtn9_#2$*wl5VJqKxk4 z3v4llmimRVy~3}rt||t7Jr0)W3H}#}9TWwweR>w50oSTjV!g9ZPEE{HE96IreeBxp z-tXf&_P#oV<+ay|h;9uUee zdrn_^pR}U)t}>+A;09Mz$n~~OuS{u+?8iBbx9giU5p5&Hqf2*4@%R&F=J><)uH>RS z5+2ItzK_IcO%4g%#^ST0k1g$p7+oNoTi0ZloZN8Z6+X7Z$mkO*Jn5@4w;5bd{1AHA zp7cGGYN)HieqSi0A_>*MbHoMW&+&$6JmgZ3vForZjiw98KJPandws(;ukPV}*}b%% z`6o;Je=|E(^`5&w{8Xd!SAoT=_$cw1SLjmSwU3X8at7X1Pd`3M2%{~)t7*S1Xxw`gD#0+tOuNOP&@wH!oTG4W>Tnw9d&YS-j%=CF)?2q_A z*%G$*Eb4#U(sdu~+O9OiN(|W}W=QNaXy_(Z!|VoUNmLLVt1k;rPX>P+0kVl!dvlkB z?MRSFxS<*N{Wh76X!SD>>;P}}lF?r^z#FCxHF@A(!gZ*xCww(dg9kfq1}f))FEzkw z0?HbOf@6u7`4Q{SsqjAX1r0Ep5iJl44`oL3``%z9W7ro9;reKJ(%WLoj=t&cTPYZ9?(JKqFgO`b{Qja^#%(bW#+_Aak@lwJo+t$ z0~-^*;!)=qBOnJ>#!~s&5SIhUz0;Rm&3TH36D!^XubZ5TafL@WUW;EzU^{$cyBEqg zlmwSZU?WoL3!thNm5q3P!P*IWG{rkRh(Vo`WXD2UZt!GYk2kGDX{b*uqL%Lq6YL5d;D!lS__jb0s0 z&yigQ2Zg@@fA~ys5)cHiitNp317=O>)g5t-DDuW2w!x?B@7YM#80*pG5=OcBMV!XlA*ge0uQEp{xT z7+=I0sS>0GV*1H!)6`?UjLx#)pewhbeMM*Fz>DNq4<^*9-|fyc)%w2ulLH#~%oJq$ zP+`7>P)eNhVqP8-Rqd0`#-KjU2@3K_gYBg|WqCdOfzpt^9a#~7&lIC!!cp6a4JzOp zCSow-Oc+~{J~mQr^_Eayn)PL{J|Z%Lb%!nD=5Ry_lC8Ah1zKKP=g($Z$jae`mi1f~ zEEvh-TIJviutUL0Ek~j_7SG+q--AY;|2JB~-o*Sa3l5Ue8}cAj9t#l!xI(}q)#qEY z#f>_7T-{EwF>|`|gFB|t9#_c;G4S?>S@4oX!KQ41O!4J*o?UIKs@xSMmiR;yl?{{$ z*^xZlOACz9UFS{}=fdGj=a`FW%-t}L2$*XlM>HYHf3Ya-pv#TD4|-1(e!`{r+&|OD&+hvkoPYafSFU*4Ikfg>?Fcy)t_5-hkzSt#c6^aYFHDy5q0@JoCjW3lWy_8rUz zysM~7_(W-yVuW2Ij&hIR?k3-m{UD?H^lvSGUGVIWD->d98Gy=F1oLw^E)l&)18o%o zilBS2rr@}IbSl!|M)S2Q%I?MV%T@TyhI_b5^=|JT6IVW`oA6Z^ylmPgU7)18mP3W` z_e~C>q(?Ecmdl|BWTQ8m^CTT4JMI7Mw4<0!s@i*}&{U)0Me2lbJVn*SWmq?(cWIJz3bD{uXWsC_Y_Ho&r?`>?Ay$sK0-9}pT4wL1qtXdD@wHNQP z&1y|JX)DwaJe&ZZK@05I9qU$A5f=uQ=0k1Uk!@E4@rY)v_k-sbN?};crHOK8qg@2C zgDdi8DBhs~wAU2kt&ZsEvv9>W#RL&O_1|%+4u`j4)T~b{HeT(>5@$kFn#BXiO8VJ2HPgC;Ip!mlJL9;)X%2W^xuKUYlbv_ z^st!c<<0v^DIB#0WVMZZhgBqx&n2rSqI*G1q%$b>VHmcWk(qQ@?+-@*0jp}7zZzji zL$4u|JnJT#35-AR*~q&Ntb;@G4w z>)kqO0_OkWD`~WRE?FV)ob-^~Y#ag#zHg3Qt{f)wBh4|*Umxl`E8^X}wc!a01zl=x z#qiPX_(IzL>0!5vKs~qnyqV)Nn5$gryvG!H8>U+@k;RA-7=E6l-QtmpE>To@itBSP zI*@kupB|jJ28Ko0PmY5LNPc&~Zt`>Jo8Uf}N@%mLHy35>f@~~I0@@%5xDMGFx}?DN zUuie*T{o2aOncydf?h>wc3>GZSW&KnjM=S&Z-fxgX*V)`bFSfmpi-$ z-Mw9{$R^ffJ*#}}DUBxN-Ie*LmqFG`khzi;w8%1jq?POBW+zw6-WNF#1J9R#PSFSd z$i&6TJ~z$j;TyuY^D_v4nFAcrSEij$v`4={!dczXsn`1uD)0*r&-karWln*QmhqGMUyt^jY?1f5iFkZ{YgZZ@mx8 zhf?^vG$=a1!3{6)>Qp($-l*g@Jd7~pf?7>`SjVY=3GKOcHx-)~GR2fMZ?5fQ?kM@bpJ&2_W7w}}0t;j1#8rdq3AO)X6 zo;&~vOD}mS5?Ho-dv240d$YJ1QU_VCm+;mNjfEl6k0aGEYMICFC$AgPfG#mrH*yWMVp4eFOhMfq&rVz?HqEwmuRj z8?5dn{Jh8Um)-YN_cXd23>@-t=)z-89Xx;Ga)akV#r3x9q?W7_Ier&f#X!L)TL59p^BUGmoJ!miSqGCQ9tl zc4{WuQihN2L1((oPvXW9P>8YTwQpP&KIytVu$~tcwPzy8oyetN%uZi z?s)R?c1RPek8RZNzI4PC>xI+7892?;&UNOl41AnjI%w)ceVs2V>g-Ir|J$j%r;^3= zSJqABDro?k=3Dxofd@zW~oxM?PMkL~{|yB2{(?tA4ia(hhw& zJ=fj5YD0Ed45Qryp2Xw67F`y zxXu0An2F%BS=;e&ncJRxh~dl(xuroQ5o?+%E21D{|arjlJ_dz990fvlD3XkRY1xPE9Fs4QhU^lOD zbcBz8&G%QZ=dVdmn4=50`wLd)**U*4uUmYKAhrOef&olB+pTdkifi@gZJ?+Q;YM!+ z%`6xU3%x2Pps zMfNLb6>yAdt0RvZVvmFwe;kQHDZ40=|xPBz+lPM)&l zDuY4ITZtbNhTbJTRzn8)3mnvcaO<;s=(n{av;ZtD?HzA1T9Wm_OMMa}$T zS@63%PlR-&U_8d)Wd3!zYugY&B!cvnD_Bh_fz+R2dw9)3=cX5(3%ZIT%g93IbO|5+zBN3Vu%UsK{?(* z@=~E4P`39eS$Dt2<5F-miC;c6I$tTs{xihHbe_iZL_vmXW9tl!w zDO<<89KUa(^WH;Y<9)S6cLtD&@8fJ|TD#!J?cR!nN{!Qzc4?6;8$L}%tEq8WMSJtV z*a-Y<(a94@Dk(*cm!)#To=7bVlTD$-#}b*J;*P5#tsCcizr%KK!bE)7xffV4(_IRG zkq?LRLLX;RBjwZk*Nvz_RW@9jtQ?k4d%dKDXD#?x%I7h)s4SVaDP+I55$1G<1ZN!| z;&h82TCg4JuksK^?~ZpwB8`ra|LhrDOPscwi8pg8!YDHi4yP}3vVg%t8Zq2D3!w@( zdwsX`u^%7CgV2Wv0*V9m9PDIv4IY-hl8Xvg07cKhjwmc5g%{3cYTO#sl>b$G)G9te zSYm?H;JCf*M>Ds-Z`Xk$IYqL3D$?}CReYiny-e0F<@;Ng-rc)?6?a?cjJUo50Rslj z!mwr$p$I$#qhqW-qqup^q*d#`SVUlj{qVKun^iPxKbvgAiy5iQ6nSf-(#*`!1Y4<6 zbNM89s1zeCQ+99WI6L0IsmO8GuMZXoT}wt>XB(S;Jst_m+O84#+~c~~Mr1~(MFj>- zNtJwc7upGGip#0VDQ+$8d-SP|FCLp4Z3^Vy7e7c%aLpCS9O{PflViGv)6ZjwVnl8E}rU)3%u5`%L{Sm3gnamvk1-l7EVn#|8J^i**M zzxufDaVVK29i}!cO?!AlLtOl^R-UwjUz_}qL!Xj2j@s+MukmaDbFvhVq?@O4KaJ2W z7nJ~i^goh3hx=Uy0c_e_ptIVGrrga6$o+aRsbF!0#M{R=YWH6@A33KW2Vq9gD+m9H zYG2RbP>m{Hzcq=pY%K}YlKhcGi_*skL zvcg)Raf)@LP65i_d1-pP1Y|8ucZR-5gs8a|Zv=B`ZuZoZAo2*{bra1ZxL8M${)iXx zcU3c`3L(54ufEc{HIdTo*Zps;0$73Wwa|RY@jK_^Wk!*$Zysk7C{CkL-h6-uI#6BN z4bWuUm;#qt=xK$>hZZLfPVZ&c=qLqG+(4_u_%i(ih zLBzw%eT{vPwt?)bCZdbnsPmazId_n!n5VK9plam^BGDjg7g}jVy?2(&rxU6q|F{m1 zRws&`zF6sej3{rFcCwjf=$SJ})Y~aTn9+3UK9tf3asd!;U5Vf&DPa-hlL+7&FHLKc z4Zd>H77g$;8d8{Sa2y98Vjz?c`J=n`wkx&G?k>;)$vFIgS`jz8AfLz(-NXD$CB(fP z5zD7tSYmdn2W7c@2iWD}$0XeNFp>!-*pdc{%pV_)$Q-n~%5KA8{^}<;2itZNM_Onu zz`gTtdJjGXLEO!go@TKhH6NU(XIS**_~ajN!jF7eJ7GgbR?MQRem@3i?F1UNNe5Za zi>yk8Tp+UrNTygvkd60ED4T%4)^O_`Lw^E~59GWby>k9pETn zCaf}PuNG2X*U&fQEXvUwqJ2`b#uM-qiQnNcT_;oy4<_7yqcxG zl{K2l)Zpu}My`35-TVYmadNM`mAW z*eRn4FcEUDKq`J*7KaqtWDDAcNQuypG%7F(6~d<=gW@}@2~|=Cbw^P+i^+pa9-T$I zO1Xn5w_Q%0l?7}t>jl`(V0C=pIa$AH;c^Am?fqp$Y1ta!ScJBgYQ#=9?Vkwx?l;~s` zBf=@6{eFNz5sqbt=TARhx2fvUEOk90=yqyP=P94j=>j42e15iJGwOReO+g2Cc9+wW zp;5omVPQB^yIK3Od?N8$265$7W(VXm)J_xNP%=^xcEXkB&y>2J6y{G6ee}?8G3js! zO0PV2M~z&KMxG$_3hlQ);X_oR$p*~f%XDY}A5Er`&AFr9JU{**KriJ}>Nt8ztvZck z-0_YF#wek$xXRwXZ#MnyF6Y@zsl~$k!48#8dMT~g27|Ulji53eJ^M^^=}nT=mMhh6 zI#VP+WhmCsfxS;3(xZR)x7WwMZL|Cp@Lc}a^zB&acOfX@@99(`889EO5k}fxbFyBr z0csLVT@y`7r%FW-ym(WD2}h+G^t+*HCO*MGT2~8Z^xrzXrYNNrV-(NU_f*Fz)ttKJ znOdQW)S%66RUbzpCu>Mr1CvkcMqBRs*gA^P9CuLuTL@C6oOF`&;=2MMJ2+F zWNLff(v2Tczpec5szuL5=dj7?q9B(l5rf*56R}hD4A-=zDk)#a(K?385p2?awyF<{ zKfZ;Y{B?Ho>ns4}_GI2WFTrZ`%(WA2k|>kfQL{Tf%O!fnH7nNqP8-bdswsFxNGVbxI|kV$^xpFDY1-y=D-gUthlLH91qSwM^Me5RA%jKPzx@ z|6cwE>OYW!AIhzUI11TI?8e;^-a_GgAty&CfN8eF-PDESUcwmiV`KJf(kO96ifAK+ zLi6ImBq=XI56Wn$hbV4=6w%7%x4W6ONUu6qj((H-1q-tJ*XHY3Se!P8+it?6FNAJB zn!!ty5h0=FVuKN>AAh6O0^x^u?x!r+h;bp!ebxYSLUWyW4?jXackL_8DDk-zoea_2 zbbRT+LvgkEwL|ZxVsSlL=?k=jGYg5lGW0j36hM7N#C!!SMuWbf=$>3Dn5KwS-a>2m zh%#1Wg%SKuTG=pUwf#ixH#0i*v~e4sUj(02mLr&p`8+t1xsYJ}!hh(n4F@J@NfiI; z_PB_wpGmyeN`Vk#3o<>>4Ksy6{y-oCu2`|*{&-#-OH(GiseFWDfIMdzFg+URmcVr~ zLYV7g756~dL)_e%-9&eqwI>42v*@+Phw#O&rXa}{=eR7z5W@KsR52T37^RcQrQv#L z3YpZ(#m6Yc&+{Xnkl14dX!I_2j&LsBoD2)!07?gh*f>%|m|?7R`u^-J)rN`d56wlu zz;!NZoC8iN1f;wO>2-QXsVqCbaJMXTq_#1bJ_@lUcU3rONl^?^ol_m~(tag0BPry+ zKK_2`^~}+;L)qIFe=;f`W~OO9yNj?7e1*)>O01QkvtWAJi`yefp>4$c56oW4x_X8= z-&>FeiadJL9c{X*n^OrfmO*7%S7tUQw#uMHcYW@A`>Fz=uRH?lhSzSWoc0CV>ZMZ* zUOhZ8;(|Jy{V*yJ?jeJ=9K{WBcuJSR4D!P^_g?`kR3#vxBPyd2;815FUx}qO3m}O} zT5k1SB%A*bltee$oM zDHhuGg>xAMr7wkR|LNfU{oO;Y0|))Y^O`H=Nv=HN0qxMaz=(f580HbA3LuNT-Z8^> zI?}-(Jbo(?oU)?sI{u^1{y(xY{p+)Jv@rhmz23x3g9$Eh@IZ|Y&x8+=cY+q;1Z3EJUI4r z_%5+fxpz9le6JL|Uy$GF*K|>>{mVqf1=SAf0{P-5AL2(w(~Z9WbmxclND#4iQ>W=n zVTX%5J}GI~p#tV5!v|4qj4gQsA*@JFPYaJ~1B$d6Z{-uBuoq=$7QV@dSanXkhO*T& ztD^)#^jw3oD!*8^f2;Ai(^t7YSBlWULw-J@X^J<+@P4n+O8TSyS+S3OKAg+=!3IL_ z+dEeM$%70BC+rs3U?-L$q>Lf~eUsha++`Lh3pBs~c046GxWzT+2|sG~TQ}ss;S8Jt zPow?6dq|B@hjs~t+S%qm{4OR_*J+n;7*(yab87^0T|tm9fwUWlA9er652Ew9q|ix> z(#!LWc8q=PkolA&V*9sQ)FB3rh~Subk#YRN4uv7$L_V)v@J+tUb}Sd1B1q%5zNEg7 zp@7M6HdYwI_+E^`%_8=r%> z8z|G|%icZ1{;okJN6IC~PA3B^_-hisM=tc7I`YNSNTr!9jT<=<{`ADP5rXq-VfA6n zz>k+ME8-r(m!})f)e?fQKj!&pd++8XN?a6i^IiL81U!OCD<>u&TqY)8BqjGJ$I-az z+HjZsaM9(n$l|NN3IH+pplIs~1c~u)bedqZ98QjWn0}J6*^$HbXKg)v4+!cLw?^N7 z{9BK=&Bg`)8O8nyf?px+NBh9h>@b z4@!;H(CvK7r7~nwYLMDPBx@LdN1bh#ua+9QdN(Ot^83}XU6+PJwx}h&{ZyP>d@mIB zKKN^pVX-+@!K85bHnGS`x}sp55I9R=l97|a&x3R?e1DvE{QUQ0ORWw8O*!A_%-V$J zpq;o>#(BV!E#6|#gn)DLiT}wVClpygJUBa&c3h-7_n2>@xVVFcTwAl9rqN%&k3}=Q z|BV*&XGo7CytjZ|==g2f2(kW{uii(C-d%mjiut^<^FsfZ=5DhI6{{RK*YqYnw&{g+ zF}R@Y>8cHHgr(u|8kf9vG-;Yzu?aU)`j9N#>i1n0L7^nttm4~`Jkhy)a)lQo+jd*T zq+Y1&8Sf3A5Z0}&8xV@`)Sna5gR$@96ISgmgV7!PPQK3S@&OVzp*A=PnpM@D7)|HZ zyH|?gr2d6ui5uU%;*?PQ&o6wPe#1Q3#+l#&-0u@0>sHrkOzVD|^P8sVqvr6sJA9kW zG&@TRi9kZUrmw6N*W8-RXYAZ+_5tpA9+;PNUG~4rN;~|-0$S{f4h z0Ykh*y>Gi`r$g&iT5YxdLZ_dUuy4eU6KNcchHB8d6E6?P$?-uU;UPMO$D{NYtWss| z1zuI0iN-n=1KX`g!zW{r^qb7wB?m&-RROPRhbw|)d}p!rN;*`XVtwjzta0;tDG z)fi;1ioC8r_=!2u+rslM+2B)QTg}b)_tn>lBlgzQXgKVODR8im`2lqe8qqIz2Ge(% z2QnrydBgybFrdp8bpm{pVR)3J;wXG$ZWd2R`CRS%r#h~jmpS1;;(FeftfKcIdfS-s zbX)u`H@2*`dN@|7=&i$4R&f?G>`gk+LMXwAi*47?)Zq9Z>PsP0Ie#i~`kaRin&WS* z)@O{3`BkwrnF~%w;)&(bom)%uj5Bct{8uC5EVySB^J@S8xwIlNKM@U4>C%d=()52i zjp2`&J_Wh%NBVmJvmk)V7ZB^wLmc+ZS1aC6oxDwCrWl@h0w)R$Lyp=@S?nrOSjTj*C?6M-|5XjbuU=k}O z5I^oQ;Nz^h)K?3Ue=i6^{0&@l8F4;Vc-pG-k>@l91E8g1Rqq?1-l7H~R4&%XZJ;Fl zBo0bpE2%P9#*$4t_;`h=oYl zgTGLU1_YImg5Wbh+2O{p7HuS3W2ANR1Vqxm?p=Ab02O=e0xI|Mbq4kkJwR3@*n$|rol2wqQ%b2>N6c%B_M!E)dMt#%3Uf*_eAf$;iP?Aaa) zYgpaXGyOKo_*Pa%O_3hGvS&&Deg`wdb}kBG+wlxpJN3m%=gKV=8-$IW@036sTSafw zGqkT~zn*iXw}Im!pn-uYcX#oMz}Ijy(}w(WD01P|U;IJ+QTSMLwN1nTGCt_w8LjbX zpxYaIrVmcdxPdX?kN=fl=n0kIe3@#E<|#P)I;|E`FtGIavcpX;*&8DtQf%wrf2_m{v@*AdpIKS?M3aW@s7&8mewbDZfT;8$sDOyrX(}QrAR<<7&YCkb z=gzFV?wwilVg7;SQ&y7a-TSv2%b7cCjWKsWy9%5U==ffE^=RNDYKd6SN(y^dgb8_-^-y|Rsbbv*rC_PjklCw_v_YK=HrgZ!Z z2U6cdN$nXkK;p}i6ZwTk$(rF*WAEQ{Hcr+8p3D*zTXHU8@8`9&*t$+sEezK=eVwNy zzn6V3(mf;^t+_-PNSdrv{(H>6miUqH&_~?=4;K&G4>Ue(;hx$o5zZ?p+2Hju)!yL+ zzOc9ZgTbc#WFC}=eJ%wP2N@hOfn=>yL5)XVOF4ra#YjzD4ID*`W}^!gvqy}ah6iiM zj&w6Klo?>|>x?wt_$jfBy+z8{>96kFyJ@v-y?qGit18Zd8*<--tE%N_s>32u?))|n zmK9&bmc1;!Kr0QaktUX&Tj7$0`SDgW#wsHH$LaPT_?`V8l>e}*2NA#2n(2KtIY!pM zB~<^k^U{j9(G&g?2;(3yke>g$5WeOi0gnE`2G55m~V zelk>^G|YQC$MX{2226v%r>w@r7(#uwps-^eqrr! z$nyR$GI`R=xbya(9fxb!d{E@&=$Ac}>|M=u9A4Y2LXRIIPjsxLD%-E}T;C`%8W>=R zDs0Oh^)ouPfG;atT9&F>IG9Czqq<3*Na8a7j z0w{`>!5+Vfz%bLJGCk~%kjXur`*-fwY#wiMnLP?(JpwS7P8=#EbAG(FW@9x!L!a@} zH7)-g zjjp~itVXa_^gJ}inSe1wG7pSm05cTS9>NS0;Lq~nL%+F1RDWS-B^);ObAX{mI|c;1_*42kW7=m(ytliWxL^4 z|KL5y$cp5^0vQl81lGZl^egY-{Po}obrkedh!rQ7h~Z?m*q*qGT79sXTmS5I2jHie zQv0`SO65qU8jPe4GsfCyiSeN&iFLTPC+95E?O>3OG`in9`4`;$i-yc`1QOR#j<+~m zJGV{6(zBuCYaxRZ!_Tj(yP-5#-`k$U;tkf4@LDNHOJ>ef!r&Ay8nD( z&u9QJ7AY_lDOwFcOG~#&;A0^ovBPr9QWdAEMrtCG(vP21`cMj`KBv&n&c-%4-;<-yj-i{**uPmL5Ymo}Pc6)txUWussIe0h zc5+(CKlyNub6C#5&Pk+I4$+iH02%kOjXH6a`oW+9|IEC+*?hW(&J_oIz#j^_b*@_* zAnKoc`&Y})5NS2v-<@-NKNI`DX*5l_yB=P`-UlC4^bE?#UJJ=}POFtC%5#Ss(D63! z15j5@?HApsHx8}Ri2vy>k*fu=T z1Kwo&+$wimqTJrduQ}N)LxaB3bYKd#df&0}K4fF&K6;d>tuV*1>+F3eU^b@w(8(6( zQ@RZC-Cj>N!v&#?MGrn0^iNXp!3ibPlwVnowiQAJXosrIzV4nu5kZYT*1ipZFF69{zRAgi9I#0U^iAz=Xlj|O)v;WFXrB6caw3SBrfB~5boA$d} zVSOgb)DYQQx$RB%e0}5fSp}~;o5lnaA??-51G%+Iq{HxmwzNCad9=m$d;3%+xwazw z+j|gt3ag}0G}@1d7%U*$iA8vfDh=1cZ(mBwG1xj|wq>#n6CQ<)Y)*_9HLq zztTk;aJg*I2Rx>ROrf!!t!Nut(_`i5-6E8l%CcL)#nB(mY4TIc!xGs>Em5u0!)vIx z$sZqK#bsL`T1@VZv#BcD1x~#cFpm~&p>=fC6jmHbN!6hCaZ%rf9p=v)Ouqd5ISvwWDlp1q!EoTS^^-a zYf2Ot!6a|dv$4l}?{n}TLYNQZ^UJz<1#)<4_P}F9Ux^XZ35H@(Gl%hylRB4C= zG2w8i66EB2)`4}B)(p9iZYww?xV=#NOZ{htk@5OfLZG)HN&osB+!# zQ<-G4UQ>CJ!gX;GUV--@j=unT2*e%YJ&GoL*fh9*jj&Q2{2H0;GNUl=QRQBUKs^Nf z7T{1HRZWDLZ&BuZhjBQHD3^)q(%7KCYF!;KPemGb!SF;+vk2I@xVMndF!cUN*B8Am z!okQ1Ss2K=SOwN)IQm#5Jd|S^qT?^10x*><+;N_%N;q33=1K=~T=eQ#mF(=#OMd@$ zHMrjxV>wI|&0(ns!ci1ev3FS6lNk(WHODi!E<0<(2-wR|!v-Vi-*O_CJY3|Q4OLv< zjkn_MBX?mVip#lgGH=`k?<%tPKFs+Ii*86F3CazrYNeEMHkf>S3@C8KV9OYkecmwQ zX3=DZ2zFgw5?&HBJ~4c#c&hjFH+25}W9N_Mp9d|E7;Jx&lo?fsy=mzAjc|~9k`O)L zdqjP5Smr(44mSx7~(&F~%)M(jA(We}>QW4l6bcE6HdYH$Y5uq+7c(&DQo@ zVa864ZBD$(hT#x7j!{iP6Vv8-D_%~~7p6)9H`PQ<9H%WV82~4EHxpq54awZor{a#C zH992&x9?;UDvhMkFoT0G2@(;<`rK=)dLlar`lE_Z3_)US;VDnGl2i5082L>=|%Z|w9SY?JaD&@w{Up9L&+Tk*J!A?|M=~9^-Cn$K) zywLin!sDQNcwtY^IrTDJ&9A8q$uMbop7kp$WPxQ z@1Rr@KSot>#9sdK#>lz%Y_{RSO+#j;ZNfMtUrAym2$!mp{7ji$a1_jK;w?$l<27-5 zCr9*jNlvA+GD{~8b$-PgxpA1>(lWu8MiGS&VXkITBQ_TlfU~^4X}3>Bd+CxUyH^M; zw72V*Qq|5}*3Gzb;DA#*mI6y3`9!kbP+New#@@~_Mx`pu3M5*kS>t@`-zyXMvJVeT z4RnP|$l8#{dRNc7_;Gy8k2CCJ(>vSUoBZo`elxGD-NA~Ta3) zua37>)&Cj!_}?7w|0DA8|GncKWz)%ud_W$SRj?u-=lX8Ned4dKfW%f6dZSYB81`S06n)8@FSdw+i)s4og0 zsNX+41R$hK$4&>7RGZ*9nLiG#bLv-sD;PJVz@pVD|>_UQPJt#6MBNY%Yr6T!&6 zISYkrd-FCrpZA{Fn}3er_^GQHM~yx1VBPGR;018Mel=tQdJ!9Ke(7Q2XP;aWYBcBa z_r1-Ar(wT?KVAO3a81Y1?#p5H)*BL1?O>TI7y!F-pP{i$t0!TpSHZ1#d4KcaG(OQ0J&$+G?OLR~lAKWzXRQU75>6T2K#L z=by}c!eP;DbK=GtuhHbnom>Zo9%?i!S$7x@u}AA-N0AV)dCDK6wp>#?+Vf&6;ZYa$ zXtyB&vNMW-5YW`_`ZUI_bbmaC6vfxT2OFY^ePiK(Lbdi+2@eEY;H@WOp==lT9AA|< zwi&$F$alEm&`^FO4MZBwXB6>p`SE}{&+Zo1pd0@q^5Iy%ThwCHsN_2Jz@>k;n3>(E z5^Oo`@nW~6m*sd*o8)*^w_mv@D~M0ERC|kY@{HG&@7*S9AIGsA?=AXKof{cp9^cBB z27)x-E|{jrp08L&H|tKVBgtDJq{8zd-A^T{@%>M#K8aH>8`e3&$h7ygfZXriZu}VT6GyOT(Qh`Me5#X`@qZ7`QD(_iUqmCn48l@u8CLr zUU6QxD8hPc+TIul5D~rbZ2HYU4JJq-UQd?Fc>UAN^0u$xwG>n1jK9BJDTBV8lJTO; zhi0vnEk*F~k-+SX?tEF4#7cymqi<&HDv#_C5i0^g5m0saxsy6gj;jDx5k}aZhisB2 zDwyLlH}4@a(Rwe(88@GTx$3{aCsa?TQ#I4KOLtY`H~O=xDE!`db1+r~l;rF~E^9ASr1$C?Ok z!$QSGKC!zJ)_X6-PgY13tb+Dd1$&vMF}x=LKa?IQM4nzR<>;3sv?ds9CKlfQ3Xr*I zBvWWc7ikjXAqO7O|yqBkIdKepHp78M1*z&Cr?C zWY`^SGsskK=QzWOQ9BL+n+mQ~Y#H*7K7Cq3(gDCo;7qFOXgta_}YUZV+2S4`X%j6_D3@HN# zRj-@`{B)dO5I<36jj^Vs7G$4G4Chmu(lZgiO&@*9zKtY3v_E`KNohV$i9IgGi7->o zG(SIhT}0?QR!5Y;T23>${n1}?a*d5A%6GCK%k%eWKA;$_z%dyzLs$j6q3CGIp3A+#UGQ0T~A2xH=?qemae8%sJidks&A-SuWb>q% zA_(?}>?8^30HZoUV}Z?dbKuly+EzM%YUZ&5#qc?J#2#Qy2>5wy0G9w18B5!uxWCj& zf_+Q4!8{|b3tV4jkBtw0co$lv2Wqu4`mx|v1tp;DL&a`|*V4EoOdtS<#oNT-a4@j%2Z zg2E)h@>4=j+colo5(MHPJ3%u-pz%arn^K;Z+iARHWb!i7(@ex|I}Prat3}S$#Q4Q5 zN1Yvy>z(A&la_NEL_{Z2p=2t8jBvBRh`@vfxDdh1nY@@x?iD&1#2U5YB@uJ@rBIFp z*YK6>qtTv)&2T&oX=A}S+U18uVR(Dkc2GRm-&-Ke(eU`ppSux9OS9O9JgVtH_bl7g zDB^4>g?XsMc%6vhE92p$xu?cP41m$_rt=A;AUhoDj{>@884=aXGhV|kDv&9Y1XR@I zY40RKcI;2hX@6pHYZu856VJaj#SAjt1`a4-0s@*|2+Y|I$QJ@#XL|4?Nd9?4njVh z;Je5~+Dyo{HF_$QvFau0ws)m$dOQ_n7!5@pw<*jW1m;~JRIetN#5zk`#5Ub7Jf3fJ zq_CqlayRnZ@RWLs)OF<*lI6U&ZJn(}SI1tP@wqo)ziH0&P&0aykK2jaYRs1WdK3KTTkJtq^%mN+mvkgze zvm1q`dL-Z@2P?r?|0jXSQyajtFsObCNS@X9kq0g@VvLx{uabZU7k@}TEQ&Q%tr4;( zjCqa&+KB86ILy@y{;mvOGR-O66oWk|7Xv%O{3uxp0DLLqyCCQU0=c4q$-mvukK_L{ z%jrlkcbZSm*U8LJKilyWI6oT@6xk>;7c8n1dY8NJS zo8R|vzYaPCJ+%_TuY}>%t`MCg7bo$hPs!>vpPzC*f3KJ%cj(Z9bZEK09oAiQ1zH;t zFAO5@bL5z|CX|&3%y9&li`@ARH%)T@lU!LcUN5m+Xs8W_LEAKV2(rZI4=n;3q3t3( zu>tbcNgWJj@#6!SQ^k`IiSE5*D!bZS7>!dYb++eNt0MINF1STtoJ!HZheG zW^7X(dP7kp!udC0JiEsLQ8PrELUvnuh_7hR1imN88uQ*zy4@u;ZZPP+eP5M;;$k^4 zxb5q#EPx9Mku${oeZY5*zZYl7-bi2v6VnZU@eXe%CK1jT>UinRA^y1YZm)%O%K1Nj z>elPgdX*)O>q|QoFk{?#uiQE_aCk@jQptU>pVEg(TG51{NIIiE}Z6)!g6xm4f zyEkjKC`7l)OWi`Pm{{#6-y`0=UV7JvN2VVmgVs3pa*{V;`(_wxoen&}>wo|=Ac1r3 z@_y{BNlFG9bFxtQ#G2Mga6~uk-xJb})hM z1}S8mhVh)dE3v|4YYyxrWv$QR43EgLt%UT2i*UCLz~;Kp7$3JF*vT3p%508L%c$wl z*+)e%1f)+e+N`nhtmvU(@{dG}4>K8t$#)FFBoUEOpy-G}#Q9@N=ca{x30SbbqVFss zd=Sy-85B-5Ydnt8zi`d#mCu!BHpAae?CqFOI_;TD<}+~gjoE>VdH^Ra%Vu=A+#NGs zGlra-;;ZHQTEi7s*PXGV|3RMvGIS4&=U7ky5(q=^t_cWuDsRp#XS)3Id7f56y5tyd zE#f5i_$Y5}0f(g@C%Hhmiyh2lA0a*7uY3%~qdR6F?~Bd;QJDp&JcdTj!cPGIUOhe> znC0@C{gwO}Ar9)moATSv2~^Dq-JKJBJty*cPVDcTwD`O%=e+!hc?GX|+}(L4+xh*O zS;&e~@q@P6LlwZpat6C|+iIx4!otDtWhd0IH^Lq{;rkHQWp=V_%G&SR_1{pPf8}q-|yyyd9E**`u-nP#h;4g9r?&zCw`M3Q25W?CXUSuNS>uFQvSGQT6)O z-PdmpU%y`d`+8OU&H9Nq?{i+?k9-Zrvk}EXFRXz4l8~AlA9;<-dGMQ9DURM8o|BQl zp#5#u@Ik|1+#3~4uG!Gvs2Ln%;9DfHe^9$ zh-29Ih2#!L&L4g&I`ZoNz0A4gjtM@bFGxx4RpIO^*W8;_anVBG$3F>jvfM}zN#sNW=FXbo=o!Syg7 znO`^4pmD02^h8_Z)u9*&K?GGY-^`y_m5xHuus}WmNMn42)UJSusAzG}DJ-N=jV*5( z1)lxLjoGaBdj%fkzGFOd^&Oxligv$!W>*lCC5P@N^>S46H0inPd;w_xfC1kZ{REDC z*bVuv@bjYQMN78qYp-&4k@du*8b;j?Rk8DK zf#Oh?66L!EJb-6^H!liM90k%gEHZh_TpEsvFMLeqW7croA#j||7dVK#iC?jq zt3~<2xRQbMq_?tN@cem%#9Luo21;FR^@1wq)b?X8B5(o^Z}|cg9^w}_|B7^TnFB)} zn^$gHSA<${U>@H>Jfc>;evgT(*)ZM@G1K;lw|}CL#rsdxTrnRJw#^#i!912nP&@gq zx?D#OnF3@#eZ>Lkoe0cZ;jfpz@OOdQ@nGo6K5_?^0a8ZqAUnC>Tm%$;R%B1jL`2FU zShw2tI)lNZc-;#~SMRpHe*m5}RWk>~1v-kB*+wq`S6zN`O4V~=IJySQlwJ64{^5&Y zJamvkS1p_P6MX%CwyyM+e7#53Ak>e7STBvMmeNo*@(s|Zh*$3 zS4}ec1@~{1I;@%Hil0!cFH3b& zZYO`)a%u{B5#6s=o8~!$o(MA;OuN8?J53h)NyiWs{L(xfWx%(wHc<<={=@Nh9nvPT z-ONghT^cf~4a}D#x&EQMx({yMdS>b=a(6>Pch8Eb*L2_!kZUKjsVe7kLZqRf01-WE z-~irJ2ygyDpSeQgLQ5b!}S7mwPWdg(>a6H=Q ztIN7(n$q@(-~N@SE~z%XAn=fp&qcmbYs?I48N!M3eAi^0=O7d)HWu*|q+$IkBCo!s ziLP`({wbICldS4%2A~WXkXQ`PBAo*A!663|2*+{5(1W3~{y+gdCtQ&yd3)?{wL>w; ziW`DpmFq-HO6xu{KlwN37Z+$u z7Q%%39ynaxmeJ1O+(K(Lv0*FYCU**sL40$;JhNh70TlRCEf+$2mds7{g?=(5zz`rZ z;&_c7{(y^9fN_{Ax>bWXxiJI;0aOK9DRxu0VN9oen!Jr4+6y;=Mv%m(y2L9k8L9kn zUuWMEwGyTF0xuLT;uD#ZVu2rMpxz-)hj5GQ+6C(3Zrm3?&kYN71Ej#d2)_EnH>WoF zK>Uqtf;e^#ra+w;IWboTB{e>;vMVT$SmyKWdTB)8VV6Y^#K1!4G>D)FwFHUxED~&dG#@x8P zcIexnRorLW1Y6^4x*U`NYd2;rXShR3})BEo3R=B)SsIRf9U~C^HexY6x9%|wI z)U*fRkZoR;sZrfp^J&|!bj=T?%LbRW3OU`NGZtzW*Z(AU&q(O<&j%;9{2%WV?f6H1 z<%tC%rPkXEt*0U%AE`O^^fczXOo9{R>I=NaejvPrtv<|c?8Q-kl2KcL>8F=BAm|Et z3m}qzTD_svrGJs%`|OE!ukZb?_x7J&cY65A2hLG3V63GPab}n z|F{&0D7kUvY~DlmUB|A;&ejCKyjc2>`%D`<_jTjQQ1XqXO%GhOXhB+gcCb;Qt5$IgEoeIW6R&gxZ2 zolT!)or=j5;adLO7aH`MuP35v{(c8mR2nXw)cba9r4%!L;j~cscX!%fw3t2fnRSBN zYew%?vcz}PrL>$sE7{#ArV2^;#+Uz($x1&gc5zlOTZUn^@le0i|3C> zft>WOrNr-YHg4r6cIYqMZlBO2l5;>N`eHikh(ev=^@NH$SF5qKMmX=6!@wy0p!)}K z{I6TbG=En#{|d1jEMZ1JQ>e6W!wX?sy_=^6mn?zS&Mult)_g zlV`-$&D9o@@h0owrCvfcMW4KI9P|`NmYrcqZ8(+oS*(t4}GE%IEtE zsMdjfUKJWTnw%SdFCPVsEhAoO-HUi}JNw;xd9J1QuM788On;+mFM+n^ax2wgV1fH9EVi24 zA^VY(Q3%nHkve*zVep6U?a8k_c`4NM-+up2Z|l#xn|V;5X%FHKK^;2)NxOlyXYZF! z>MEj0I*D|Cya5>}Nv>&P52Fi^(vsayfcS<^gArxzj7Fi{uA8cPvl^j>y@vrOo`>q@ zZEFsP(-mGkI5>^GBV{1J$gg; zB1^#mrKd3sLF;V?N6McEu$#6D{3Lf*E764`gtE5_4}A$m9Vi_=tIQktJ5Bb6qMwc( zp$r*(IvR*)(0s|k1RAXdcJbqI2EmA4b4*PI)i#}O%4aAhI(VOA*!i-O;w$$i$&mU9 z?$0WJoTvYTa=6^d+?q7$CJunwp;`cJT$Ei=6bd;oByS@e2gQXxfiS*QlXc|5jidJU zDE-28){Q0})kh0K#(QY%nJURkv+6)4?%fC3!*vcQ8c=q{aAX^Y-o*oCk{fdPB0@g(dQwRG zcKbNB8_%3?x7EzO<_k?6MTN^4({wcs3HBQL7wE>(nL6Y`+sVnd^Lj}U!UccWG-BzD ztecmX(-p#Xe5vV48|lgTaY{1%lGCJv%0TKId-t+(x+a$&5o*7E?AtKhotUOxjxyBM zB)2q9@=U=k#{fMhyP>81h-S#?+b^GMit=GOXQr5c*b1pi*^FDE$7%Y5P^#O_qbn-f zWT(?pQ{9G_Ks3$4V!QZe2Hi^Zcd2&E({~GQX?>H|W;vu%(|I7; zHH$3m$w^Jc((PlGow~-risdv1h=l1HlC@Qt>(b|IAJgRW^o5=Q>7@EusI&1Fo;J?W zrOmBp1^^S;2OI%|a6<2m!+AbCm0Ig&j~T6RCic1rs(v%=M#YE92aGmMt{A)fM%Pu4 z>9YMmCS7D-s&NJOn0dVUe2lHZAT*!`9@gD19R`&bx>{oa)wGAM|ITQEad@#mMqM;) z#??>GJkF>o(FE*&2Bxa_QnY=cQk(qWG4x~p+#h&m>i#_L?yq<9)gUidvhkx0*RF7- zz}*w!XErEK+w6K}nQI-!oX!sC_49T!AImGDuAG@;3O(-GIHm{crQURKsGO5Hd-r{| zo#c0v1MGp|mWe$B`t~?qdZnUNoMZZ(dkW(7(prw^tf1mv^M4yURs-|U?;I6PJDtxM z;%)hqw7B@e2yLOX!-N?})$aw^s{C)Uf@(5OTX!C0_dZ#ypZ6YwvsxnM5GxioMH~!VxNN<5N^?LY%v1P^=yx-t?Lw?#m^E5S>4hQe)^|~VsG5($fvEx zPw>Wj(eD%C7g`tAdu^PfU6&_W{f&wjdp!IZj#9SlX8?r$Hf($8Sx{KnX)pOp?-T<{ zg>-sdG&Ecf)4fmuSXZwpd*`W4pIdJ0F>s+I=Y`Wp3xB)yt~@Pteoi~cqDE%!ZNNP# zf>-{YDzTm`9$UP?pC!a=SjeC&anmpl7IOL*4o^V*iBws)?&s?S)+o^&Do2EQ^ZCN7VnIO)P46|XUk#Y!?lx~rU%5SfNwUnkZmQPj3<=*z_nswd4MOY(c>`ao z&3kzrrp3<6rwG3HdK(PU>4 zNgIfSgERpK#2y5{!SJr$_1bK_ONtXLaK6_5-8%_~j3Oa@m|*Q1ssl4^@9f*d9O1)v z?5-@W4p?qJ@{08q2|#+(GQyWhR_=ungy0^!%S@sVXmL5ke`$XBjqC>P5qM246ujYWi` zAi7I_1|Zm}$>qIFf2pR`51BH-xY^4a5S0Un9zbQ6*SngO_M&a|h}}`ITWN;2?*8Mr-Y9)ms0&bHD~f77xkZq!4OgdpTuqX8RTI@oaID)D9Yt zSHJnr-|=<>Zm{~|ID>K=M0LXZzR3|Z`L`0^%5j_)*nYF?#A5ru69`{onzb)PU4Bk) z&uuUy%hX{V&}gbwJ)2(;$dG>L6wcwH3)jR#ofFfViPa^B_2|INz>jt899b9tj(g>H zdzZ{h#9UckI8I)Y_8*tiK6vLcboHyJTiBbX*50#S{)IW5Xd)t5J%6qwsk&j-%%gOv z^+qszpG>IshlH}s`vVY%eSVg^Se%deSXvVLW)+HUGoUh|pVF@M zypwN=3x$(IX{gP$P0G!`p;s|^4^C`WvA+v^!5(g=Ruv`O_(nY5=v^a?onD+rvf|>9zk}rY|9{FIz>b8$Qdkpt`xy=l9FhYc`+uM9zdo=IO#+K^rSC_doLo6&6!Izm<=Y zy0reLuW;2RD$MxvyZA33s!=VpFCVMt?lYdRY}srsMqTCH`n>-o9hCQ2V5qe>_shR8 z-`<;P0_XOE&hd}IeRU%_KY!kD`l`!D+sLQ4=Q4c>`M0lqJ)|u*^g^GPv47;!KCUYc zJv`Sjp4Kv}UiJG_m%K(V{wv&vPS5maIBvK7hPck2d)lwf@q>;?2zT%OkaFQuNW@ClKe!}4YS$0ulQGb{Jd+Lu@$x{f6`k$3uIyM;fjADF%S@Lto|5|n-7=8&^ za!AjsvCw~S@tRo+NSTuyXn%S;cv2Cyxzrtmx_6CSvNmEX>pSL5}#e#^}w;Awc7Sh zPvp&6m{);H6t?c=U@C_s*8=a0%YPxVZ(FFn-#*ONCs5-{DhH)9%{te9W|r)+$}U-l z&xFoB7bbhv2#d<$A9wGtsK2Xu@%kq(fnPo36|$4`u-}8@mPtKiXs+&h5!B-xv@F2O z-57&gq4Ie*VMD;BPAuv#eq$vaOT(?wWlKU?CPaok$A=3>ZNj_!LF z^>>_AcJchglzB|p9{je(qW+#^PJmDI=AQTsC!8|)yd=XYwhC%}m$kceRMzY+YCVUr zHTuL(|KHfncjXZUEq(@&6ibXgbc`oe=ku&3LqBr=V{`gR^ytIVMbABJ(61K$)R@cK zn;~><<`b5~id#q{oE2i(tk$T7@%kE?(i;tM$eOTWxDCvj<1^6kOrUQ3P)Rv<2{_$u z;W*RwsdLXz%3cSIbA)k0UO!MQ8IW&}h-ISqvIvQEJ;u>#mvGhSZzdmoDxr}VKi^)S z4+{MM5A~<|ec`lg(RBb$==FO630YkmhUqFCuP#-hatz?EH8Y z`|STs*+p;K=fTgU^&2^M2e_~@37uQqt#z53|9ja5AJ?;HYy0KGilU~Xk-%iN0 z{$DS^(bo`1jz$^}~OEetczdr|23G(qa%IvQ0wS{MWL} z3o8Y~pZ2q|cV1QnX}S#wMFU6q{`exRj5#qS4I*W&#aeBC!p1t3ZF)X?vSwrmiHQH zeJBHgG2_#!AFGa?!;)IiyiW5RDqQQ?0b|P z*=+D*>hN*Os@joT$?`^SAF?STdo^(Jsi-fCLZP~QwLlKeq=G8!@7N$B1ZP8^J#R>J zIg1OMv@qv5GS72sw*GXVoQ2iod?CfYj@z`=hFh?u%)_Pze9&y0@ZgDv-&!+)GwhTw z;z=o&mS2xWn`5!ZSpAEvivHyHQN(B*4K&iaU!JPZwrbs>)X@%+Dsg376r+;jIzRyw zF<8tDv+ldE9v!fopk&>Cf#VJVD5l6^iLO0qoA_(_;txdJs9xl2X>v;fx0z5TWU{rJ zuHwFV3>bWX%Ff{DID0gl`7kCv%K2}HUHPWMbmqQ%w}ouWrJ)zI)h=?a?^eQttzW)4 ze6iot`|w&+Lc7r8-FWYN&M4e3E6k|~Y1txRk}E(!-m^3w+xhU7$b0-mDhzT{pl?Ly zB#$F`5?mnlL`~&N)~Fbdtj%L_&rpgoaP5uXH9kLMGrAw<7lI^oRMw(f&7r&qUWeUC zwuoiB(!b6HV}n>ijX+?5v<8gK(_)L%4tzh6!jvbc90Z}GjK z+KZ9b89=G6&KD)K%RXRJlqOZr06a1#&AKWm-zRr&Kg%!E=gq%vG$UGsIwyN5)JB9G zc}jf%^{(>YXBvxSt1z%Jfqi+!bQkDd#+pDN?}S!20eBd4Dw$ltj-fUn3)aX$!8kf} zB$LIP9B;5fx`jaL9Cgl=7BC0o`EZNvLtwvKNGLhJvH~;z`e8)547-_y$Si~A@yt;w z+&8tn%Lt>Hyu*dL7Y8yKuu)kL%b(}#lBB5se5tNj3d#gKAVzvU*fkFbH`ZZ}eDUDY zm#Vvg zj_gk%4j&Yj^ihPobOrnKgarn^B9bN(n1f26lpCDSXbT#^IvmQ=6m}U1-|@853fzR5 zm6yg!(|@#nI$Ot(KV}?560-4Js@eKDv_EiLW(a@q7%rV{%z5UcWUY!sZv^l`TgPVV z#DY)s(03}!@Q(ZY6*ubktn-;xE63D`I8KVgeYWmCocvq!WE600x`(&EGU&`6l()i_6-8g-a~xnMvff?-U^pvBU8fZiA{7_@PY!6TPm+u+;Lrm`C<#nJrC zPe)tu8N;J5b-4iQ`$zYm1_n5URUHzDr0Cd6v&6qHu|vRlML(ZrMhZWe{Q(klnICkY zX;Dwa^~@S~&%!5zO~KpjG250=u9$i=BFz;@foG&3*y%3j9zq~EihVU9V45FQDgc8T|q4B0(YKW=8lGsCtyCG#`I}pR&^CV7?Egr1WnLr$F)0fHFM}>dVUZ)vIZ#Xt)Gr&7f2{W4 zXo~=d(8Irb%QCUcm^u#pzyW%MNWqn3&CBO+wE(vJ?BSa1t-B=K706>1b?So%6;rCPqQ}2p>N}fh?7TDOxU2UhxCp@UGJ^GI*vSpBzyW41CU-$-J$lak;GubGz$RZNr;> zurR_xw&=@j`Kfh^`PRyqpdA z8UK_;R|BX7z%kSvIG>2tSvT7)_Ur{{&MV5#dEI*tfZKXJcMNCNp!;ifo@2b2@Vzpg^B^SA-sFcR=Enr$3V{ur5&0K|A~7SMoB6XRF@$S_ zDl!0SQ<`8aur)--_XD!-JeQr*r|V0RE9})Efh~tH9tV*~9iXDI992Fp&L2Sz`KSbi;Et@xRgb-cL=2 zZKG{~^aOZ9?C-kYExf`THTfP$ie zjT7JR+q3ta^TU}__J8oq{Y)~sudHh=fai>pQePHy3~0Ct3_zn;109Tw&^cdR z?yZ)Qh)>=a*+}5$$tBG7CWu$Kd=#~8i31ddbzAj{l=lT#FTxmjSo-5Ir5_(99Y8!R zG9b;7KKl`jr@hP$f#|i?P}lHX%jP=jjawYL_lQVjKnbs9DQ9{6jf7e$_tc=K+xVhu zy2n6%3|RgW@Wh+Lp8~l~K_+r>fJV@=H$Cl=G0M6KW$=CMwuhWutHc3Mtu?HcfHCk6 zFwE)Pi0GheLL9NPP9a&!9a$FYWJ@WwT=(k1vRx=w7zGsjJ^o>yulSfE%#Vzj%Z0TP z(DjiV-B;01E#msrX;l}@$n);)kSlhcX#96nH4i%t2%IwkQY?_qBYR))f|9U6q&iEz zVt)0>FE-OSJyMEn*ev297Inxjdfm75dv#@V8|FPKj*eO|y@;qPs%6HZ*?loj@a!Wp zJkWAf6&3)SlGr*Lkq5nKT;W7AtD7T>QxlvHj~t<(YH@x+AozX%1~FGA9+tDs%c%QZ z1&7^$-E*6=p^&e?Fgo74>;;BW8bBfvei^vC&I{_Mpr+(Fs_@7ZY%iN+Z`CYHKoZ#T z5zmFNa{PwoYGd3sP+d&}UH+(P2>QuvVOQpm`gS%~NmQVPU0)NbmzVqa8{wM|OO!U# zHjoFI8~!Xe@J52G_wvL zHhD077c*cym4e5vo+eGM>5CNz?)cNB=S=TshwtqU@6hY?qF}!MFtkeCEmICj zb<7ig@k7WNLyid*9Q^6NWHT1k44@iiP;}TyzZBrlN6a;1yM!w&5|4S%N)hCZWRRVZ zaO3BBi^cNw<94O9?115s{Bv{eVIWxBAtc=o^VV3G`zD6V*au(4R#`>x!a~1ELfvG5 zV-3vNSD2e?ut1qsS<6&j6z1(!AZH(urVJ$Q+taTI27h6qvta&+ontXO8%n%`q2pL4 z!@MUk*o*pf`*UmukQ{6~rU%nliM--Ciq8sQ{(U3N0a!fgifskK4A7Vh+?dc*jGJ&A zU!SJ|TTsr*ynr0KUIxuTTA-sY81vIWCbZ=g(ySM0X7+s1Ej{!osChYt-mZEN%_2`m z>6c=h^v9S<9#@X2hJ9DIHgg2cWM+ z78$hR3HvZQ3pfq)N;Ly+5rFhRu-v_+t+)J9p`r5iTqo-6mU%kU#h8P-yeM?dL_`6K zw8ZAhaFzsqyMm!DTQuU#@CJgpL_~oMB9{ozV81&=#V!rZ?V_RKKYWQv%XZbv&v;lE zo9KJ;VU1eIbGyAp8_@gvJc)(#(anp>CnN-94o)Ne*7#R$SWiU%ykD`sS~zzC-afu8+WbbN{LW2hQpG4x7QZ$n#Tufx z7D^M>(Zd9XS2ZxOdg99fRtIuna3r#38nvG6dikeuvBYbP{Y4hPV-#r?3cJR2t2)(& z?sd?>l`F_Nc}6}7e$46wCUhUFx}Glc43=f~dZQPK2PxkTi^dnX;flF~be}=A+_LkW zb`m)Dcm=KZ>FGe5^y}-_84SzzZ$~IN#s6qB6RrHjr-B4P_6^D#)F5mTreUMm+Twi_oesP~3LBkVcffZK(#^CyVtm4%j zfB3wWU=kOG3yoI(*#qx`1r0)}zL#ESO~$*vov`|lZGlL|0&mYDJftx)6p=1|P%h#5 zF~A5n5<*Tpe7UcuBYgR&D@rR`vDF-YivYhh3(F#6nD9UXWl8hPP8#tYoyD$fpe?)j zhsWM9uYy}0{^*H?=dyDz1+5X;1o*;VSQdcjGXp_ofIDUYc$Q91W{ZyUDwQ8mF#Brt z$*VpA(D6Pxzjk@mjRaoCi}HMXF7jRO?#O>bqLk^ZZ;#DHVfB1 zFC||lq@PA;YlmK%!Ss3n>iZ0eT0B>iSqh6gJ)2wKnq%%0yTWv&f=Ym72O+Z#TMt0g zL8exO#GsVu)KLiZoLtw~ovl<<80gk$jfCI`ud zo_5+=5>$K)gi%1ZK!$oYrXTqJvD)Gv^(W;r_}|oDG?<%KcFBfc(-XdE_1-v7%I>c} zx3#Dd!8sFK$PKasIjExO)eR9`%`WI$0(wO@AFS?~c?t+E4SlewGYr|SDYEs{t$NyX zTG4oa8t*32R;E{canGR|NQ>aHPuz3rVhLIpD&F5INeVao`?kn#pU@xA*cdFH!py5k z=ft1jWNQFAmGx4tHCF!064g-M5z6lnygdV1=h}@&*?pXAa5N7!%k>=>Za%s8X1J7h z&xZopA|lmk9of<@J(S#Qwwr$EqIxVvfS3S5+&VJV;H-Oac<&4bHXS~6`pCj+dFF#*;gc_t!;&-F zv1<1;vV=ei!;V5k!I>)SiH&p#puc+X_XG2IERxD`sl>s(KI6qa`2-!)#3eqmwTxPr zd^CRW$Z9o@x5l^{dah2~1Vb;XQRQJ|G?$S&_qCG!yl30fVBr1aqD6wXrh< z|LQw9O}n4Qxyt8aYV6Zfi`>oaY>P$&A~r8w)U|V34?azx5m5zaBfljtdXdbw7yS_| zKOEz=TMf%Vvy6BFFGP%ibI@(!AeVbl{Edz`AOjF_gAn6!Q^zqqtAX@o39nMn(k0rr zA49?Y(!{;$j!N=)!%|B{*U-@mXZEhDI&w@om{B7-fJO7>oMM4c_*$XC>-aad1{}W7 zn2V+Ua+{r3Ih4QGy{m08fm=0Dkk~ZKs8liHJ=C(QP^cyvbmAI^_&Lja_wnY>E|-{q zcQQ{p&>%1B7yA1A5r6jO>bFp&Bb5o3eBb-lmvs;1#h*B`b8?4-h0YULL;!C?Hv$U< zAz1F023hSDoo*32HD^cpZkF2E``4J+8}p;Szl;vf3v8SpV^XZOoi9zU}%4At9s1{OS!{oPmimZ!l=1<$E6QQpKrG^OrBLGx!rAO!hE9+Vu z?f%mDYfNOKF)h}?v+-6YWEdL}vw(}^WiaaNyuPjN&~uF}g-J;Jy_TP<(dhSV!jN$$ zR5t^lf&{RJbWlNt)K($Bw@ry^uMP4@OYiub$fsWXHP9QswB=_pI29@i=W#7a;?QZ% zxX%{To9?IWIO|@i_tzjc4*f0`@*z?4^$;_otZ5d*F>H|DsPDQ|jbn#Q0v}sJN#+4b zaESiB@KyymZsQ$4XW^0tgABt_-F)*_?luNOU{R>8=l{8)=q0WquX_2I;t4ZDSiD}CI4&imh#hMQ@c4q5%oFF zQ>94oS=`?evNS|(R^W9u1@``aFS-1}txJK) zu+zl>(pUJ8!Gu^k`?+lTwM0Bv5G3%;OS|puxpcIR;F5y4F|6X5QJ0SECNlLeNN@5L zSA!~R$Xo5;+y-IjJBM~d(e1oEHj6I3Dvl3xmbTdok7jM8uDsd`Pc0~}xGwFbw|coo z^uEnQTAa55;b}L(b}`Vkt!5w~*&4xOyFp^$W0Qp?z*+2?17YfOz5-y`(LD1>jF9MQ zlS^n8`~G{v7laOWYCd+^53m{NiC9jZ1bt8DbhQbU3Nw_{PjJXG%NAy4ct_^f{neO0 zXvDZxo^lFcdA71!ubs-zXy+7w)b2$3H^U}RHPy#{0=7`&8ZN}lf$@(9PN)zsn_W)uuisyk)MfpP;58ZuE~qd zS{8_yyz(Q->GqhYE096=316mVS;;lS)! z{cG48L6>7YB_cRtq1Tefu{GCp!yCs}QXFPILUI!1Vn{dg2yydVT~eyBNxCC*x0Bm%D(k-l-5 zBcuA{R0DUVm)%c&mC?DG`==>7g)dF1AF$djP5A1hnuVL!Fp z1cEC#|GYm|h5K1~8WN3{8KsxkkOa!DqnVjr9{khd#jRDw zVqn;aV%FC<#PRb@2KtM&5L#=Lj%)exxgi_JhS?hK-=D?MU+mr?6*D=H*h*SFdEmGI zKIT0RQi=a+az6QG(o_nXwmzfU7wdrp)$Kfm9VRWt!reL;wCrnseXV;zxF^L5_I#-V z2W#CMedIFQZ9@C+c13fzl1kct3U@+j4XGo(q>6IS;k&64ETK z8681Th5e4{ms;_&956{VjTNBXz~!hNDMB=nmeyl#YP(nYSfOUxQl7Ats3tXbH#Wyk zMu)ChyIrMhx~u;L=Tp=3j4XY4=avxs!WYCPtp-Ix?4L(8wQbWJ2rcTTgJh`(tu-cZ zLzD^1ZaBEKZ<6&<*G+HfIRCSm;pj`@8nI0fO*SToERO-7?y0f9DuPr>W{ln;Tveqh zc4+`=#lfuI;*`X(h0;6KN56U;BfmuNtigawN;sHF2!b?)=MMm%1`Q+WkMYM z`>*^)E`05lG}79^r8`Xa+Q5m{*y^gK(d^$Pa zj&MHSi}|X@Q+qPRMr8n0V2}@24FMZQdM8+L!EfWq)_6#$Fgd!4Z0e7;TcU`0P-AA} z9pMQl_Hg34S;zqooZMPN1RK?K!(!3ITQX#u@Kn!MxOMm_i7SV%2jZ|FpSnD3Pt=Xm zg}C6GGB=DWkQ*c8lQzg=rf}AI{WwXoFFf9cI$9PtPGJ}a?ZdKH^fR%epjm_H zT?4sHNU0>;lbUz~PV~dVuceN+?yAPNj%NeVcwMqm5~NiU8bukWF(=&$@D7`aCvj4= zGl*J(QEkYU@Rqa!O<0{qQz${L6((tg{TI$|;Uo)5mNOZLUb zrGqtSRh%;g48r?hw{S=>!^});9LRsva%rT?{epyjf+w6_lM7;j@A`?>>=&LGTeuJt zo@%`$NmaNIk2UMsnYnzFNTAXwb;Mc9h%ro^TP>M1)FoSVB=$)f#m~lpR7|^fW(ZBN z$R-G{f2=!_IAvnMoYr-##<=dc5yb`!S?-ZP1gHHpisdq@t72d`i$he;dS=EDW)rU$ zB-)M6n(c!f?PD1O&G_D{cC$?mg5!1JpqDmdaUEtc@c0Wy_!EwhXN0xHz-?$q69h+y z#alo$0W$AOvxbr> z`9ckR$g$@yTf*&3T5284Pl(ajrzIs~rMVhE*Vvf+$+75wzUG79+hEW=isQdI&RIWe z=g$z*5sT%5Xs*R>_Q#k5gD;L)DqPdC!M3?IjdCD*rO{Z~eFjahvmF+O2~l_lm4vfL zbW%VJ2!P?dV)4L5WAPm8*z|$oP8FZ$R~QirG!6{AK%y=v3HMpsC#ZMC+_qp4rGQ=k zSRZtN6^;r*hZrebD7ymv@KthT!;o(l1lI&T@uiY{-pA4e5n)4&PiE(PWCY0}OIhqp zJ1g`eRC*B^I}LueA3^CGu}lw%$#%joCB2#XzBXSDhbRDXb~1}Tx8l`nvZeG=$Thf- z>eF~6@tZw#wU1OZl&x?mZSnE!CHRt$nYnoslN{Ee)i6m>JRTG-U2`o<%0K=Sn}icp z&H?}%?}ImgO>cTJi~d~d>wvh4tC)$r5*|ChR3zajGtkwBcJ+^Kj!#z{%_4v%df733 zjKYsqdVf&k73}9X4AThv@uZh>!?wWjwga4=E&W=$`xN8l9?0~yi_R9Spnb@XS;*yC zh`WmZme(rDp51LN-m%7c;l1-Fu*$#Wzw(;>_0_KU`E%nW{Ht|a7p2oK6@28h!wDkj zeR_j8ssaAo=~J{HOUU!E}a zb|(kv+7UJL%0M>3%+!Sk_K$p4$J-v*#cmhLT{~{8fBDF3{=Yn7q;2|C&*PR4ue!s( ze*6zHRJlnH=1{r5@@9a{dd6k4quC)K@bb8nlgzT($UkCevNP!FweR%xXE>#aU9oK% z4_v0Y+IAMr0}7d%CiqoI72tabG*8&)H`G(Z?1q!F?VwsZgp;Vu%HF$q3b=rC&3Sxn z>5=c7X=kYd(7OWr6W*FVGh!520wVLJuKU-I{dbkQ3Ccf?NnR{aD=%d#hGb~SkP!vu z@LD5jg#_A(LgG2_a{cx>aLX1jg)fHdO3iwL7UNMo-cgqoBu*DRV4&@aK0Kw(8TcP! zX#1k(cBy`58l;nz7>i(3vXLnRuf?YR#}k&tXuy+gs`O#wj(MRxpUZi?_xoIX8ZngT z6l$~m`62yGfAv4^!tacyNMqpyvm3i zKHKGfecV(^RC3aGWv0F{n>yW~^#|fE^&OK&iBDZ+6^$7BX!fpEhxr`+OCA1<%Jz?S zH8odG1}E_Mk!(BZ2ZQc24UOMFo+%Azj+m=wc&;-`oUi`5(=zGvGDdru&BjcRx@#|` z{RbG#Q2wH@v-en+qmNN*T2j|cZ-l1rmk_GA8>G!)aDc+EY9Gmtqs>SHaz4RhK>HPV z7NR|8#Y4USQ?$M*RIIhY;wb|odhR^ENG$z%gePgdpD%2Z|9s~k-e-^K11hxy@xLEv zY3XmjJD8C9sx+gvZ7L5`zb1R6;3K(&-6rucMyGb3_c{ljh;lKSC+sS8YKl+q)!~9o zcY>dRwB7$EV(55_k|_OiyDIPK2u?5 zfA0@+-uT~641vXt#BT~a=!h|zLPzct?=mSW zBmovh4|r<$GIaHiiw|sKbIKQHWm9n&-av3(@k`wyw_^dH0y$7993K!Eh_+j!E1*YQ z0oCCcoqY7q^#ostr_Y4ZjM-fM@L{u007!%HPBEPdW>6&-R-?B+7U|P>Bhy)B_29${P%AUd4lS%;${6yZ zF`(6?pa}$tUS4Qozxy{wy)4JUT}dsIZ%G%{#b?yXQ&HvHXZTWI<5A$^A)Mmq2$)QKhsglk*u z1^yU@D#15e=7$^u9!;!%iulpJ#@HA>@?gn_C9h}OtTEy-z3!K`A8E`DquvH$yw{k( zttQ|&)kZ?rUZAdvPxJM8{j5x1{-$$uGEF*h>(jBsM=l&=SGCMBvkAiQy68J&RoVUW zidozXY=lm0sYK!lAcm(5M%tkE%)7Biq~?o80U%9bAoFJ!uFpnPdm|H2rF8;Q;~VS* z)aJPc^hd<{v_V)W4h{dWBgmVLf2d>bvHmY=pv_X+Dkf{mgJFWd_fRss-N1t?6b=hL zFq2cmxOa4(2wlAgFSOjv^)$7`B2N=MFm7+oGFNp9%HDTNCyRNf>SGcsri#@*dh`;z+pFS>DlT-Hu^BWm*YCk#9OF4MTdGDT zA4?a}Fz-UHgxee$LK%X3%ksFH*%OLA7sQq?6fgjnHC0~C(>C9=rG?>I;FvLbgzi1| zw=nlR9XJRh$d37~HOme9qAkd#h(_}si6~g7#YBC~EckwRlXbigD}NV7yVu{@DF2&B zmQDV;&deFN29xNJVQ0!xff4ii2S?l1X0MZaj%S5}n=`jmyf9DT7OSHU^LHy3-lSdAOxTTb`R&lDoDje|BI;6m`kGQmg^;TrO zr@cEUBJ#kd@M*)_%)4g?M|BDYRzb1%I}0*6;8=rmTVL zRVp+KsY^waw~=8iJD?gZq{cbJfXCS8V0DibIzt8?j@y8UQ~76ai&&oh>zOVvDr0H` zLk@(VfM3&MWV8*`svBEsE&f^zMck8Y^3J>iYy5m;J@ziQ`!QOFSEy|C)+a{oio4>y zI3MbF9R(&#s5YNqNMpEm;OqA#V&J}O@Ox6yQNKY2t6aXW&xs&$i4#F?8_IE#A#V?t53* z{b88=@3&bn;jAR+L@1_s5$MiyrJsvO(807hKpMHQFyign{A&AAG$4{J7XG&_ zjsX)--*y|R75#7?;xjzV|@IrRc(S`CzeuwLqpJ6IwNh- z5KJ^u%O(n&#FQ0Ss|4)-2!vb0*5U{#F;f&5h{?`O){w8nI+lwR1Diu!hqHWz1#$(T zwOBBWdC5BKDRvm#l0xdsR+3k_*&h#rJ>fQ;ztaGl=`e-B_Z_vc9g+4ukwx|<%N%OC z3Yl-=Nnf1^Ik*`x8i*JM+5zDZ3KaCht5g0;azdyw#{2wRHfL(8LDr3*9T~%;9A%(X z<~a)iG7U5UMhxNrxj#~x^=EtsW>`ptXpEtq5~mGEi_V5eta z5l&$#zgf5D&w?SVU~r!bSWz#z%huB43^6(Wh@2B*=9_y0eo!;s_kLVBtA-jN*br#A z2V9o%X3&aRVHG0CE?{)~2+OzVLV&g5Z` z!#Da&)SQcbE#|a0a78(bu{;B@4zpLvd=P}w83Uec7q zcKt&oy2MP#9Elx=9s>nh{$!;n=Jq}Z^pb%`M4*eN)>6d;jRUSez|e>509_%gCF~-p zLUi3Pp%b8nTHii74O~zIE@Sfw#eqhBjASw<1W433%%-D+T4d$1%Tk2aBP8OKqT5e} z`bX0DRd8Q|UAylI)+&&dy^yeICQJtdiCSGFgngm+bjC(#VG6)FsBKm_A11!Sn8@H- zZ9jJ(o^_Q13b9fK(n687nMiyV?7mC|Gl}%2^X?@&um1Nz`*@DPxl^vOo|jGo#vspe zI(XeUuvz60My=^-LNS)am z13t6?1_i$jz;16PaWaP9WX?yo>Y6lJ1fHjJyGeyocrekRnED?W*`Jsm#b|cxhuaZK z#V1&plOimk4uj0E1lAwrs{k8ysJ;e<0I9CoCK_r3E=OfMvS9F-GW||EN@wwz&gakC z84i$x`z`aAifI$^Nj#EAoE`ohW%LRVREeQ{@OKh{At7B%u3<;EQty->c7vG|BbDAI zq3(X`iu6IXSl~v!b&1TmJ#1=5lH8CqWM-}@vlz&YWcMoWrL#a*5s(2VzkufBwrESK zE(_EX;uA!cj>jZgIXGE5s-G2hAxeH8M+2-kgTKd_FXC&3**T#-@-tbPq9 z{{nOb(cOK37Xa_wN4D-GA5l?oUQo!-A(n$`PD_dl2WG@$5NZj{F9HN1p3ka>Z_g#S zs6D6~hbk);u41_YjgYn@Zev-*l*S+pd?Nl>N>Ied@-g^#+0QU<NcaSP^ghi_?QfOfTjlnXx^`xZ>BTf{buMfGrxL}|5Rc7 zGv6djFPM;iYV+uj2Jk3{}kGFm@NQ}+C~S~aywLePPhP&kAkKdU991SpC<)iy|NFDS4C zld*&90->jzUOpiX8ur;1*-8~K@>yAcX<8MuwoAXiY2awP7C@IEp# z20%WTec_T*<&Ah*1daQNVZ_jeX}KVU=yP7mjBKZWvtGrc(7yzVMFER_NO01v6lxJa zBZeqyl@Z1!R@h9Ot08d56w|^3rLj#XnrsHb-2m9R&UE!H@72Hbq8>y za&4^zMBi$!D=guXl(QepFvzT(G6$D^jgl=5@5NBwL!+n#Vgbk*0F)qu*_(pLgO<{; z3dxba^cPnQ1AGZwET|6DyW>vi+}d)$>hIyA0(HRa7CW26Qx@FYg`ceIkt|_U1YPE9 zraAc5A4S%#{;#)SL77YKqrlILT^H!#7Uq*YI9TW&=E#}l!6wf&nVCLkz+DFVcjXnr z6-wNDbwv|>&O+&^`jtVS8HwVGWieOjGm|ef1(#3QeHr5`H;ERV<_bXi{f#P7-4?(+ zYPohx`ed3jL1u#v^ai{RrthO?ICy0`0HtXYudG-YOIU?}V(%+qoo!7ijRGpK5Ac?6 zlw@r)yFN==xBfuy^;|oxMS4dmots|(WJaYiTN~!s4+J3;xaS5!b4sAR=mCOlm^KRC zzVZEivB5K^cXjjJ0Vw!1`%<`*zt8r@hc~yg1fTGO60yKps-nj)N(~2#BooUs&AQt! zBJfpH9eV=Ayp^dT8>`o=^Z_rQ_@g4V29OVf8XmKoQD;d~fTlTHb_9?-E7F1WWSt^D zJopSL-y`ob-Ck2UgKf45RwY_I zgEgD-+`$*!}p$$4OhAEfZ~D~B}D{dceFEF$;B0+9}S^B_ZH zCIc7<*$WFeI@R}?3rFb4{KShxsia?sXr|558=lPl$@c$hSo%5}`wN7@uTc%?gc)@U zEY|HN@mEBo5Cw)zc;&Dr&V>pE_?{tW+a+cePSRe#9CaoWImwKt6)HTcE;i^q7b z)YD!e6P$ig{yCV%^UQ;MQk~PS?;7{b%?2Zd#1!h4iTo-xC)ZGi!N!4Q3cWYZM*U#o zS6d%UJkc-Hc(oXpXS1_)u6Y1&rngx#vF2A1t#AodJl_rv}K>qtOOMBuu`aVeb zZAWL~FL_l)6|6{3 zW3pC!lDACLL7Db*gL<59vFK*~_X@VQ=Yv{WZ7*NjdtSdVX>Hz|oTF&x9RGHnaV6AQ z5vD`hGwK&6>nUCGJQXWf{+zD?vFv${&JLneo&H@DvB_G)~ykt!5$5%SM^2yAzjOKb5Rfc6!; z14exLlYLumXZ3VGKGScg)=J-$H9T^DW`1=XJ%V6v?0K6NILp};8DjW8Yvh}E>}0o` zs-vCZO0ws9d9F^qYNv0WAG{OGK!l8Qps+P>FqyW5LD`w3+uY*7gWpD`9ZbW{#GLyi zffRI>;qr{m77__b5g4`}9TN}Kj2G9w#ci4{CH=T=&wEeu?N1}rK^1S@(gmEEuj&5j zx3x-;SzWE4GbT3c(5Xv1iLy9-l`o`B?v9wmR{)tz4Ci(Wu5j=Ca+eJjnCc@E7kF$^ znh+W9teXJ_dj`K`;&7Hbvj5uO#IN{4$rYH%$4HkX@%#i0#{d4VtKAb%my zCHr@tRW{rj%izc_L1XwBL4mG0W|JEX`bJ8IPjih#lQ^<6dD*yy;t_KCo&ylJkdT3Q zA{!8TSCS^>2Vg5=E?dHiBS? zFrT(UCdbW(47fjDHPwWohatvs5o5JtvNeehDwg%DSUcZY!di-|E-BPx){RU9F~rnC zA&@O?Ga4!grWmi+rE~k}7d=lt28 zw;!xKuQ>X}n$MrU^f50aXGeM`j`V75>}#0UMDA<22DjvkLEa2qvM_@T`b&A3;NW5X zG5M+{6X(ppAVc%5&%PHNy~!G(f^3P=B$n*i)L^sVY9p85b!r#Sc(eF%1hWgmHRD7s z`K}EZ(3=(_E$u{yV$rMN2x)M-6NuhYxw_|j1|oh=QdOI-0Vk}ScAw1y!bt3p%cSyRP(oTFWK#lZMA4M{j|$JS$YF= z1{P1%F&VCGh}?g2Blgx5IlS+8gSNc7Xy6dJLtS{}`dE3&BDCQVZ_vkL|9#Hpp2wY- z3QBh1)jp6~u%7*D?ukLOV&<1*=AJP&6UKA9&yU;7Oq%L%Bn~V1xZK-3@V(wQyf%&Yyb!PNG7A?Fatjm6$*(%dTid+BH zu(i~iiHRN1*PQibc?HYI_P}Uq;!CFsF5d#=g8$~FW63!Gnl$`!)Ez;gRxy_`opCAc zB+~6G8+XRCoM3_}f_IEwD<7OSC(0(up1GOM>LQNO zIKpW2ob|xcg_E%>4HJdE#g! z+%RL0`ZVyAUIBkMlb>MHUQUHCsZ(Kb)CS+`dod4Qp6P*0K0UvF9=#!&fjno0M0{Ps zGYR*xINd#8i4UmY`y$`hQ2dlbnDySTjJg)_E~F;cV4veepJ5WpFCf#iSm5PyAFe0q zr%-=fxYj2N$Vu#-s}CLs#cAL1irq@-Zz)gG(_%Tjo7en6Tfw8b|T2#gqKiL${A3#dAN4a12R-pTNpTJ3SThl&tK2fUDwtW9@LI1sXU#8 zQ5e*#Pd)F%zxj*rfQy~pW6(G%#dAW(WF!4zgtpnCu2taRg&y>?7$r-Ep$G5*>zv*f zNO{}fp+?eqTMZqD6pU5Lklo;rQ!qK~0p2+(zs);V%TIjwjINuCq@hBV>7ky6*086O zkP}b=I_egnJAZYOHT}`B#c7ELyhGW?`iDNSN>d z39c9Jlx?1=5fPV}Z85MhkS7_eE5()}yODKekhSSuaV#6Ti4|d8s~%Ot8K23k|AA$v zn9TM;_r&F87Z110j+O>Vm*dSg{hTa<+cYCHXf)lo-vxkjEA-|KB2>Hd&~9i|6_xIq zw4$7{0-BdMfF%t4=+>nEoj5YygWNhh%2Sx+zNX^0F(f40o1xy;lQj;)jwW#x*Cq`V zt?8R165KOYCy4qbl+HV;1`S*)&|0`CkV381&+;;?(?Wc+kn(txlewQ;kdt(4m$zjh zH$M`doug5X02_CVRC^_5yfdltLXip#U@s>IZPFW3;kSZO$*uEv*5W{|1b0+(8X|KM{|vOOEw9#6KXOoM8s%A5M$*DHTQi`<42BLVmUIzG=T z4up^2DS^A`#M>Qpf-)i19gu{5FqcnlqDtEC;q;%>{##411R&ntF#bgjsic;VM%;gwJo0I}mT|Jyn%)C1e+gWFid*->WWYAi@c34VCEgG@Y17p_2=wy}V- zu+MzxndNdG+^wHIL4$bt;ZuQdac}e6v$NX@5N>uWyFp9xQv9Osg%p`toaZyAh58*y z2Wch)L}Ya)S~D6`jgl8AxI*v@ZyO_9W( zDOb;Xdd#T}%`5g;SCLyazRlxS=93Jq6Up36v!0q52kxiB~ zqDwDi)FyZV7PkN@c&1x}%MX;WBrL>@&Z@31*i7~5dQCHHPq}nk+1lEgv@OKdlv~%7 z#(Sw>dT-0RyFl`qj)PwWtv+{Ayg2O(RkKKlgQu7*_2ePv+@-SY+tOxoUXXz}6E6l) zI7579wl&@|1z)SFH*%Ts;>vt>q3YszI6}3f;JD{vp<(P9c${0>qJ*n7;IKHp53%c9 zy#0qmbw6hbyc9FlXWn%2RFZnE=aO^Z1Z-|0;eA%zH>=yV2h!=H9H>zhK|hIDFtB z3rInl+mZ=+EwjTkQL^33g+3+qWhF<$R7@YfB?@g}XDv|wM$wkZw7 zL6mEn>r1@PvAOs^L7Wfo^9czOn*|>K6U1r%uvzRsEU`rcalE%m!#8WU%A)>(I7H~_ zZA#of5Qi*Uw_TB{^zk2vbNWM7&PAUO)dg4TKHMt_{rKVjKM<#;D$nO*ZOy&9k9GC! zA3r{5qN#g!>RVs<>@;+2($qaY-#_j&QlV#dn+7?2cbi8=AMCbFD(&n(n$f%7eZ3l~5Xp^Z!q<@6vcBZW#P)G=RDv<w`|3Td&Z>?hnieb23 zr$9ETbb6aA^bmNLP<)XwFvjls@fzG&;HLMOUv#T1CAQ3ByDIV1u~%P}K&nhXSj<$0 zS|dRG*b0-6+-rFi-F3AQyg&ZAJLTip{=f~le;`gq)U{HD&%eLU>YVEF4%4u?b?v4{ zUB&q>U9SYj2>1K)M^jNKl0)%R)Y<3Q~V<0^Gn*+qYmpPPD{n z6S>I6zX6JyRDG$-1{>g6o>e}3*vA+)Iw0@_$*5Vv#(NS&i3Rn@kTXuZ?MEc)8jMx^ zpFtd>>OrZ9fZJ98nK2ojeD({13F1oO{>FBm)YKQ|YkJ{qe|GQA(1FHNAcg-kxy-?!E8H#{*JcS-*=;N;Y`0rYV^dC=_n!t1HMuJcHe+2(4kT zcwfZxy;o5%#t&|d5u8uhx5Aaeb#=!&lSm*pTp3|hT%VU19bFX`3exqu^DISa_s&^w z8L91H<5snko`5#CPD#agMZjur9@dW$?{C&`{W>(Ro%gswz6&={>38@z=$K9`dfkS? z{q+HxYK@_HfKlb?4Yu&1QGWP?tf(j2TvTd&m{6cao+)dQpsle7gM94sb^1`}ZjTT# zmfSza;97pyQoO&`T8&&B7o}t1vU^|(h@iu}WHDl8_%UCIW3ZaP&)?GtbJ@+TNw5@7 zl~wS=Xa%bXJ*CDA{_tLlKkDz0oFjk|a&o4XJPL1k5AcTZab&om)9CgO%wH$Z-6H^! z_;}0jYtJssYgdK+(H)Xt(OP$}%Myv2)doFFL~Z*FmhCu?inokgJr-d&>n018&D_cJ z05O~lv#LTR7k;njA3kC_Rr1OBtICD=;O9&}*v3}{2kf?1oLp4mrX%qs#$j6!^n`lD zG#cZE|r4`&Dq2r*-Z=a zVY`M#-T1TBEM759M-B}@O$=kPFBjF~}&7Vm7q+7%SNz+-cT@w5dPIuB2 z?3~1MJv(zT|F(0JQL?EqZX%V@Z!}BmhzNTSOt(%K-fp>pKdj&^6Lli)bNGYS`~LV$4V5)_=d`&GfuQ zorI5^dGa;mK9h9UX|HN@v22jaa3!;q5zagTP{4}n0A@48zR=en=E73Q*$4A`;c`h@;lpTPBoq(Aj1lrZ*7n>rbOOUsZswr>Kvc8Ju& zz``5}S1%y;!JNad5iTAgzMj%f^s~7lC08RpV$su|$%1CzYIOiv(D8(L(Ln=3CIKAU z$IDhQ^)0J)m02Xj_q#n-M>;T|KLZp`YWS?K50Orga#e(w66ahfpLu|bWdDUim?AQ= zwR^{`KiA6cw~ugW+szXXutgI?{D_@Qk9X-}_DB4J1G^|mJA{btuKf9oR6H1YGg@A} zIQG~HVE?71mjj56Iw{Pcmbb)13_n9QvQ!$RmQ^j**_LN9&K25!1$o2UI#pu+(jx`2IJi`{(hA~ zefPE^QWi;&Xl#!z@n%3gc(&yBYzYTl(Jw^G$bbxGl`fL}q2*GLcYrdTcxeoEQ5Ps! zAA{n_fQeWnKt;XS1QY}4CMxQF=Q*$-mCFzx>=ZA5wojV%ssZ6zzhH?^36RH#!^vV6 zD`CU}7-Z!dCwknRExFr(eOOU-3+y}rPZ&1cs$3?ueGov}T&luuJD1fp~gWWFEl|P3&IZUt#Qp4ZEt;Ji7(b z=kpNEF-SadpbHqVL=(!ZXPq*oz%|E?oQDxEo*PZg0MM7Z3pcw0CO=Ru!AhuLLJJfl z{S`a?F6?wky%Yth5zQ1iUXmlWGi(rfKo81gz7XgkRF%> zDO3U5xA1(PZzRIr5eoNey4E(`;|DxDOiW=R_RP8gd_3_RQ4C4wwY9ww-~-0n$anD+ zn|8Gw?G*iR1x1kVjduOMcD-lqCO_NF-nW}8Ua?rWxw7%h70Vk}Ha)vy{r-xX8=$vQ zM);=wccfqWk|R73el1WliQ1rxRNROlUd0d_Ykl6mZgZf7F9IO3HercOS~ekt9c?3- z;zN(BB$*&VIYohv`;LQ9HD7|z;|D_R+5#uAlX;{CKx4clX7NCk`Z)J8bWhoQ{u{OW zh{UK$wU(Q~z-=maWn1S0#5w=FQQ=);@7MTLQIoLfy1|vsIbvynpO#Nhcm0jD21Tu~ z?(XKF=KY+47MmMwl-!P^H|p)0TD-P=N{i0ft=oP{G2tTS&e4tgYj1R&xp@oHJ-S1E zEaN6Fv8A6@|Mt$!ym4%rzRZ}Ll=2Mq=}+0bbq!qoRqmbfU1SZn4*JzJQ>V#V3?~ZL z>)6vv={*Pax$|AFN0go?M3!A5J$t`tpZQf2$^}QE*U~fTA)6zKUwe1ZdcDn^&Qwa_ zmu04YlG5nN<6}KRQJyDBsB>qs;iesleAjjkGMXOZ<}7=yc#nADmr5N9lleSJlNjYE#nZxQ7)L!1OGFWnzA^Dpl862yzRBdwx zggQKyh+Ep(gGQCO0R)`#8D3vLI}9v>AEypk@LeJ9M4`#G%`~&6B9C^PAXRf)NZZ*o z0CmQGWM%~u96dlJ;$Kp)9lN0&gp+GiXLONo82o~N)d5EBfp*{i2ZVlKyKBcGBb@Ne z>y801ufb;&k9nL-?+&R8(+0Bzy~j5WqwH{II9c2halZhOVq+rpIHtk2Tetd3pAn@ncH)8NeKp## zZnxi$=*o|6HGGodOk!Bbr(a?r>5qt$)~A0MgY+ixK8`l>#x8jwTMZvi2?eg3O^(Dq zS}2NGx@j11Xm(K9u-)XLRSg}DHDZ1+qkehv%nqm4H07Q2ghz;I$(YWHSACVddGz`8 zu@Wb);nT0-*{4rxY(D!`()(%E@25QFnZDc8)%TUl4j^}i&L~D;a~!wVUY?ntc^~3D zYz-xMoZZk8`fO78v|nv{(*~#Qr5GcN5|@b;$R5qny;VA31@V zba!}swE77e{9;2|^po`x>y`~ql!VXEb5Gg#orI6ubTF{DLiIaEFD2e+9s#Sz#ZDN} z4kR3vm$^WtKq>4U6YjUM@l%oeQ=m;UxK~=ln>{~7^aW92zZcBAjD1=5;Ozt56}~ZU zJCaV%EK6T~G7#3Wy`kt}B5&kkXwPxDqW^MW`>uG1L(n6kiWkJEBJ+l?A1FN0E22MN zU(aYq-|946Dexb4kE&zUny%>p_H)GYuKX4g8n|#|Z&lFe-4D)ges=j+(3i!uQ>yFU z1CC}fQo#5K)fcypPzkY|+kWRH@aQA z%(25k4B}*%4&LdQLCG?r`c0jb4|R;lsvZ-XI#c8^{}1y#9OMX6ghu@rysN+D^YVhyzj~y_dZD8oF?Y{Gj(JxFh)O5_-6MU{V#G&qtO?4~|L&3Q zD2{+HO_UCEsJ^#el zKZcXvm!s`TM${Y051@hT7IG58`gA+kEtMQ3r5DtD`R;ko-do2qH^5e74O_0#_{6W! zQ=TB1D9^3j7Z=4Yn~l>?t-vL3LqWcpIe-n0raoph3!8mF{h}1*Y1?o0k9mH0D%&fj z_7vTgcJZJ1I&uem<0Bu>O=9!>De8r~2ib3U>3ADCM8o{QdZhIKyW;Cs-WwFGfSTT; z8P1j5gBvGG0ULIJHc=>|3#gk59eOd-@hdGT+hh3Q8luy%a3 z@)F=|@Z@o(I6|lF=WKI>4VPF1?w62jOW!C~RI>|=L5H35zu|Y`n@ekyUds(xO53znDS?=9&pZ1X#oG2l z-h`TQMN>L`n><92HM3rHT4Gmpx>r9d>*cqN5{8k^OvyQfrQBa#Ou2-BEjEDoiLa={ zzQp<-zwl5!RC!W@b?_Dc#nO>OH(p5?i^Ij2t3`j^eB)t!Xb?pYqtUOl3*Q}_}@}*2Lnlg zsS2m7l|U+r8SAnzv9Jf$KA--Js%EoG)A=ZS;T>66@dsz`lhHQX^krPXh|^E~!Fc0h z5Jlu9f2pua%XQ{GbuGfPlACH@cP!0K`um}Dmnr~V+kUx2paW+fj}kH-95j~33ry2! zm_VF{1gznT$MNudMygVrL&*8zJ*M*U@SN@*uKFok{+{`+pb z3~rvW$WD$K2FOD|g0TLUixAy(AL*w&^`ip>B)h*3Ui8j6`>;kS<68-)FUMRzUdn6l zvMcf>Hl*t)`FuwD^^4u3{Hz^gXyLM5*kwZa^6Kea@EX;fuuBcOtuLl-t=yLDdJ2G0 z%GaI0w_#1u<`2)PYsux@MVsYld8qY&Uwm1t;KpIUnwWKMj?uf}63^~>O6gkOpzq{8 zervk#M2e+nxP%$T3RbT1{)*0?j@C@B23sTSv{j|%iqK_4?Xu*%PTH6XC`GCt*fMvh za?{B=K3++9HwSq=4 z2s>}lE+{p9%xym}+=KCX349=V-pL1w~9w@S$Tv){pwQ z@BcI@6@EvkIoWrjy|%smkWOE>Iw&=keH=vPfABsK{=B>Go8NH{uCAQMQ!vYZoff6a z(sG8uA*M7WhrrsR)BhBY+6GeM=;c8Dau zi*#6wk~p$v?;s5~98?vGYaGb3e(A>DL@bJ+7CVeL+lalJ@LVWmp09QIq60R_B?nOwnkClj|xN2#-S zx5$DpJRpOP22&xXn~p#T*Y z6xv3k9AbcvLxo^LTo$irLmK)=wr1b#me0O43q-ix0=AdKE@(@wOT(_zWDeF7q8$q( zz9oIuiYZIxzF16#j_>1g${^uo5E|;p2&NcRzB#7USQ|}4YyLi6>X(Lnei0CmIp<|6 z%%938F^iq}2tPk9ovgXU^@#TW~@<;dzGkm2V zd_{$76}@V*b+y(HeuNp)X$=_8EMOB*?ACl?0&x zFJy(9`MDF=_&;b@@h=AbMh)UX?T$9rmeTW6ggWm=xqH*b3uxQ*HREjaipo1)YV5?H zt9xUutTzl2x*pYuCb06-p_8)KT_VrD3~Ex?f&LF;@=IIK^Ij4RQBPttQxwKf}1tZgX-jT*vb4LM~ zB*TZ;*`_aG(3X?c+14goDC+nXbCrokRzzKJoB!5{2J=Mcs$hc^1_i>EZRrMRUT%1b zq=erJMVJ4Tc6^sD2@uN`!2y(a1X*I?;ZhM((uC=wS;!|gtu31 zrPk+elFJ-Lm#dB%hg@X3O0vym(omafS{_HRqgR9bIG1~gYQ8o2-z&@x z%dqh?&^Fxk7~~G1@|)Z|v)XW_7-27xbkqz)t!#svn&DRPMn?=Wr&(j(mx73a+nA6G zG@y+Sc-R2N;49F?7D(c@ByQIS1w%&}+dn^Wi=&d6@0%X&1%8R}H(GJZ?Ra8GQ@5++ za}oXpIAc2L5Xsc^YoirrK(dvLlajTX#JV2@R@Z94VHXo4Qw`* ze9ur^C0|~dLu%zW78hM;sJStASEph}&-9s|nH%Pt9(O;xq|I5EzV+&ij+A<1bfPmd zP_JUZ_S+R1rg-3D6EYQ}cciXW%Jix|?Bvj#zqfgT#=(ZyHq`hdq#Nb}a1|h#q8jp! zG|0O)mhWaeO73HJI)Ph|A%KACsYP^NH}`!ROB@t*%DOw34UzLpoToQ=uiYS)r1a5> z1Ws+Yjco6j-_+(vYm@}vu}E}QD^NrDCRwLSQIY-B)jnDr@pXmTei@K`YQM#}|CWgx z+ieGYl{OX43;gbBoh5-bR}C;D`opTULX`%iLI!uI4n|iE?hP^aD3I=A^u_*?k0lSd z@sA}IC{8>h*(!mOjtuemeZgM-rFA66@{qjgpraSZdA+YUE0vi2Xefk@z0E=HG#R!E z?>!ku2*n`>Ik$q?BNkqs>t!RFG+fv-((BjALmXs04tm)~nF-A#I4gV>@`Km3tpP2dztt7AnRL#*W#dAxIy~t1bJG6gv7}5HjQ=or z|9I&5c)t8Cz5C<)`tI*sx#<--(bPU+zV3m$qI5Ud&RL;nyo<+h4;-6(E+c(%Q1AYL zUMMra7LfsaK^W!>`-;N{_qILJ zwZq;e!}~;%(R7&Dh>&hO1NE9g#$)>h$TTu;Q-}k9%>6P6+YEZ(^FzJe5H4UfN0DLI zLp^WaA8?F+WZvU!r0fv0K6);WJrEGivfw`Lh?iUdNrqBibe}z>7T|yDH@1Tn8-LmU zChL9}4N=0tNuHHiSthKu9)|`H<|1|P+6QUdSoMd7 zvvUH87XnFd7OZUSCHD9uxKmvKNfklBS{#wNMt@a)`DqVNJQRSx%R<5A3 zt7E=o0{f;19>9Y>X5#Ds)Q`9Y_AJKdC-$5#Gk}DuW_mV~-;@$@XU5am9FGqBD8g=~FQzg*FaKQ7?|8_!b8e^NoSDdTENJR1 zGPM=`yT`$2SWg}PJdG~)iHIZHH;saKjt4xwe(GhwaM#90{0f(NtoQa&BW-455V6Bm zfMkSkwR5I%j(5P||LlSz|JPk`*$bm+_lnip|BRqMA1T&$E8YAb zF1WulyaSqdFVJhm>ycL*A72XO|1sZVbm<=iRoU&@GW`Jf5gfGl-w5iBFCic%cxwFL z2&!U}w&Y8J*S`_ev+=NQsX#43Lt3)R-!8Z-Zy%Ikwkzr^{<9u=X;8uAu?#x~W)}1> z1T|8Rux8Jz1kEM=3qj2o5-WJFp1im6H-h?hSv#I=2>syk>Os$qzy4W|RQ0@dQ;eWa zUfTKaR?puqxPLOd-#^zrzkl_xw^zK~hY+tv{^No}Y1RLo;VqKwMRJY=n-$w=VW#ZF zwucViTGi>9a#=dn?9VVV-+o3}<6({%K|R0u^P&%dzE`4lcq`=c;#{Ha1?^Ltz|(i! zL8kV;t~5Rh2G;)7F}eMeIKz8stBHT)0ZOtYNzkU_O~&+bhouTbq0;QrCD9kI&y-G) zN*-?Gvh6tf(03^uU7V2j=3J`L8wza$jN`(?UbO;^uvNvB0aa3Ykj$pe2?gRA9sY<-xLNukPp~i!I(F8 zEMLPuHupR-{h%B6+e+W|Bk8oi?I+l*yZN2u4TUuBl+>xLr1kr5Rl2#yv(;zw=fG z>ra}hp%)?M#|Z`2Gl}x-lpInXdCS)A5^@qNFdZOrxbf*6v zDYG+f=R7drVYc=i{|x0tMoE;L9mqF`qtUfm+FGD#;MK4}mA6E0>3Z6VX)g%-v05hh zrKud#ut5Z#iBsFf>HCJ%acAHMtxaSq$_>LZz-Poh?bog zK~3*otVCVSHPmwT%0sZKJ9rKt;Hg@+qq&9v)!^)u2NWvQnoB??ozmNHW%no6nVf8J z-{U%2IrHd1N>|K8aO0J*wMQ4NLx+{MDmH}3J+7yDEIl%4cyz(~u||06(pZX~AOH7U zqu1p||IX3J%}2goVn|#H9CDp%ul(8+?Qto%?lpR7R)CECiXlH2akn7u$U%hlT6|aS z+I}w-oa+FBDL&~BoUl5lhfXdknxrd4VOt2!QCP*&?a}rpH=s4V%k=<1`Zv84X=ncp zbLc*!nhnP+P-^I(Pix{JS5yfZyI(AEo~~a@);aKdSP9bl?EYc{9`*fx{Qcq`)j33~ z+hoV+Y;4(A!eh-IRHQ1BIP%VH;M%>jZc&?7h_1GW$owFTQv2PqX&6Hyp0Ukc%k9Nz zQK!vlg=^I5pD#byCg}~DG`PraEBN!H^Oh39(F74P45nmpk$Fqe;6S9!y>Pq$&OC4M zp7=1rzV6&gOO|>y90#LzeI%SWXi-`euUCz;ya^2@MLys9Z%7vwJ&q_if5`G z&@Sv&FerBE_R{_YAg!V{a!}{rt-G`Hmm>(P4E7`8J^1%#>Mz05{O7cLT-_YSJblvF z;9C5_6lV2iaVYMZapTOQz4pe$Tu;D$#QS;+t#+B?@-3oQ(KONBAhqZ;45Ym1jBfNf zwwGOX=LmC4Rpv?%ci`J?nX0e{_A?k{rqk6u&z1!+1;=-8TxT_{m#|m5@x2p zuKbXIB>RaWnbO_6cEBX$9`Yn+{uPWccvE)uL*#OVZ0~etC|YgVQ)!$O?!`x z{IpxF&h+bf6KlGHY5Uv5b0kd~OIX1~d?T<=N5~SKgTDc2M^|2?%Q6A%-jy1c)VR`FK(KmbG+9U%FZ# zF`5aySx}S!N01VcDZD+fKBTu?rV{@kf`-;Z5RT5Gb?US}@$ft4vKW?G5rJ7zDOtPA zv!c7Q_D*NTtz{+1Wiu_alLE63q+}SBq`NB6rg?oa~m!UY0 zO%^GJMgwx4vUddk=z0Lq^{#xex~FqE|5jJN5wQTpKi~^KsN8mBzKoFB1&G(py2&St zE;1K)pVVG)7ES?92Z>rTxSq^NGT~$&c}wpsw%(S~k1NEEAX;NOwRAe7B265NUb(+wcPqgq_~b7h2FyA%pIq`#GE zEsQ-34gW6~Sn@ zMjfJA5TVCUI*SVIW}(5nk_`kj7(f?|sbF-08|FYzAhCz1)bJ!vlZGAS<&wC5E{njn zn1oweT=D4#OlPAB@((KiR_x(Im(h z!%Ael@*_>r5MjA7q10^z;}nB(st{{@R0`;T$HODKAY^sg$lWtzbeUGob3qVft3`u12>Y4GYj#hho63waRUkcnb109LZ8( zUq}gaS}W*22>dE1)wvLw*K_JOR!aF;oy7+ebeKTa81lqyN!~0-IvCJu#Z)jLQgomu z77^ba`I1a5C1Ht+lz*NH< zaKE^cc)hBSe#r0NO_g+XWD$DY{sX z(6i3ZPc#8n@R~RC@*(U-Fav?@!&CsEJUY-chV;=@ZXA`|Mr`YGBHSJXc3LstXqBxG zUZ&B?5*vaiHMhhC0XKFfV!VJxAvDYB9a5#l0LBpK|wMlU0Ps1X& z!sBwjoPp4yLPf{El zz~okm72st8n6PjN8Z?qF#=JqVcc4xyDz~|nUP&R{a09d(ui_~;jmHbH*O={siw6ij z_`a?eG=T=&opicO$`m!J4?zgQ;^jJJQ8|Qw^pyowQBhoGH^j6dQGoKHw!p36&_2uw zPz40op+~@AL`a?dT+W z&VkiZMK5&GEF2mRg7QJAS-`~xUBs+#(+BzkQ72pTX*Yp7Y%iEu;bhfQoBub0y-QE| zd#ffB+>BKdSg-Vc?h6i@NRg$W=M_Na>n1(h8Hg|9kCO?!xVxf!1~vAsL~JrXCPJmt zQ9jozvSv#X=^Yq;N%K*@mlb-eEg(k9<8jKDL@kyy?6om$S^=T+8HtgEd~i4tXi}kl zzuf7rTzFxm{bH#~r^gV7t00bU9qD+$Ypva)20M7^@R35f{_d4%UvI~_a-3mH&L zX2@?!hH0C`o&DV723Y^i9HEtLno0hv)3u6i2*z)M!z_WhOEF2GV`?p#$S;Ye zzKW(~$BjQR@xLdmQkd-$rqQWq2_HL1Y;g|7@}3?b)G()&`Cd{EH{IU$?=-z+KknpG zKzPZx{l0Y{oV{0pEmQSddm9wx(*+#o9h7-t@pBihw~DZT7V`;5j0Ku(_-C|*12eM{ zuK|3V`tc`S&zw$g+?_uY7?S`IBEn*bb5{c1j!3D-Tb}audJyjgHN6)E?fju5W9$Mn zoRl^i)>T!1AzqKHJgWWZ3_IZIS(Ulpl`e)QDDZHAsY%o-m`N#m_K+E+18e{f`6hc2tgJY?LeDT z9k1P?uia^p8`~1E-I?AsIkS^8|1A*&@iOoOZA}wpQ0(US(+-;ohp_BE2-h?+@@^G@ z+3jz+vT#g;AM{R{@Jt!>J54sErf9evc>7yMK7I~#+s9u*4z)KO7Vg3{X;ldKRAS?o zfhhO&WQ(XU;Dseny)pQhz3=-wKCr=;KEioruZu%`uhU-`4u=U$-V?_}^os+fP%eTr zg)W${AhX{B;duPZy*?WrV#Wimah}6yu~`Ni-I2tQW~tu?6X?5{H>(Kf+`!|iy`uNg9>5IS zV0ex&Y$mx%HF|iPeA1P$|G`PQHW7-bKt834^dy<#)#c9vj3Pq_A`P=5NK78^b}ZXt;|j)X)fxIONd5JtU6OMQ$6DtR@5E zbFWMH*Jdlg*5tGPCSZ~Sk@E!BUIxcX%EWGwvNC~$Q@<0&B{S>@jE_Hlj!TL}lF!A- zMlbMSOyb)Z{^6JgB7C!S5}tX^jLlOzc>LY=&x+04RamX?b&llnI#u!`h>P?xs3Gb# zDJ($wln+WE-%my_?~@MGUyBFNbY6dvAQ;2O@$b^szc4;Y6rcZJ5L9UTxY}By@IS3b z>MehDo2@fe^$;VdtMlE5!OIQ*Mo?e&S8z_LR`ezPfhqXb+eL0WsbcYz`1g9`*)7NP zCbaK`!J+W9O279$J9hjVLA7Hy+>-)H^4jBH;HAI&e+=n9_~E659^r{`_-)aje7Xqy~o_R<8kTd=!rUyb=Wukgxl4J^NgyF1YdL7 z1YV!Fb#uY{L9Qlr(z|h-t{#7{*jC=1m%ER zY2Sa5Uzajq2Tb%`3n(VGjA?3mlZA-aYDZ|fWO#>=9UNEkZZ(oF!Ooh@lauqTO|%L? z{Ma?9a1yg}E9}UZ(SGIZDhX$`bZ=vpRbf=Si#FQK?3T{?+IF!EuHVefu+!Xic>QC_ zNjK9WjVmrT5YX;XvnNqkJT|?`*ziCt_mS6jn@U`%P&c>Z~K~iyL=#NU2`!WF!%A;w9w%*`26#PkC&6?RbL-Z2Ma&HfL&Mp0(NFv z_y_H&yXwDV-+;xFd86^G0Xt*k?)2`=)=bv5cu?&&9Z|L`+2+1d{Knvz*vfl-9N#k= zcX&!jP#?BEk9>V;z;^Q5^X-`{$p$%`ucO}kUk!YIcth?v$~*1(2j^0s*@d!+y|UE~ zPutdJ)2$1}P=`*YCH$=KKCYT9MaxRS9&)+fY>k?!lZlj#xH&H&D64Dznxb|MGAm7? zqh_8o-)f&QcvQr%beD^~tugpAZGt#jstEVij85>33F3Jb#YUdoqWG(ma%=bQuTi!a z2GiH~WG$f>4m?+4bUs^7Sw}+l=$+2d3w$HLIrgLN&Vc=@ApIh!71CH%h*rybxjA*p$o6I4PGrMX6IQtt{hNOstt9OkvbNJ^sX-|fa9fj^w z3kaih?+SB7#;tT`j6}vw?Qzoth3T9RohaRJd|BQr%oJV|CqlDQf=4_aYd0Sric?J^ zwuF*JDto6k448X9I{2ny|E;O7MbEeV;`y)p&aO8(o!G)|mF@kVMfGwpe~z@N>izU- z=fh*ay)X-;Z5Q>F8Rq+uJrY@)<7_a0ZfOIe4-eV$-yK2rZJE~3J+?dT$b-mE3y{fT zz-O3JwWFITfbBIov5e*;{hTWx3WE}cN_pr_U3Lma_N0pfUU}p)nyLid(=KOPEM)(MrD8INZ+b-ctG@W@zst9+zl!%Tf2a8vDHfGy44auhmQ7S)`i%YC!`*3ams5)+Se!u|h`nugHtpEE{)^QKT%2VWTeW+Q zrl=##-LZIEHuvrxJD1G-$a`$uw^=7p@@$q{RrMLnK=j3;ak$y9bj77H2mCY@O&^2s zRuKt%GB{m~9 z>>oi&{H^Z^{~JL{_t*E+e=imNe_yAL4S)V9zD}uLyz%GX*D0RY4j8$QExu0isIe?_ zd%UE7boikdx$%6b=OK&2>@Saf06+5S=;|c3bBTGIe$1afZ=V4tBMczp`{zzt{u%W2 zh0-F^B`iAtuPy6ckq@a~IOVU4+^4?nq>aG@_pN5l#e$TFUuz`AOGW?p2vX$sG_4FO z9a>%)B4-<{4r`Rft^WTlND*JBEZtjR0(($DZi}u?UcixTYU-@e@pV}v4Y5$Hz_zNj zg0=l~ox1e4T3w+Zmx!KseV6l*l}>wL|3vD2ezM)q4}5j@(Yl)D2YWu<>WsNB>X%ft zZNQ&hG)N zyH358UVZYnAmwe#`k!BaeG=bCalC&7DGDMM%AE&kkUb-wmECg~Jn}8d?E1yoId%~3 zmE)8XVA+*{-VqJ;IX=cQVze4(B}%-*so^G2wGvF!AUd8{(0{B}s-u+>o5#ybN4=JX zg8OmnxkU)hy*jOf^id^q9RP1;3QCr%4l7zCT9M`x19YoN`)jwQ9Z1aI3syr0%=H*+ z)g1$)24PUL{X`c~urF85ZH?XsqDSaj=g>h*B742tT&qX}4E`6HqY}X;7u=Px8K&W@ z9-E$g*?3QN-+@AxH}yrQZO4nZOx@WHzjL(0fDn@g?x&|Y7Y+?q;5s7<{JYyrdHjK( z4mp-v$QuT)Hpg)Ob#~Z~BF=dNpJp2^jSn*d^_x#Ck%-R2Py6zQ`%#LJ*{r?6S1QfN zYXS<_${#1r%eGIWj9zvX`GqwV%KpkRp6JTo*>UA8STtZ56;Ti=@YZi7JI;B>tQX{z z6ZH2^JAazu*zfpKtpBcRT1u+j@zipfR;@vu-%JB`a(Ke@{f=mdn@)EhR-}=@CJrEH zetz|0HQy1PWuW5REyq|F}7zrXL%x;xYbpY+ZGS#t)5Qv)}I=A~imq zKW-KMy9sH(9KY}E9>WoX6x00M_akJ$I!YchCiipcbHr@v2f@0l&XpGX$;WSsi}T*o z4@G?Top-e!>S_5myW^yI(;3Pg9A0TTL|W`?Vf-9@A{dMyqch#96svPp>slIRPPv9W z=25^iPD5VZrOIS85w``m31s-(IqYK&=L0-awsvJe!L55Uqdu_?9M}}uh*5Ys(SHrO zV&qk&(6Dpyo0Q?`(Qv2|QSsbgYC|45###n1KvAA*`9MQ%4x5n+g38(%qGMKf6ytxoWCS*i#*Nf- zQO5JKCPsB%wc-FdB#&*b;2fwpNhfZ&&@R8S;=IfY+Id#39}w8Wlva3n3^P=7P3UadZg7fnqBn{R6D^j{iohrXLJG&z8$D+Tu_#WAu zsdVRPq_RH1&MoyR|M93^YuGS6t+G?VZ{xXWU39%vra6_-v#jY1qgiKL3;0h$g3^&M zK-m$B&!!=|$##xzMILg4oz-k}2PFxqSuOnmGeU%iQREWHxtlCZji;H%#=m zDdfGl38@e^1Cl3sOvj#bGvP2h@HkM)a8Okv=CTjmS}A5Y zEQzHj&c15%m_C?Ra6-=b3D3#5>>es^U&?*;7oro<{bYlPwSLv(lR{Gm-AbxqF-552(jzv*>&379@VHv{l9*zhr4LqRXSL&t_dM#voCZ2TqojL76L3v(PJOoCxn@%@1JUm(4!qz1;-b* z;S)u+y7j>PMxub8c7FvA3zvM$N>h)-zIm*1V?InRns{9%Lw3R|KN0`Q1n=(*C`P1H z5|QXGf(1!l2*RI?+QeeutfQsPWI+1PM4qpGu2l9d_K73gaEvuld^GVQFD_I^IXQ*c zL&o{Y<#d?k5NIGspCn{G5tb88rfLIDMJ7G1n~mR6u-OE&X@$r|pxhkz+9}U#&puPM zJxvoUe3YF^i9Pyduc0tau1$Ui5#)~2drbnpuZc(V_m#}il7IpQT3kk^j5v`UnkHK6 z5I)I*oGpPx7T(!8uX+N$!vypB>Rve5_AJD{aqVP9G@+L7ncXFQ-dRdQ2Y9FhoH5ry zPr&br3!_wb)8o3azB&FyF_Y`Xae^o9QuO@kBTan)PA`|&y*YF~< z?0(TIQZa_df0i`IY zp-K}0m8M{*0wP94DN;i37!c_t6zL@(AW}mIDFy_js037+sGz7QDqs9P@3Xt_JG(nO zv)?!K{li}j44HeF`#P`lJdWBQ*))NihT}PnwmHoKIW1W^txs~=1612fM@6(=(s`$W056V*C*FTL+9>vYrPBXHVX*(fL z+w5kVSS78fBgO2?aCQS36;6k;cFwP?43FK^ws$R3-9`@LAUXu-ZwZ@OBNV|X)?Oc_ zDO;kVUBc>I+EXFTG(@GjM!E;;tS7g96sj3uHK8x4%0A@RemFqnvLkck;NWG9Live{ z9b{IO6Ly_|ZXw-tZ{_~m+9aUA;kfKrjZ6Zfl9{ezQPy0HLl={w1um`^@0141VjF2_ zOCoxQ%(+2=7!VNQOyreHZh=))D*?*-&c`@=IfLXz@TpYiaX5W(Nl`CLnS^`SN1ukS$0by`+(Zx^f5gI=i|a zSw1?CnP&biS%xuTc7h=1e(qKZ(q#+z`f16_O4Q=d{QnnPg$eJT3YZ4`SFq*FfTItM z^Z&bHmendeL6Ll3_TO5Crg_L;aZUej6DnG>vYo9SzQ0>$Rex@7n-n<*~sdH%OasaHxXO7GfnfWq|kIRGRW$V9OW|Mev2=EBdn>xJyN8R`8!Vv>G1(&r8Rmmsb$EvZwmeH!qgk_ShdC9BvYagGil~#Rh-E4mUv2ANW?o<2D z%(YJ)yDL?nI)8n8|EUWEli#9q9Q4}ih99Zk>Ore-ZuJ6ZI^2m{5Tt=522Ae}#HU8{wKAfl z62;g;@qiS|^}#zA#%dMn3S^^T5Nr?Ez7MlEMr;XZXvi|m#!?PT6~?YU)dmE`6Nwj; z`E44D@Uh+fiar+n<7Dy2cL=&+UXGmTifEQ$*5F#pcG3+V=OPEKiM#)O*J_y#t~#Lj36c#0v9NdZ5AiWZqfUZfGKWk{ zRdgp&mv%Lh(oEL)oz^dT zTdY>$s?oE+`7imqqh+VQ5AQz<`T2-Q-|bgQ(xzyoMN&J=^+7uv53D)ph5If@^(R>= zsCh@6HxSEh3>OgIrQ@!1!`;L^dCn0?2aua^0pnuB2>4-8_pU2wmN3~o#HOl4cGnKK zFpD|$sFd&|GMGuCB&hI|Ym0f>Zp88!<5Vp)=-rYC9rG}o?Fv`yfXSJgu;W8-AF|c= zO5JD6CL$yGZR|}9uZUkz3;H7CE^jDeTpZo#6Io;~Q{vI;Y)vOWIJUM~MLhXc9FI)8N6uE1^jYAb_ORq@}ooJ1= z4cltcpptQCcj+-&`%^O!jUD5c?NwfA&Vo6G`w_>-#geB4C2ETh_r_P~Hplx^#jbU@ zgVIjCN(_(0%>0fQX}$#0+)O_l4k!2{RK`3M^~y7L`;JV?U8t5mCfy7lAUG_fj(5J* zlZi7AIey`g5Bkg{3(ZQxg{Ao9Up)ugwpaztY9?q+9Mt5GH)X_IQG93k2jQ&yM$07- zz|JRh$}kFHoXF+`;grrrJ9+37@EIA(U99rDru-SjnA#oanuXv;o@BDMx%7*zyC&)T z5bY>Me5JT38S$P3OUkn1xn!jF(OB${=)Q8u6J^`WT7?HLj#VGF@BtZa6D5_LhWo?@ zu4G}~B?%AgOLwHLLzMWJQ!k|Bx&VW`P{(%-Ewdx~>8Pg%XNiLouZ_$ zN9zdhr&0*fM-|S%s2#3Pn0o9Kr)=TNxMO2a2s5M$AB6j;F5T=7yllP+IGqf>({OR= z?yX@)#)_3>(!aOj=j&Q$YR13T-0gTz+;5%jHTzbd)3ND(x^4dX__wCEjt`{JwwG-V z_Xf5OCqe=~>K*G$FTLjS5U$-{ftVC=(D3DZ&q+Vaz7?(F@7gh{tsBE1a?uE zT9`z6(0P#?F~aO$g`WhR2^o$)E}h12vlFCO$zlTvy`Ai4Y%6|KI6rC}T6-=ud0$Za zl0J=1H-`-qj}Khhi^hE$XG`gQgJBB|7jDIs9)xE`vHeUZgyTX1P!vFBUz231<}v|L z-edXfA_T+ZReGGg(0$iHH z?q#^9iXrk<5bWLP`Q}^536TzUKy&u4lHqlWGu$7pVp*p*mS^tFE^$H%dtFVT3s1QH z4J++(U1!_!`w=Bt4ECKb!P=kO1LUiu8maw_`7NMY3ky25jWlzO(VU2qya|GmrK9L@B)>tRBnwg*dJ1kjss}jj^MeAIh)a<%IPEyj zZZA10cU?Zvty$AeUo2lHPqbQmG@s2{V|Zg&Jbv3!$rTOZyPWI@f&s8<68Vk_f|kM6 z*e9Lv9e8D77MF=#JLZeuj^!!5*+LJ=jlJp@?VPWHReGSUe~>2zYHRD8WWxhG^di6S|Q}ZA70xuYhW3@)DGDSgC~{R8fSrqYHxZ7x9H*hs9v1EbJYk1^W|V z@tqGg1$JoofCm{WA7JMRN&$mXRF2=r3xM2t;^F(sNy7CA;p05;;~F1Y$h-BPXbT(U z!xYRmvYD56!TlbzTVHu8Sbyli`79u1m0x02=|C2je+-rm3X|A2Ih%Eny)f8go7h50 z_Z$XFVr@=qaJzkdU%^$9K9#NoB0lwq0U5Q>L`3Gfah;LRKmMJYlIAz5W2xFF&IK9@rb@c@U=I01yxa^yTk zBjJTb&rLm_q)*+1BkGgGj3QXL&Bp;nfLMMifJmm~X>4SrY!#ymi$AJlM@C#g6x z`x$uQbh}F&DDeTx0xLmQ5?^GvXRNV@;|`Hmg`b{5As_f3DnwqKzG?v%c_a(Sl=-kJ z9|4vs-s3r~uO1$(l-!_;E%?9)F*;W$_9wCcG81-MRk`CWDKRsfKg^(y6vD2ZDOd=- z<%(WGijBqtJKBc^rWM>>vqdLNZu6oq8j0}lVh1R>L#&6NUMqq{$M|!*t0wVO@(tsG zHR|Pe;WS~3fV+Yse45xNfx_pc0cjUBeW%K_209X^;grRZVAJxD+QVfEo- z$8hkzlRJA#>fxn$4I>xg1B=nQgDiFE%n3Yvk0zn(o<_?)Y+<_w4VJtas?=0(8$r9E zsd5Cx-2n=v8#jy?0{PZeH?}#~nBF`0n})VSMk7(%C-@dX?!QwVwHFjl>)SdOHXlQA zyVGbh%90!hYTxPHb9Qv!kUbEPV>^4Z$>MHA?A@dB3jmD81i-Oe+Ztg2MfFw-cVVGf z7FHY&FxXVG-}BnH6!xfzmUC{et3@D>v)_a3X(XeE$h z#~V-$x?k^wz|txAA`&DIMpaC`<2S}NvxTLZSRAT&$jP&y6eAVJT_{2&(2BP@`1WtP zKU_E%F2t+u#985a7}m>j(zC|Ju)cCXmR?)xhx*>&O+ysVnI1`wH|B4INbNR21D-%< z)Sy%D(d5)!qezI+qt@lFN+zLTVtK7NEaZ$tnUHD-f8r!cuJXOo50V`IR-5eSxX(iP zUkfc*?H<{eJ>QPBI*S!19_YT^+nnAjt%g$XnxY3kN9|{yhNO4>>}llDyP&eEBp}&$ zc-xvx?K@Lwa(zLutp93Lul2BoyTx|*H#T$+^P;@)aiwyRSKYma6NPNp{#Po2nXWch zw0hYm+C8>S+(wmxbZSeTUAy&ZSHf(%rn*JJaFJ^=N=L|9e%x`#ixMX6$ircgVt)?M#ps*$47+R$C zvc$Xuwvjq`>A(nAH}q6>l(depgFdixXsa}fp0lhang(>8h2b{*4~ zSz?sm(?pROr;{@-_A_q5Gw#91PUp^e*&lo9GI@RMkQz^@`1aJz>%ux2*u}OHzw07m zEO|UHBUnMemDL0PX72tC*}zBuQbr@L3;EDd8{d$%G?#Mvi+jN$!-;cX0F{*_BJq3f zXBaZa0=q~$=Kk_{;RoOa0D7n}zq`cs2M>J50d<%KMj?D$4a*`KHerrg4a^STRjr_5 zD{1p8y^kI1v%S~VYG@*-B3Pd+OyxK4EqctgVzdsspy(@J)BU6cmF-ssV(`3+(?+_~ z;w|L9=FtiaZ zo@>t>h$T{xwTHq%7Gq@I%<={t)pyqqgkYuHo_^n%CVT+U!xp zdIoGZX?tyqI>a&kfrNy8g?|>reit2hkrr zS@9;BV-N?o$8laKaugFTg|G(U z>&1cXPqKBN`4{<$$q+gVA}Pe8Na7%AbXW)z0rH#Wt^eHA{(1NHXA>*{`X5)wb08f1 z6bJ<02eHG24QbTw2>1cn%R{un-WcGpajs!~QGWveQO}p<7JP&EaJuorMhzvy_odJO zcaorRxnt>Aj>fHxm&1?Bo)!G3ys*{hJ}WQGGOpoIWTtDK|EK3s^`gd~jVWNl_bjje z%5!c#ZjjNzroSQ_lgHkA$NaynH2pg-6g6$3E%nA8kb_nfvw9v0th~_lKSVgJ74lI% z394=c-_XpzR>+;Us$|*=T2#&dp$O;ytmpAx^TPkMLT3II;Veb+{LKsb-O5=aoWFS? zE?RmyRwDf$l3@9AynOT8asn$aeDha?^Cn4SrTk5@);}acs0=GFv- zDnHiNS8r_ayd5iuT=|x)@iy(2xd>a~bN51ugH>`7m>Mx&lI~zvL0HZF;$Cw4H=F0V z`{{Pc$IG*iu4}wWtbDH6wYkqtuIBi^vs*gNd;XIZg--z}d6y&{T zI*G4F9{|aLH85ZCRd|uFQ|8~Vss^-zo;NAJOGlY%-{LT@os`4qQ07Bv_OYR%94y+z z&l2@!?O|$1su;R+Ux9M;i$#@RVq!UL^cDPplPT!N9F77QqeZ#F9KssIFSTIgp9|oQ(USR2vsm;56p>OBYX z55cVm6SQl$EZQ@k+(2lZ9;Lldtr_St+`CKMe{Z7H0{ViCYSAmWFd2I*V2Cg-e=Wa; z?e=1DCttSG#ZOlZbn$_225#Kxyn3G^*pQJDr00C{4O`BOU0(8Sed*xKOS*zD0nlX^ z58h#ud-$DqO`NifFn}#unOVkrNx>VJSCxABjsd;Gh9RxwJ4S%c_6Tz8-L4NiYr(pR zv-9eSCTPK>_u003amgGQ$t5xH5-vuHkAqWYB3%cx6vHasa~t%DYl|A>D>bh2%UL*S zCu*aWlQ)pOCSpbuX^LiIjKyK`!YUtFH>ITTz}j{!_JB)5+UzII7D^J&_cd|rT$)xN zW%&?dxbRfZ)s)0v6a})FP}GoeYNl6Qjo!N<(?FjiMp9MFnD4-j3FLGB^GaR8qb&oPMcsJ zIA0nx1|t6GsJYnanuwiv5#4#)WOPUBm(~1>T){{_AEp$(R)*5ku=6l9nETXkLCYw? zorcV@YBzP%vrBj!3`+(8g!*8DW1mFFPyQSF_ks+S)ezLJ=b z8~AVwqh%eB`ghJNKIgApCOuv5*h=~&x1xC}Z1e?hr8z{=1so%1zRcTT-Y)|+WrATW zg%PM9K(WP}Ty{E;7fXxe)rli;^t4+v^a^j_U{Y%Jy(D6hkb$Wa_hW60w3%{zp-D7f zTV@V;R_EaBA`Th68Om-=CxM-E;aH0X=o-9%@-@EkxG!h&ZRrJ(am#d2E~NLoPy7)c z(|5A>is&{WQF6_r?-agM`1JNlA6C+K>H%innj&zWTM|K(`(D z9ef8>#|`i=2avN>X9LyOL#bwc zSMg`V;%4C`_8JL%#+~OoXPYX|fAIJ*Y0bxy12uD4oHDu6Je?7(blp|xQo3dOl(AhC zE#|D3WAAyu-n~~YBxT)6vu&F3=a}0Fa#K>^&HU_mbMvFKiNfjI3q81jrjg79GjV>=veMcp z55k*weq8PJv3%Pg_1iKM5Qf+rGa*}d)V(_ggSzg0L|^ji;gy61b=|Mu8NZvq{zvLp zqbBkkT&45K?VWSz3XhzZ55+)V&!)b8Vum(OTwZeu4QP2Yw)c9kGja3RUe`VC^+yp| zv20=k>%l5c&hq=G_Cl(d85T({iB1Q42(2quMA2UEZ}ym6UHdGf@So4ly8Jy{9W~cX z5{R=)3Po1l&jOq-Bsl**%Q2;wrkEMcpJQwh7~m7ABSx1 zAjg{^^OL9_CFk^&Lq!b_fy)A9SJC!o!UxH|oa$t`wQy5+vWY)=9u%P>9rp0ztv(vU zo`C3MV)freoCvdb*p2vzjnrQCnaV(y(GVTDaL_D?&I~>~8~MhXYyn40s|Sn|g1%hz z=pn=GsmM_`bF+R+-K9HD8qxcAeBuoQDjA5{eezwWRnm>!$eU}Ch;q!7`Kc*Fj3wM( zsVwG;>$z)G==CG0j@x#Q{;`Tq(K<&ks8v5Y2~kWzOC5~6E={^`6PIBaHxJyZBcbJN zVzm8y`Z7F{qoE{*S!ut!MOplDHWC9sBWL{T@W?y@dI}fBVEQRNP7>E3JtWZXp{z~X)c$Z}_ge4>2>}?zDDg*tGSIA)>9*Z~7;9)6&yo z$+vft&Saq7!ccYJe2oP>1CJk0G(_5j&E%AokT{v=8sHc zpr#0kWyIpb<6))xv6}PZDRAG5CrC;$MVP1LVG67fo`JV6u6FZ$1i4)}Q+R$uY*{9N zDP3~uX}HG^&=2|0qOv$8Ui|(BsfXacG+kLcU&-;c z5{yT#HCMXukp^+4NhfZW23AU?R$deIUCfM?kMR>d;#*1dRWm9ID6iTAwA(E6T=zh_G@k10jp?^~FpCryIqlrdA+rO^^ z=b)Ets|nu=-fo003D!=TqjD(d&?DgFKm)46zRuMV0fbEJFfx(uA)yrntg>LgzAwuF94dDdD?xoI^1lDvEp2tL}FFeV!iu&rVjT7kLEkgVOK#O$xLP7_a%EHLO zzwb4kH*n1-b?2COvdTX}wALyVtdNEqs>*mVhW=!k#jab40`<5rH-B;QWRV z2~0Su1jEqPom3-0Wr; z?}VS^%)StN1!Yw^$%8A%1Y7c1~)AnM5ZNOuFpUn zpJKFtoCr86kBBhnxpujqt&oi^1(cCE0;WLDFO2exOo0i#rKZ3&^fQj`+1=dSWX}SM ztd!y_USnUnN$MQban|d@T=s!BwY!LL>cFD;3y#8hFll7Y98ySXE2bcaHIW7T0O;fW zr`cx#Sl$9msuavv82z!}&|uk`Hh3{_UbAL2Z*0cm!TA;oab8 z2lfzA^1#E(i_sli+nCoYoAvDq*aehMbFx(kCuYL9~%qfRG|9na2a<2X&^aK6;A^qu^CId}|q7WN^b ztv!MGH~~IJ?0B;|m`=ik5D>k0pUHV7vHE=JrqlRjrch_Aw+N_$ic~*w{kG|tSoo4o z^7Hx2&%prvL)G%5g^9~%Fg;8+mhXr-q{EBk8RE}HZMJ| zUI8qhN+~ehKEPx+Uojk0o|W#1ggdBI|y%x(XwGsWS$qFtxgZNrfBn5+_<%+YOhWOsCgybwYFRV)3XOBzb+aM;C34HO_bzKgk^Awo z6j6P=JBZ9uhsfvLZ-2UX^bz6xfsY?VEFCR>WAvzqK>WIgFlda_g*9j^xZG4X{BdzF z5WEFt+P`y=-}n%FMeN?Ew1lp$W!Q}^s5A4FapD;%-ldmjvG?}9x8UOAny-+n4CDps zfT}Pu>K9@Ry+k{61x&tzNbi1m;T_M*4O#CMJtbhb|E*AB7c1usAvu1R8|Bt)s-?WX zIAp$g_KSe{co7Y9(VT0Z0?{MDh-6sKd0(lED`uy6zCW0T^EvY+beRc(^0xX_PwZ?# z?&>QMi%))C)dYeM4SvXceFgf>X;JL)!ZO$#YD3_fXJ9Nz>^@AWar;;OF4ryng7b2y zKWorRa?d$%KmmF;U+t8|v$tt`#9$@B`rD5${nnSi?jB0*ZmELW5xHK{F_{JIK4e%! zOYhI>Yn)B;Wa?C(W)<-I>s4>hEVW(ex97AVqNvIDq|E>8+r|7(TZpJV;W zp)>gRxR&(R#XN<5<^xTsw=hA?q~D32Lson=Yx_-`w0Ek7I!&p)Aw?5B8aru?gO zO8I6A6Gb)~=(+-LQNmZfnI~ffX9^sC{}tgxylrnk56BqT?%X;r!4T2%|3zjSNq30d zjzC){#y#b`oS7qiw3%D@TvHRh*IRX4!t29HjQZPuL^#TQw(d7w`G}D=(CkAWnGsyt z<^sx){ftZA6Z&ToyniI7i^NDY7#?P^%qtJwKrn|y?xK~AWy(tau8=Rp z6m|2(1Q@M9@lR8YRP>w`A>aE&z=1K_I`)0H~1Y) zA(Gh3b?P(7)!?{Yq>(;~5DDfs5|BLGU}>U+`7AEE_qOr;xziBUsR!P}y_gG%-G{lf zq?gcX3Iwcyp>3}d_xVf8*DWvD`@LhWkSoytlJxwCWBw&5gl*z~6Rj&d9y#|nTFPgTK*wG(_(2gwi=;QuIGX>;IRI`TtF{erm1m+t!=Mo02R^&;72?U0weRz~}$F z(K>S7=)O7U#WNzeMzvi*AzRpY>8G$q0p$S>5<0`>v)&a@M@d|1w(Ea(%$H|{BX#P~ z$52Ya%QEgdbPixtv4?|cQW(WIwMM<6s=_#QAE{Rn)=ofXib2n+7=bA8wUP1!C}^}e z8);=I#vWkIDEqd)|9G*YxU`bLs$eBPF1QToyHVG*lUh&{_EpSWEZ=y!qNKLrMO85! zY2rm3;&U3pf$1mAC4NH=jMnuvh{ZTP;oISm+n-aWv{G6v&Jg9PIW^iSG<$bw83)O@ zvr<}OBqz>u?jS^-gI3iH3Y0O&gC(8<_%^Dslp>l-iy{H0#Zw#6DcNqc?mm^8ix3|3 zbwVz8pP}|?Aa;b%St4^Z=hDX)2icJRWOH$KbRYb1wY-k*fk>cygb=miw=!h4BoBbi z<@933Lg|6)vP=;E2DVF!gf&c z$m_c%`=;N|&#Rd%Jz`rg`aZ!vz2kR&$ZWDDDp3V_3-nmNR)$*VV$8@-UqBA7k{Ty| ztd(SV|6DIGtNpoA{rKb0_q0L9z0JlK-g_TfR%`b@wtxS)_lXWu3QAJqx<~9E5b{Vk zBsLL)%IUYBx&dki8ht;5Uu#3Z>8~syzia(`wWVa=t9Nu4Znc=8JgsRLyr*JkqZ*YBge3blTxf25sr1ZT$K!(HhhJ*ALFe;!c&zmqNe1o zXmAQzfHM_Y1@VAG+v|`=B6lry;V@MC#S?R6%U>J{&*j0I)0$-e--LD?L z@L5sCwV2Yd-1Q`1-(;<~Vt~JY>V3AQw_0xt&xGZgUnxS7<;Ylr-IJdvJVq`^53z(R zj8D8_B}HNo8^Xb-^7n@e&w$iqMxCH!(GP@DmHTtaM{5dGJ8a$xUpbz7v?nF7fi!z4 zZbFY;wjL)FB!<8LXxJzFQ7&AJT`~}h<`l<@(Q;$uug@m<*>0U|Fg4T|G}_NS%iWi| z&+$sK-}F(gj7AQ!L0+ zI0-aeO6_J!vi~wS;z=LC4vw8nRRgiqy{b53BKND8np--qgC+?S zrQLM2*UKJ0HhLuJvLmh+L;p5JI~hjR#&`~i36)-=9OvoF2NOStG_<|a!gDnR!IcjE zV$q7sb(;EyH?=>j0wZ=-xVqT7pf~U1qoLHoZx5sJ2H5`d9PG)@a^|v5HNViF9CYJ2 zKJB==sz3~Sf3S-!qmY5hwaq(6Kg(ODBfr6j{

    Yq#gblF(x41OLvch#P0QRMeAX zZ}(4~7Z(<)Fh+iXHrVIgpb8f`^KiZ8ZOo0}`*^8C_`A)Zl%jHo(7f}|pKIRIsxFEB zfny-8;eocfs`SUzu0m|=JnrSah$p5i{I&RKt=xt*gtT*$lkL7bBlhUATc`cWd%Stnb1tWXH=;Fv zEdf{WXph=cTIQE|U!?VhzOf-ipxz$bP#7w^p>s2wpXVTIUpQ8|WNv$fY9}}_+b5HX z^}cHoL6Q-RR!HsMAf352jCn^aY6T%3)27B0l*UzZEk2$9_3U+Zw7Pn!+1JWTzc*~2 zoltMBPjuFE!|}jc?X1_$(*};Nw|s1pC1|61gatR%UqrurQiy3?==kX0)%Nqp1)yf3#`4OG~! zY`QA-@e7&KnKf=06)PeCvPo93+i6@zjB?&1ZN<&IE&j5az+aj+l@l7_ym&x%~pe zqPuT=_Z-2i@At4^WO@WEE0^h06VahHSPxcCHers5G{E3t0V8;?r+nV`)d9#_Fd~-x zCMICH46`G~YRCj|uicIr2&vRVl~JMI=H}X~Vb-_rh`S3;6VVwoL@^WHMnlzski%5W z1jBz4n9tl!|hrA?lx@h>lVqnf63@iTbxiAn?OGdGH^x<15;}x@S2c1o4 zBdPV*Z#HX>6VZcos1pt~Lqb|@FQ!KW9UrS49(9c zCgLWgO0Z`)i>RX@W^2hx_}AY*G1)QAz7E0R05)yfEXs;tt6r+ z=%EAB80hZZ+?W83Omx>S+OI6&;`eCwdf&+{)33ZBNjKo;?aw0qaj1FVo|zvy#m#F(Eh5JzdcvPv07?ov6LkK2^!F8X8VyQ`ieDH? z`WEB6s3G|9PFN)kodH4@(^!8PqLv~(!eB+w_ZnF85*)m43+*V)g7`%LiuGf2#O%Z4 z*^H9dmk^u}k&E|(`1dues&^?B6W3~)h%ky$5CvUFhW8OrY3Ar!M#{W2e2|IkVj^nE z7_fQblZ@28*tp;Bn6xc);cBq;nWRY^I){0?l7vK7xSVT_H|W1#uFU$a4;Wi%b%1}6 z9;Rmt*$l!^$;d{$RM*x?2JwNDJ6UesuOJ3f%Q-N z>*x-`trTb1Vw1??GVNflu*6Y*>{EWwES>dnplMQpJktKYD@cfO@z8pSdAwlkfO`}e z%V0{feJdr&D%c%0XIp}Wv7wu3=#%PKe>zcNcBNi-N-GQRenk{6sCjahd0`%VChyPq zPj4Y{xB2f_1%vUW8grCdJyN)AQHNDtRdi~S+FeOcV2YG2IUB{MoLwmhnjsf<8f2v! zWeNPe9sAQWW6tHugLt!O?;NDyFg}oNyXu%9Flb(_F=fyLIJ$F_y0#P+djea?&V&J% zFSpavpD0mD>9(Jd>2ozZ(=}?tHD0(AB%CeOu@)kx|7@x%TMW+Hcd}yHjIG*?Ekq8n zj!LQf`7=ueS^Ik#$%@u1%AGydT|T?!CLFu6sEhC;C|}r72KXH5I5g|dWJfUSrzen( zpsAML*o+q_Ru7EyM;{wROI$(wI!YeB)CHG@7SKRVD?^H%E zUAt!NK5p)0#e1!T=VSy=aN^hcw0hrRI=a^m4F)y!OI2^eVi|Z$tTw-uZJvsIaOt;( zTLT9_^I^bS9wsqY_g39UX!Y_?+q=6?#+L*J2xwM{{(^*Ar#xOKKOVzL9WX%?*`y9% zs*b$WlC1H#4~OmnwG1#?BKE4HGy^4s&@8F&Ah{(D)skq^&@WqkXB%}ikhbp>nl1P^ zrx2Zv11fS_!L-(F0Ljv}kO6o&v-VS9Tg%~QCrs9!4B*-G94pPs83&V<{;5p3GxF)6apJgTQ zwO%F&yg_v`O**SI0b8=2?oKW0^4$+|bzmIwyIf~FsB=XKDLUHuYXPxu0<|N<3-p0G z60rXM^tM&Sj9lxUo1tg;^#d>Y7lk?xCic7&>SPIMSfM(lNF#KSr2hwcc2p3)F1S{jw2mYeBOip83?eSbW_& zeiS+}&K@?DBMIOxGV*ZGHqg(Yg|Gpw{$a0SuglNax~oW|HV>CXSLTrjTh@FK*TW+ z1=UG~my7ESCilE1A=(gKVUUps$eBu4l~bEs`gFf?5AAdxf+Zx@UFrDP5W( z&py7Kbf|$_4h>iaKf}8f8@0WN?|#Pa2uY{TenNNZk-JnBI)1bwbki6$ql2oWPv@9i zf3`5OiS?f@KEHplXE9+eqk5uN#3!t$>Tc$N*M7v8#I@zs{hcwskq6}ec6mCMr9S^MMETX?r5V5Wr!~UJ zy{dt92(kbNe9`Rh+vM6~yk=AGXWbC|XhV3mE9rL7i>PCL=x2SSjK!_jwZF6a1FoE% z&v$ZJEK6MUYo8?7pjSBI1cVTb5w5HBEz2i3n`h@%M zPv_tsQodh2^{V`Zks^P2)$6IvXIWld@`^V$`)3ZEwRO#9+U8^2%n&Fq+uxHl&vR^V z>|Y<~%jNt$(#E=ot6&t$&8!stUKzhWXhj^W$$9#M1|yUEKj;G$xElqx9fBPC;oDvN zvcT2j9odrbAi5pATZ{U&%PWX_!FBx}816?!zpjG0)h?!+4-_(CMFa%e;*EhUzr0b@qpCO zTm6}^XQ=6)%XLnH=~Q}W4jF1mhml$ObwZn|DX{pcu)6lcf+&b>-#+;z-7@%v_X8_r zFM{0)p#(J=ZVpWOTB{RSlL$`fx7T>Q5%ti6o{aFQ3~O@w98M%ACVENHp}Pi{z` z1{UwT9Qt6+9`*uKSR!kH(o|b7wkI6M{BRMwf$^$+GZ;;6f_jr-`NaF4qQ3TDQI;3Z zuVsBox2>?;pTLNf@^tImJT};Hi0?;_H%wdd7FF_un=vBVyJmlXN#7fYj`^wZ_4n0& z{nZ1%eNsM^Z7J!x0UOJ9x)L>wde@;#Urc^lO|#D*e3vwLtrQeiWep04U_|vY|C3{$ zSK&WJ>n{4%9HAVBK8)l%&7cz<;W7#73XVaY<>FE%M-*)9e4&(!TSpX%AaSA?asqK8 zx{*`%Eb?LnJ>_DJLq7}fX;u5zF~4xzs#i12tRq`BJzbG_Yp8uv_5E7Sr89Ya?fT{i z2iw4(`KEX^HiWW9Zr4^^E;YM+6Nxiv>>ht8RA7*2 z_tlf-m^bm#1}RWjdqMvH%Mkf8d^4jzp+m~^_HT&%Zw?OcC~h090=>V?yQ$T`V>_p`r@m47Z-eMZ&2J7e1Ft23Ub zU*%v=Itv;u6*wgtYcgv*_}BE_(YEb1uglJH&wlGMVceU8TW)+|dt9$V{m1&R)18Se(uEd^fYygiL>Gs@>ZF!;`0|(c&#ou%;Xi_hdR{q| zZ_ngA&w+JQ1M+`EUqt}RIw(I+4kFqUtrIKa_WrkcVq}Y|e_pgih?Keh9S-IhB|2l- zKCT4u+{y3VhpTTwIwvMgOgX+@T}*0oT@i|CnVP*E@J~Nm^`}&>f@psDfM6MLzQkFN zO+dm;e?CLvhH13SiupLN5nAEa(7{oq)2T1=(xFz-u9+>FeT$j?caC3Hx;CEz6|IGz z7fteReqrMry>j(xUaXm0Now1Y%sSOv@r(he*7pob!Bo_L(LeB%vF+_!A;VWPZpeD3 z1~l(Ro8T)O_v@k3eH_naizl=C_^;;M`(p8@F~?Hz%@_F&+~dReR~?doCLA9+3iIRaIEJXp%3uWH3IxIJNnyCaUY9oQuXH{RyNVY%|l@hKWvVzRcO=f2HlE3W3r`nYN%C%sJ$G*w^U3SRwq z`(@NH!O@VbyIQarku(;;{~pHgu*+)hYu|Uh+HbiBb7y#&9{KFMPvPODVQC-e=8$5a z>)FcHNBTgFEFwEXkx4M5P zxbr<;?-mdmII)=^4|+OKD6~7!ueHAs|CAV^K<3c=2n=aui}VRDbH%VsuBrz+6>vXj zXv0tBbJYi2g+AaSUH9EgqO%lBoHZD_9urSX+BS`?g|Vo#7s-p+MPcbj zS+r={+|8&I(9AUNR;+u{(?>mms$<<#tTi|Hp<>u`8DlY-p24v{ig0T!IU<8yJe>=? z(OzQBmooc3@%dDZJz-3%o*ha%&E%f{i==~X3DzAr!TjPnce`&d|1wEPM8(My z_xd`nYzMXQ*gm(>3by5ZwrzoX9CPwlsYyH1JRz~E?B^XpSuz-W<_cC05Et>lZ zxZ(WtB3s7CUTNYY%D%0OyPg=Xa8*0{GNRefc1PmWmcF3H0Y$znirE=2>Uc^mQ2T69 zp_w~OJ{2z)U}vzUIoR^by;VpgM7BRA8yrV zbg@-=yUQnryrQQ2JQhD0A#WZMt+_APOku9js;fMEAAL3wH8b5*%zD-PW3=)ENmNJS2~<@wJq&9 zNTf0^$;mQA?YK2a)VJwyfoi1jJ5D8^is$1FzxEd30ZeiS#4|d{GT#fRTwO^4({t}~ zP8u)ACaRR}%Pa^b`9>PmK69J^&m~^iIo3Ym5%Yew`1B&*tk#dQcCp_j%2&rCOk-}x z5DRCMIg~#)s{625 zbNu5gL7Jf$vM;l83;Ox3ubL$DzNfkO)!Pr98O118P$pnsDnV8~3;3rL@e4Lep+-3J zw`0(_OKePK^Wi1>4{A@#Iwv5lwsUveYQyDoBODL;f4Ng7cYUpX zcr1NZzKmW5;XZe(JrNThrWEGl&SE=7GChx_)L#y@R_Z9Ah?38hC^1nAt;{?r1@$&D zDvJ^phzYSCh&ZNX*5#!$ymWl)XeOU{L$VLgu19iDVao`7${Rc6Qfe8DLCqtgDr{q{S4f9^r_~I--w)sv#mT(ctx?adaH;yDUy>HGY+bC>N(P z8&I7>X=iktLk>J*nKx){nCK`VV2+Hsk)FtiK=uf6htlKtG=Tba1{;V9tYs$S&=>Af zW@_0Pomo&u+(-S8d@SlMC$$ELHZ=8wh*^qjW9DhG)dOMBjWAr4;v6}VX)GSxk@B%D zWp^QQ1S1`=gOY%tMr_0OSK`66SR3nP2snmYBWVnC)ieEeRDL888Swf7MRG9m$9nuv ztGNB?lw?p08yC8QgnEELMPX6-#JGrZxPE#hvj>VwL^YmGHL#NnDkR*AI2oKzMcOi( zFQh`oP+$^*I?7Cif6J3P8Li9so3v z@{aQY<1?xCd;UWjd2~kpNy=jog~FH8vJ65-=m>gkeup|e z+Yf+O#53hHerZt^xYP#*=M562ihVFhJaeZXaDSAAF}`Bnl5Kf54r0d`4PyQcqH#$e zTo7^A=}}Pr9A>+8rhK|GDps8;rYV&XRL4GJ%j}P5W<-_#9l5t95lWfahx|}EBxVGzy`ADS2<5wct`3RG4z^ZiO`kF@P!*$VeH_U<<@1 zn4Xo59x9tx2-A2-ZM($UOJtiOGJ)yvS_wo!RBh?e`+`!aklLK@n!qe7Z#`2|lJett1vR|_)+U?c$K2Wm@Bhhalvn5rF{8 z0>{|Vg^Y}{YJy<=Z(*J|c-p~2#8VeiDRWd|E%Rj%ih}dYjLfdlrcK)CZYiWe&~0G4 z?5BcoNu?t)sfCOFn8-ck8U6bXSY{#-b{5ZW13-NjV7H0z*Ra^u)I(({iJsWnOZrv& zMhP|e$`u8-1H_4GXp7_rgT2LmBGY*@FOZmPY$1-d zaBoI<+tCf2H|Ava;7j`>K4f*Y z6XyKgiWdE>@?LmkBz(o5w4ATZ$o68lWo+*NW8|z%SL4j5GLHoMA$5{cF_kw&+=68= z*dMaPbFx_=MG{^vfAR<g!yeeL34G5LQ@0dS-wes9w@8AC=#C3;Fb@5MHVCGp zTZy5ZkMFh8LxG?%?)#yP;dUSh4PP8%j~zSwc&tQw*Z>@>WH6jve-T`3zLPH=XQ~z` zkWW0>!H&E|&hRpvK%Udk@(|8}Y`YTcSr^Y+#>xpD!!~Yj7&xJecPoh$AjvQ9? zSE3RmC1ds4)^`IXdaSBu{>igt)SpDfF8L*=^i|jUbq@WJe`~yJJEkiAZFifIs6_wG zkXiP(WrI&swGMwR8?4R#NmNE2J@`7`5&E~??Y9F-($}8-gCX<3TQ*>Cc?9@Z0K#JQ7T5g&xM^yuvVKR;(1nsD4~2q@9sk zElR%Vyjq-ovtqTR@jKISDSf|dHM;}afyT8KWjdD^MtqmlZlxboptXG)HE)#H)bo?d z9!&Eeldoy(GSV*FYdt0~&@~oOH>~>UbHnHv>9xj*i!N(T(>E&_hD=7|{lP+n^p}=* z|JsnL)oXIL6;>;A9?Ud-vwgftlyC|x@$--z@KyxdHQL!7hyUF8g6$+k()jraw!`nv zfZSUYX|m8=CJ)@9v!&~O@@jLqleibIN~Z1G_UH^^Bg>T${CxJIp01VFBSXxmS?ZoY z>4dOrpFhsJ^8#Ksmox-N>n)Erd#yE18Jndk>F6IW+MaPNjr9Sw9D=eaRIrG#OiIDm zcV64w;oZ=7-aS~`9cLB}io&}=FdMJ0!EqjM9;BGD8E`%rQPmFqaRt}ojdt_~H3D39 ziwWp3wYRgU}&T-yp-WJ~g7_oosMhk4EvNl!JeGVgwQ^i|_&xjL!ioy@`j z6EgH^*6_imIHH=&pY@!ReC*3 zh9yvSGqB6}luQZ~W=CpPZzR-`6Ak zBo{pnHZSnny2{zo4VNl2r%p68J7TS~4$HPK_jKpS22{*u0pW$J%{S_9&nXQYC33J# z`zg3t{Ve$G{NVKbp(^Z)A2|Yf>VPW$b=TVhl%VB-vtcsTv29@ctJMA;9e&S%PW3*C zNn5yuK%t|?#3GxA?||W@&3MvqEPKkp;CcUg-wqs14ipk`?!-8S{Bu#<^84V`QIVuJ zyJ8s)z8E!*P)rCOg5{ivwq_(My^v8I9Mb3|$ShR@4O2Li08`)Y!e|^XQMO#wOF1Xw z2_CwnV5W4=mK@v=A9W3H|Xv!>x-3W?tj zj`@|mxSRaK`k5=j#9?TQw+GR8Y?K7IOWw+QR#=@*zs6aqY+ zo*vTXVGml}>M*pdp;|YT;ys77MN{7fU?LVDenymaKaNTgj5N$i4!wLp{SwD7s z?)k71zJ=baWTFtMlD&lK>##|b=~iWimOc8)D|;Ec z%O4N1=IWQp0;uCI1uU537mrXjUcG6fZB){AsuXNOVA{zZRD<7#lhn4*2b+rrXa||M zrRRAS(!1QdBWCM0AH}4}&vF;{uS59;1~p!l`;BA>_Z^!c!fi&0{bCnyn~9z~;qsBs zT<50i6+Hoi$AnGZ{s9R8Ql-)(zjK2wx{Wuc3GlOtR{m*UTtNb68;4WBCc7+b1#+N^RO1bny#z)la4v~;I>gV zV!eIOCl~uQ^O3q1L^Zo3>PYmY3Y=X9jE@5BgasfHbX-}CmjhT`E* zIU7qWZL1s*b{A~n_0EyD$Ong`=Xs7@N;%I{{bf>4{quFxSpTQZTfJ+<_~Qz3+Pkes zMEQK$e~5lqfVUlf`_(2Y^vfHh1jG z(qeu1lFK6cx_US7Gd%2Fp&i-TDs+1W2iMsCx?NHF3$fAh>&u)C~~B(@1oBc3to2} zz?#bzrjDrt(4{ow2##UALV-tF%79a4SeZ84kO!m?j<;w73i=5i-LM{ZdH~&Es}*}U zBuUojOe%Kn>g#szDr`aET?Kww4Sb@ zT1SzW0mOp^6iOX+TtC_JVXV7#N>xizjhLofiSk^isjUXz%sOiT7C2B#<7!ER)UmrD z)5Q${Mi``9h9-?Nr!AnrZbcN(s2B~PqKrDykuieMig;-5*_f^z1z46Rf@!36QLSnq zgVDFWFi6v}PSMjiRX7?WT8L`IhC%WZpmpqf3#k(2s3?5MJIC}d$CBzFayNa?f|+I& zE|3x2OiKzCGL@psq*T*w1!2L=^`N8Z! z1lwN39Y)MT$h?>VJo}yv(MD^lhaB8GDjvm-_sf&u16{lzqrguwiparca$86OOaR0j z&n)pUhY1`hsfqe|E03)%`jH0Uh0TW76@oiR&_!GQ-4tCZp8Hrp%9c5kz+!HTgohx& zppNCJ|H*5Q&I_2wuLltKbUaxdnbTw zTUZXD-)}{gm)y5AEn-xn{efx*^VVX>%&0pyEg|pwW>qVp-y-V}A%zfORI+Vhp}$u3 ziz*5sbC1TV;atHKg2*B`*kY1wrD|>LsHJXeBJRX!d_ooI$Q?Sf5nX1$9-am~{16(!WT&Xo46_7447_dq zE_ryU`KC+rgcM-(>F7=*09jS3l`g73ILw{9fRqS8vP{APh%h$*b;6dl*A@~`+v2-` z^eFW0|6$0@*NVSOuBZ$icD}#Z0OZ&{L2*1xHfvg}d&x-nI+?N)57-8EZ+BipobUYC^2f&SZ96S&U^;Q0It2&^ur! zI^gQH%zlJF@rJyBdcckQZkj;+qm*!%g6U}zda>&XA}LI?`--Up&m*M7qu|mG|F>yD z$+kT}Nb)-++CcQJBQX(>)gI*@4y4+-XiN-wpzFF%lsKWK5At034Pe9H(-6A#p+S~qb(gWh5 zzRtd;3qJ-dIa)UwqQ#+ooSi9G%7Nm~I;W^K-tZxh4PS?!HDQ53hRV~>m$DS4x z0#?b-^7s0%rpJd|pIsk|el|CPUL46TTh(&KV=y>haqEMaeOYr-uLW3+WWXmtcQ}F#{ZwSkAJ8b&U!{NvW&rs zD^Hv6{{tPOb*}4y{Iw8+?Z2{&#qP`DNU^>a1%;kJYajocz3+dnV)*3okKOgRPxDOL zpZrIA->F|ZjJ1!%Nh30g>hz2}z`wHaf7RZ1OuKfwVL7WK-)vNqI9YyJ;{!#sRQnF1 zC=UOATGB?)EYpFF{ys+OyhczW6FLpUTKG3PKobAI@13nsNDgsTG-J zg*wh3D~c2tYaiA12U5~bWr>=f?&nGJlL|9X%97O`&LwdgAKMDqG`o2!tLld3KDjoG zYDv2_PMmjfYnr}V>DD~w{>kmZ!aZsChMk{-@k)dF_9&eOmY%25YcS~vsqR|N4k_?- zwEW}k<>N8!U+XsI?>vFl8sQ#cs*FHr-ig{aeQia8aPWksJ}4d9VdBNEE0ZFYxUM#c z9~LV`gK`J$Ko)&NnfbZo|Do|+6Vu9!5IdrDca*t(N zlq_HZ09=R9f%A@k(n1!y@);w2!no1#U&djW?hGVWy zg5PZkMCcePeTO4IR3 z@!`?Ig3Hg$mci!s8!w-KXEN56{&Zn$yra#&)x?SY`UAWsZPybt1|{cA*Y#iBTElTK zgfJm8n7Z-V04Gx1WCH8u_Y6@WC=V&mR@#)4Br(>1YH5TcN&5B_{H^%Aa(CxyV(Lf0 zJ!mb%Amhc;pjgBNW14k52an(-=|dO%-*)!&HH)%LDSQsuY?%LLy!oh-o9z9?PT($? z17xeb7W#N$0cyHgADy%2`suK+A$hS0ghyc1xb%h09TRno3xdKOkFXkbb=qzdv9S7H zwu8uNZflGw4|9|Nhp9cA527c^NH6MeiF&U@MNd>feF0Bp0oxU~jc8kzLQKDYpJL`l zjH7WOW9_3)wRIzw7*iKWiUwg8?1>O&Z0xNQ8HA;Ed*G0xhOU zOx$3Qk!2*N4;LL%8ywsr5nOY`md1(NLl+VilP@V3OPM;Iw#ZZjwbONq6Qzxu*_$I6)G9G!1c4_))(tsUSCwoAG(X0b` z6$q!%!|)*C5w)O2(R)e=A*R~%CtA#~_bB4npM>**8gVl5!hIidB@c8sCb`c3Rz~7t z_>!1oH&eTReu#BVIG4!6mCT}okkBO?l{~zVuc-K5+(;(^G%AuQ3$+9Jn~ua`4;88z zmKa`BOB}3Q4<~Nr8wc%arrv|*m+DEzCT29|rfv%dB07%JnlGe_Z1Jkz*GFf38!UNm zUaGKPWKwGQk^z`%cY&aMKiAO?EyRj*td&;%uat{JIMW@&rD7|FCM&u)F?|p;0M9N=h2AT@YyTjh3AR@)7}pxT2XJ1vU#*^ig&a;(RV~ zA}vheiUpZhU{GEecC>W?6>)ZIu_nxy+I;wPbfx)d=K(fCV6yi16j>lm#3Z3(*Jbni zk`AWXN>?aGVKw*3&*ag#hmm4hTOm^dI^N!=`Q@}@Dy#WZ*?BdiYGW;@gkpzpq&DcU z4(}BAK17FcFGUBScW6dAdJu6xv)#5!*>Q@l;FeH+M=;A}b-!kL-r4Nuxx$4PGnzGE zea79gdpEyeM%nA!JdueuJ#g$eHL5WQDa&zb>({A9pYUas8mfu>yIeYmxrTvOJjQzk`?2OMW`or~@M${JT$b;#Rf|&uojoI$ zdEXs_3VVadnn5q$<{!IeOIGK;;7_LHiVT0TJ^1<~iP|s8#GOIVJI1-8P9A!geC8ZZ zJA3*0z~xDWt3k$!{GPrUC_T);wgo5HP+RTZhUq;h2MVfyDzgP@@Mya}0*g2LK?k9U z26*t?YP=Z2>3FvVtJgXTbH$-k?*fPPL*$MDEEXh2*$`HCqyPuZ6M-*k0HDrjoRfL= zU7EQ-6@*aqMhJu(SwAGpxZifAA`9BiwXq6=j5 zf(**Spmu1xW%N80p^E{rVnFXBQKjplU(!OPSIjkTn3_#vhX}xK2T*N$ydH-pAt-jL z=#%Ndms`ilh>&_b`gal9@Zg;vB18|Mgg;w$#oda$OTn(l@YYyl`8RLhndvv6$1W>tR%F#kjOLxym7cK-*s~DF)-Or_rWv`Z$>2L)howoK=NaLV}akaScoe%bZ9|jM7KI>vMlyTZ6t#r`8G}ZC=qdkH*QH?IAD);2G4l5zISR5 zRb#7HLqg@0#=`C5neB|bMDNuQ84(T&;{@>Yfigf5P>y@Z@4`6}K*f3#b2;kQ9#Bd| z>FdF&4{Xt#<*4>DQn@}bkB{%4jy-F23idGZ(0C#`A2~%w6sMy&HGm|C*jX#!2QC@j z3A^lgTu}ox0)VVEfcv=60IT>}@{(Q6_J)iear z0PgJv_(=dt4{y5|2;ax2K@$*hg?@MZVi^R5R4w33Kqu&uyUQ3C~3UO%(Z`G%8p=B9Bu13R9GCp`<65IGNzy0Dk^D?cIiz!tef0Lr2e z%`JY+9O=6>>ThBS(k`|UmY89{_+fIO3hBx4T&D3 z1@x2mGk{ZkpeTCYPe1HDkzI)r!~dO)8H~_nM!mPBF+wnK6ma{ydhS$csa5{bP1bLF ztTh_h-BG~%snFO}K%u2z7#6dj>@PzV{>=yKB?56u8eDuF98~&gzBEP`6g--M6h^(? zE#xNW|Mp{J(uOP0m?6R^u33>GrphY@!0G}m1dEz|P;^-zU5|@FZp1Fgw2*I?5%p1(}R5yN81@+m%W9m$Ha3D1sYc z+i)WQ#3l)tmXvdFAVTOTDGSK<^hEwLdJ;eAo!)t-kh0WQ*wZh90szouETDl0g8kw3 zu#&kczL$ug|r=8Daj_xn@J@w>@`)0rO}7lWbkD zyV1$4`0wM4|8TAuH5bP*o}N?x>0JBBnpwmcXGA1P%ozPmwr+W)uZ1C7kIR?*w{uO@ zaCZ1%!-r=Xe?2`bUv(<^A9;HIPtLV}kge0*A2ZB5VGX}@7_#;H$)^zEqnTQ51ign9&K6xu4Rr*q&>fsgGVP^CHI|h> zmfh)L(Th<43viVbSEV{Ut6a7^(0ry|XgIYP;n0PuEUsz3^r_}alho(p4xZ@4r31%Y zKG*jji6@2adQj zuw2s`!^i(1)io9~lX$l7AceDSBS2*`AQ+Kp3}&y8l2gSA);|(>aYJJZ+O5NEo;iI! z4WDX^1Br9#5B&^%$daAM~BfhfUV-u2sdDPG&j#GR=dLnnj^oZ%o{gPMmyUK8*d%3~CiSKiMP z7r?So&49mGp}puC)j>Sco-zL}^nL|@3S}As!{+gw8^=oznMN*kIo#8~DX*vbB5^^g zd`*=xS_eUn?6k=+#g*$j*cnv5T#)PoOshAbNhj==EG0jF6K#1zImlaNBZ65 zIj-4UMPV&DNp`h$>4KwGR4Sgc%9HDEnM9I3SRqlPeogkmF<%glY$uQM&8?#x<}BJ! z?k;4d%Ygj^m-@ibl{x!~TBj?2q=1>U&-1hR&{<-DvOj`P2N zIbi?iS=pV^k@uC)DuNrPRYwmxto)6jzH9A;mT z(!b=+Vn2P-r;HO(VJrjJD*MP-vVqMxomJ;JcD$8i@cr~jJ+w7qn7e`!`0n&w+L-k{ zFEHq|yi(qGBj^Gr9sal+qU~=6$Cd`FFAFYX;p&Z7v3FW@KkKa5(q%B;Qu=6_ z0Wy4o+(bghP5Fu`qnSj}r7y_MqhuKhI`%FaTnlsVK-YmtHCUyGVx$u-t{aVRLXIM( zfGcE!6_W7BG+d4YiWg9f+pB)m1>%7|VFl2{fod8Vw&?y*4E>mfdZz|dgGe9<38I9S zTe(8n4b##I-@^me61bXCN5-ovW8SEIT^ABUfokhOg%wK=&P0G1GD&e4e+kh{+Mjn} z^K{^@KKcQk0>(#r`2q>PczCB)>H57wb>MLifqIJ?X&I$JW}hJd8D&6JEtR>G0$xY5 zcSbXXxH2&?b6B!K03aSDW%cdPUK>>b`#xX6%fo)MRF!l9{=x+kB8EM3%5Sy>haccnhf&a7fzKfy3 zwb9#F@n^f@nL>h5b~NZB6-)?Zx1)jm;`cFBavAN!ChPA})Cdk0MWVDx#4(4k12Y_{ zqmky*ag6Fk20o^DAVI!93hEIJJ+Mo%a*O~%5}3v!g~w1+wu#D;qD^JMZ&Fh7S)lkW z@(F@*a@;J##Uha$XRQGX>txBqsQUm%A)tAX9{%V$a1qZ8rZXMQPu^8SDV3+lc&4y{ zQPySAENXx`ksWUUFsdG89BS<>K&|!j^8+w5DIzoR?yDm6j!1u7X2$XRffOBV09<~N z0$zyQr65~4A82Yc`_TXpTFx@mk+Y5z z)m%+tC~6q4U&f;&6BrIL&3ddXfzW2yOOTI~QK0nDTC13$Lm+v^chixROuuvRP=w5w z9Q0tkl!CqzfK(MAw2Kl8&ta)kd8`*XM*;3(5d&d}7h8U8`~@;g@Wf+)IUXut$d0U_ zA6oPyuN&n?`n8q;Y?=O0g)FTh5pRP6FFZVC0WwXBb;H6{Oug8(i;sBZT1bgfa9M^@ zA(YYVxCSV65%u+M$+e|qFhk^kJ9%03x>xJ5hKDMbl~9+7oK-WWhKi*T`$zxrB2owQ zF?s)s2dsaepHesF{!bm54nx@ne_&jWkeRN3x`?j)D@W%4>v}WSUyjVb&DH;pK41k7 z87;qX@#gAC-`_PGgNK?NIM!Tc`T+0X!droCc9?w+@xj3o3n8bPI$?|ltd)O+arX`@ z@cURL9uZm&pLceH(yviG%R>qXfh6(a^Wf>FYoK=X8w=E@uQ4y>`%e@X-mHniT;;dq z;G&r8IDd2S?J$1XYhkoBa5?r;r^Nd!ASMX}KmD}d`zv2g_X;Oo`}qEb*~Qdyo5ZBY z1o;IRxu3t#u8BBXv3O{7LBL)+}xgMeitu88PAF$PLd*%wLML$Fr7Tq0v_$U&^X1z zi!d3>1e<5xZG3WPa*4Jf^jB;j#12VHyg2u!n+c)U+kQ6K!9a;F(d8}` z1YzUQBA>k#^%_3&E4GJ<<-|+T9(fw}Yqfi^N<_t6{qDkEiK7Xx(JPBFASz+Oq4`o&nt)jZiMrW(xuJc4RLr z=Xl3rKZ(Be1cVXVdyA}OO!whUEaf;>1OZ7P3%p`%@6?W322IS=GKmkoOW%mO*8vgw zybe1)tqoj5bR;x_;Hn)VoIzU_&%9D=&+GJaWzqG7e=WcX8zJnBMOCax^8 zdbV^Q%}i0UhDK$NYw$@7&xA*v!*=D3eg43FmgC$dg)QzbgqT(yL_O%si|kyA@gK8O{wmRy!(^TZ>)`^>rRZ2qxOgudHdYKveaZ;gJa z0I5zPO%YzA(3`98#?zWzXUr?%lF%FYD%<*|v?o2<*)-M=ZQ|H@NBpFuSsEAcmw4iT zLkq_K#V51EpPGb%PsM+Y7TEaq+m8I_S(Wj>%&Ol1S6LPHudFIT?C)6>H&2X5ZGUVy zN0zZ)J?<9u-)a(+mpaixZuc9VUgZ6iRjFKcto}b)llbqls(<`s{{Lebu+*=1`_6~l zi9e)4AQe7z#v$=eoccX}8cVpwGlcvBt9crDy7IlN(mm!Pogg8t-tZ za_>Ht>%$7*BGj>x?7jmjm(uuL>T7wXU*yX4hHsi|CCxCS?3#9})aSYv?@Po?gQ07uibL0O`AIwL%RJZ&mS=HmcHTmRcpLByOgFe8kGw1^^ z27RELS7r1}GkT{1uX1p9N3J1pe+H6&dor_UPYKEY~GR_W3RBzXJf;_g?_WgIDEe8ilu~F33 zJ+orfzGGS?&5wiixDWxsg`aW2?8*e@H3v@wgUBS}oXTokYsjizO+!x;e}7QZOr_Ex?+>LpzQ z@h`WhY}=u(BJiTnaWJ3$XMZN-6_5xAY5z5xOD!NCr*o!}M~6n{Hb(9)U!=T4N_Z(G(GQ4~FyIn&hBMn?JtJ_GuPGBBc-7sRPi1xwNCXODPW zF&4A_2hf7^{(l!wT-aylZ6P3dS;>YGMTuCa;{(zV($IRwra^;E6!*z`Y3qW`vT2WEV08WR*w*ug(;rA+@X!F z?+E8Ssz^QOtAqW@0+PUcAPos30C}KP3leewKjp<`lUlJJ7(<>c5q_5gE)6&ndF%Jt!>G)DElpg7Am+o31UMl^q?%M* z$@o({-8H^*sQrXA&89BuyiE}oE!_2th|$c@B~{U^^-qG0qzEGtQv;oK?Yit?>oL_- zM%u}2&HYKV&%c1{cKDi$snP7v!POqF!UbL40T87SuXtJS>V3=o0Y2hf%+iys-WuB%hwWP4 z+->LSbCb$=*b16=?AT=Pl{ELDY7eH?x4V6ogl;ga*erGCsN;eis;Js0cl&sKYNbTb zS1^?YISoxUGzT=*T+TUdaHlppy>hbSNr88bqvw^E6_cwXI#^HN)5%9pNVIpUGz9nF zztVeR854Z*ejzdZ%9it#_>Y}~278}dmrVi}f5z#w8UC(49)(8rkwxxT?^R0c{X|)| zEgi}&)8$}PoCyhIKM@QjC?kYNuLS1$L#)6@cQxF7qN}LQq{N2uWFsL zo(}!p`0$1{QoU@E&5wD9a_#5afHdFX9668V;I^nEcbEF-zWHR<#D0BVo!P_2)|dys za&7KQ6W6GD*1!i@(PI$RzM2El=OhzBC(8jl^gY7vY2%MkW-Uv-p>dlw9><^SpUoJ5 zb#J}d;Mcp!@2#`L%=__$L2lP>rM~{2BObaT^`apm`^>#%rGkxpH`yN{EG~5DL%Z1z z=IOJY!Q5&EA2M#LrM2`73z= zTazkVZJavb_joPsy|K$9&5OpA-rny}AbPoT# zbZh?d!M?b-n?t8DOtHsm<9{*tUSUnJQJZdn^n?(4RYGr~p@=jwROv(nscJw#q#5Z5 zY6!ikp;s{!=|booLXi#zL`RkN^Cm-}O79IKh*fhxXP7c_K1aYjqxZ+5bPxj0@ zc`=L%ipAOGI|d3yieJPa1m;iGzZDcckZGs+G2}gKF_6m`i1cW9v{SrUWW0HPyk%#+ zwR3y}fpj`QzJVCoZ>T7wZUxE_)I5;!i&LQ!kX4vlUBT`#=M#M*6Mgd&{W=r9p~z0U z_2$Bv+M{*r;eLMo2vqRlrnu0GFKf?65=OZZ3{NG&*~t|SQpV#e zz92(HGv-oaUJPdLzCeL&4NJEg!^Q#NFPWKKvG6JqT>cvzA%kc+q-3$7{T5n6D;}Ye zlXO(gQ6WXP1_S3TMRKsX!5Nv4u<%D1G|V`z6`#{eM0DW!a*eW0ugRVj1uRj}2N*OY z3$CP;b4)H<=F91e7IM})Xb%|t5e3f9Ht5u31y0BxpmVvtz*5+6G=GlLg_IPT+dAmG6WI>|fgDWTHBCgW68Z`o zlGx_cG|zcpA#?p_!4FpMU07}@OP5paG*Sa`;!y?%tq^e|Lx#h@X}iEm32iM}$T?RC zT+2XeoaWp{D@DPZnc(>?Uf~Jsn34>8E7`GB{O0gy-rJwLDQG}qrFTLid~>N7D(rFd=%O{Kg%cK~oO2~#yKHN7P>Q-}Wo#*L zAzwLwdi7cvb{@|5a{_sDuP?!8Xt2!!xN@5QW~1af9T_JHtEo$6i9N-0;W%p=$2RM~A@#Xmm_{FKpZ z*mIF2H|0kqP0TJSBw;C?z*JM59Q^d9- zlc3pv`s|-fc7}_K%;a*TK(g2Ut6d5lC+zDsn$I;y?6*d}N^*0>fFc3VOizesM?s@A zI{9RiS)FX8iyIl#|e<8>B z3Sy(P9bZ-w<`fa^?|0HAl;(qI#hh;^AgPoGG2(JPI~`TEB@WS@jpH`+=E$0*PAktG z$EBhO(MF}It_~*Rt_Q>yhZw{nIw)O*X|lzLOy%F*MNyp><&dpZa0nWy*5>&5m29J1 zPU-KS3sHz6N+ubH?8e$ozUr}-?w$SJO~=C7T8R--j#EL7%S5jw9~$uAYZzAm7_N!` z!!&$u{aN>E3K|% zgZ5RGsmgV<#6zKLfD}t*d|A``?j^k)){cK8{jYKWZ3N{X&@_IuE};2;1npb?OI^L< z|4n2h*X`o}lgJ3_VG|h*J*@WMuX|_ygUG%I>`+rLdp%g{Y7Cpute#31kx)ifkfdcd7T|vnddN`qK;d zzs2`$tFeI$#up{ZD{td}fs9tY=Klg@>_i>jk`Mit$YB0UWUS!MVSn86+aFF39znK> zcp*7j5aY>H4kTRW!U`?a@YKkS6NW$dtdA8OI;a^c@P9RqN+KLH5C50Q*zU|K`DF!F zWO5j#tYFbH>9l4jw+%Y@k|rsjY6|zOc4g|5>Ni_7hq~;)wL^-1#HgPp&sO*8)%C%E zR{TRgDcgKr+z^Kdb7Y)rsfae11Ej`8)&1$ah#g=hjDexZ%YW91J9@BxI0@KTOn^b; z{+sZxPY{Hyb+Yh?JLlPE-3lE%#_Sc-qD&rr(U}#+Rhj~|P*15p@*!H~7>o|^=>e=r zCu)DS?7GCOMkc8wDV&2e9KHaKWYO1>iN40X=RK9AkAF$I02`~P{=ZCaj7S~#gJf(g zd1Zk)-WlB-oUkTOW^pc6D4%z+B)86Id%C(jhw`O6(G0nv1tkpgtNr^kSi%6N=;_y! zT>v~P*WOan5OuX-yDJt`tLP4>P@>R500Ao2TuUR9*AO6$=77d)KM@67C-WDaAsYiI zks|>8ER28hrkL`4w&voq5>!*1!8eyfw86pt!;@d)BpDO3Azk*_?Kty|WU2OBs-yX1 z5|t(s;nSnY4Yj*biiTH!(}YZlcc12EL!zOjLqoIhujcd0a|&qJ#UY_qd?k)g48Rt} zRcg;D*|^j`%exm^t{e=K{I@&@{jJ*Erq({M+reO?6k(6yI{JscP=_ zyywA>yU44^BqZsMd!T$D7$12t`J%o1+v5P6U5T$LU?pEeR5)eW<=y1V{yo74|8M@T z9OBLf@s6fcy8n?+^cS~uzc*13j>`ft>_q#Z29=EcQWsjDJ z-;TL{fhQezk42iA`uknAa_c-y3~#MCGUsgP?=~?j)EIs+B-l-GXe$eEZaLlH7G?G7 z*`7yL*K<`D4n2qt-LNbEiOSIz#HFs$w)XafI*AvxcC1;$*5ALbh3d4v>X=iL zeImIo+&k4kA`Schq`dt7sjWWtblnmC*rYE(-}`-^Z$_QEaRIpRgvvw5yRP9OfL%fQ zrzgX<-lc=ze5(6`a=0Yjd7*acWkdd|%IEfpNnhskc&=&3rGyQ=sDJ&kK7v|%gtN)+ z?{e(GXI1}mTxzL5_Dbmy#01O-W)kP2cH^%RHrp_L4@Y zxNJG#HBgQTfLj8jo1(P8E563U4aQ6PW2wN#2yUoj?;uZ=ZyotF1+3)7A6x%=FVwjB zLnFBi)s<-65YY!dRnNg4nIBi4@)33lFf>=&36$14$85XgDe#~(uC+%sAn5lXKbdH( z09=C@?JqGx4x!rP?_Pm%**)V?BA~>VsgUaTrNW&v9f_mAE^O9%_LhIrI(lgka>;5C zb!f0#@sS#&4doONt5TLs*IV$~^mu#gD5wN-bX$*KXDQS62~|lAf@c?RntwK#eyS3p zyt@x~uI9o7H|+C#?s*)73pw&00JUVTF{r-7!VI>-N?e3z;gVMU#HYO=u7m9upY9_- zwXlJgv3xp%^3D6W6kYcf{sL!Z zhCC2X2js(Z83XRKv%O85CkB3cX`k3juabDXM%4&ClItCu5_R;ErLjkGjaZJ)9_8l zi@`+5WjZhb4++A?+h{|AC=fq-NaCna(|O1vX)>25A1dlEfHg?q8AN9k7lZOQ42$@dNqk}2aFeP|sH z3}gsz;F*_-Xp^xad_z#3^$c?Gr*l$kJ5%cyQ%@uyk~H8|Ldfcc6iG6o z#s_kd2-|*Sx%eaPtlDYz12>NW;=mzcj%n@VQbRZx+vVPwa0_x$kkpxeRNan)faG9U zR(wq>29jThuzC4=8|=J)O7pAk_21n;B!*Qv@iEg ztLe22C%9FM9Z3|7jk}A_0Q=$ulx6RKQiGsGGx&5e1Y9yoc+U%M%dx$Qtyn}0CF9bb zaWno7#wAmJTP%eMZy;v6dE(8QGPgtSA9InaAqmtnGc_hs^p~ zL6r0ZHo8cGE;wXMl);s2;C|m>Y`)?znm-i_uO{iLPh|5;+pwd?>^$~w8s7n)9q_hk zWM#M)NNI1wIMs3uN^||Yyw%wAG>1YZ!2Qx1tN_NQvHY)-*>f*Z@RUjP<%cFqV!x~pCv=>@v5)9&0!;`5R zwJEa6fTAXsqIR}zZULd4QY865z3!g@DmWJZ53l?Gq!9AYiTzg!AsBPgPwsrJLrSps zaMtmEDFl8g>)6Fsm$>(HvZEzHw-*wY0;OlKnRA&NM>&XTJ~S=2eDI4VX6W9K32Utt zsJ2hLlx6>Dr)|R`U*WVX0%zlDTW2&j`9P)ZQN0ihH$DEWWpgIwIcJ2RFSpxC>W%H@ zP?wp)w__Z&s{C8&`BbZ^dds)9oh_R=FWj%8J2__>CqQ{Mmu9-#b^&#zI(p#xmuel} zXR<qgnBOI8UV>w>3S(hJ3{iC#9 z5rgu(Ms5DHmqzB4!;Ky(!YS`uy$z%!NpM7p05G>%Yddv~zYe8#>sx2xP)zIwJQ?%t zkus&!>0TjU{m9;&U(@KMWqp0e>%!fZI90vxUQ5n)Sce3Jks3Ara|@9wcTp;#3I5_0mL3qJCC?FOVQ<$Wng&EF+` zZcO^ehn8{Wy6L@%cYHvia2TdLYu5UyR~$}HqGA~3;1u}nxxpXw$O|Llkr5tOKrrN} z+AH31F|Uo4P?Nv6HjH1K8R`4>!k~4Vg|n3XVtO<};_%svWfD(Sn|@Y2g!#wuBjQ{CH=c^D{?}?V#{vm>7Lk-cb+MakYU;bIOj1+B#Az%R~@-7`HW*56ADwrv-G|?dCDLVe4 zSeiSCcm=bFp1l0teB5ZqhaJv^OT0bkH52<^#c2QgTUX&;cD3~*Wv7YB3*CD;wDd>E zu3AjFF7M@bPCq&xF)?+CtpuYZE3ruy)1G4c`Qz4=>Uk5>KDzq_jPy#)DvKFE*Zso9 z=}N7RiJ73A`|SR>Ds~a)Y;fUz@s@R!?#qeUa5k6CO0Ux2w0L@RdB5afy2{|k#NpH1 zzxE#jxT|pxO9ol&D-~)}Z6rL&NYwpWioRQIqF_0f>iV_p-=@w}lXLfOel5pv*O;HR zoX;%$TA^rDW9c+GpUZCQ#NMs3zPfDT&REFn>%4X>B$aZRcA zZI`0FK>kXuhD+_7TS`i+u$8qO0Gx{jw%S()=U{BONtJw@={CHIfKgJG^QpWeX#fS0 z+Aa2jQ>r3|O?G>q-f`d}AP5IO@nE%iAmSTHy>pFEi+gwZ1v9bTu>xU_CU1r_)NOb$tF7L zfL^;PxA$(@G~RqU_4<4Fk3QDj#+Xg3H@}vD^dHPL-u^N5=I^f`0{|3_1hHmviXYIS zwluQvG!v|MFo?cKi&wB-%lcJ03dREX;UbQV-32fms1$VlFfBZC5jzv-- zfAt#&8|Fx~_r3$rOED}Q-Nay+0Eb5R6Z!Zzz^b?6+rL%-ZVq8y5D=0G^B>q#0~ z3X)W==m4rPR4Qmj2EbP_Zd}M`{|tUyN(pMB_ZI{0Qoi;$vD!q>VB9GQi4?j)ivtga zRzfnL9fdHf6%F_vm{p-VOuwNAEa~b-!pIZF~IV=1X$6^I(;;v2Z``gQxiK z#c^A$=DIYny1OCF{(w^~(dOd`WYOaD{`R( zUq>_)_3>Xe|FQ7<(pN30(HB0RIH6{os)X%>&w2`Rlxc;vuCy5Lp8N*oc2+`U-t9#{ z^OzA{j-+E7QoNVVL&`G zb6{1>5Pvm&xNj2+w}X};sBA|Q3l5frR^ei@2@rb?aBaGlfvl{APXi;@O{*(0>U2$E24sGC}1Z5+?USYMuP(J5PKq6H!>lT z26Mqfl3C!!LyYQeY`7cS7=wdddmkUnxE+K)9zaO2#6Y7Mq>EH|PcZx{80^G=1*4&n zM34s>@V69n4GlP!7j%&hG^2p~e8~P0*Zpyb?eFj~EIf(=9wdRYSzsf8a%vLvAr%yf zh1=60B^Yo6CcvLS^k;zrhzN@xpmGw#nFtRff?h(QB`i=kn_G59xM85}fVf{jVBr`@ z0|S(Tf%>sQ^kley2gsZXbferDKoj9w5yn4)N$BfD0>qC5FT%mzNrRp6kYH@EFB5i~ z368*|g_A%;3bY&z<;|0#;vq}Tpa>e6-6iKw1;yaN%q>_p1MEeCd_EKbB$KiN0q|fv zB!ETI{R#5KBzVywge0KBDT6GHxuHvUl#f+Mq^9mqS3~0Qo*qH?G#8ddg;o(HA-y!aVJu~EE=5eqwc6|uEyHxUV zz2w8sl0DIfUtteFr5xYMJRU#?I#G^u3?F}>=wO>daPhtdG(--tu3_x2<%~)re^Jq5 zrD!oPE-8lryur^aXoNCV&<8OT%T((hiW8b*Koval!9h`JD^sfKarmJa4~+ zK##~H*X~E|%a1PodUU+~23MH>1`s(yulN~X`7$0+MS~TAE6az#5qO{m9eA6hOw?7b z!XT}gaC<6v0O#acSS3M5OkqImRvAthT$0_?8eb^WOhGyUkcV{c5ery0HPq=>^+OLs zdkpeB6}5~jrZQj=Z8gQUB0`~{K`PHW2~~a*l*fP_Cf3#{3zsM(8z#Bm;Zffclah1& zI+jK2#E{=Hs8teo6#;0Efo{nlFqM_Vmi%>v$U_3^6MKXpfji1nODMAQzii&n&;{%Y zN`P(24kUmITxG$H0PxXZ6*3jBA=a>=*}y3U=URg|DfFBfe3l=R9 zZDVPK=)(hr;<*|RJ!>tz&*#x?b1BUb-iS?0^j~H4UqH(U6Kq6170Xm6V_ku3;y;6J zIVk|nSRNHUw3ELiXGZLrfM*dwmVH%g2!;>2+8wyI@_gZTiMAO6AlcOhW9o44SGJ1T z0Jg8~F^lFa&dymwjnbO7S?mbDjc_z)-lI3N88VJr3iyuy^t5`~-ms`G9%&w*HcGW+F~jBKP=7ct>;(cXaoxmB3qg z5A*OhcPImyOjTg(0=~M+ayi~(Bn0*?wg%J7%Px)l;UpPN87f7?yUGS{s>4rwfH&gl zXPeP^xGtS~-Xh{1_7QVj4tj+-kkJmOgT->(m#O|Aex0geCY zXfwHXRNQ`8q`6`uOYwZIrs7@Mlh?2y@>lcVM>9o&R-O`F`|GwP$8W%oShj8r=V42) zy&atqds=|wq8D4X)jlU{-1R%{(o*h7(Z6*s+cLb4ZQ;_nAPx(0X|{4&K|k}EyXu&5 z9%9RlX#Kp{N`k$RTNK=VIh?%IZX))*Y>`fpF%I8NcWt|(2b4$ieR%Y)?O|Q)_q5K? zrTWaL%dYLyE`S%0gnxs?dfvItE!4ZzwIBHHyrDb2E|m=+sQWG7n}JfOPlOyNIAyQc ztQKhaUj8R_bVf+&`RL%Yqle;`iM>%fTP~N`U3N{r*XnCjvvLADG<{zmNqY12jZD*( zS!b?EC@gzzL2XompQJV-@|Hk;D<`uS&)@E|nh<@rq9~}hE#CEx_B#)V933i~jvc9} z_Dn@;`If}JFF0EoA0!uo3>$Sw$X^*V6Pdb)fXN3x$Vv1pj6f7Md{7VzJ(O469XF-?@|=` zo?VT*Xdt2(2h%;ztu@6iG!xHD_ndaMjs5CTl>I&LEa2|FG9@)y;Zi$@SG`g}PP6 zohC&)C+aS!Sm#WM>`%IBU^$>i`<$O;-tNookv!T7HiF3&LFY&1ibB^XdP_*0@TMnX zMaQbk=Z$uXtKTn8)wZ&3oIM)Fx>0u|52)SHCATVtmW+jZHes^e%hY;{M)Vr{e%uRA zt*pwf|J*;F=vrBD%2J06us--we)6VaK!{%?^BhDXczR7kJbW?s>`;ur$0SL?#v-+` zFJy`4@t?|R^(tf_v1TN1Pi;(YT_{}RY*_0W_^H9G8)q326{lP0NC3|pPeiUyH}%@S zQc+hO!Eal_IkAVtT@_8cU*DK+rFBo%+(OR*h5RTPW@3Kzyg$X#GCzhK@p%&qkv#jG z!yL17d{wPC52=cu<$M%{}<97*CMPh)kK zugSP;N(Oe=SSU!JpC96q3C$RjKiAjr&jmvPDHC2@5MxaLGpb8KNh%6qISivRgGCc&=`4Ew<=H~aAgm}(thJbi9 zP#p|_P>|)QQK*>)_{Lqt*Q2}{bl@q=!TXNL3xaJllB$2_y`TwPZ)#&A5R0mjxU3*na0nhyL zTCvzE_=Zu+qU@PYU?MGrkQsCphrEp6Y$Hk!hYtGlZ6R%%G@sv<@ z^grsN{Rv4J22@oOXv8-ckW91o-XT1&)TligCqifcBJz>WavYK{Ft^U(6FV|F_kzE7 zprnj-!cFeZ3CXr{paX*;e9nWOT(!2(!AX&E<%hUo1G?$BGgduodBhC+LL>m-J{T`F zf`fShOi7$d;~%Of5AsO`Dd|);pjJr>t0%z*^=!?^$_6j49e&PNrEo zfvz(P`e|DD(V@(+s$eEOY#&Edqg=u)O9ewoyjpvkmYXms@}=a`nLk^$Ek99~+7(r2 zZT#pfOPExxDXP_spYWy&##wuZJY&Co;g##Kb@ErCa8Z)P%H9h)D*WtwdeU);;1@%- z?ah)#0YK^KCC0sQqY5<1!Rq(&yg|Ou?ZCi*Xt%||U+tYw{@J-v^m}E?_P?$Vey_6b zb@Xo9e7^bW_v`;yAIyBd{rmSD08b|!V$1r^^?~p#D^c&y8v1_c$bYO4{;Z2U?HoNd z`{iErpSKvEuJNWY)IDnL$|_ti)YG6s#;nDq>!n+ z!)z8^q;167T)%j|&G>4@A=TDFPVn5eNTY8YX77R=Ax6n;=tU5LnC;yI3Mjrsd!6A~z4r^RI9!h=8px;3>onT#4Bf5@m>oy675{80s#Fs^DyRZ!YO~$BRuCI{&jo;Vf;LE z#HwQi9K~fkI0V$#@CU}?IXNsq9$fcBt#k-U?GAzCU<+#uwA3@=YJ_>bFFM>e$yp@P z3u<*m(<14x0{j4AW8!6#)`|<&lQ=$~gKnki&%{IpHUzlqsX*_a`!QE<00>_r7;!=H<7UdyziqQd#w=EbYUntk=-2 z-?3SI9$7k~*@j(N`l1r**Od9BvMmd;OkHHZ_$m+5Goek{4ode!$k{e9>1$^ZH`>GV z=*nsDj(u~^(Y8qUu}HU)Rv5w{IB?+GXymW0%=rjqlY$)W8`9tNbG<~fuP)`e%HMH3 z51ILK;=A+xE8AI|QaRz*_(BxCy+`wIi56t0TSCga_eMQ%#l2YYG6*3Y663{;C(A^C|31DeR3ZtdRB%V-O-ai`?Xk zS}cm>IPy3cMbk^gPh6Cni3%k+us<4bU{c&`ku$!{d)4QD8SKHVXvx(>7x_L6vWiJA zM7NHysF`Kx|ZuLU9$G`L@NtEh(Qn;pln>sQ;UaIKTAZ_(rSv887p|OeFE8CDzRLOv?S3Pu*+0%EgJd5B7MKBv_q*Nxy!d# z8*RQ6!$AdurMz3a)XSTxO2fyFras7Ukslz!GoQieIQb?E>bdV}XW>4M7Zh^8U!~(E zREF;H1fwY30i2wjV_B7TH#MWf(fCE_C z`Gqx)4oq0XhMbR5--UoU1^xG)7)l5LC>lEcwA#8!u$m$ymp`t6-?BOm5~zWm8P&N$KgbIm17R~0;9s^RMu z3+neEgOMhAj|{IMFL2hUDEU0EEj=w(d9k~^lL!xD7Xy+IpOq`if*TKZ8o=G&-kv%4 zqm=!>!>`d}0#X|6+8g0Lw9;V5;C~@}Qf%i50kW_pjv!tNUK-a2~?K zla?d*l4*j`$CP`T<(@Sk|J{7N4*oNfUCRhAKcqN5;cU_EX;JHG{!<1Q)qD6f^KngC zXbcJ5KyZ{ZiU3XciY#Yr#~#&cmcvTRpNnqW&OoyJA=?4mT1HaN;_aSwM}?b_51Y#^ z;i}%@3IhOru4j>89khRCgk4X@J7Pyc& z*Z)_~>s{f|)-f0}yi0h|!-(}6>h0lnQlX1{yP zP62we7Ki^y8#HMh)JpA_Oz)P8@xJ;VX$#`+#w%c_V<&WvQK^-~>u`2WXDRuFTwJ|e zoFf@i8ljG$<6x(#J$D7Pbg;lTRwnjzE>i&9iFx`Ax;I2W1#Z&M>E3M`(=Fw$(9as{ zCm?orkvlZxK>>1<2z!6XM6sBt9V+S*6ZMXS`h(@UmyY_x;MrrM{t$SI{)}${cy>sr z`}&igXcM0>s3Ml@1Ws-W2NQmG`Ye;nJ%`Jl0kWoW+0l`%1mIOF(1>dNI;0Cvk2_2o zlc*ny?(J_&^7fkNo}$7xG28<2X*v!mJ_ zRXN4|+I{v`4{V3QU6;nafk)`G7tlk4I>up=DIAw^k+`F};)1y<9#cNA4=mN&BvlxF>L^5jyuOj(d>^ zUuB|7+)*3HCRYJGsy0uzSGaXfFXjjEurQO+{@r_6o>%FpA`&V}26ecGG-bj|6XEtG z2+j%NjfdaHfO_$BZ2-^{b|Q@gy(kCO20+SKTtY`iE>iCw`IDhxgW6=g+QgtX3ElT? z2qVS%RhZNuhTiK68vQG(Bbheuf9F2u*(IAfq zFV494@1436uJbHfd}S54R-MK@i@r0mi9r8Buyw}0B-0tM?kd{+#x(ajahAp4en(lX zbX&bYJ-dTL-3sJcUg4gn8L9lUn1|<%B6ANAkwX+NS0+50!k$d^OexSRBJ3)i%e)K} zOtT3dgBYQ~eoQXBrirlteJ}6TQKhxP$Ea_B*Yh@nIXw3=0lAu@+|3xNDf9lWtdLE5 ziJ2agTzRqUhHAw^*ujFjSKN!NoVj2`tAEepp@4-B4W~=w(#8Uf@b>)rV}cjQ!lvJ~ z&qO~^S`%d3h=yM_QeQ4pCbvH-46)w-fUpt#s6N)%y$D!%|6H{SYJ;@i@^}1Z19u)K zzMoJw1enU(;G!6etwxWXN#72i9(d<=pYS^4?Jd+Y4K&KGE5INfvGAuX6x9gX$bt!R zA$l-yA^=Wfy}$N-r|I}^Wi-lz1l>jNT6=6N8f+aiRc%E~=>yFCO+E+|{g~2$ATB$o$>8C_=hfezVFJCn&p}~R8E-$%j^Q8{EHD!dUZEr1sL*T- zC>aA9VqeN=5Nj;B2Yu%;YJ96L8wGZSfqKR0-SzMOdOT(-MM(>@uX+80@y77P zY~Rq&K=h}eDm}s+iF==ja-|?Wh$u52c8&p_Ob0SlL4$bsRUEU8eOWU^grW8->$tyB zp;xdxN|K+y9N&`V^KMOpXrL|nLa&^W-S6@r9a1sr?CH^Cf%Go>JypH)`Nixrf?_lp z8iEEd(;(3_WHcR8PJ&hwfY$+_+bozL18fICoHUXeW58ajuFW3)S;wM!19{kOAFt6U zjX>0^m5$qob=)O1BrhLw6m#u;h=D-1fnbG!d8t^iOULb#GsJk{`RsOqb|K=gx)2 zf$zF?J)s_&ts3OG<;i_0BvvlQb*1tELy`Aeiy|xAKdv z)xJApb$9nJ2fdv*|Jvu$ty5D{dIOutn;X4PscRq^vp0`AFRd3l)>#+Y5cRw}R&Vdx zbgomZQ2G$bc*-%idtGtqcNAgd`&PD6wbjrwz&X8vNw@pz69B8mk%?uE8dG64#9i6j z2eETU!!E^|6$Nwl#?v`@Oz?)TA^}(vnfo!bLRUWF-bzLT2c>u{ZA%mMWE)3^W|13_D+XSuck|;AT^uBpS!>&=@Ywuyuhcy`px8pX$ z@-)v$zC&wMN3SO9vtt4lM*@A9ZkV1rJMr+~@HZBcof7R^;dO6}Wa-+&UtWU1Co|j7b`rSOJ zapZ}m+(#M%8)TbN2GyrMnzv=QT6bPfnSpnxyG-$d6~QUu&9-)Dz6*4o!(}`Xa&eHV zv_JZ0<>Mkyus&p+=UumbK7c%-obP==d@Fh6#`~~Lz(-NgWZ009q*I-f@vA=SL+<#&$WBH{k?nTEe5qXTsa^!Tjyj@Axpw>vaVzu zr%=j4mJD7_gnIjyXWEGuP{4h_hw;=e9gM9G9d0sV-(>S91*q{#?1&1djRfCgP#EXE#2M zd*Q>t!@JB?#^rAS_p?VMZ>pctiBeW+CAa}Tc%@Ysj)`1UGgH5pkuD81mN27n$^Bu# zeAN;TMFtN*SfUWF^3l_Hg-|p21Ky%Vli`Fp(&%qb=o!BSM&hS(vy=6u#vj8PlU}!s zsxKySA5DFF^ZD+m`X@Bh5Szir{sRTwH5lIE+$pg1T0~~^lgpt^X&2SlfH(L72xXBj zAN@pao(c*S@Ia8q<1m*vRP_v}g+iyxM)Irf2D0YvKl3ly=x?nyJnkoxHJ7M4Ijny| z)sFI^6s(8@RsiQbZT;i&U+o=8w1+ikc?!H8(3Q39U1<_N9DIT)=eh~xFsnD?zaIBQsF;DFK^hoK}tsU*Q(0dB+3UJ$*otTmU2(hOaNceq-tA7o?KeI{1z<{yLBS+xBmliCIhTRWN(oO#-hu#3s`E~9Z&AM zogExl#y9p(5OjEFhz0KLX9p|BhfP#1pM;4a3`2EgS~({dnghm~N`Nwl=VX9QfN@R% zu0k0_;VI{HZJsLUK!F!%wdtDLj;QO^!{Q%kt}mL~Q8f>SC6;jzn}rwL(UHbMj#JBe zE2ZHPY|TJ6Gf{uR1J$+471(B(q|036j>u;tYrgFcl;h_5-a=PrI31$?8l@lh@?A(b zPW#{|d|`=U>Cjbn>DxR9Dtz(r^?kgi!3GCUg!AL`IdgC;uVKD7w0QL`T9WSKU`N}O z@ljHpy%O_O+jVGy{6X6D>r^NH-xXWdu;_Mc3g zkiSAv$b(~f#K(=^C?lb z4}TGZKZtHVCPvIu$%fT_E=#JL&40c#V_CWjSiu3vDaLOVjy7a~qz^mB`|s_91opvB zntPz~L~8D@0iNUB3dR#qKxwF6ss-4>Tpy%XY;o5|^Sbv!Ex5z!D}@AXU6ypf8*)}t za;|&56T1>=Y<_v!1cX>x>hEt>-w~fb;T{`li~t@rGE6#*M=jMJ$Oi*n&%DbxCmwi$ ztF2i=eu)_IWWoD_?UR!YIngm(l5dYksQmfDts;v9?dFEommj;Hx~|I;PWVpcz5OoW z14o5DgHu3t@@cHF4&VaehXemn(kb(vwHj(gm5z`fC^zD5sb*Ns!~QSPK#Vx1>dUFw z2SM2#dbO;-if0X7^$ssRSaoUQ9BNS`D20~tD+)%(-+A!*!etl!6m)zbHX-yiW_P*t z_U3}>--#&r?VZ1@vF8&uS4JT84F}xyo|e5twbqp~lb-7vM+S0$G&csv_>h=>_uSoX z0d$Gv-qVC*&jTV)15%P}DkV`j+EjO6k?(h})f~T8-*I?*cjx<`muGk8GcR%ON8+oG zI#6=LPF$XMLg5sRQj-g$$>p~J|LmW)b9`QYN@ZJwOL|)Cci!_7!;Z1OBL3>Y)d7(& zsV5?|&~^!94^NMq@&GNvW}oWg+IBdox=v?1O-YelW`&E_r|3O2)_eL4ekS>} zt$$TAmwu}MnFhRC^%Om|uKPMbr|y}q3bXq#q+{~g8N0>!yQ%66D$Nwd`XLX%t7L_M2P&jXY^tU4c*EVdT*B$Y;n9luJI!Xm1lz^xUzsM- zyV`XvU8)ji@&=7l5Q1M3BM!1{wO5`1I+G6ldo!NF^_X#{71FPWCLkoxU@`90hrtD| zq3dYuc63=$_uY&+6K%_e7vjw?-VT1u;>HYfC`NrvcKtF5BgVav% zL3)76xOSRmOtMj8%oC>-c(Qbf*h0_EuSSQ@rsCozQxnU$KyTx4R3%9rkk=n09Pzjg zRQ)kN@wB6`Q)}tO=mDPCBM!o!G>MbZhGJgE9JZ?>;Cd9oeBXmSiqLBWJ zQ)Y|2GSouhJ0fY3up?IBzJNIr*N7G2`VBv}URt&yf^o?QAv9%P4NtVhs2Q^2@KAsa zJ~4ov)EP4j@J+m5QEf-jdd2Lqu{vv~*ms=3NuN|ZLnyP_0&*6}I*M3i0y`Crv8Tlg z3x<^JD=cnLz#UAcrcI8X6A`myP6I?}x(GmSTFr5ldW*@s=P*Wg40177P4eWKZLu@0 zH$eRo1>#=A@;lQC%UGEerM7d_!}AN%YhJas2f(-Dh4ms_XR7rz(v@yXSoHtCyX;`? zv%}DeQ!Jy$AfJm&STGrT(rS!-R>SjX*1Bd)+N8){A`>Cd25*}KSk9Ogm)U5S znCY8^?_|HGCuo{;F>y00exj@xQ6>((Q!zWzJM3j)6fj&N-e$ibCBXk=g#VG*o8l~| z1CSGxq`Q^yY@1tc75+?W{P6y{^FknvH`Vq37h~@g)>Pc^*=|TLKJnxf^~$&TK@d!P&ap3!clE zGZ?6IF4>Fs;^%t~*Lmk-^)5!LIYxFstVguGHeba^&m|VU0!hp>V_9&T)_khyed2#x z&d&g{tc(8#IL0O)pZZ^L%zra{=9g78m0R3b^!P8sr>2^D7T=dg_y?+02uS|Z%JXTU zTSEVj;nVUy`;yj$0JR79D*Hyr7KO7Vu4bX4!gK$DV`gHqFODx>2qHZ3>c5n}Xc;)$ z1Qn3CUtyHpo>jhHlO3$zlfE=B5u_f%gvh;^vl+A({ zPR!_fy`G)u((xRadT4R<(6XoNXIc~#$`zrAulIRFgFF?dl0}1~LUye5?myf4B04Lc zgc}NOO*=WUY@CG%?&P zm7GLTsFx-~Rw&do?b36{8*fM{C7V9M@=&=l&l?ycGnLk_T<1vUN%IE$SHYBJ(t;e# z?S`ZI@%!;lIKPsG`JjZeVmGY4QA*9r(bwwY(ktBd)I|`#ofl?KKhxJx>x(C`~iiRA`#N_d$gY z{<41QdGq$z)kwD^HMw%ng*<2PGhWp@brx$YiP)TA))y)s%>=U(flXVNVhcpWsZXM( z0-5^HpHprk`}u4vHFl6cpwq!*>iy-} zRG3)ISQwelpSl-He~C_cNI@nJg@%x;^jVa1Wy|C0>3fliEZO^i`GvN z3Z{F(#G(P#L+N7T3EAH6%B_W7v>(e5J7B1no@;~;w&SV?1v%pIX!Kb6c2Ki3a z+k6^ayvg=`*zBH8bHRjiKlk);53RR#A@s%}-ZNmJi(TgrCLUvqEs5u`&uWAUJKoJu znk3z^kRK7g=d!Ol8!(fu7DzY1HI#I>ecLC((f9!-t$?RVKLq zUif=Nh?Vy=1qqMRA=2|elAV;~8JTlT;cx}$Q!E}p=jwCDV|%dR5+IdXtqxz2?8;?#Dr)MB!1&pv)2$A_ZniP^b5@U!%soyU%gkYrueApZ}Q- z;O$=ofArTkQ_@Q@PQXh_RQ0nrCN=nS3iSi;z@-BK1IC6M%=ezza2k zf41=*#~x+4guJl95wL*tpK-xZL%~pk=M!!%4Y4QT#r$LfL=oIej$LA^(3$@nS6ydk zd)*axY;!}G%E>7}#d3@7Tgy1x%Z0W-O;F$T*0G}MqYMCF?DOOO$EX}>wgRO>b?PuN zcMHsWi3FUzDu~5%nLT3DIA+mo=7F&yfJW1KZGWI*|FB{L@dhSd^L<|gR}zLxorJ#+ zs(G<(^JXu|egq zw<~nhi%sv7rJU+zlmh~uX0sfNHiP$_EHN9`H)p^D_1rnZ% zTU%F(BL<#oNrD?cnkPVUhYX1H@(lSjZd*-qXYTfSwWqmjAfa7+J~&|zSGr=NM%71K z)q0_95A?Ahr@42T^>8^;ViFgYtX*4zie8RWs_k`H{^ejie|YzzM6+_8@_XJ`28k;M z7}0L!Le%fF3eu7n9=j!RTs~w~r>;0Wz=QN}Ey#0SW=YWr)~_TE#IlnZq+d8ZAW0+f zWYeLi55)zK#y@%V-=O$RNCPZp{2XGe|q%l)$0 zu&qzXXJL@=4Bu2BcY8MAL{k+(f9GU(-z*DuNX5R^G5D(ju?HjQXn zF-eVO{92fdX=yIs+rHd(bCv~XB6bn`j&mMB1kncMf?3d#1;3WoSc0qL#4(=Px5SH+ zHS`}jD0^aa*=*-o^8`8=I`m%NkLy`nU~h2x!0+W}))7{aX>Bzn9iSKiJW1D2(_u;x zLzm;^;~PuJrN7^==aHX6NGOu7uDIJ#;Psk2Hg)ci7MQZ%1;>4-q|c3u1E!uM^VW5{ z#R{(`XYLMb-21H7vd$a-dATJkgW^2ny=_0)vE-Z;?DA4*RZ6A3 z4*E7b|Crl?_nD5lS3SoYbC#}4`O|LAzojS}7w$)H*p1(?q?9{YP*|%TIRzB`==*qS z!Szhif}2UgO7-CGWsR;6Gu~f2f7G!@darCm?%IFeWY65UU>69 z>g^{lRGfYHuK%&JuZ(}+X%05M;gi4L{{Hua&e3y_X!U1R_~>xNs^@dg-X|$XJ2g z*q<vaY29Nbb7Wc;=%SG>%Frx^9G0T`fEV=tVifc-U)<9O+B%i)< zRbL_jWD~lZfEjAI_A%k6D_rAJz*YE^9TR%E!E`6lZ*)nZGusI6aCFBq$~}^KwhnU< z(A!@RWp3=1j-E!I&cWyzGgscoBAbLWj}ShM* zcnmBK_DP%Ry!%j*63s=Z2#7cXLk|)EBYBbyNc2o3M6{*kHihebBb{DLfp{^`er2K) z37=)8dZ~oRv|x*z;Jr_fVrxuS?5Aa6~P?3?d2~+FWCljPf`7;boAV;mSJpO17C&>+X2xIPg zuQlw{Dgn9>UgdbVh@rabjjCTpP7hs$^(zih(7XG33JA{ahGBvjc5NrQth$|a2txJe+E2*4qGA4x^b-x?!K>Ieg)z@!^p5bxj=`I6pfXX_eM1l1y@eoTRDr`O=R7nPF#$G(MJ%OV4s*L+yWSKu^?PBN+0qL1dF~fX{Xa1cXc-o#!MF^5;Esv>Z zPB@1X!vl$XGz8%w_0|ib@zrbT0+p;IPyy%4gkN{mj`*We1BppLnVIIQZ0D*6H>;R% zOnygI;bK+suPSQ(ognkb68Sr&=GEoDVlwipr`oDfE7j<*>RO>_Yh;4HGseofrlX_A zPqU`Up{Ai4)1_TIuw7FPE3f>8VLw|twjJIZSR1KP=6)QV;(VR$M)iEk6E0W?BmbtH ze+5f}Mgdjc)SL3UqhdTi*eL%=GcN*3< zW|%LiU2dB?rd_`2`isWfgI8(zhQEt}f}QpMjsnYm1~Ba$Fpw8z^F@=gg`J4MJWZz2 z&1V1-XbCiPdAcOjOwA@tT?{cRXmJt_QMEuB2m)&1$XmHmQbEnOIxY68 zc!*Yr!{e6FoqC6}jeU5O&FZ5y=OC9`t zJ$x(C{q`!71tULS&`rfC{?o#ImxDu&!Vs$pJ+S~hOR}rG-x}=)(_QGOyW{my8h|Gj}S;oP)B_sIa)|covhCQiJ?do2e-9#CEiG_nznr*x%ofuBA~XHB`hs=2!&{ zU}!yy9vdkfd$Ba?ONCs|17DBIVFY7*`2k&Zj2RX)(LN43SN`;zn4{1{Ei2j$rzU@G z!ZB~c5vLYusBa$!*%X-^t1{TCo%pUedFVRnK+&oknEdm{=CKsUn2Kld1cT0FKzozM zo?!h0h_!CTJ6&e)cj7q)?SY>h%bOC?n-u7t68k%a6`dCEhWrj@AonI&inJboHD-M? z&GL5|r3CgRWN;pJ3v;KJKL^l5lG9tdYPx@C@Z&R5x2KJ6o6D!4#_dhRZZk}>!({1v)+oWjGlt+=432y#R@U$@ehdA^{#8eng~K<9DD5DL1EARdf?UL_#xzF!PsKy^;SZV(WKc2EKp z;%yD<(j$aPgPAn&S0kux1IU^g>Lh?Ym?4}c2*hC=kUMw*Awq{K;Z9g^2LTd8ff-@|zXr0R zHv`tltmT5TPVT7Op38i*F7kGzkG>cg^6EYc<{ye00{S8e?UNYvBOF^Z9aTkv4PfA* zEzm0s=x74eV;1rZhh#29DzT{DHyzgj^ehf}K!Xfnp;i?1DG=(MCvzDJ>H>Bm8X()8 zz<=m0PmJy@!H)gNyGk>G$9FGJtxR~LHov`cEJDXNfFBajL@e5k$q>k-fJ_mfz71$I9EvGF zW?s_g;9yDeU=89;CpAB_0J~;FC(QSPHs|@J_QB{SZqH0GJ6wsQC7emGjV2K+czhbZ$Uw=fR64 zk%kON%QAx00QL$6S5uM26sQ3aR$>D)r-XwWp*om#_;~_ya^2H|$8k~i$*SV>1LQ|p z=JNd0m))74L#KD`m`0_sU~8x!ek`QnS?Da?4-5Sv4DI!Rig-Xh0q9_T@w21TEFWfe zY9Y4364%iOo6|UkE*2~{$au%W=nen3d56LBWa-JfgAh@4oB>MWCL#v&sE=UdHeSg7 z=OT5U4osO)@#?`#JZL*>@q$>eV5{ng$>@NRi%g)Lt*m-IuCfrPqq&g*_#>6*L{MV7WD^KRV*6D{a{ha{UpUXRb7{WPT!{Ckv5Txu$Zot3fLto`3*Ns9J1;CtbW zqng@XwNN)uhDrxKTv0LRZ;Rr>oWw=cUzur@g?~eft6W}OCBw^FA$Z<}HR`{6$0pB0xKVxH$} zHy)Rc=jLDFgMyc9l<@$Rd~wrhp~**T z8zvSKPhY)fu{5L;Hux-@98`8JQRM0k$u?xJpTLlA__&6@Kt5UZ)hoAZLCc|B&jVm> z!zU@sn9s%cvd;JUwITG=9)6E#tDYat!u&4(5}ZV?*K)3=Sg2=0Zmi`b2Ip1CJ&wM* znb}$xzN7UjXJzy$?2X`M%f|OS{uyDf)Lwbz+>U6!{jtDmy??g*?>p&Vj|)Qw8Y_~N zzzb!se;mP47OEVIXU*F0qv!HK@hmd&fkL@Xk>jaHR-=}k)f!CF9>7%V_E4JOs^Y3^4o?AFuC+$65OHJY=`rFv~@E>&w3~3Ij zrrLP(4B$woGBQEta0yI-H6)7231n=Y$p1LTt-PjXRi^ZwE0XFk6TfbFsbic}S||y> zqsqwY{h~|42VhxQ;NcT5N}>THv3(*e1xn(`hW82m>jjHPd!gJKm>LspTS31@_irgn zW>y`t_p5mVcfF)u4xL3<9qg33+R3T zNkUv8AiGj|43L03=NbxsASBye`^IzJ24XXKvzX!*Ozr$??0owZD)!&%^`P)K3m>Xe z>?-@}vhrWbG1r7P!QS-=3LDbeHc#_yNL+ksv(n73k`q`1%$iZQk9KMzEY4Mv>Jz>zo@hjJlPkbkSOLIh>Fx1huRXE9lJ&%(b zO8n3xVHEoHO1yOGMc0?CeEbt&#XuXB^QOd;-g$Cx-ca-Ad5&_8>vGSiu_?)B6Y|IF z_*DtL7q#bT{Ayk`=T{H!=^z~Y?o|oj1qHqrfA}G!n_!InbA(BcC9BL(kcEEs(bG(J?Nf$4)Pq2I6EBCR=d;swc$J%5I!J3GYj+jF zxZF@Lu)V{8w_ae7Z&DLI6Xg@fqliYCXA|$0kWa zbOBC0!+MbJr=lag5O7KYv+~L^@m0;MiYt$~8xcmtKJIrW1IM+ew$6{fTKvWv&$mrQ zTA99nU9{iq!KwQ0+=XAkmv0I0Mn5+BUKD@jP1S0H7WeRxIOtE7=}Hlu*D~AicmJ^; zM9rt4IEl9peWv~tv_@NHrd+(z^?pHJMcN>YP207f&k$TKk^PRshJA_BRsQ#2(L zMqFQ1zv8A))Y>$@n$|q8Vf{nttggz^$(srtQ}^AolXVIgFdTF}jOg`C8o#)TlT=#k z-9mg6;uhYGB%GLTOgwAoyyI(U$lq79cZsnwKWP#H)O|u&FFfm?pQ!;zi9F9#WE1jqlSo@v$27! z=c{K1Pe(NUX#8~>_gm_*HF)@=r9bl0bc9K-aVFcbJk0n}*g+@kv=x>;ELzHadq5)w zV7{N8CA?a6yI(JB&=~yqHxn9o94VV0n^b4M$h$QZr?kl|N^}`5@c8Sl{)pYp-dUO+ z|GIVZwdv^ct9SpXsy#baT%Q2P)vb}a(?+J?7oDx21EJ@M9pG&3@gOpQp{ED6U&@3y zP*p-L^zN8;CBIIrEYRMwh_BODdm4M@wNL4iLKCs`8IQgGV}hoyU2IkW1l@&*rX?n$ zh8Ap-(wJWwsyT`voQ+*;^H^d7cLSEJ?3hR6nvZ?M4s4l3nPx@alEuYA5I__MZKd z1*Zpe&L~))epN$z^_%WUY2g%+SX`i%ed#l~W>ie4CoA;(>Li0B^@Xm{pgi=#FV&y! zDX*pWXHk0rDoMzwD~sB$3fV?%8J^EVOv}o>dO+1#$WQT<679~3EYTct$rjb3=ljw~hWfNq;{%Ndmr9Nk41@_ffrKQwEepFH zXjH^$Ti^z>4xz`Fx*AL4*T2Xg^-8H2VaQbqJwm5WC)u?I%?~8iYV?93!;5FouH7p; z)ONXQR4^Gt{c#XiKxyiSron=n{S4WWRq9uTf=ZhkVQVtX69xC}3c0?4{AAY}3iw zZhw-@XRu9?U>R^g-X9StgjWN&qPI>$OFqYMd?H^*LVZTMotZER1LDJgxN9a0k0boD zv~kh29i3#hV5t6P>oU6KoHzr)28^Z|n`ax4s%!Yz+=c3o2PP( zMh~+J)V&8V7iNx(s>saCA~za6q7tpxBR&8NPT zdMv5nGn&d{oyl8{5-i zk3c)KsYRS_3^JQef;B!CkAb=}99?tmGX0LbM#kYx6HYd;gka+Yi4Y!BvX5hIW!kt; zWr8Ax)iEGegOVT!2RY&rte06F8(8!YSsbtlPBer$5T8X$xJVpwEZ5RMjJJX_L(->6 zgDM?2+f*o|52W(pX>&Vxy`9Bu`(m>t!&cftxnEnXHvG(@i)0F$`LF)@F5XNROoF;& ztQN-Jod$7}#ijq903ze`D6GP!P$kD$PX7okxdYY1Qjz|CP^%^R4aE` zk|>3wIG=2VQ*1zhZic0Y$Z5xZ+iND-kT$ZHRBc=m+oKc zTO{QlFFL}}^3<1Vsk5&)L^C6+NW3(hJ8{y*l-68L&YC9)M9vA|$l@cUlk`|SBH1k$ z;xiv7K*QmZV#Q5aWHB#28`?E;^RleLo;au4H}P3XmCTd9eCjg>E zh|B#F-`l5cY4m!T_w8%)X-nbS{O27V$lizH1>NH3pT)i9gx+m#y6D4%mNg+7O0+D7 zqZ<_xr1wNofMjIK!u$mYP~s9lFimf)GNw@XgBdHp*}rnh8w(X50p;e#>Hmdz2&h=m z7uV&-D!bx=k%@y7^9wEo4nV@S*S6s&HQ4La4&S$vLX3}oE-o(`3xAc@s=c~!A+ZMgs3_X9*j}_c)U34oQ;Vj|=0mYe&6~nERuO-q zlU)wBit+D9#@3>~J^T<>;8F_lJ^%xAaxOsy&9Pf8Kh4?~l1rwy@30f6zLu@CSy4@P z7{H}}$dtXc2_s3i1Z5z9CkG?FNSD}?#+Go zdHEg3e0(fqcQK)4zE|i8`|j7JdXL6`!A_iOnn-Rf@c`Z?Yrd(UTi@URzW)*WaX(}KQ=N3hIAUaI3YaHV7w-UaxbjKn;~#eFe`oGynYEh#3!k;FX-MgRWA3V5pEH@exM}a9Xl7NrFGD?id+GnJ z)qHar_f)(5Qd?qBtGUWJ2%2T?x7}PlTjTgN@Xd=B=|)f1Fr^xkap&o}02DM_hH!bY zjqv_Okwu%bsd*0Tn?}2VA<+;9RQoh(y|{IT4>YfOU+3R=1E|dvM!+ z<%g$X_nLT#LK9<}>6ijEso~;6rV{$LykB!;k;R+u@8Y3bHe!+Rt1lGlmL<|p21(IN z0Hw4GKI!Q;7ambyRRVC?QW3LMrS7iCu@mF>WxUU+i{&ooYkF_37Z8S`1jK$rmWQQ_ zDpy~qmX=}h5Q6}l_~Ua}-qnbwVaGS{Hx8k2cWU9I7YZJ$pHtH;O3dCzOiLk)9v8)Q zY*v;%NXhf6ej{!z7BQcB7F!T}Br^c_=xRzM(!fszf-iA8zPE=rnR#b$d=5(#A}le9 zw8#jpD#g}i)-+XLcL$*m-9<;ge3|_1y|(3^!9;vaL&+e2kdy^N#L@aQN-5j?_h|WZ zaK+`;1@_UY`)~Ig5_xQcKS6}A%33^^DNg&Wn0u6t5ROP#RS4_(lMwW2P++4OA$A>1 zFvb|j#t!m@Q1zKwD_1VL)Tw_Y3za@v!g@EvR;2d!o0#Dtk*n8ijDXWTu>>{|&7KINneb#E`*Z-t}*tNjp@fee`pu}TiH&>;VXk~vba6|NpHx-3} z8_VoxHkn@TGrQD&b_1!Su)+4g<`wy;MVh~nxj901ZV_Q8`F_k&&MN;rs|lvY;Wg9f z0G9`)Bte+)A?)CV#cS3v74J*(xk)x(9Hk?*UEe~5Z-*5bvg?3tz}(KkHeW@cSNhia zHV3=r^PaU@?gndG?f?10P$}JBW7+itfmltgAGp}`cAFKJ5diS1Dpd;L;dQ5j{(j*&_QKQT%7 zgG<3!7g*TE=l~DA1b*#gA8+(Vf(}LL;$y<#%1u?3ubOC=T|2Sc^l(IFfFwY#1aW^( z?0gLwzv6;5>^MSKoG|Mq*`kGKqSXhrcL#7r+-Z+^R9n+t!sBnUB=w?Gu<_W{6H+*%O&nE;6Jo*ukz#rJFpeEn)LdBcYAw7umm?w!KNGpuq}0$0f>-2Q=a? zo$Sc4FU;+d)Bc=U?mR?;PaBHBSK??-S=dP!6D6uXp`NRF`q6A^^EU~thFD>c=tj|K z`s$@wdV+d}I9zd)m>7*_FfGr%UIrF?KE^st2Xtvg#<=QBZ?MBDySF!XBT`}+GPqf00X&!~j{Cp?iyD3N z{h#KM(P#^yvmhxWyT8Kr}}+MJf2&U6=P|BhkYNzH24HZr)R=*`;hD z)=YmS9ePsu#mkDAvqD5`kU`~7NM1*_@N*!ZYyUe){GbjsBF|-Z|Dv`X(noc!0jkcd z)udK@dt&V+XQbW77NYo`>&Hyl+pjY5ZpA@tzGI+i(l4ZsqoF`OKo&W`qO|*Ft0?Ka zm&?TA>aG;5&ZdWt_FCFH!AI~qo+Q@BkN3@MaFR3fUL<4|rcNm02k=PMpZ5gU=BAv|8`iUVCgIaOT`~Y&T^PA0UqL z?&@RjZi!`2S#DDShX!ZMx&~g3Rd>Z(@SV+uMEk{}T;^Z#vCytGM})UqfF+%4T3&WR zb(h`2_@11bWNaDnOx@o3hrpk=6PChhzShG6N*F-!a5>q-`bR%DCN=h>HB6ExzLkYe z!V$feV*wC93pPRNGacM{efEl*DM)bm@mr!ZQlOVUs1U>QA?JQmHjCx!(AqYH4@OYH zI@B~bI84s7(3{}|A}6KnhkA8r@s zvB4dT2^XsshJ-&SwtikpcchoYlXIl2@A`+YBJX*E@uY88FG68LWR1C8!)z@li7~|6OhO&$P+EXLp5toR{?x2A-fIOXVJ|+Ldcl;#}Mp zy|pULb z)7L03>SQu^{sa9-2tfKEBexsg$IJEjHqGYvDRJWW8%(n)Cp1BfhC`C*FyE6%;|D}0 zb0?l4w*Ly1Z4h+!Qmoiv?D-4kti9fvM*g3NZ(wst@&fwvZC5luc!63;|Ch|&x%qg@ z!+2`}vaKfB-jRGUlI)mEW{x*p=gIDeWKV$vZ_NZ>$AtgYZvFpiHJXXn91|lV6C-mI zZ_*N@=M!TN6Nv&zB+aCF$E1YFq@>)W6x#o))f_4{FgP+DlS32OA&u-0Xvs6i>`b#o zZU816i`m9v*67KVn)>UW>=lme?{VyF%PH?MK&=4q0nc8Ro6>P;T637vbC}u?nbN75 zW(Q6i(qykOO?x40Je-u)LQ7*D>NaYoztl{hicFuJNqe4@z695*7XY4arn1JSzH!VD zEM;G(vVWwqZxS=M4>NWI?jC5~{p@)6YvkSUxpxm~cYn>_{d0Ktp8y5WqOdwqz)_UX zjvVD99KkG3m7YkrDhkw#s>f!oZ}QaO(6tz#1_KB$WD4eGifN%GqlmTmdoycHWD(Wd zfKsSJu>e^R@htu-UJ4FFK01JjIl@_p2o^d=h)I@O9^XAI;-n@5)Qiq6N73ooxGI!^ zR(5u5HtR~(n^&3BYbfWcdo0xZ)^hj5!T=}+&~DF4JID%dM4;D5-~??G=z}mX0EU6V zSF&hV&J@_O>efv` z;3wcMDv2qO%X8IdVO;@hCuhf7W7r#z+|=AOLGSu991Ft|!HIfrf@Ge1D;%=I0a8vL z2iul?9}c6ubr0Q}-B-ok=8qA~xx&hM|EG8uSpT-75oW^dPP-s*zac9U;oXBPLbBZN zpx!SBqw9~Bxqe?FO3Gp)mJz)NMXqvUI0H=UK|ufjAIA7KsCcyX7apIT95s+mT zBoR{qfIz*7cnqTO0IWuMaBl-mvJUIQVXU_98+dv45&ZC%iXVS6PoE=+L4EotLiGf+ zb%ZulAkX+QFe`_F(peExuq-Sh0gFjQM4_X?)R6bjx8G;+%v1;~L{;DMDxt2h#Kp=H z^Z9^b?6rlnB|)!XcFPbJ29wldInj{$TMkny2xMXarf@wM$mTnael3`lvR&?dB+u1M zzZ#;YA~<{ldI`-%D#=O^=8(T*cFEl6J85_s>Fep%i>V5EZg9sb>?k>hOey-_md_94 zQ=E(8Msnd`Xkfic!tvJL*&sRqdu&||k-5yN%^v|E%Z+>o29wanejw-#qF zW~Q9r8~8Ft++48c6X-(=`Z}rLJ^`AOwW0#>#Oos~|&8<*BOe|@+8Aiq- zoSflK=5^{Ud>^X{#S%QQvHC1T4HG(eDGO{%gvQ{sGe0A{aiZf#+MJJT~5FFA?a-okBgvA&ZZg0(7R+gaJ`30GkrQ#uQLWr(a_! zsEzyCtujy)qv2bMAeTm?`e-d*MB_7xW6Vz5Rylt#0kQ;&HdqEF?R1zjE$uhMwhz*m zf&_2z0|9nXJQnEh3iY8skb3^G>vV#fC)n+S@l1t=7Qre9i#8bwXtVM7zSd_1ZRQC= ze-G*(`j6+`Ys~^0aG>=VKr5fH&{~(%z7VN5R`%X6+ONh=n-J*e+*ocNkXfyqP1$b2S>$d8K+O7Ac?fO-| zftR%d1#nQ$py(meeB_K^@f%(=?-7bmiTn6el`k{`;fo(h4ygXZ%6Aoz@#1{+<`*{b zoIk?+dGcm`VA-9kSP=mq&)?s9gRn2s;Xcs-yz8ba=(|rHI{AHaG~d%F0XIh}mBZx* zQ9XZ>1PfG)bpI!F*EKe_G&b>Pj3F{UtvmkGb$l**e7XKHFLKGauIC(V(A#WHxk~X?z_Ce z*{`TYKTI|LcHJ^E=k@|pT$g&V@Nf^Yatl#*ei0A7>X z;Ji$MvJhUg(4p7gKzsIHvrswS(XT2-lDmY_F%d3w^uc1!K$q=)!F%*b3b@}6Z8>(cHezgoczkRZ2P9_ z?3}@uqOc-!|H?1X@ZvKW z#wTI!tNxp>jP@TKn)^m6zEVvRdyH>;yzFZ-_wr(qucFkff04(5+48(v)x6q>L1@A| z(RH5Gw|$u`vf-|8_FPHYMNff$nbJiaBVn>v|%#H~x0l z7<7E{Z9#}H@zPBL^i;T8^G0}UsxJ+SQ;Q(zYoq* zw$EZdY1gmmsqCELkQB5!usvutW1uPl7z2Qr5h1}1kS;0amj!gFK-rnWL=BPto?YG) zCOrs2wnCZ6t~DNdod6w9?Fwa_^uWTpz!zDvps`0^%`t!prOiGK>WBfmQP6H!h(8vh z!w*;-oMBR>4w%5=;xF8H#%>)W-{!dXQw%tF?9i&Fs~!h4prcysQKbYF{%%DW)+)`fTY>EVta2e+mjR}x1M-GyY+MVY9aqS zb7!0`X8d2w-6ERr!nS>NU%>Uud%Vf_Y8`S%PDCg=@mY6v6lxnM=L#uZzPFb7J}q5A z)44f#fwd-`$Dy=r*DK}?n|`dRAmW(bQlDg z@jAM=xBL{huml`*4Q|Unl1dKFk~^B3-~ML*BlKmgxvF#XsovkOu7UUbsJ zcHcl*wt`!E7gyPkBhjWAEPk)lFRRgpkm2_0tJ(OLf=lzYs`3hCgiI-L{n-ZuWksbl zW9@Q3pCVy_HKnh$vRpzbAt33lwl3;@7SOyrm?VEjYLAV-y#uWWEa>#JC*g7J47M`!>xd!}}ePHPh`{ zFSC{*n@4`2-gEFCsh?y#P=|kTfX>8AY#SsSNjZa(HEb8W4P@{u(nJYXYeP8BRKjNZ z{?(mkk2^;YO(t{q;FFzooYs1-%_6P;zRE?v*&6J98cCt9nZ}y>yT z>gao!t<%8y?uEZLtBM&oiFJufVtq-HDLB@R>=b-olJq^g(?D)sl9p|Dn)Q1lQceUX zf5pQD?ZB$kN5~@q*MQ8y2fnOy5WB;@5J-=1uGnVclP&8Ej87PeT4|DghBQS*( zF2kXO7atOEVWp=8H%*#!hO~JcSND}ghrijQeYDhC1Acw)JdnzuScXYwjPRGQN`@4M z^WXC7iCT9l`;$}Y+wK~*Q$H*=Q$_qqe&DHI1)?}a|6Jp9wMSrUzRr5w+3gCtBl?e` z_2AuJXKXDyA}U=Sk-PvsD{=%L(Y()K4PP*{SyOD&b;k6wYf|I4q!RH+rmw#@F9nwo zmZCByeI(cfHv!yP&=)*wZ*z{iA?=1*n_CzmO0@;U^AY?)O#~EeRFpg3I(|UBUOkT6 z9Ye09vAQ!fk@lY79F0=_%FK|_xCBL+03-Q}Qz`lgXjO(jO1Gi+Ov@%&A-V)*5A^dn zdl~@Q6cYexi9APqfA@ocj`q#8j7FD*7q|zidf#oFXES{$DVX@&wJ{3W$X9|ld8Ami z32vsd%zG=&NUAj{*?lzu!)zE^*?)+-2lkUScH;CD00|IH`~L@DZyF7CANYTNnSBh6 zZH%>1i0njmgRyU8-!;~RG?qlE#+YHO$u3JHL`X=HN@HJADN94rSX0zRtICyouJix> z9^B_X|NF^2oCn`CGw00b^LoEt3XhIwdu=R>E*3&8w<+mr%+Gw>;jZe-HhZmaaitMB zkR(mtA-E%me#OUO&X;~AHz>4)W0F-p7%&&+E^SZX!oCma_+U}-d+pOUUbf-Ch3ge|YInR>e>(n){scmqdpZqc9h~2W%I(Jz9CD&IOmI zmg`=(?U!X3IHiIPv-=Jlgjy008wCp~TQ>c*+;Im~NSL&l8VUuJ@JqQVF!|?0(Oai7 ztF)F9B&?(Cuyl=SoPY8XrGHBHFfMA+nPIz}vb}j(JIg7FTFqpc zsgDPxsRF_RqDvMs>5o4t{yg5~dh6)rTi4ttE?sC^%KO;Zd)v%p+YZ}}J2$g9zwz|3 z=hX8RU6*Z2h7qSmV81m@dU_nXzY2bINT!4;*vU!jD;3}Lp>hqme)e7yLps28MYpqBY^D>1T4(|r zQlyz6Jw&SXetZ*AW9Mgh`BSHvWinyRtHf;2Cg`m=h3-MN&inQgy;uT6ew1XS>&f#)^4-y~%JaIv?=@qq0%2+LLi)EsTG}5-L?Ir&GJh1=SIMmW z;U~D>$L}RMpaYiQ-%?J`8chdw)6aBgWKGfln=5%XkXe?24@=@>pT0yi!X0h+4FS0C zR{E6DyMhT;DG)!FiJ&>%olI}Dr@Jfme7?}9np5A^)C@^eHGU`s^E1=!%(U0$PUBcE zaC!-I;6kH?_Z~DQVu*_%67hU?dj_{R4cxaaYwT(Eb%SnLh&vV%G(C9xLcKkk*Q5+W zny?HK>2cMAxU+{Uz79CAKIw_OCY+=1(Smp!DMOYU5tyc3?9RBj4Z92nylIxDY%bQ* znT-RS@vJPW7TPng~=q+5Q2n6i1@4i6Ks5SK>A<<-27!vsfn z!oKCVfmvP)sXxte-$t*1M-s}0&V9?c$j(T7lyUahnBgN!_fbM?^Pmk1$lQbK=L`@P z)15cq9yY^Xqt|qHscsv5op1_~1@l4yVQ>m_%Ccp^sseOp_Nb{8Xsm?X(KI-2VmMZ! zH}0Ka?Y#i2PoO8Sj(xt+>{T|{+h&rOfVhvMxaONw4;uW4=TcRm&)UPrEsTVe%nMA= zY`%R~*>NJuGVj<#3t?iguBSF3v(RYl!ftv(gk^i}U`ssReRK$5!G=|A+oG+9C&LV9+4qPKMuV!A2dRq$cP3HNX5V42Jy6`o_R(KW&+u@j59pnQYTn6WmD|FraxUl zr1>oj+~70(Ao+OK{nh=>F@Q1}44$y>?A>1&m*xkwizmyc-O5|we;?kHNt?F4H{(}z z%{kYZ$nTaRXH%>F@bT*SYzzE8*wGa-WxQ1veAfQm-is3Abe8v2Nt>$wz1gVZYqbuP zEanuz_6$CaI59MMLwnc}Pb(oh7OvWp9bqo{)^3efSwy;f*-LS5r}CmB0C^pbFUs2O zO*5+c+T;-}&!!F)U0_&TBR$WG7&6y+o`t_I&QF=%d$C{Z{_-66^QI@(ng7&oqSqb( zTdcX1CXIMbPi0M_U$i;C|0T!08M^NMqSOQVdje`8HFs^0ZM8#l>7M%RM$aR86D(iW zRI#)4hC{z`U%j4*5X-q}BWKQgSL&Z@8s+!qtCM6-bkE=1whJz{B=ZA!Z(n59(^VBi z;>PQ>>DMJ(?OTLpwdiOG{2{=CyF?6e3D4n27IxUjd2K|~>B-xU6ZojP#YxBs9F$+g ze~~oNI>g3r(A;JS8fOsQR*&>csXy(-A+P?`j>_(rpbgU#SRrQJ}2HvjYI zGgXcHj?>>>F@j#V=vmaD0=vAi4cBQPO2*E~yu5KLwHqB@>O||NX_vuVO++Ekb#VcEH!JoxqA0X@~HqOl9N?aPi zy1Qt<7;ibtcbagy>WvcrJAqS05R;h=V@_%qN5nIznrz^jhA@Q#W}G)p1`vxD1aAr4 zIAFG$j;Q>~zFUvj5_TvpTNHI79cI9rj|DTgY4_rn;%BA=%!;I;PmW$flr$oy)<`e% zoAHC0t?>wz-Y$91B?Cb5wtUF`b*%Bu>CC%@vn9-h@_dL?`U+pMvg))p*WUI?+qYC> zurKDOSl&_ow+_yYs!9&=8}dU(wJrL1lL7q<}~-kOK! zHB-*IL&kICKKDNmT6uVAEvDpTjOV%+=6wbEz17{yg+`@It(7UCML#ZCxmLcXI<1h> zGhd4iRd>_Vhx>p@-vG*nNrj$yX5xE4$_B$KENwl)ayVH1Zv^dcW?Al{_fTch=Zzwh zaJuJ*lEhPs=u^iDJrt0WO*O_>yLbu#|p)$YE}K$IQ$POtIs@{CvA9c zOQgLv5}; z-~E5yvC{aS*j3z@KF+kN-_Zo|N4+jW{E)fyMe|^92cvJX)$eHZN6tX@{z2zUXEuPO zt!V^+oR*M_Q}AlO|K|_u!F;EySmxfkHMn&Ga_V6rqb%T(8=QOXITAUqR4vqV4>H)v6rbkBWKK zZ9Fi^$nKzwgGJHH<62|j4l2OQMw4!U=g%=~V@5S$;(qxrho#Gc_csn|)L!y#sDhYq zHExfnT@zx4*jRe=IUp`mr7xuqXk>PzI_6CJhNHtnK2in*Ou=XZ+J>|px7-w(xY~6q3P2>@Y9TJOKXb%@WAh*o|iOLbdx-Tm)Y^K^TH>?O4Y_x&8yrSFF zrOFbuklA;nrm9N1jz)g8nC{u!8NuD5S)d&fYKA4EnX%kNV&#`C6>4`XyW~R?-=T7S z+@pbern^L%h{6lm`a!iP<`X`kS*g>x=(AE^rij*6g2H+e`Q}K?Z9G)wlgnK7Q6`5f zH!S|zwyn&---RGxvO7V;M6y!3p1RTBNR6l6KV)x(3-50Qw4Ma1edo}`^71oPDF#$b z%yd-Ck+Fb{F?F%hPiwb=*3ozYE?hS5ZK9Ghh>7rSx;glFi5j+6aw6{m2P&!dXUiF+ zH3?T5-E5mo042*RR%5lxUwwG4sPLYLWHBMCOOhlAEq1uT4pPydzGzNH+CF-wW#IVd zC+A_*LxEd!ID(*+o=Qg1S-)MwlA?RnJ7u%pAbttmRW$7dzF8JVcRy70()Vi#&)7e4 zAinFoVvWr;dnA|%y#E)KNmH#05}1AnUR`*NSUPZL7P8M!O^;E zmOR=e=ua;#p(0YY(~pNR1!|JRyrk$! zEubBmy2ZI-h##+((lzc0Vh}O?i;HBe>ZySAq$Q;wfXR~^DV3INK&la>q(k*=GVPj( zmJcFFM?cvrUukrZPXaVyrhhd7wuH~vG`dyE^0RrV9$ht}?`h!gFQvS{>NPSD6P%n$ z;eI$?ofkm)ely3OV3`SA!qFTHS_4zNX()?dT0Uqu3Ix=(N-v z?pZRN*QlP;<{NWExNB=r`BKn6pa0$sF@V1j53`%3AVbR`^#TG$u_zK;4m*xY*BGRx z!H{N%aKho6!{4<|{=F;q1b#}LZ1$>vi_yq=gq!hPdtTDxu0F>bIyS5E*x^@iaGzi4%uM_FwFA93`E2RljxY%dm2%R zLI+aexZ@T`6shGH)67G`=ZO8>Eu(N6XpG1A9y#kCk1GFIO&V#8Rv$d@A9ptG|4n^PR! z6IZ84ZvMF57od94+F>~lUVI=-pTXZs;qwEph*;V9iIEzIQxf~jA(o$F<~A2Uua5{L zV#y&F?Xp!@5mZZZjpQ~-<>B0+TgG`E_$0{%A#USP>}8=Lhy+rS^T6=vL4>I2$McKF z^zZM|iH_qdif;P*rcAxjNWpQ38lhT&kO`h&1sZ<#ziMI{;GHVfTQ4Y9;&tO-&7$J0 zH7mn;+@T*UCEx8_{pubF|B=K%KDZrc;No!{CMi<$fe2 z`_9FEbw(^qHvc6Ql@Htv-iC<4N#I0{OFyqW?~~HRYJPfx1ag>=nUJjSFQLfzvqT3f zS;EX~7=Wt+ya@EsrvOKy2sZE8K$P-Bfi-m#r-iwuL(8BeCp+mm^ilFi{T)4qG z<2dOE-i(TMHyAW6B$z%yK#wq04z%&QqTwef5P=mjDk~@{DLsqrnuAH(+Yb%3$%hK_ zW*8SFal2;T9Hivy6k1xWEe>o>hD;5>Qu1M?ZO++cSrK~ZzDbAy7x{o^#BabNN#G`y z*H2IDt4|3aqint#GoUW2ySdwCPV?dDl$|4#ZLE`4MhZ)>R6}HE z_X>cJnmEZNDiJ(5I7A5+m!EXQCCk|yQA>8dch&jINvpBrE&VD2|lGG=nxDRZTlew9+h%c%NgG^LWcW)iM{_|rex7Tk11#hKmqkPas=sdxv>}y|wOYS##Cp{x zD^rk34lSVzj&+uA_Z+~fbc-Z(aH6DKz-=P(lR1EDhquTh&vH^gDlaI{R^yzJabwC z*kd(Z9OLEf<5f4P&m*Gw_BBxG?bzgxWnR$mFZFr(vNRD=<9D&fJr+tHih4L%D^-(m z$T}A;i$W%%mY4G2HGG@9kXDv&B_jcXLlPPYR>H_s=58_>tk!K~$F z2GOV9j5>@Ba-;Qp!y0^1`LJP5$Rizk+(;cbwjO*{^-3b#*&u&FKDsxbsHxckU-E7` zj~ud*-rR`GUE_QHAlDlPi(`2$6yK4}0FWFW_*M9E4Rj6*-qHp?HVLM2VqTK{ztr=2 zbw@Cige5;9$&*~8obTHiU-Mbtg09mbWSjUg}KM(%*k0Ihs9jRe2kc9ZZs>K6-p zc)g7^8OXDbKfP$(bU_h)ntYcdcv1XK(5+#Ick<{kc7+ctj>Z9pqXBaX0LlTo8KCu! z)|vVuc=Fqx+(#DJo#@-<>ut+8xWVTD5qf+CoI;9k7$!;ofAHbb7zp1=2PjrhEYFK@H^hJj$&J&ht9YEGV55JnW+ zxPMjyDXtW3r*pC*7S=#U4d=H6Sn~Z{^)8DdqUB+yw?mVZU7;Dbhw5*iitOf%y-8~l zvs6a+Y_|v)q65VR4QnAQKPwVu;vOi3?STV%j&#ChyBK1avjDsr&-Xg1$F{tvj}ije zr^iP#kuwH&)+HZ&(Lp32>(t*oOx{U7sD}=^z$aC6@;nAGpHxl6QHF5|Paae~Q9|(= zu?BIdVIV0*hqbv&ydZi#S@7aK73{zSD}#_#IL&*WEC>q4iz1%7j|gZ(Jl;misW^4w z{*y|!f9$b5#{0)~?=6%=z=zm&5Q~{x^ zui`0vU~LkJ*y2_7mHhgPwl^8#OVT4=X2vtX?M z8V`(&f*C&)q=^pcdJphufc(>+ym!-zXoH4NK%*z2(fQB_ij{9Z^xQrX7EgpB$3}VD zWQsS$quL}zo2yVsK zmI>~D1WHtKM8pqNR+{QEz)AQC8N)mNC&QN7uHT)ITfLBL{u7zncGQXkI=)~87dGH5 z7})?>B1SNl1~LMVI!pIbl9$|*bBFF#JW+ZP=mPU2f`#OqT~KC(RnTk)blf`tH1j+* z>ns8CqQnqcoB~-ZG^NzNm<<-9HyQ_6573;Tb$_k4IX#sp0-)@)$SO zNUQ`^8G-yr@{zhp2AeO}%iDJ#RPzQTwGHZpn-2YkH)Vp(d!~%xV8w=0(aJK=nE+Mj zx%bf%H!mQ4^TEO`U|}h6DH$a*!*F=kKW3G4JR^5lqv&V!$gCKA^C(KXD*ZS$vT645 zL;|W|vTNqrgR{@3U-+Dod=EYDGZzZLZeqr4&z`;;dH7V4FVA-9Baz9A_Ndw4?9cXW z@XO?Xl@nSoqWZ|F3J&x!?}>@Jo}UeK-rduU0cDS#q4gEe6z&;2j+}Go!o;eV$-UT> z5m*%9O_+I8b}9h|4}=+`2OJ(B*SY{(tCZPq4(9nweS6kF|M=bCf8PNz99|O+IFJLq#DQ0Hki8t#B1hma2Q9NC zWU?d@xP-a1gsonZ=w0H<%w+y9;bfK%IT>adE-Unke#N2p(SXvWWi=DgFSrA|JO_@c zt?mjS*_3RqrRwOSM~?p;+ATygrl>SR(39$HlwT>KSc+`IB`?Ua)>ieMk59c63Sbr)#axEtM@fpITM{0KF>h2SRnC=j@y9Viyb*N*56+^j+aM{E#KC3MdvDsgx7 z$)zh!vL73zMFwKfiKOA&yIZ*fT~w7((915LOz5=JC$KE!%MXaYEgD}3wLd<}Z2^u3 z!d3%6hos!9Z9kab*Ji#1`)jlHs%j10flOd`Vi|NLu7O$8|<-JCy!$b2C}XzfY?9Gp=R& z^^^bC&b4; zyWLRAfAko;7aF;}n}26_rutX;Kf9Ihb}Qcf%G-zBF#R1sfpVcS2j*^o#_tyO-=W)( zh&IG;0SUCqMuV(T=jSG4g}DAFV+h1z%hg};*xnfzqAPr>#|J95>*WxEOS}0%9A#} z1QvJwuW{&DO(-u|QZG>r=-Gm7d0bNsh+OQPtA8q{>cAWEGSe;Md5vYJjE=AN2IfDF z+wC#AF~>%a@<>6Owo<$QSL4vKB5~RNzG}#Gho-Mt1J9Oqw9fwfv!}xG!5L6*>yWdI>i0WP)~g|53D$ObaC_^~A;#f0Jm>&H!wiBL%u#)| zx9pS!wB|#K3~0AnvkfBVgL4gL;m>k`=esvBrmx_)QQlwlLW%%3(V~GGoRW7;pBHD5 zD>#N9$W=YxnThJ_?4}8+PUolP+#&_l^64cB)#h&Y;s*G&_Ac0UQ3ZV4?A4!uwH-7^ z2#WgJSO3uUnKmKROywkrAps><1e4DT??UI-59AptROfY}KL;XX_=YiPy@IzwaG##qxeL^hA~|MmO?CZsu&X!5YRlX)ajUYZ`zQ0in0t z_)mO>|~TH;&@<-?ko@9d;GLa7t? z>86|FskG8#Mw!PchP`MS#(9-RFR%yutcd90H>q5JN@nPQs_xj~eL;_$^^gX&R{*^P zSRk%tyFE;zTYI5QEV5munY05jmUVKu{x9_8bJE)JV6>51-yw=~+r;U-K!IhUuz>^C zMzKTcA$(YpcceJhKPS2V%vaYp%c4eg=s{7VU|GsW{3lV$AUYLGK5m9}%)8(np{=hT0 ziZuHx({f9#v$1x2=!LcE#qY20G^&oIDm99Q(8kjEx5&ux1IHtJ!MT8|EnVs(2k8L> z^YQ4>kK)bJb*28%4@d%4Z4)z8IkEsOfv())DQwobye|?n`LfB}BC`rR#^0(~&_e@f zx%it4_;H)c+vsci5OcmWjUWt%l<_C?O3Hf32{c`gaHwEH{>p`SD-3SLpfUBt3xg|x zPHu&NNtrr+Hg7t+(@g7jhm@9TmpwkZU4NjsWE%2F0MjXaP-PBwbVd1uplDaI>e$P? zb8>~Tmjnxqm#LU9lHA!|Y!1NeQ*X9)JfCPTVWrz)m6$AdIH-2i(oU!#dn*r9uzhoC zA^j-fSKV$3*4ij9T6shkuIB1v=Xw7X-g==xlM<8xg5t5@Q_o%8<3~TS!gY!k)}qvY zv0iIfBCUYg(?!3mnv5WM-OO6$jI(y`CHB~kePaEwdk>zC>&0C0+o3;VvtT~p5VDr0 zoZ^EG%a?GssL!1U4Ud5;#d%AFO+@&SzR`)4OFJ1aR~5?KZ;c1Cd9f8NGwGZlJ_>ZY z=74~8#GB| zC`2&3+bp$!`w$%|kpHpUr-*cef{}lz*gM^zE>s7fKkEvnH-D%&E^WAZRl%gY?xVO+)DqgGP{B4{SniZq;t})-we0ERwWEx) zYlbH_paYM-INIoPonLS6n+g0&9*Ma#nQ1@Dd;5>&HgS%a;f7t&%b%*1`2&B}C!f(T zsw<%8et&6#9ene=|8too0Os#dis=Nl96c&eh<34u=BAOSg;mNcFrBx_yVl1SQu$>` zHNq81L#Zc?LSqtdJW^fRmMPpvJ&@C#8*@(d*QlHjI@95Rz2gl!IL>G4m$Wm)chE#bYTixg&UC1>l=A;{?}8o z+HBd{_JP<+AL+!l)PvnHe}Y#}v7Oq{jH{KahVSR5k{7i#a?CP8LIW7J4_e2bsD#)n zM@+=;ju)(TlH?^ZA;fH{fQ5~GSY-nWZ8*+TBc2!7RbfSe5_Wo!`rOsA?dGq=C^+X+~ zSi2lN2jH_L4VZS4>H7dD^+3u7?!nIE?a=x+OItBrd({dXsfu&UuP$j0h=rcmQQHw6 z0n!C~cCv8MRH34cnFO8QFNHddVHK@kpQim;(hf*sk7zP7)Ps!luYZyMF5^G!bBW1S z_z71l_8j5jn9{4M2hF%SmR@{Mjn~D{m{bi1t(32;DcWq1cw<{s&Qu>{0Gs3u>UKIE zznU;NY4)UT#&}udF1t^_Xm7dvRe~0A;yL3##ws_`irSq7VG=g|f zeA$4q?$x7a-TNEgpX|TFpXO2H4bKnY8D$6l+nq~6+lyL7`!jE(6 z3_O?=lsfvo>%eoE(P)qWS>uV+78$1EpL*admq7W4bnf@-rO)3-E=qGKe}IV^0iJF_ z&S8P2!|7&x6eB%7J0`?am<8SA-`}Nb<3K_+cpV~WDj0;KnJ%p0e}82?8UXzQ^%=3t za?S8$$tODxK|&KC!|gQnd|o^DW4zu2_db(PA=Mu@3uznWbMbf%zMlH~um>9a*#!dK z>yxX?!DpH@yU-knU`rb?_-L!yX3`IjD!-v{RZszasd4^M6^T~9PugyjxgX0>#D|{4UHkl3t!_vd?@Dw4eZ4Aj!mwDdMxOapx*s z*ih5vo5iY|35_Y@hytP#4E>HVR#xav`05-XgnM#rHvhOg{Ei>bJK>G*|3U7wzOUF2Mapt zJjABc%6F8Y9NKGW3wI%31&`yrDk0=wgFf)|&zm*}>~Qo5C?SHdS}T%!l;QXYqVct( zOzvri|Mlq6v5;xoifP*r6}Y<%n3*%2?Qi4G-A?a<>F`lt(z>-}wB{Q`7nhb*Cv2I- za3xyPj5NDymE?{+9idGG?__XEvP-KY!77Z4We#Vh=t(s;WEX3Tt&t2HNQ8rp0TtxS zEJ~8K8h2+rZK-1KmH2=MG1(Ju2A_q@!BTAO#}{CiI&Jq;$|jzvFqYGX0m`7)u5G&a zQ~HKD83A1vq;Z3K9^^r4*+k`*qYMEaz1J+k*S{e0Vn<5Yo;|X-2mSgD#x8n%lJMMz zL7y^Xd`D5dwl%^WM=QhL?w~NekywrV#&6n`?D(IUMie*9oKN7vtL%Z6C|GvuY9Fl zq%kO4Pkn(`A8C)fjH)6Rgi2FhX$nU~ZEdbq~S@&q%!#x0X=|47A2*~rB0(=*wC zDQb7RQ zYY#X;WIxWt+7KqK9KT%)t$MxRQOA{}mG;j;&gEXu(m`}N41tR(Az;N7fr)X z6Cg7j)En*_fTtUDgM-=h5C9T~NIyXy*=$+JiI}5nxLgE7dX1mc5{8HQ0Xy8RCy}9q zqPb3b(emH!(*U|N8vN!oqtI>er_q~fQG%o*Tu%dfSP`y-lk>*XrAE19N@{3Q8g(*N z-vMs!8kprh$Fnxe{RvpNWoGRK3`;}m3?FE~DOy;N8O58>4W{XtOzxG?af@6lAT4R( zj^*=h>A^6rc#fT}jpJpgrU#RX19p|Yywi>GsQ@cgwJ{w)gPau8i}`tZhv65D7w415 zY2Z>?y~#Tet=0$2c=oFK5!{R^oj&@GD{q6zbpxZ+_)|PCXu4n<=;<4J*eF#JP7&`; z3)A4ePA17t1|c3SF(}@>Dhy*hWB>8HuABhjRx5gn3H>eA_c54ImPhTL|Cj&Ge){OE z%_xR;wYPsxFwZnEErKVok&4~s5gG-V_tQi4(tuIg;nuV;EH7v}bN*j-i9^_`$ zij68mWwH5bZYVwf1#Q(QDh1+?rK_@qKk`wWNHx!M#KzZrx(0mdY_oKYwSPqBt;4%@ znQ5w%JkM0Q3}LFyK7()$vVr9@rfSB;iuSlzdK~hQ2KlD zoyR+2E06d&-enKQ4+lo3{PZ1%HERA`hIf59#^~K)9=r`y2}>1cQ6nM>y|Ag`XkIxu z#h7c>W2O2k!V`_sq;x~9txnRqdsV{O@h{;o2@LIUhWoYQe^sA%Wkgs?szvniH2`gC zMv8D35{Li<&~HPCXqpk8=CHvzo<#2oyEC84p-nbt-)H!AZZIa_W!TIz?w?93I>qC@ zPTj@?H9{`;-rX!1@KYS1Ym^!uR_EXRkd<#GqK#0i@y=}g*nlxQx5|E~>~>`vm*xHiHYL4ff8@g1KAKm|ER01(IQ2udw~qE>ZoSzsmDJypE%8P1(|-M z5i9|L$Lp2@o?AvJI3W8A41xb2mTeAD;GO)xvuui!d3gN)CP{%AlPoFQj=HfzMYksZ z@(w5I5{-~?Iqr4ty>h+(VcF7?ziO;sJFQ)Z64i- z0CMO39$!AJEG2<^QRR4=-@Js&vb}#Hx07(IFg)XcWK=hz?!Nf9lSb$E(09Wf=RIC? z^=Qvk^;ks1(|hco8=wq{nEUrWf8MmlRo@B)d+?XP5(l!R)FOOYF z{60JX*r{s#WMPBbWJ^_7vhc;<&)I z`Jmn9EBMczQxXm>OVHd)aMwc`BWUe$`RA-+|9lly-AMr+4h}5jmC`;eox+AA6-SIP zuRYyw-cpERj}~xItO*_k9Cg$jrPkEwLc{U>I5l-mc?nHH+eMgJNhadE#}t}W4$J%N zYOWn(7J2>_4fRd<04=*zDKw#&2;QLpHr@2nxRSi00X&y0OA|2n-*2~+ATyH26lzCb zVFO#1=;2K)=)*#7Kk&}b%@jb0fl-yivF;wmx;fIn|5Dr{7_3s(L<0sht#PGEymlJl zKYZUs&IUGr?h&6$x8zlvU=B(UZf;ZVzR<$ipT=}-UKQX8-L&|ReuLadAuh|5PhER+ z=Ly=nMNnrlCDjb9q|rBgj*2rM6En}*rfBZjDeYJp)@^+}aHgPL30Io1Y+Gwo-7`I= z_dW%!^SrxetzG+zpbZY0<~kyp_r>7)bABF`d;u#?ej3^#x+YzUE1qjUa^EH`SI4OO zxYAVU^(|{5OPh9x#Id8w9O<*$u@0wuhdp#H^jAM+2Q@HF<`@09vtX*m+!})b9gLcdM zv#B_J4QfqWiJUy-(1AEThz8lLFVK6NDz;F~j~4`j9`(a@;pT#&Lr{rSd;f+Fh{pMy zY)sE2m1l#FS7Y$;&TE*OmPz&7)XAAl$fBPxaccW2ii5~Qb?HZhr>8o=$dGT#*a|qW zz$FqmtysfB^D9l6vcrc7-lhgr)}YSV46hLt!jS%He~aW8cy80P2?$ZoQX~v%26=!5 zi!^vie8HVOFwli5G2N0naxN94+{xq|A{q>j6+%;L_AgLJ^uq=BjZp&#&fL z)&<-*GDC?kAHw==_z9LVA;-FT4*YrOg7h1;R9EYu^Xx+8&V49fM~A|!*u0W>!V$aB zF9PvNmSXRBEwOpAIoX>8r4V+umyK-L<*%6Tm^!3y;!a72BS z5y)OHWY#eiLAYmD%T#Oyx?iMuW4~UX)Go{_854Wt+A84ExJ>t8Yitk)Y8!ILfEcgh(velrv zfMA+tsD#W#ihP>42DU-5fBMzDYTjF<$lKLmx8u!EAD;JA&?Eb5oIN+j`oben>%Ds9 z{Wb3@o%^^alqeu4HN$KF6M*o=%8mR!o)x1Oe=FW{>tx2mf`hBiR5Cg&WEK>d|2!(B zKUq_mOVP+O#(=THBEu3zVze8*EfGvy)gk9`pMb=Y?hRFhL>-PMMReh-6TJqyST>I= zIbNzCWg*dvgE)V1PgkzQ32#~71I-}AtMZ+WzkXHFz2N7G_37ode?@o@{E(J{2^h=+ zoHooKQ#V*`kxkJa3ZyU>di?1^8O zY*4BPebNIwy=0<;K5Pd6eEq=Pa(d5G=PjaDILEi9KI*}mo1vlX(;@DDRs-qTTH`q; zlrPB@P+9++>-*dEwBFV~I4Hp!Zh#IdO)u9de`zi;LVll9@q6pMBu$ITj~AjYLFJ{g z+@iq*X-YT8qze=5=)}-CZrsyX{*C82Rz0vo2D50V)W_`ArCJ2~!@iarbsY7FlwIR6@Z zlaC$YIxM5}d7%`*_gov~peq_==aBJ~=6n%QeEE-O@V(U4fix-Fx?c9~QrsGd_W7JM zUMr%HKY+x#3!ZE_d0QUB8-d3y|>~b4 zS5BhteoyKn(;wpz@i^G+vh$B|a64TL(FPI0#TH1Eeo_EYlmXg7-XZ7wfZ-B>;I^II z_E?DTw&dVU=KOAI(ImpgoBE>NgF5N<9((1SXioQJE(dPhfI~fLv!1<|{blz`KA8LH z@sv{AKT`;hVu*r5J}{R*ACd+WOy~`QapRx^p=n&f5*N)#B*Ms?d|a}HmL4)>jiR8B z47uSV`=B7Klbg3nR}n7^1L1^%LbQ?#_4dmPxh$K}T%pOYLcDkp*Mvs!DY8l~vMDdJ zq@c)lxD;UW~Jwlfz&Y_dI3yE$Q9%AXm zjKwlIKoDd- zf=iyl5>8k~a_TC=3PG&}AXjGTpCmfe20f*hi-<)PX^C*}gk3pMCfR0qpH%sI)nl^Q zOp|~@%px2{Dqk-j)2D!ZJD{~>_%SACEuP}$>$TgbF)p)ABlduLL?3--i;nNZP-yQTMB$Oln&0L+Q?S|U# zlwu)Ckf+r6-Qz}!)@`H-lH0g7xP#|28n>1}$~6~&Zi)kz zOlPILpqgSWlSxPe^X$l^+|}dNB#E0VO6Y?K#S}84C?86|f-7J)N{6p|6ob7-4`;q{>?YcyrL)StYND}E#k`aW|NUEH`{iMFwEg9q!3QWtkarg>A&MU+Mv-AzPE3HZiaxY z@}UEA#CJ4TR2M??+LaJFRKV|qCNhjm23g{+PiEB{wk7*f!h{K^P6{-h7}b8XIktpS zyA81-N_qS~TGx{t-$u^AZ_`aq^6gfz;3?ehjO)+8HON6SIXQOQE#BkadXpz^r1SA+ z!XhTEJ7#XX_t$<6;XB7AZ^pfE2Kn1Ck%h@|*ujRDvZG2zockEbyXP?U@LF9Kxbc+T zAQ=&{eHm^qpE@4O;vlR@^^-@h>*ApW`#r6fJe7)Ky=#9t=+Oh3SX@RF8o+|4GTnPZ z&30k6%FPOxI^-+uL#OXSTq%(4GW-6I*>^pZ@@}GEga%Jfx5xWb4&owX&pJD9c6Q&) z{#tk|AQDwP?;f&hU%Y(!K#-a8U@i2R#rk)17W3Yz3kPeH(Z>h`=%9mB`n|N~yP14~ z@=y}rtW9301330b>O(1|26PY|twBR)^T`z>1#2I4Z`gL1UQj)qh`#<%He~4kVeHN0 zp$`0i-`RJ3>^o!MN`pv9LkQWkWgSBHhOCjso-IRJvSjR%7)!Ee->XTIq#A3Y1*xRP zo$v3Q$36F)d+vRlf9J1x%*E2?q3H&JMoro;Tfn zzq|W|dj_?8hMjvxV|vDmdnUVkrr-2D{oTV5?w!%@optV=i|J)4Nf)|%7vJ>0``ybt z6z*Hr?pt;4J0fVm+t#^`y{46C!=`uEOx6-9@p$V^NYLC}X$|1z9SWu{^xQ87%3}r>3dx+DrUV@z=)+)bih=s^AxI9nTG+Jc++z(LZJksg)1aI^VsO|6coHd&n>8w7-DPw+ z;0PU)0YDav6(Y2}4T8g8z*EM@jl=?92y*BMm;Xf$)zVBjYfghr**R&Q^8& zpf)@*V4HT^Wg?Izqh>YAhY@7LME;)%n#g2@&SaU{v0x&?ln&3;nK*V(!OFtL61p=R zMD-1<&v*fCBqZQJ!M;GNb$M8FWHN{_J?t{wYc@$Uo9;H782dx(#UWjpmwN-JhXN;R zqNb21rlxYv&zk|AI+I4}a97Wqan?NABJD}$bPxspG<9M<_DN0Elh@A!p*z_3xXEA! z!ZslOW6AWB#b+;Lp8^Zdp1Mr@V%_3F$S;4MQt(r|Jx@-`O#Nt>`j|QKHVqz#N3v-# zg6NE?9t8OF^hoSPfyhij4-ITS{cC!PBYlG37~wC4g!MkJKE$COH4Jfl7F_%^k`?ys z=@Fz?KMYJ!qA;fRY@XcuL_6E75=4$*Pe+X+M$n$04CmMS_ zBIx!@+iR1~Ox45@n(f;uThYnwk{4NvW^Z)>-BT$6{ZHMgS+NA{`OgU8_(UizqVP}B zrASOXjZyy%6VE{W@<$3?n`m)(!hVnx49o|CkfEVLk(7z-pq!cW`u>q{@HQrzfrw^I zgp!ea6^uyy1ntkYqyhXNwvY-H!JZNE_KY* z7$VvVOJgEw)Urkz?UXtu8Z;9?I7Oo*&=`ouLq?es4=9L$3GYX&2AMH`iM!%a51GPu z`*Y6gV1n?d>l>IT=0qOuP0IseUiDYd@~Pl{cL$m_yB4OA%=~`#-Gdm++EHW^C8>#o zq*0KUBI9Yfh>N)`0s~Ai8RL2lQ$Wgz#=mc*ziwgV)Utj=S(Js7%x)wgJ__g!O)n)- z5Gh9;{h9GWt`q*G7a2Y8uQz+E-fqKTUpSD}$NosOw78)l|Mw2FqU@MxCdStk9S*|8 zkfiyeFjpu`>be3ZYnmJwWHA*Jd>j)@z+kRo_=}b+@yLuFuG@r|@NMaEG6vAXM3OPE z05c8AxuZ@m=Krh^l?Bh`wOu@{noz#=@^&mHVHW=wkjXQ4;7XOPy%p%EgyD%M+n* z<0!~L($$o|G){=(*;j~5fuH&1-!=5fhgwy9M`DWmk=yKw33%k37^r}TcvOpM{xNaE z{Lyruu*SN{i+Qwff6%K_jOpp;4S_HD-@k0onfAAu4xq0Tmh9}CAG3GeHMz!maAGSQ z?(ug=+WcjZ`7xEl>>X6uCv2Ip#ls>Smph{*?4zTvUx@4}9Nlw2HT}zFT8XXvi`f&A ztfwMDdpOJo8wPy!&qvPsX&G0B`Lk(_>)#sV0~p_Rv(FBI$;)Fmw;hjtmOV8i`F3Vd zqPw8 zrbGLm&i~z43z{h}*^c87x;txPAqg}wGmhGxN&Px8+ORi^o4fb;p!V58qvbT2fv~&J zkoYc}7M%KGNZG5o|& zND*Ysqxq>gHi3>K|9|Gubd%G=o`{ql4_Vp_x7+H!4{nQiEA(T_vBi7B>0x*tU!%KL z{A&z#?!&9P@Xzl?iXFbX^Z%rxF`)Pv@o48R)RA7@kvbkl17bizgbmNDNmR$Ju z-;|_J&KH^wrkj@;{p|=j=2=W`Y!`9*5xDU1FzEg0lSgF#cfFz)PZ=Mf@;PWKoqk&C z@+)-xN$Ky;qNS1c&TVn%E0rnbAx-LK*OB6GfA-fdM4mf)xt)HL)HK87v{w&!GPU~o z{aBg%b(^9OFAm*t{LVMfAU4y?k8tG`j8xERq<9ixaEEWk|3ng?Ki$&YwPLEm4i}Qo zyGt#$)aSM|P%(T;fMuL;o-y6J&wr_^c~r>n-pz;FZMQOO+R0q!3?)*fTa2rP0=CAA z1%6jg~LJZxrCZ&>HyRmX5AycidFnsR#jMbSe^;u&n%1I_wYM!(O%5$_f z@4bk({M-S}27RH-y#`5+C}e}SecRb}yGW99dLWZMt`LQZ32ysmh9_JXY)*RLj^DRk zt%5gG8A?HIKzBL4YvzRf>2P7XL+iu zR@3D#0~4-yRWt;ZW1-Zw8V9p`uMVG@m8lx|Y(cJESJ*QYk|)IU4dqEz`A z4xyt$8-2fV{ci*G(INPe@9g!0CDWoKJTp?4dcU{rETLCMBlXvKh|qB#+U47w6N{y8 ze4_H^8j-zGD>5mkKpj`owRYxHb7N{9+EJjWvITZh)GglAeKB9N7BBsZ|8eI}jqQB( zo7zPvIfnKlUg(ot)z783n_s_jp{kl#`at@i($#m>09P z6`t}4c244)n)v#n?&t>&V%=QU__5YpK1R)GJ%Wryy_YxPn}b@1zz}~I-Sn7PXhu<* z0;tKWM&;jf5r`on`ucE#Y2}t<>Jg!K{TR$ZjAU)%c;Ly?R5x-op?tjLwxpU}gY4Iv z6&PKK$>N`ZZ*gP-^&)N9@T880M7uLUm=X4ynx(g`p~j z7=z|a9#jIci8#WSLdQC_^|LcjL;;cqj`4OCdFSJrfp?dl0*oZ+WDGvm&P)`+d+BGg=#K6Fx zP*gpxN+5y)wfee;ePvZqQ0)s9OTUVBpI0(Hp`aYME91PrDc1>=7?R8N$aIx{m9saD5ibn9}{51Pe@Vk-+0vd0nTA{YlQ2qY99Zh_xb4O+U~nFwEX9zxzQiH-KF5L z{~6WAL7xAAqdMc}ivOCO5Q)0kq*&k{8xIe~5~LHo%kyd3h*<=B zPF6gXhRl8jigQEXmNow{^WRKHygr2ZCc}`z7(gQ!5h}> z#O7P)^F{q`mYfR=&egM&;|mbuRz8~Y`(DehVSBbOzphLbvSug#Sk(<^$5zd6a}v*j z)E8*hYndkkLFJWoHm&{z5C3B_dKIYn;}S(uJ8X5^1KR9A)zzA^HZ;b5G{Ck}%F?2@ z>-!e>(W$&Qtr>uXRv2)2LRU1#OoH71Zh|}FrsBr^CsSpX@4LMH5}1=~Lq-{#655}L zB0~3m**Ra6|4co@6}r82!72jOG98%C7KTp{@Tn`epLJYG6^RZ@LW=mYN z{J{b?>|oQS6fa`)C8P@DUiJA5?e;#~thW)g0 z^N3LBJlIJrVmu+sX~u*#JK^OcZLS_?y=;^tfuL3K*vzx`6EvvhS%HupM_GfDsMSO+ z=c=VqkqAOTs@zjb=gQ6KFCRB5sZWij`N;Dssfot9)=2rvhUP>z_r(hmRs2hM2D=dp zn+cN}F8QjGj1Es&#a7Mv-_MvKuOLvqR)b@r5%Wufc1ez z(RNxVUr?6n{m<<`Oe(W@a3s=jTX9DPMqWIZa~M}XStIud4Idch^Y5@uJ^v&e@;>m7 z5BBS0P=Jw#@aZbXAg@2wIEBwlz~c-?ZJuEmANO2{uCFUy4i^fV1}`+l9l7`*ti>&G zcOuvtZjKK)e(9{J?;k5Y2xRsM5vvhc9tir&qJ8Wqs}A7#5vxl`@o=5UqmOwGKJC3Q zy>P~aKX7)5bj2Z))C%IZP%=h{{o*OhJRFrNT>M){hyK>J+bBiB5#z zg<8rdzPZg+joE8_<(oocE5&0fVGlp^AMg0~r*XaKr^VD)=23FGT*hTox{3zRgjJN4;ju%? zPKF!L4h4auAfZG(K&v^jgFNzAYfwg$?vZ@-HiV!tJ|bLXhOQAZW=|(4AFI-1Z#>|Y zzk$L@*>7iAW=j3R$Y*E`e@P1MkmT#Hgz^uP6Tx`W(r7#U%U{5&9bX~5G(K$fZ&}j# zcBS;s*$k~oi6c?ATzu<$_xMK%xu&tj332_fqttjd-{Z5QZW5W2eIW^u=v66+lV^@u z?B*-id$6)Xx4EC{nK&`4*cu7_%A31E1g;{Q?p(=vAThx>bDc{~)!fC2`^?AR$@Hs! z3M9Uz>qF9{<9US!^gAikbftwh<>!;`z)qfdPmPY{j||QbwQS#Q4$W$-L*hjQS8x?N zVbtQIil508-vFf+en);PTFchC12mdy;DwA09zZd@5^&Yg#Lyx$3>@sl*+w`X1735e z1(>jtLKFVFd(}4~2)qwZetHX-&6%ighKg{s$5wGYGet8bkO@;)}@j00cf zF5w-|S!4~O%1aP^KYozom}jIwrq!K!pDE4Ip-LfU=U!AKd0oNUz5Vf{dmW6Bzp+;& z^{~9d)bTD`A@OvGSaWqbOhA0FB^hru!CN^F=5VmHI`dpV=kl6-6f(2aEi<9V@xdA4 z83tT-o*!u(H6kvfZhy|&`3x0^&UF}n;o2XbQz1m3@zPm+eF9`c zrN{94tNwry*-iT61G4oHqK=Q)_ODEeLUPQ%jK1iWw`lQk(Q}hZdpe@sub0^^L@Efr zZ|=&72P{HxrYH}Z|3hb%$Ym`g!DhmD{T$eJX=oP{aL6`(vHZ5T$k2ptfmAeph$DR) zwwwMN{qu>^EI8?-na8A)fSYYnBIo{*Op?n0(s2VK z1SHGSxTyMk`sIA#vnVQE5-iWsUtxfgS-)Fj&`ie;})hpWCO=LbH_7 zo3?vBPQ*bn84uT}i^qY+BS#*>VIA=1WVkWGQC3RuE*R-fRjCCULbfbDErV(_iar;=j1aO-aU_*l^Z9oH< zxGB~u#5N{@tZ#TICHSrqVM>E38yk8@rHNZBypu%+vt%IsESc76Faut$4#15muGI5F zFW?n5kt}&as)uSk9j)09;=qH1XzFUzD`R-9Jum3?827D$xMD(rI|(LwBW==`vwa&& zBS+mh>%!*auFu2}Hv+ZfWBN(BK?WieNP0aVD}M#o!GLI7gyQfZ91-zs55r23oQ=XM z$pigB_G%P*sxX^d0yj#~8MJc?W{`Ag7q7_!<{z#;W?o80CW#?&x+@q3D>YsUOrsTA zOhFm}umn7|1J4VlVL~*4dQdKSTjwAu7vMZ1;VEq^jT|tLDM+%TwTf^&g2!1Q|AXql zR!EC0folCAGy!Tu1u4+oOo1FJGTKZMaPN-{pdzdk06!w)Y<#Z$J%B<$YP5?&^t8qk zki{S3AkFAnX4+kru?2+jzn4!sgPR~C)cT<|1f(M!(Vq)bKM%W2Mu&eu>!YrLiOKN_ zN$w$eDSkiz<6NT(5J7<(F`_C7$=Cftja6fgJ6zEhDBLr^)o+WNSs_`__1+B_8V?Q! zQ0QOWN2Rch4uyB33+V~~>z-O~<(%;Bv?ULi*J z47P=YgzTPFbtG#u@Mqw;WJjbE15pWpu4!VV1&f;%P_lRAH7uHhUV`v*@I~eD)CHinV{C#{uv-*)Eop5Zn(t2JCnA?0r<5?%Y@NuVDwL&h@hm0!E9Qxnc@2Inx3nONbR%cS~Nt0{gG z$O)PQ0rx{S2v9W&RD)#-rK8w6;Y6jjYM{;g9Hts5?C|IG=xVqA-Cp1!Z!s@^79SrP$1X`{#1n$-bO5T*|T zCkyKEW=u@FZQ;r}MF|K-mOm!{UWqvJTy-qaZ8{~7$n7?7nhEUziYhwVa}N77jZo~o!3cY0mb z45wu?v=x1-o{W*|Ol6#BTyBJ+n*ewwU77@F?JikKI@ulvS>1(Tq+^zVep?N2@))`0D79_u1AAQ*N_vle45&tCGRwiK!ugpR0UXms@5ZH#kR ztGz35v-k}mnU4k*YGn8c7-Wb3U3|!Of&Y+oo_H13de$NWXX&o^cGuQGX9<{Kgc0Q@ z%U7v`YzhZk)<>#iZVva4CB0i-&|AIo5?Vf6`NRy6Of zX!Wf;8sN}zTltI!{sJJqe=A4WIX>ZmPYm|YL=GtD>K=i^FnCo`Y}Gt?&A?)HkG$sm zZq1f`*+p#K?cbUtJI6K=@Cjb`ja&D6w;ud&o&2S5&5C`Z`F)6PFS{F8^i$w;_@l_1 zxljX6fkwbXs88`4(0mvPJo^y)UJ=Ot`vDQy09V13GSMvSTA^4zm=p)!iMtI#NeOI9 zZ6s0S@~$5M(GHxDy6)`SyKw8FZxgkiDtw+g!0qmL)w-38L?GfHFnRAzH|}lbIl$sW znAu_=qjXFDW3iQ1Q2m3ks!za5Rf~Jzxohm7C*RT9j{|T10VjAi-mx1aRhURH#u?x9 z+AXD5jPtXgosZEMo9X$i2Md#vpW%84qS>pD@0c)lCMv{dlz`bgkqvwL0&#u&Ejwpm zKf+$)T(J7r-+jK^N%?o_`F!q8`FD3Jndo3TJiNc0H+v`l?nmkDkAl~C<;!*zAMYMH zy<15}XI1Ct9X{RlQ{Y95?=WA^lS>zi8Q*jdzv;R+1yf6lN%6&2yT)aErjPf`IQA?K zzg3d%iogG6^7UIO<6G{{Z}RI7Dqh&z@AmEj-;-_kWZ&=lT>s(wY)|?$X8t4ccHged z^^c-8-%aNX$wBd^*Y{YtHc%n*cHEw?_at4|FuSrpZcYCdcUOX$GNioQY#IA^gj97eks1?=HdRF*UwzbUo-~##3O`<<@Y;% zyONLddBu0*oATuz{}L?wIBEW?5|47mBct4ZD2o5AEjy@xeBcuHQ@U*5x(Oag#x&D+ zewhBYJ-wT9c-5YU?6vGcsqZF{M{G!|EMC z^>z>3MvCmV?Ejb93H#4Z?Llw*l7(L#RqhJsxcX-UT_Ie|bF5eE<;T2w2Wi(|fg78I zx&hI%y;^4Tc1MQNxw~xhPSz=oHmY(PeVinWCEa~pchWFG&1AfZ)jccaseh4geYo~+ zwAA_kHW_Iy-h*YlX+dM2@u?Ol2Vdp=YbQ5I(;2dG3$q2$gwEOgSrzQEd|L04ya$_q zQDa@%sZG=z9N!>K@^^>hR9w zlW<@iVuCu=Pt1Yye2X_N~#y+6Bk%~ zCGFvl+)b>^@sGd1(#L}RKUNpWhgP4q?6_!FMf3HTX0I1mX*i_+qj+V?%EnKhzb9n* zyyd@}jFcW)3DnP#E6ZzdSENN0+r;R4B3D{?!Js($5} z{)y-KtnsndDzDWWRh%X<3Ivm4ee!v~+UjgyzF-MW!A?FzSYATOXdo;to>ja95;LY zjRC{TOVLh~HCNcyJ643GzVBa5*by}Zj(##my$e;>aFo4S8LPRjD45^rQ+!=bR^ZIx zCq9Wiol#A%^3*Sd8Vg4E&S3SFRh@hb&ZPYExyL<;)PF_jY&Xo+r7On+kUJ~2FMLG& zYjq*Xos}~(0vnyY*-qpqueIdUw5g!csRRwV(yi0bx`4n{IHNrdpR2AEJO zhgX+QlR#3S?^ux7_%>!%fuT97LP9`qoM!i|KD@FipQ^h^hw54BD_-9sVPvF{jej0Q zqi6V%+xS3Enhdt!y2)hQjx&p~bdfdcSz%*e{h=Mk4eYLSP1UNx@ztexc^yxllV>xe z>&}R7FjKTQtzbHUN}3I-~dM)b4c{_31icI@4%Oe7X_6%N8NiM=*7Ar z*}WXtQAz?w9L-ctw$sEOV{z-jZAs-MYnT*_h}xu$aKPe`x~l^mrQ2Lbl0QB?)*D)= zu*YM^kjDnf2Z}i3A!wmjY8T@?Ch?HRb?jGuJih!8S1mEb64;Pm77GNRfCJtt+e7W(xc4s z0_zfe!1gsvIdg{*5$9thmxk4z$W1+IoLM>8u%wa{g3+}a;iyNgo1C}@uP<4`UYdtk zJfpBG(h_WbM5rZiSQ==5sX{f#n+3Ns%=hEDcvWO=D&=+Rr7P;~Uf)!#TTXxD$gSiy zl1|uAcxftD<tpN5>^R~2y@&>v`LZ}I>(z{OdRyTdm}7C-151h9=u@bGrW1m>+P=J!bEvQZ|y# zTbE0zrxy(P4W!0|ANF|3maT=6o+pOh(|4>l7L>WvOt+&fdMRH*-_7euu~U$_*hnbs z1#59$ld0b`jQjdS|w8Q1+AT`|gv3 zr$(gLo9~y&Ji!wkobZnY_LTpvV{d+u;E9y|R%K}Z;ER3H3vk^CYxouC30&kaxyG9H zw8n^KFU-9>FsxR1nBh*TNTSh`q4Du=w6wFi(sT{8rxI>}L}IibrL?!%2Ijeb^2Dn3 z51_WGnV#>n!)>j9I4VyD4yR}>d}z0+a3JP6Z9}@X@kU3Ja&Xpdcy6$KihMoS4SYj3 zM*z#e_bq_$@Kzi0E%NaU&=8t&?Aj92nI)-8r)HY*B=*^HLhTYlHv2!vD@LOXS~;Jm z86*iW$yv^O-?!qmRB6Y82}VcLt<(8>ziJtWm-4XUy7Y4$7kRIome(3ok6}KVv8kVpPbp;USJu%>tLItac07Ckubaw7 zy+Kna_uK=fx_ExuRz<91S()hF%V>choWHNCw$oVf5V5pO?CcPErDhB48-=g$zBzgG&}1E66C6fkLz8C4z4SQb7`+K+%KQrh%?FCWV>$+*`|c zQIyWoNFdOSP9FM zR6cH1WlYG`Whs$Oa#wak->5`Zt~6rVqfnImDcU>WR*K?gU6ILoHWk0NehT01`6Wb= z+3=xL5=T#-v7(-7+tLPK;Is$QF*JNqE++1s|EK10f0-=x4zheQCwW@}c{_T(#(@3d z0>cn=UU16@q{}!tMk>Z^;hQ;SSyj$Yb6#0Wv4JfnVu4}tM!`{SJ8*5D32K5#sQP>Zhoy*+v4 zkr}7@*tVVtzCB)(WmS--_Ct^EGu_kXMYPEv!)+~Py6ESVD~ZY{KJUGNdR#OIO<9Gy zi$&1&5PW!MNh_P-KZh)JFUzC#!T|#1hD~yjo9P-C3$6hgVXs_I%tn1Ux-s7tcqo7p z3!POm

    0L>I46Bf{Q6TkfV#{EOJ z>t$R=x(`>t7xL=$QLX}*NF>W__I&N1^7QuOs>gHsACYw3z3s8XMTLaLu`!YFZq^3N zbh&q~$H4s~M38))Gz+(xS#kbK@a}U%J&XSW#e=zbb$?yhPG~BJ%Qqly==AHcxmvj% z{^9TT5~NG51Qh>b)aw4U0}=_D9)VZ_l}7MtUQv zFXOEp983A)Z!}1BNrVPC;%gyP1LVO@wjZtv-|CqG+Jo>{aVLqJrKZfHJ(8SVUI8Dd zNj#D}vF8HIej_F(EPlZFXDX9k?vqkAT)rZuXC%9GnfFb_tTP9=-DFRhOgSyU_#X=- zzvmlHIks{6W>`aI)9_DI#E+e9Ac=OgU}E~#9z;N>!k~ihC0s$rCdR4FPIL=&^4y^6 zt=7OA&9PrOZnM;@lyixEg%nLv0u~82;}hz0G_z0#?o3LvUYiStIqr3y1=Wj1MPwl9 z^A78G8>JQ`syZNIrx@UWzjpipWnsSitwO*Kb$lyTT+;qqj;V1%4o(Pm#CSl$XEuk+ zh1dF&#qoSzb3da?lh53uD&o|kw z_iWV;G8}H$0PW8uI3h_Lvqf&+h2kd zbTzn(t%AlRnIMIM{=pk@HE{SfJ9LM3LtP=M>xPfwLna%6fMYGs-~QPz@G1Ey*B!gr zd+bP8l+iI*OqB>qg01tHB9|{1S9de=oDuV~sEc21749cLgf)JI%VhFRHPwg9tldvB zxK9L02{;vg9Tgc$ZDNJIxPq7J=A2ZueK&^{5KV-HW+#5_PQUhzk<*t_kdg;8y@pmJ zkyp%Ix0cJtH1?aD71iyzgnt#A{0k=Z{a)3$e)F&;eHbbtpsp!Qk`Nrz9Cdg&R;sL% z%;CBnBmpI5TH9eb7LK;0bt+{Zzy9djFuAqLnGaR8BmvMz%I$A$Lq!71b#7B3mqW?E z@Nn?mXxeo1%xL$`+h4K4q{N0x=3AGq1Xgv1Ia{IGrS^+<{i?OWnK?&rL-+sVgZ zAaq4D;quB~_;Z2>TQHh9ekM8fByi_0cyuFWBtjAPTbP0GH5)P z?IH}{WtDWyHjsPflX~lz#jg|Pa@B_P=4%IgHrp z9N=JWm&xeV4QVXa&Ir%22^CThdelbGm-l+M^Q1FDD1CJlMEM7~A90aqj&HyiI-kx+ z`Sz!CW%Gc65x|3S^AxmUUE<+}+fuq4tyo|~!|1N}08)K>fG#Ox`IsMpp>Qp?o#TVORMbOJ!jJ)M&^6(l8bJ zDCCGC6(WF#nK0G0w^?mTOe_;IxP3h$DmB9Qa-|j0c0Tp%4mKq|xqb;LdI=iI#0`?s z{vb>M!SU&#k7%4#*j56})EDW9hq)xfLYW8)Ut|;AONlSNLLmL)dTPyvNH0lvE;Tlu zao!0;yvdK7>POr)x-wUe_XAl1&0ZI5+-+zuSBj7?YXF%6!Bato1WXGJQ%{U*+|Fcd zV4mz_Sg5)-Dr>6TK0%(3Ou%c+2F`&|tntUy5aH{xY2&K4u5_qjKO%x9Y9JC$41waM z;Nb*TuPpoAL)%{)i2Z%QGbCkRlN!Z|qF(YU;+F{ov7Ru%f}I5bsFDFU2Kd5j@xD~( zN$O27?fPj3JdTcNu7INHig9Fg03KjXi7&MKFlBULg16`%q!v0_beE^#kS3wvhdXDV zI!MNKc?yr@Bn#d-LJ5bTWI|aKKY*O3%|x(}d^-upp#Y51gXHt`pt84IIt8!qVZaW? zNPXWo8o&ZVvMVHEZUE^=Il@=KbFv+JnhcL-BEPGt#pAIb9eg1YxQ&|JpL2N$cLbsN z!A*c1-_5yf>S7x(5JwZtN@na-k%Y8W5Q{b%)V?@iBLg8 z%Gn{-?3xF%p%i%IHf}M2ZGr&NOXqyk!W9A3=1inUNw7V#gMGaRoK3f0C$W1tv9A!= z*FbeE04Pofv`S=m*Q%i$wqW}JP#_KK!4G<|jbWp3j>rMiBzuIf?KuwjrQ{6(czC5N_7Z&f_~B zjY}Xvj{c~Bs>Oay@%}AIj5iI-HUQ!z04%V|#Ug+JXzt*_yLxOFt$rs2DYxeN4D%pW z@xiT7_!T;mY6?s%7JQz7$+V%~F90sI2aBedYFZOWsqyW4qozt7s+f)npkMaHjF2#6 zRNw|@-pf`*pd8SH2S%vPLe9WaJys;6xuzdm18QXYH@4=W)E_lIpQJl;;pWm?5IJX9 zMwDlV70@>}SoU~CJpR-qH@1mnuQyfpEI#o)Ume)0?tvnZzS-gwTFusM!55E^asWKH z#Z0@%nW9xYE@*Q1tp8lwQ{>f0H!I{ zCN?k|0H#3^*lbZ_(QGgk>PpAW`Coag1T;-q=4zieC4__%y0?}QRzR1|VLy~bJ;xYW z_?9Q@stBfcHB6!C*p7M)3o=v5_f^)Xgb2P2$?3B=tt}rG3k;zEO&REy_bqSXJAW~b z{+7P-K>}$=y0N9t2TOz(GjW{Sehu5m2gN||eamEK-yfjo_Z|;b;wXnp$0$T7o{DGn zEC*k~UY)Z*ihzC*&U-FZb3nOaPIuwWsCW{_ola{o1Vff!_kVXMSpn>H3^#KCKiv_% zBvDDaEGGo&p<&199S^=kQ2kD7B^(s&h~JJu_1J54*eih%O^yWopHSUX_< zqbSUjb;AV$_8T1A;;a&`AKg zWE-Z=?0d3`8;~2N;W#mjQHTfV2o<lx#*9dSo0F;FXMDbAS z?=eWoFc?6C`zNN7(9K((8l>*l68AY~pSUgy zlD~T;6VQz=sK)6h*LNq7<(df)?pk_oxZ}u%&a(?U@IN2V!&HPc2vwA2JzpBapPCCk z<+t9?4)I{@HOR0U=_XdNJT8$Z=kA=Vg`bnJcB&Af;j^a4Gg%QKG&pt5o8eN#n3llG zUYik$ipNR79jvU3xIq7wq1m~x;zR1C_+_4YBCfLIg?5(9CZ$dKugJ}Iz<5W#`OKXs z0nj_)nAY>!A7lW_0vRee;c~JWg!5^b$gEQ@Aihr2zXRxQLo3U3+RjNj;gN$-)3Hez z%O$j4jgxoV%g|oV0aiGOA%Q7}dc6(S#KRJ(moWAbur}Rce@Vw%NKu5{&Ah@ZZ|8aA zS??+un)nJGe-u*gY)V9r(hO2q&f+X7(|AN9pfhy-<-yu~9UJF57Gp?<-W&jWcjSFc zad9x*L+CAvBwsWM=CEz%#dE&+_QK#3pr3s9GwL#14m5z&#{u(Fl0BE8%9@UyC%cXf zJ$R|$V+=lyNh$}n4`*BbuNgz0kC%wbH(B|zs!IA1Z(o(ZZ8?MH2*G7*%m;vP%>_xA zgrhThYx=YFudPwV+W{oRX%($(CUc#)kopd{#-mO`G zUUSx6^Hk;plI{W_7YC{9{{ODerll&GlwSO|Y~cnxkxJk#e~(&1hsBfc0wAayPylQs zh;29;s-&=^h7YYrL*kZy`W9hxav{wK1%+XO=lNi2Zkuety|f|NQnkW74`vzZ`vF;T zGa}>5a*PvzF9jg~fQotGNJOfyOKh9&7ICgXM-&$jyQz5h-R8>HQ03c?4>$w#un(m^ z8OabW9{>-6^LxZro+tw!?AGdCf!fcrYkT&bDj%LHFDCN6d?EH_`QLrGgvX@XmyNq$ zHg&(uJpHmEW(k+Twb6C44?n%NSi16Omc8wZlQPkouQ_;!isAc`7z2>rtx1=Y9@9Ho zp?VOQL;Dc(r^U>={~Ow#{oMNOFa;Y$L_GhFeU%aUd{fA`SC5BhFI_Z`RUyc%$KvCmv^mwaNmEz6NorI%kL!dUv8K8+nKw8 zWaRt2ABL9uY`R}w`(OvIpnXZm$CMv_$M);W4x%^?>KWh0$UF6yzm{BoyTZO(&4Ho+ zz_^J2W@!nIS>lSf;pS(teU_hFvlqBvzkA8JMi7$aFyP|zo;>zzmg7f<7cPQ=AYamU zJ>>Y|aP3c<_?I^bq#qM$Hu`s@>|f03ul>~TZ&LpCaC~K+UTlNn20<7vCZdDBQ{?^^ z^!yx?m;h%JGnmKnD?1Hazzd;f9{TBUC~PDA|E(pkSuS3v&DA&6f|{$L_kuTpkTR zE-NnT8vCNZcHBzRUj5Jh$2V`!h&_o~jyd@L`F)egk^a(*LFGpAWBo~i=*(PYOu)JR z_=TaSfyU+E$;ubjuh8|e$J#gwGq&gDRX9$=a*kDH=0LODHZh#TBLuJKHEu$=&{T8W z`8q@4%fmU3cp_IrnpUMHq3oo%w5GA)P=inzr~K!GY_bp)AN|qX|M1}QQdK$ryoJ7a@@><@U7p)xZgGO=Pd&=)T*&|>`Q5ka6UjP0aon3bNk^4{~eKJ@ernpEV5Il9R7?{mYn~{Joe>g`}2eh zjW@R~){v#ajFUzvRoIS!Y0xu6hZYn5D-o*k%VsCuQGHDi8Mb?9nsCVEb4irx|3%rK zctiR4|Nr1*N|i>ja{~okR?ON-dID@*aTpg_g3f#^dyE`+$~*V);0KXcjY2BkS7qvcT{%fRT_a%+9V-2ky$!Bj&pTItS|O=b zp!eOuFV$*J?wA20-MgB`h-4S6+R)12%$2t2>6i-j`$dmcxX%0@= z`XQ~uZeUHDUwnLs+R;sUnjN`!m0vvm!$kW2Y0>+FGunQ=pTNgd;z`{)g9HbnUu@p_>P7^PX_Y!8=`XpMvWZe!t-& z(s$kOWE?tJE3YM$@XZ1xEOM#?LoUkm*E^QD^M1&-@G6E-A4;~2Sd-oU@SlD-w(#`g zc{xu}B*{^ejMAA-^53~(u5Fr*cAicaSv{_Wwqo z2J8NOkhPk_815zU3PDp&9;b2c=pGZP^cATi2%rCI34~kE|0VhGU+*zh)S1aTk?JE@ zr)#GAT3&9j(MPy5^GMQXB~gkT?|d(B$dy#)<&Uvtww-H zRZ8x9gYbjx5rSZNj`kP@qe3%ofwMF8MP=|h?BUCg_3V?|D9nK6 z9!q6rm^E84GoSrW9rjFsju45q|3F10Ftfdj5o>R=z3a|pq(zS_yhHo$= z{%h%e|3v1dw?XG9&z-I?qax3PR?}ifn8?1{f!6<>OMX&(@jWydHQu~ulcz{xqV&V0b(*A=ya5Fdne++t%IpW$anjBNm5SFa0}Od+I;LKd+KvCmyi zMI5fV%9bVk{Ge1e?-cn^t))>5M+}({Kg*}bW^k1n{@s3igDff|0+fUpnUh)-@gMxf_8~E?RZ45K)uwP7}1mI3RfPtlTt=Y){o(Au>XG zvWT%alhQ!F9Qc>YPd`6>9kM>nW!u&8@B=g^jmk5IYZM3n%X{wU$4@Oa)u$e5C6C3e zDkQ)3uHiRiGg_K}B4{qDq4zDj>*cODTFi~4nF7FRq){GY#75)T-+I4CYP7M#QVO(( z%QwM*%C?p)<^R-S!l!;^t2WWvu+q`BRc8DKhGb|n`CWN)?2o<)R$($CCqvwev<#tK z@5(X@?4N~pze-=beF1n1a85QpO`MKcfAEx6Wj?@tcV?T|JP zb}%h9nySt{v}l_6YrU3BJ@<9|15=x-nha-iMqT4h4g7^rohxCmu?XaX2Zf%BQ%4v(s%W%;)jA{M5g62h)s!J|M(hinbK8jz; z-@ouuxMG#eL1_?|(S2jaq}dBY;KDz`?^RD9NY+%UdV~k}=HavQLMP6(ZB>dsQg)(N z4GfJp@sO;IagU;qrvtVUS6=!k{W&D$mKt&Pi-ZJO<-Sdvm{z*jqnmaaviJp0cy;B< zQcVc-CII>CWIDY5LIX_m!5s37p)&=Y)4BVNwD$q#=`CkN z>90(~!BlIq4$!C(;EorwsDSFZfc4~4c78*Yj)|&TMBY21pP3|4hC3p5`~YFc~ZNHjG#1;UeR%F@7>8qO@J^+J>c4morav&q}^b5>@|K>*_c*2g*b_ z*r3b@k{c8WtAP#vB1`v4HW_uS{@y5j-q^*QkRy9;XL`=G8rEO_{HC^6llLxMSjXkK z4rAwPu$>A?bv<2gu0hRR`Dvb4tHd_(7Ekaxyo9vv?LUa(O<*8N#Q{F1FLtwkiBCBv z8D*ao4H8`Ra6gtyB#YB!M04$Y>OWbav;{K^qyAn`w(&GJ^zyEjP81YgrAWCE1V!1X zU$-Z1O%%isg5R?6(gn4)mt~(Vjx|2YE%F>XGW~pxsd@F+wNM4`9^;DopI)Eo%#`jO zWm_|9%D`6^+8rVHa#^u^ELi!m?Zdcb*~F4#=lZN|4Ac6KbH_PuT1=dqnoE)@I)#w;T9kj~_r$O=bw?|fvoG|zqKXaQ=hF%B()=!rZAvb(I z(QZJ4XYZA+7>0pA`X(W>pN9$_ z?teD%((au8z8$Ghs{!SLKi0x8a;V6&bl9fq=j2N-N2sSwJhpm

  • sA#| zVnK)0tJRdbegR$J-6@cwZcPRFGQdikceD5{igiSEcj?bpFlc&fR)dFdzPF4c)4NU9 zg+C{e<||oB1g|(ak`?yqf&_a;dgxU7a49OJIorQct7v#5BQ-vsj?wna#H*}UQ@ZRE z0d(cZAyYa)wuZXPsmXQI`Xy*}G*nOFiFPN>U~D#>_NBcbpdhD|&x&eTG(x9lk|_ZV^Z%eJ4In zFKESsCm$Ld&z=zf&sc4|*@+ci3@Ux>y#N}Sg=OjO4@oc*_d(a>p{FjcZhZNj$oiiW zzyh7|F~E&_1U+>O?K+HcEq7KGGEI={3%@CePz7;f6s?s@-L(s)bbz`#YQxvsR+xw% zJ1KoquB>sJ#-9Db0+vT|tIpE5^HuIv}emM{5=_+DYS>P9VsA z^NH$H-R4f)+0~yp{2A&0WRgJcl;yeW0=qoXA@@Bl5>B#eGp5Io=jn#NU-A%Lwt4E@ z&hz5ixKA2re%W@Gp-2zgoG!T#ehg%Q&b@tG9q1$od~R$jIQPt(DNNPyVG8{Y(KSTY zl^Tjx^9=a00J&nnPm@#i;NWTcH8gA5;Qp!qOJf4`P@_Lr2cT+7zZup7U8VgeAG__M z#4Gta)1%cnCHV)TzrrB4Iu}FeUH8%JIWd*u_r*)VOnk%4S)qoeu@&3iA+0d@4lIB9 zr&pHYY6_TC`4lZYd3a+t_2{a+gI}Tjsh%88%&JmlUWD-MW)fHc41BzvbK@|jc(2iw z%6G->n1$fdV$6^>>ae2M(>9aQAz*r``0YV z98{JgS7v7BO3OXa?46mWrI~w@nJMlqf@W%{sO8RqmS*L|+qC@$wo8{eiSuw6^#e6}|*b}nh zS^;-KUC>eEVoyXT|L~9b;Ib9+D!U!FaQ#|M7j%t?GgQe$nQIP|zm6NK?NmeGoh2LF zQg%BzvdwCMxM_NPh4QQew8PU)7KqWAi2#$Y$V8_5&(pyrOBxsH_QqZMP*Tcyd*N!j zcYq7qn1&A*B>>-}wlcs6PkKhW=O1SnoG1@ELP2E{Wg>%R=k(@d+tGO{ILk*y>8A6B2C&ufQTbTTXF&X;4^19Hv(;n+K(aY*vS38e{)z$BHDcwb_ zg@Y!hxc+n!o;+an*dBIbY>gFXYUH+z;igHYF2@JcRh6cH@sKgDf+Mq=raP>6AS-^cKljCyo+h>S<6g?ZjghpFb>X7}F$CS~S9t_a^%&4z zDWmE7^#2Lu?X6a`jOu97iq&umm;*TN%mVNq(oUZ!@~kLUk7_rp{b!y_EM9+ufUkX` z)conUB{_yO{zJ;UdFQ)6g7kuefkTI}rMwRU2#GR7fd>6q-^B|X2A$}=(M`x*rlPvv zv-vaR{Dq2Qa7LBVcGJzZS`9_JgL9(+D`RkcMR7a$ic@{t@6zGYDU2zQZgLnRMXj4$ z$}pBQjD4_t;nupE!bSeG&u+moWpp^mCpr&Y|Jut2wRKYjVkO&H?TV&h3g=IzP|iNZ z+h#SMx1KAjJ|W+-wt{Ta`85+CC&!y$4ht#?OoB4q!;4@BD2=q<9zl#hBgRL81ePDE zDZISt@1DPgfQEe+s*U(c@yN|ROF)Toepv5rSXI7Ut+S!D{G>!aY`o?l&$6<{gQhLy zGaAc~a$WVU?MYp@(tccSUQCo?7XxtC5JiKZ%>UH+vRrqVg%;hlSWK|#@n%FExy4iL zLLYK1hND)Z@J{vICtbBQCm~fApC&!UMzToWZI6UFn|@)D6x|AwlhI`Tn$cWD^F2G& ze`E66ew;6ze7fV zVE9CWU{|-=f7ZL#g}7XENPF$ZGoJ5BU|CK8G2WcmE=VWM%5*lNm3D9=*&T)Bxv1I$ zdfK4i>MQaq5`_GG>f_7ZNQO(d09CJ!;s5|^13z8@JW9d0; z^WT+fpZ^s1$2M(UI~G%s2j#-CvKj6?HSK45w&daGw&f*Yqux7s_hjpNSo(K(GGQp^)DLE%*x8J*Vx-pvsuIA?9a^u%rps&Wx z$9qM+!}5N~Qu8(_2r+oE;WXQetRP#4cMA4L@vYwO>8rzt z+)bU62iY~sFU@Zl)bIRt?|25=Abw`OTAO$~@Bw5_+u>L#Z%=vqojZ=H|3b$9J3RC? z08xmG7WwiJDr(~)Hiy4qaq`Fh*GTFs>JRs&lE=HLb;ThE`0Yw*3S`-I?S_NL8;y=| zjfMYGRKMIUHIw1xrasC*qSODAqTU6aXbEhuQUSglgI@3S*d|lyvvKuczr%s2YdYrx ztokl9;jgSKFMr(ILiv4;qeu`=F_E3u_J?&bzHz?GI!q0!-0jFAqkR0;f-oHb*jwTdKmd&ToGimnC%E zdq7&1H{cx_5O{w&9VWO{I`XxEEpxI5b1u~qJ11AHPpU)(d2>vUl{50SA{d02J`fjm zBtJC~uoBdBsWsg*rgR{0v;b|{@M=pGiyQ3?n0;~sZ~}CAr)=-r%3P;9wPO3F*Uor4 zzxh=iOiS5Oe{uGu>WYqDn{%ub;ya~QL=OJp9Vtn6{Vj)9=Fr3izM~S*v3jyp>W4%n zyLDk!I4)fMsMYv1bvNst##)1t&G!t}?!3>xtPTwN#8GmYMt*vRyXCHyr&EJ_F7~g~ zWn@pnWGCdyuz+vZ*Y!rv_*KHRr74>_WBd1P)+82`eKef-Cf5g~ggy~izeAn))C6%3 zPy=hjv6L!d6v?NO9ZGyB_D|UA(CqT@b^TFmYr9%DDSFMLN?f$M#ChjHR-cP$Om}>cbzVp46RaAd}V}&-KJ4amX*v>1SWHhEe0I$P=So_o)jU z=czq4HZS<&Gi!P#z9>80@N>2#$2^4S%^rx%@9LNp3L#=VamlK;;3t1j$BJL#CJ<=f zf=}uo<8GCFHqS@4luuceLsn(V*EObn#FY?CLF$r}xq)Cc!_yA(72n@NB+Y_(h8+<& zn|t=4ETxO^3N$~i!D^v#u)Lwoj~u77_YQ0ybK$rWK*7rLg1nsGY+skP zONPB`d}e#=hjaCz$j-l3v_h}W)bP0~PrHm|X@zGZZ}~Ctl%I=ZV{g|{d}b+;Jqp3) z@Rj2p_8Wa7A!U05p!>H!xsU%TPLe3bbiaHpRX^I`cjddP(vps3THWE`wgvqUGySY6 zQ?G(^&S)VlqM4mxqRHcmUo7KTVgger_ZMg?7gX?u*!?xm+rud{Px>tl>qy?13dreL z({BJrYz8Khr>Ote63t$HzQG783(&9d{{T5Es<;Q~?S$z2GsjK8ZLwnQ>oe z0JD;2wyLL5s_em?32E*4Pjdbh>{GQ04J};&i`nYG>sxVB_wkpFm-Ck+vY0WRw%3=zHjvb9;^2N2c@Wq|Fgu8x?8I&t*uJA8a_Cbar(v6ul?c0TfNZEr=4pE}5KY5#<| zSQXCgd#;NC%i>*lC(gS1F)ITmxJ`{ko3M=##O{9qlYT9y2yE%=D>JpwHREw0gVnph z0^7Oatq%|yozWn5Phoh4wfFG2etRnDzoB@qN8e)QF?Nmz%wHN< zzb`sHwaORZb2{z9s+dwcdiWr_mt_u(Hy>6uXde%2Y>lK&YU#PY7+m>NgrS?|L4il~ zrP`yi6;qd14-NvnhSTn@vEy^%a#ds1NYT#8 z44T%o0HjZ1?$cs;Gra;IJcGB#zlSpcIk@k4j0f}tIDgj|CVZboSH6+#V9-Be8J;ij z5)xCl?O!P@+;P8dEF0eRF-O3`zIn;|DCzSc@+D~iG_KdtMaDhg$_OF;TN0R|nQ6=z zG*k%iCe18BhX&&O{1e`)2lU57&N886B{mEHKmli+g{2ys#~VK$OfXN@8a2-F#pY$- z+eN&jN!u+sfcud7j$CG=e<9 z^Bfab1%;)MwL2wdchpQA{=T*#DU}u8B$<6OELMQoHuAvIy!zUNyf$L?B$Zc5D)~F$ z0an&4d;GpjhEN$_!5rABgUZJd>A<9L&Qh{wBo+D4aiBDEWxsIUidf0bmL`PeL~Qe$ zts3x=DqOhd2~witFzP4T6AQX3L%=<1{%$aCd5LR`W4FVPeC1yytmq3mi>@(Tf8+VP zJmsq)XvlEG-4`4K{L*<%ZAC20hro=l5ZLtoG@?;zx{(Fz2^%eZN8`!k+(jFPkVrB~ zI#5~K-dlPy!9QEdW@!9!hcTu5fi!6mBQQfiASi38f-WFGI0fHDt*50at}TJ*`K}&m7PLn36q;rlrrTG?wL>?2f33MgLkgTuhV#C2~Xg zoBz&5H0xzfiWz_hTnHJ0Dj@Jmm@)14*C;FP%`PM9AUHczE+2zu7Z{T?`zjx>t*f-jlM8w+H4^0*L-I@^aDz(|I$2yB1`x*T`|==ezOJobb3LW~v3ewv z*KXxY>j_blK3Fro8#CrZSH(^RPGTT9QAiK5g2GteIA9;#I8e(_!weqxU{hXVb*Q+|gV_Bhd`e}-%L!!jYlu=^*0#QYE`@DmF<7v6I`oNrq-;BbxScB>p zfiJNy?Vczr)iT|u4g{@_*N$cTnT^X(sIY%aA9Uv0Y~fz2+86oqPhX+-?@r(YMSQl7 zx4u3HI1Yii`4|_y^_1#@wMQSglD_XqN&b;&)0(@&!m)VXrYVNKVf=>L!jyO`Yb^Ai zu+nOZM;SKArG*1pk)FoLo=Fjpd*U+Qu6a=0^@APYVyIK*Z@_9m8ZSb`Z>OpUt4}-e&3ONh3Wxuj=Oh?&< zYPl>KHa}bVb@F*#c7; z6Wx~f$uUih#y+)3Iu=>PoegsK!tlwxzhCYQCAIbnFY4c~@xa9n;X*Dv{r@Zg??O>Z zrPMn;)@d`(j|1$tER9-Y;(AwbTjX&OJlOms+38e5j7#}%1?7P=R58@JeTet{+3tK(h>wpoDRX_k@4Zs5-` zQ4yZe0wS~3i-yGjyo29Pjl5z}=Pz=ilB|38O$`M1!%c#bbbN(!r_@{_2yL&G=>d$K`xzFS2J#393lDWAH;p6mw@+ zt|TaaY>a#mBd|aD#wOG@4A|7k9M3-pk@4l7SraFYT2C>t!u2@0XOQ~2=1NS*D!2lM~0p~79K!&PNQT=VTVJ_LQ z$YSSG=K!w)p@1b*_r~M#?{q)-Jkg0DGKkPg)|>kB!4F)jBx~s&S!|mu_N+{Z$bl*(={GJ|9hU(>ks+m!BycAhOh4 zkgZ|i_#2rAisz{DQP;>R#JqT2OYKa*KN|%g(#X5}Pf=e$&MvLGaEDfPp&Y`^br;)H zi?d!)Pg#S8oWM|CM?vq-7pE5FbtW01hoC@0UYBlt^_Y8))g^X1rV1nG;kAxZA~Bdi zkHmJlL5F&XPSIW6%*l)GA#4xt*F__>CGP{5k_meckn@5YxlN~AAKAj263P!GFyf%E zTTJWYal=XZecqj0^kK6M#TxXIwCk=&-{Ahino*I=fhhdTVxwo1{gD5%T`jt*z5Ky> zfR)Q-L$@536;Dlog33JsuCDW9{$-!5_l(ebViT{a?58X%cnSQsb~5L6E{0+!*Q|UQ z3c?sTEN?(Gq4pRzQLfK-^whZ^&{-m4Ts90XEb#J$eD{(ILOY|SytW8-Fl$jWOg*8YHJ7Wg1}cD0(}4i8M4d8 z#G9(YX_UVjFwty1co7rRg&XfxcFgf-oBjSVxUDbK(@?U5N}w*d`u zoq$8Pn{B9u(t6UCb5y#$E^+gW93JQ@j|7o^-}kU*x}rLLP)KLh|5?!NsAG~V5_z3^ z_4~xNIul;pkF3~rT!gLc1WxSlUPE$xz`ZP^wHGSKubseKt{QuPsiW0=H^`h*s6Ofb zxaRDo>9YbOiwGk`Q!W9Z!QjXz8cHrHf;s`!>Q}Czx#|0upG@v$JtS_XvAt^wX72*$ z4hnoGsFrre0wI>RNR<-&CG*%GZ__Y?F$sE*&9Q$;cmmW zwVc7fCg3~%xk<`uRA666IqsItcmcnpx@76`+Ls9#3v%6I`~~CYfvx(fsxg-yi%b27 z5H^lJ)j3^@h5pEe7EAnZQZ0@?vkWH*2XA;csKm0%{g3tj{ePq$Djf~%ZoY_3DBt6h zIeKbs)D<#v+TB_@o3r-h7Fp<@;z#l0X-6HseKj#f+v8o(URXs5__E3ldBykStDjPi zg2naUKG|j4d>ykF&N~yis0z^?l93tRH zEN&J5i&+rl_J3=B#{hx9l)LpDQ#z@&#o>mLsK#s?<0^e(EoeD|cB-qh#G2*qtj`B8 z)|ik*4@BQqcy4OVv?3y;eYgtHb%U(~=&J4s3*vYEhEFV$dw)4goMTBYw3;ZhvK+@V zu-5kP46yn~_H!qEZfODqIje0#usbNc1)eE}KA$U1v)3^3|MV(zr%+`4=m; zo@>4nYnHCp6-T-Td}VG%A1=XX7tZj}VnRP1n$si&Sa+9az27M=C#hD<4r!hpj{P@k z8PojfZ;28$y2(sv)L00r-ZFTq?HJQcGVa{+xJNQ6X?j#->j`hK9P*?#*`mkWnkQzx7I%pu2My*_O2HE8-_yk7P_BFfGoJ2v_E8&O<9}Zsm4f9f5++JMCK?)V5)X- z&mYZYoffkruy8LRLR-lU{uBDk=ioQ+UW>jJI#_Db&byLtMmeYcFokq#)@<>6Ar{>W zI9cqRy?H8}R=37bMZ0E3=?u|V?K;RT6!7iP0KTgL8jxh0X3cH`(UX^r_mgt5^n6op zS{>@&$pXH{4G!+xZCiL1`rg&#@%LPBrrr99jRfCwvad{ey<-&3x-PjmX|nFGeCG!g zDpmTGhzedm%eO}qUl()z_%`azV%^rAA8b|z`j!D=Ziqylw9+lEf&VJ!YF9e*w|Z|!U)1-?3uu+uyfgUcY^UpVd{?r^?bG+za?Pp{8LkE=hMu)|I&<5dI_t<=T_lL zn(kA;UHc{X@Efqz@Jkp8_q^5(Vb{woC@2G_CSnk8eBXa~!yTA57ZeM-pb%%863vO8 zG_U%>b2=y7qb5O(Ce<^>Uc?MfTrHRbmxk+MFtk7YPpHxOOMN`0lfs)A-mSRLe~OWM zGJ4Ir!Ii4LybDnZH(I+glf&yIDOo{o(`{VpM(bRIqYrnk%j^KeY#mo7U}r0aw7fIK zLr9^JZ^uSv(8&1mzCSCx6unFjrD%J*Jc1O?a}x{1Xa^%E#Gba?HS8i}!F*ZO zpxzwLrGA=;*^_2&Y{0m-b4;lEK^88h+Wc!UM~pLw7sgJ!g86_z9 z7N)R|C1gJ7l?N9|kzcHKbsb2|^XhtpCBbwqo1O|k+}g-kDY&Rjel8sRo_7k^`1uK( z!}H4b=!MK3{+OAPh~^~YU9q#WgKDk2R4l;mdTECj()pCTDx4dHWd6QBvHv))x%Dt~ zW_NZL5Gkp-!VFlm#66a*!nhD*cDvvWf{(nR+^l8z&^xd^&gwkls-%P}Z`1kCaV zx-|;H&!RFSn)i^_bG&PI_Qf&o9~3z=E-11$hzq9w3arw6=9$f^zx3zmN-xV8+Iw`su-%&pweyeptIzfmfQoMs%2&Mirr~f(66VAz$CJ^f z9PN5Teu`==N868H2H9Yb*b6o9C+Nh4TjZ;IJ9|Fho0nbC? zJkSOea$?@h;0`)kZJA6`C=FQxN_I%lkuW(;a;COQul9F9b}JE=gQOGI*q3r4Qopik z=iZ(t9BFYS<C5lw~L(dc=ZyZ5Q#;cD$+r7;roc@G@_jCva}~GpL`uOK z{or!uZ0N^qtV%w6b`-tErgE362l|e@t3If9ez2a)T`hDbUHYj*#d%kWdAl4qTGQB{ z{8y_}T(-ok&(wx6ypkRq3nx{A53t2O9K`9OLAyT{wKJe6@Ih5{z>@8e4!#@|_qqCE z_7=Cz#oRxam)H%Y--Kz6Ti&<>-uVjyQzW>bQGdylmp8Y%XF+yjm!@9BIUH*bOsR!i zGLbk3E7Dq~kOi^bZ+Ajt$B^wQh~8R|zp@_KMc7(fThFyVW1HY#HYDm>6FFtdoJm<} z`TM$-dVMvW6WuJ@`w11zH%c#LR3!2_HCwR0m9(qXzIyhz`O^sM>Yu!Vo!b17AEVZ% zce!Qu!Y4^xg(j4=+~ZY4UcIL-^aC>P*Asgyh@zXVF*gDddUG>#{T8#pL)pKBD^tCw zF&B)eITk4xB4-fmc~S!g{VD& zhrDS18K4YP)+&?QPPerzqS7-hB5=M*Yi8L2V=NnH!6}~x>5P)e zKcGGx_~G@3#3_^NjV?8L)F^Pm#+HS87mo#uT8Xue$V&b-cR15KjU2XHVtP+0)X1sI zPUF?H1+&>S$aT=V2PAF(V-j>}xky)jkA&kTCz@;Gj~I^=#SGmPVkOc0&c>a0J<qa50@{8S4%7(1pUxSm-tz#&@g0ey)Zch zZ0)sc<_`aw>dx*NXS-?ZGQU~9+Yp}0>3cAJ!Wj+mO0jwizcoPHc#QS0A#jH6gdbS? z^J#zss>YgET1w{WHuPn9=-sH(6&mKGW$!oA3s~iL1ZeypjE@yQN1D3ti;q0>+g|$d zhA6}S^P_B}s<2(lTZZ2P_e5{CqoTD;4G4Y8NOkALlV|}B9K&rJtHm^ry33bJyROPk z`@+z3Exiu|bp%-R8}t(yRc(K;2-O6lnNEvJGjE7BRqk9RjKyQN@~qi3njQvjhHR1&>@|cCkFTWqCP;L$pq*M876UVLMA0IGz+VC zbQAi*Qx7Tb@Y5M8aj$Vmp>NGB#jmhAEltb~uiFb4_Z2Hq6L(>E-o3*-s8+MTX7aMg z@&K#Al@fB@+`-U#HS^LRSNEStSv756AiWTt)aSMb9Sy&u6MiLvk(azp^&4${VgIklJ|R~Ky@4Up8&Va{n^e!4i;6(gH5~O z48>2Q#heC^YGhx#d-l5UVMug9SUfG+_RrO7d53WL8-^H^ zPpNlzL~~(bVRnR^f1lZ)l4Hd%m}KEAlNAXkne1BKecqVr3ZG7Q?m8ZCv+ZPBz-p4{ zg-hzz;<6I60+E;c<)NcswfuPcaA`}pXCHvhtElo4TYTTHgq#x%b-Q-P5UD^)ig z5|*0|qb&^QpV_{*$*h=BJ5hnXRQNbyUtX@R8+};fA7?dxlUG>Pn;5O}oO_4G2rKK;O zbrv#ras9@VO8cMctAT=o&1bE^din*opvhWStlEEtos)gOj1C96({#nBcb5C9PV3fX z9^zVt`-w!G^R?^61&o**uCNg@^sH)Uw5smG7mgLx>@^p>^FwZ(ygx|lod3cu-*1`r zR3QA?y7i5hT|xB$`+xX@G1EywuR$*CYSZp~={hN-r25f^%W0tWgSNHD4E$TdZ=*6Z zMC~uWmhL0IX*w?H7oAcYPub!lURDgF<;(k9K}+!stc1J?{^0_iuB|qq$b^-b1aS4wvd$M)|T5v(8Xu zb67)J+1MJ6A zyteuDZ0RD-yP{%DV0)jE-*r|t1Scik)JEd9U!m*XL;3<@o2O9l$eRA(+&r2btbV&h z3rY_aUjgqiW_P%B7)o|9gTTV9lJuvmMlg4OE?c#2Jo#LsOP0Ib&%UA%>YNtM>$hz? zsq`=o5s$x$=W$5{mZWzP-V1S+1*G0CeIzG&U2JzoUfPm_V{x_q3iT7JblPa%2v@9fiT3!bJlpoz>9fsI>md4AWzZ<4T83puN-?;M0NJ6kA=7G}_~gnv8f7T9HV-Sw#|7s(Gu#3cO;HUR7CD z<7S67br0(lU3#;iw5~jC`i`%;eUQ?<_Qz?Eob?5k^a@_Y8bZzr+HZSB>jF`hfVK_O zjmxFmycu=Yqs2leBzDIKc0ROO)ZGiFId13MCNB^h68_qk)Wv96YEV^jy%do1G?O?q z6f^AZ(kB+d&OezT_Tq*>XDV2wrDpZPZUL;bl|agoMgCY!;FhDt7I#8t!x;v@;9IMN zPc2~QY@m+G5$PQ+2uoT4z8nek6tRXslipj*j5>m>zr8oNr#Fz$xDh_5OskKWV@)T{ zrtYPVmjs0VVm05`XtPZb`c{7o{1v?EYqj{u(AFZZQ82aS?AH+|H}1x7(4xP*+77Wk z<|1|2l#8uVkKl$pUO7S?NpQc>wBKn%eG(s}TwUfzm8G82JsDwHLIsCl*a2`!?lFqb zjXap3p2FuXlsut#DtfHmqDiY=LYFqx@0?E@XPSaKK4&e>Jw%tn)^UdXqjO5Wp@#F4 zsT|0NfK$;X%o7&85f^m4y2Q~Xnv;pr7hfxv?Fru;0LjV;w%uKA1;aj_y-@Ko6b*hV z2C0TnV|{Nn$L&mDmm=cv(o8-dJX1uiXJY9!zd59}-wfbZSrtRE3{s;;oA7O5zze%^IRXAeI zpOB2gIYm8|*DzA$YUY=1A>4e2deLY|w+2)T-ZDse=2K`Z&5|e%p?eV!AE}(6UdHsQ z4rRa^WZm%@bx$uvVFpIN=}gX3ok&aglaM1LEx;$s%NHI6!+a2*lzr(SCanl_kbr?# zu}&fMZ*Gl7;X?cAFWTMo3#pKOV*P4^Dk_0ib|7{&Bh6)v{(-fApR%;_K!QJjX?fb@ z-y+I07Elhh5&fpNDkIM&v)k@Qjjd2kt9Ad`FfMF!$!1#VP5f%dfd_F>2z1E!9Y{+C zH+HxpHm&`l0afea=47X)m||>Ckar8@DST&$D?lyJ{(moo2c;8(HSukO{DWx)J*m5I zZ@1R**mwgk>)63ahmym;W$WhzCJv5E2 zD8BCEo?&#n}*(hTtt2!s1t4Xi5z_IJHjTC>4N3Ax&y!t{0 zE6ip6tC9rxCo)CDJJ;E`Qoc*rRd|q{F17SxSxC3D8@!%^KC%nyOX456*?DzUgN~o| z9ih>aj&o?=wYK$h+~l=3A&sANr#N};nd(h(=??kW)>ZqZeJ*)Q*9G36P0Q{`m~RZW z_g62;I9nmbmtGu`e{R?O=mu;YWgw=9I&##fd98uXsA-AXrelMTE_Tc#aAo!+n1=e zS4o_`EO!zH7}G8=^W~|HtaL>p4XVkp#s2R#cCRG94o+$yr;;;Gm%lRC3r0iqRUmq==E_#7Gih`u6(QW46m<_C$piXm#d)5x7 zbK27o;@r56;WM>Qcv%jQ(*ggck?_S2zdmh5ts#@auuV_g;=nEcZlar{TUzHUXps|a zPs!P^Qv39-VwT!aOTRx_)-TL*n-MZ@X;FtuHT%34+I9MZaAfE&Hv&2oK;RO+^7>^< z{9ZNm@wKA>M@N6gnJhfe2G}sS?4#jF4ux669mSPlZ32mlj6%L!>S{iY+2<6G^{1pP zQVc);Kvqai1W*24Rz2HD+#!pEn(k$CKfosGe9d7W?mWPs?!$+uqyJVTnx9wBM6VcY zU3lcZeqFJ9=w)4o0ECkb*NcJG}Q-P9jSBfA*lq5}xiYaO2=-l}}$4xq%|6xzH8m>zCZ;1d^F zRJ2+o>GD^QE1%$PZzzCwuM~7Jg1iA-uqS6ex6Dt4cJmgH5PxwfPA9X*Q=r?EJ(j<{ zOaKN%Kjlw$nKA;q`sFfb?4s&`ljQ#RqRN?_y;6yl+JbyZ~b4} z@r*cVSZ6J}V}~gqWcgNG0mV;wd3am;_gskMjkF6aI+HQoD8D3!ORA{$uY#H-DHHSg7i%rf9(uzc#!CJH8y?y{Yh z^~D^HXetPqWPTE;`8^ZBi^Ig}DyWc5oUzJ3bu#~5G`U0aKJTmIXj!3kxm150!%2yK z?r?rwwF4Q%d>pYBbj5L4w|7B?q8>>2=&+%9A!LmVyk4B6`R;Ct<<(j$uk z`3+B8t0s$|Y+L4aem=4|H_@HzPeHaW{;#%)Qo15QKk1nVeW_i|iKt*j=zG8=saNxL&>b-(b$K0K=G zjvKuje%btDAH(1Q&dpXiSk($~ydqI*$VU0>o)hrUydLvvGRib?^yS3+?`moc4(md+ zCmvvdZCBW_KwaABw~bG0hZ^1UV?F*H_#@ZZTdw`MnY<-ojpFwwqi?peJQm(6JJ$qR zd?EaX{lW^5oYd|tTBT60Q#<7Dzl6800tPq5WT8eAF_X|Z8QCB85h4ft>|df17>5>?dBIUJLtd{vYAE&F3cN1k zfW6qEf3wyza_^D;n6l8j7tH%#+7i@pqxbxA>~#1SA&^ndurIek)IPQ9o%`_9f;k-X zoY?+&;vkRUht-T(m9q~SirqVR-&0>XBfIH^?YaN>rvIjswB7TGwualXd!y(sbPrEV zN54R=jZUuRg4y}Idc4Ey*9zg4knYHp2Xhug&Ww;%U}dng52Q56MCC;F--ih=Ttl2- z-GNw>NqqiFC9uIu1ZxNM{rApvfZ>JI(GpHf(uEeTD^>s0LN}=}fk7tGZ z!i3RklL?w`tZk?@E~PZv0nAfwC1jLc=L|oKqX)wV!hXI*#0YWRjGa=SUzJIO{kl=g%5r&nccmGttAKeO-LVmaY-U6r{yb>*E@^gJG6)=2*QR zOYS=|i{i^)cGO;T@4UZ2?erp?7*mjVBtX;PW71NaZR36Orctv@iU@;xsvJ>5SIE1*zi)Pgwhuy&+v$5pPO+tL(V|`d9qJ)l|8uR7 zg$z~z>o!YCi+|&}%oir>F#kKH;LdmdJ0)au2yrQj>U$l&%seRYA6Dp#qG?@~DK(!H ztQzGl6Oh{*-b|8~^#IRf!rk_&F_HPWLh7{GTRRpvXj0;7uq~t=6WvifUKqG4Ba3;x z+o=&UfJY+L;@pqxZVq4;cdcqfM*>kwcj7Db;yRzj{w^8XEwJJ~P{b%w`^jT&o@ljI ztV;$)Dm(9ay4z-@9!$@0>s`Dv;efmcDlI@{XpGf0Kbv!F+KSQSyFU<_+oRnMBL9si zvkueaQD_@L+9J@+kJ!Tm3WMhB8vYlwwhgM%oBf^9u>RCVdrNgCl<>Q{DyP6wLEYXe z!K>?rZ&EKyU!Atku6w1EIffv*t1;p%5|o1i1bY1BzRllg(_P5FCCFzWd}x*xxfNrc zy^yJ-QBS)8>4ZF;pWax+kk*D48g43kzR`LD#p?mg%ignBxU`jx8Fuy~z`KSH%FG2J z0bSjyiiTqgYH1Z**9Zl`jZ4kG1I4GJm8m?R_!RG%PAFpb-jp=?=_+LErHXUWC>LMh zVA9lrcRG##jse@e51KsH7h9!Z>*uI5?#X% zx{rq~RG@c@#JLPz2mH%CckSqBYq?i_bwPf~81mfqit3t>+qDD6Hz&qhW`n2ao#(a9 zqz5oF)1{8|QOEE=`oKvi;^evU-f_~Y6a@*;TEv8eAG>4{oq=iu-9N?A;24>0{tUrk z$ER*%hE4YX8qSLt1LN_f8tEa!DNW3iyWvWFF4enpk`(i>NoIY^$nXbv(n_MCAeFKX z+UNUUzO0aX2)Uy4`-|=LYR}a-nGh2d62vzV9$m3`S7Js1qT?%EvQ-Mk8V0H;aXv9f z;>d z(bjA|MXgj7MNy+Rsd`$JqV?3M5jCnx>^%~#qH4BQl}J6c_lzy}-n)rS#EKDOWclU! zp7Z-V=j43O=gxiSy07c~e!V9UPMKAu+OB~Uh}@`k*JAH&Ioz%4nromnF^>avB=s6U zW_>cX#QQ_2%u~qVJI}+&+tw8GOO8|7(C;JB`96-Kh%~$Xzk=Qas*2*)(~qa%&jy`B z3IzY0WXtVU+t5}Va>WhuIsx8sI5l_30^51S@H2o`*6=<-4W5a*QFEACx*~n>Ngxvs ze%g~RN4Z#^(aVJBT=Y|Qp{0Oxj-_U4T}zV(HglPj#E=s+kmIF=OVF7#P0=!NT%mWr z`f}Kdz|b&Jx79176Rz$sZr84j)P;%ILUtsTaRL5A(sB_@c`dl}K-}#QLuWcR}kL;2Hg`V{AxgRq_-R>nV znU`3BwjtZ3_82iE8ypHObI*dV8-K;x+CBT7Q-@hAJ|!c`R@+%O=3U@GnjgTEfmdJ( z&GQB?0+YL}z>d$n@3H2X%5rr#(cvk&v@J_F;Mz>Cz~n@5Uo zsqQsWMjdaYj}?BJRimoR(H1A>zX^w!c|Ldi@JAZ$pOU}ponr#8>1N(FhCW|7yT)IC z1E0^fUTDO_yHD&mqX{Ge5qhEe^fm122TEB1HxHCVzoy1C5pwyk4X;k#*m~kK!-WOW z8&lYa=wY9ehURvAO&zGn+2mjs)|~PxDp{@9$L=HYunhRAek;KWsQeuof0FeCo7sEL zEE#g8L;_Ode%tx5Ob56O#Ri$i>kAK0dRxbY;S##A9bktRH5Bbmp?hP;t z)((0Db!{#d7&ufr5cUYQ{he@RgY`x*X>=xLX&;y9zoEpsoX?TxP9o1FGzdacf(L(e7}PygZWJ^}tvi!`+F44b$#TV8Fa8E8KS?vIM@h{zqxygA?d> zFWyX`2wa~Mv z9nFXnN3?UbxjOukTPx>FwB?*}!k9$$VrWwG{5+c4xgiL}|K++Qr5`EY^h zUH%7oZmNW6^qMh=Y}Fru6w1=iwU<%+;Dp+La@~_LFt+-^BvBw_ME`zW>AHqakZV)Z zF3M~cj6-p$^RMp^J~EuL%;=#sx4^_*VeHKS+Ofjg;*}|kyq8hwG%(h|dLAux4(1tX zietKcDlm0qtWlFNcP=C69ipv>!3&~Hix>YP);VaanYMZr<6gV1>IjgE3DKq1tongf zi<(4t1#<$Xbc4v<%&Mxluh)yO>D}l2uxSt*dN)hy-q@|bU4;ud zd@eg4a9WwW9-gvrQYvxQtC7bQkkq7&UqczQIpbV`9&3NMb#f=Q4-0&-0Nvi!{iCU6 zG4&EOF(9M}ZjcSRGN{yWvh*f@_)*pybP2wjJz6?>?|ZxfhR38A5u1{vK4Exk7C|ea zC~@Dexw%quTN)o41>(P#YiY!}oC}>>g9Yz;!&PfT!SZ=lSU#NU*}@Ce(F(4kLQi2^*E{sZZJ()lxHR@{eu2}Q4BQY;KzqB2^H%&gky*DRp*z`UBO`cJ^5!4aFBGucJ{CWp2 z2Siwdl}*zsagJ&=Qf_0Mb?d^RU&s>n(dRW(uVloPBp5bLnA_;Pc z?t!HqZ@41~B@ErpRD7p$dMnod%3iOPd4)9LJBX-xSV=f_c9B>tsy>UR!3!un?Sa-{ zv}%ft<1D@bQw%F((yA*#&2QKB1OH)ntzu~yNNtsYM9sL=T08b9sdfm%D^&+|G$&Jc z{JXBqziLK`-sPqqTEyPm{yH zgFk-p`_|c@MA-3j{W_PFHl2$tbHz_xB*mFj$q22iM7&aR+Qp2jjQ4!*{py({w~)G- z!G<>%j`3;YGqRE4C+dA-Zrk52a}U+X3BUNyW5ov*&aJg9n$F^-mdwiSQS^1>LJ_5! zE52{jF3r6y}e!I_^*GYGi6u-1f^#{*MhZVu8V(Hs@8m2y07%&ayws_qxq>TT!RK<>hS%TwQx6WsP6o7{g> zmFT(s5V26R!vpINlNB$`z z-gfz2*__HJ5A=+`JWL&E{?SN;c`a9#$ypxqWSO>jPZni8O3<7uqr3(lR9Oj}z0Ml!ez*0?oes zHMmB&%u7*(%7H0eku^S!Ka3U((-GFb*_2eaeltS9+++`4VwOi$oqsXm24|bpzT|Qs zd65=RXL}3YK9LeCagc6nTKu+%8LGetvn{!ts&%?~yZpjf)3IV9b;y(?rTKo_QNV5s zA;j*(sQbjmA=CI1AjysEpXyG@{PKEC0(kJ%(L_S@vQhBbGrin-V)`&t(7A3gio|Y-zjG=SxX#|7JB9wLte&dIn z4E~5Pc^V0HUwNZ{@h1PovZpC?`M#K=xUe(+hRh?|as=PeO)p^8K{F}f2J`FN1ty*Y zcmqj!XK$m~2q4Xg`c;1dv$iI9ej`$4IeV|rWstoF)D)M?sjr>t)6)sJg3ix>5Y!CEr(EDAce)VmRo#$&03L3kvUzxD&rXrEv+ z4NQ_@R?X=}*|qyoatCX$ieq%~UQj!w1orIs`J#zreNN#in0~4;?V;!3tEhh(7nE$Y>zPdT?53aMEyR z&_BL@`&ot*ipTm5q4^>9(ls}K#EIWonfUs7xnFoTyH7U7MuI*1p`%^puQFqRO7QF0aN_Jm5&m|;Egv3 zsgRwn#A~$_uEpdOf|NE*+{B=CEXY^Go1QH}%r;S6$Ve@(nQIN$R}qGg7( zjV|$MQ;!&fzn@a%axv6`xGa zsdlA)1nj?Y%F3jqGW-)x7~1DU&$JTOfrwDd?$_R$a4G(1KEA?(run|RpyC(kKRuI0 zV#CA@nMbBZyZ0OfX$U`;BVn4ti?TpW7Mdg>B!D}DKl4gm%SC$qEFC8h{S~o17J?Hd znhGA5lx!aLhB7ETG`O(0F8ZHO1-fl|DLCxHzix6LN~u8}&LK?Vdafi#a+KZWO}ehv zlu*B2Th501c5;`#(ecvI=SV&k#%FHxSa|`x}x`8V<#0lkT@qe~g6*QDy|prk)xSs=E$bWefcTi!BEx6&;=^eGyQQ zez@58$Gu$!dfg86n$c)|Ymhe10saMWK_|}JZ)p?73~PkovI^2YwDe5rew`)iNgXK) zY{9-*lhI6&8uZ#Zxy*em2Cf0FYWvPNePzH_Zp2{CsrnnmSU7_O7qv}~rFK^Rw%vmH$HEYd~z%fm7(Jsj-_B-@j(9-WU@AcwEt^&&&6d z=z{9nE(#wxkl;w=*fE%I9*mx7ce>ysap!zefoTWfFOk_VskyyB?C$Mtk zC3=1wwiK~XkDby6anK*X^tT(#tveoWJhNWl>1w)2mmy6ao00}^(%+>6iqNmhXkY|6)KQdcN@U+R+%qAVt&A_>0*<5>b6+AM zsZMn!IH3Q2PN&dCg4@#y`o*s~Ee}b5_eTI#E4cGppPcq`zJtKcyH5*~nzvy!_7j`G zDSe)8cUgb^=VgEjy_KW?<@cVT8=Rcvm>hhknlUi?g&1@ozfAr0$kaI)=a5d+(_d)e zsQ$NH`zwI{uGW&*-7owO0fNcwGLE$ZN6Da9y4F$0&(X_zmiOs_WOg!yyare@xU$0) z5|C0`yx?lDTi!5MYl-I6esAC~?>SA}8ZxHnx9d`9b!E%V-|EPL8ucTCEQ|V2jF1O^ z^M1-3cDecgv+34#XgMTCR%yU~DxwKsi}z)M_mi zJh$o_ra(3GSB;^^d`_;;cBMWCbSMVy%a>-oX4-O=Q8@fKlKGiI!s9!#r>|5lr}75~ zaPPIo%=ghiUCsBw<~$1lVUQHcwKo&%D$lO{KMQ~$PnIL$s@+agW|{Y7mIoX2k1MB6 zlX1J>tqE&z?x{c9}-cn8w(WKvO9!sicWx-Rzx_ z`XO9hjCS?7f4Hf4LD~GBK=cjoy_f}2pI(?OU7UaxJ`vZ)p;V&`|MT(hw%_xrn4yLb zbAvnjI7hBg^SYg>MRg|}F&`Zff9v@54${UEi{+0=4FQ24tQ_YIF)osCrv3X` zuS%{NQ%tEhOn*j!F0QZnenSdTR^SL5IV=UFAgPlm@( z;)=e%NgjEk2O)WpX%AL1L^pi&?o9#Kc9|ZE=4JUx(ail*QaIHJNU7hC$5>8VuIqUd zohLPp5)A`tW|^9wU!b%yjmCC5j)aK0WbJLx2Z4&4O1@pD?#sVe7uu$SX5jkjIY=Lm zS#X%iR}-Gec8ngVKJ^j%X7Qt>$;4=tHanK4Jsw?BiTyj`#uHpEmH>Y7z|YImF03_h0k+!svC6wkNQ(=e<7|dv zgwL{0*eL0CVrB0cor{~GGFPonoSFRw21DPpq9Pd5vi-|mBJFbc2m8c^6=g&WDgImO z&FMW{+g=MCK!|uJPhY%A>&Wm3@=erE^cjyZvu6B^Dho!Rd9G~O?JqmJn1*U9b_D2Z zR5J20q7nAH)E?b-5pW7P)1U%r(yiIXgkbXN#bT&NEqd#8_37ze&0eEqSP$`w{i-{A9~Fojp?j_-aH(4c z6ePj!iJ&jLg?>;Mx-)3Gl{zY9_@Fz98g()Lu_0^|+MFc6RI12C8Y#3Vex$!c?Pd6! z5Ku9h%zTxup~bD|CJ5f#?ttU?@9xa|b}bvjN)r~N zWdlV=)ICV6F*1T0JATD0{t$2?KFT8|>?}qsu#E3~M07(+{h^bfbtNL}uyoz|)wWVx z%~tMvrOLU7?zf3o7qfY-RN0z#Z{`n(y&J={Uv%vkki6y{kl>alQZd1)g+) z8Q=E>5^$Y_H-9}AG3V9GJodgHGNM?+$=9-?8{Bf>Mc5bY#jmoEcO&8H;Bw zoNgVk9Nd>ouvtxlBoe>VOlTY98Sy(2;rWX!DZ~oqeE}5*@|^XaWXz%}pAT(h8mfp#yu zF$|r|WuTWSX7fYk8Z+$eTCQy){v?c1h*VVFG(5XpyyhURr#sbO;ak~0&&~Z3$#==; zdn2X|AvBGp3RooJ;+)eP^u2U=)rl&!Xl1mUVB1eJh$5G-KJr(OI*!VMgW!}}-Y=H-u*Gx6tmz`VJe7-8C-52&;S6wZ>>nHUv zSTn!p9wGhBNix2MhAab?3zzzLAyA{lsN}kBtGlHU+(93Jvz!NO0tHu)BQF94L*Jh2 z1a8pOVB(d2xh?4@5VqijOP!&xa$Ya`%b2O7JMI;%N8Zr{=HuzIoY!jWvU%#~-3g>d zF#A|xIE(gxZX-rN+S2cd@EFuW#{(;Uh8Z#OsMM^)+J0zuU7L{QuH)lxJ?%UNks+rh zp!u&6NWmX$=qr+OwB;x~5^~1nOaDmh9S>2tyMG)^Jl+~MEN;#&#Vv#hz_P%88J?(qaQS5)BX1OYU+m7LFa|Zl@1fVit`{TZTg%PgF5_QRxjba3 zXT#?5{;ks=-qmff<+LA(r;)7cUL7nTV)0x#U0rJ2DkIw;VEV(^w3u1qjELwRZIv$C zpN{@ue(9Wnru&?g^7K9prWjnn<3MvxE>?V8nx39!wd(iR&h)hF6WlxzqFk5HzUYOL zdw-7tFPZ^ZDox!~wj@-@PjThD*B36sO+_4n?9xx{1~uD*EOat++v$fr6Uj%|(cor@ za^D%=7-)BjI%O^)I+`Rh#spe% zqdLbvX$^36`!JmQqG`KK_+VC5>Os#z&9=4bizW$(%0(yRfJH@7`TRkOhy}cc$=A8_ z=nmjmnFYWu0TTV9pRq5*&F7YoO=F482nUBr9 ztiC(SHt;WK;Bk*dMixcely`w|iaqq8={j2PdIxRgY zYJHD7%n%;b*;Kk{Eq>I8tLi@|YoH9xg5}MnNR)hWC0w*ba z$1gWzwaeAt*QP6=^-!4;g}}KlW)pfDSk=LBpTpppmf|EhvGK;+G~B?SZlyXeT+vyy zI3}+$?l2x=1-KF})11s1LMwxF&}_#ljE6;yE@nM=UP~rm3BWlAfQ@7eOvz_CO4V0F z=J22o#9T)Ly;|kRVM(p3y*skL>UmvPU>lzrPEHS-pr`HcdO=Q)FJ7|0jAqJxcyq(< zm#9O@9?EVvTHc)nrohDMBs$hSxu3B_euvCW9`&d;DIE|PP&=^5YWxt?Mb)uXJxSu#N!@J`@4RKQ-JI8{&_2-qjH(VBK*Ij@&**Ev*y4eHk z-oWm6n!q_q8EE{ejVqXK;X4b(|yZ>;N9*gy9_|!MV5@vyOq%(Jg}?o>SoL< zd`B3->usOZ@BuDZ=+;HhqN{gVWvDoAlHKBLE!51$+~Q21RJa!Bqrv3eZU4L_J-Oaw z_*xbOdzQ+xp<*tXMdUVD)_VJ?H+Xxu*TDFyOZR&aV4A%!A0VOKJUpr)Sj7ZgUG5ox zJTrhgjNp&pw9{^R=mU1v0J|?aHaxuh<~4G<5?RbewY|4b)m;!cP=F7LP4=%ngTYyc%qV> zcbR~G2Xdp38Qe04D!rrJ46XgI9;;9G*`1BVqE z7=6C(s^0!zm^^_XU^J0=~bqTQ&6%?R)SSzx=Q9NUS*eCo0c-ppy+}_bNN| z!Pr_9K}=xTj54O$)far#|Ay`OpR_+sYyS*&#e}TNr0O45H+|V15s@}9z`Jbt_HMa3 z4`MmWQ*()^vA8`%qf{U^=S67-B{l*`%5d&!`mennaQt6p5JgfkfSZkc(w(|c2yeD> z*~MBc7D3%m=AjiLopV7cG8p5YcIo2%5UiR;+1`AuRA5yWt%7=&^+T;}bJ8jyRObi# zcf+{pnqcGB1cs|;>@$u4~A8~d{nG& z4~Jy(#nprS#x2xKyj??zJ42Ub7Gc<$-3g}q!9%?o=4ak@OEj8c(Bnq7&-55Wpy)kF z%WQlSo5RmJJlBE#zs}Vof3rw!`Lq%ZRT*=lJhu(oN!54#=s z=F@22Mc{aNPX{3BTP28YA#M?`a;zma4Q!Jo$urYGGFJ*^5p=kpKV#u#lhGcY@wL(8 zLj%tj_<3#jt%MIqx?Wi zk4L@hvkRMf;wV!_Y{XvuDmC2}7Ft)@* z%G1aAe)|U8utu4=t&y8DKE)7n#Y8=?iiDu-@$-xOoK7qt82x5vm=f`4O~8=-ZkO`r z#`AyOb<77l;B1Kk?Ma)Q-dr{w{C-8}6IMGI@d}%X)SojDPkpCecXZ@bSa ztMG)yKi7w$i+S&vIe1D1AHt2@did;9^tbFaCt zm)W&r%=x;_RP2wx`CF=|@S`5XurdocUVZn9}tV6aYqBs3+TQrO8M5Zt1fe3=u2lJ zpz6qoKfhzy5WO(5gcBHjE9JAXd*i#xB>2Xv_SV`yWK4>zVbRk87keb2IoZ-aD^S3| zn)Gf_ueSrR-}g4^7HHqGy_@-QN)*2lM1N!Ay)!T%Mt`*})zQzO%A-4Hr1YqDP=baR z8I=y6&}p9-`QdZ0CfP?LnzhZV!s(H|ezgseUKJI9ue25=Q9j1h7rRFf@z>BM|N1T( zc0(BjPfrdLmTC8UGAnO$q-iU`n_;fr#E04#& z!IRD&lv|+>7t)Xnl~Cz>3M`}Nm)_MnY8;%8NC*nS_lqehy{n~c>!j-E3wZeU0?tV+ z+jZq^(agRYwPKpdJ5gg+eSo66;+ERf7-8mu&)5Z>S7nV6A)b5DVr1_!zdQxH zp=0@DC#Q1uFBZq79;Md9g4W+`nhCOvLpRcDBoA+EN97aBki;80j>7@~oU#HV=;1O^ zds)*M>C<`nbaJoWZXP398;Gng#cda_g88zRz;YYrk+5Ym&^3D~mpiV!erSBd-p3F) zu9VCaPsV=?{06xnkLTw^pTPV;^9xri6Ufx~7|$U1bEWwvm)tCxkqT!j8A#ZOLp5P` za~BKKC+{15f!#%?Cd}Od#;>YTXb4PtQ@n|cqtlyo{g_&K2J7xEo!uIPjD-(_ZTn3( zyn7vHYDXs4zNTvm`)#yqk@+iV9p=O8y@^Ubdw_Y^Tfx=7j$2BV=ab<~yNU&0wO60L zQMIyp+%5}J9lCs{nQ_}eV{;?Pi2A5|x$TJ-4S+)LDF^&3X3d-`q>}a=U~gvqxaH^j z?6zx4Jk=G$0kY5FvgU>&Obg0ZXGcLSxTOoq5~*90i%KQXLd?g@A%tQWGjvM+m;JUL z$X`qHd>!bN8HAgZ4pM^%btc&1zRON!DH|I?Pj20$xxxw-%TD%+t%CQ8DP1=N<`462 zdaymye*4U6VBDvOfM5B1TnFAg&-Tm$j5FC$-(84xMzN1EFD2 z0I#@q_9X}j2hqH{NV6nGPNYS)ixcSRE9rEU#=?Xln~c1p;mqS3aorOk`c8w(DHr3g z2qgMZo+;(|P8zv!YYrD%;`PIbjV45B<}VftqFr^uPeIMZ?IgGHa+B7zmY2SDnQ0;=;fAA6I+jIF5Q`Jr48{;rqHyXz!wo&Z^37|xKf3H|JGJF9k}p*+FG8~^=dSq z^H#E_e7l;?)#U(RUtbe8_s9|*R5L!wAH3CQo1!+|<;*R*s*ws!Yu1;fE$r&%rKSQdTn+Y(jxQ*C0Yt7wg*JJ6T`#H=0KH44z z4HkTJcE9d5V_YM8n|-?JN|4?3gxFw%TV+xjX}j3Xz=7^3O&>7(oii%irx=zyK5=pk zAiw0d!1lA=c~J1iXg)4U8hlkg0E4tXL(iMBPCJj2)WmyIOjq<38os+(mHk)y8hS+i!P`p7bKB2FohFcGHN-%+NmUBN3W<@dE$l zDR4spNhOqnw*9q(?$7cm9eb{@18YM{vP_Oxw>0tu+%nDo5;=>XmnHZeuE*iVF1JhH zKDCA{VQ-PV=?H=6h2=y6Zz_BHoFB~}4e~wE;Wj?(r9m=mQo8nxo7hVILFP3m2Byk3 zLAE2jHoXqOXNF1tz%uPjXdWi{RqRN>!-qb6&Az*2qg~#4KtI#6<^kOM4Z3nXPQe%J z;FdFPdX^R&%T`R395g+B3{pUVn!>sHd-s04{E)>> z^XXT@;dY_Kt$d0di(1v0_{@~rKO@uV&LhsZT+HOHX956A-_z`^Q(B7Fv?jr_ z8NK`AkbQhNql=%$YYoJlb<02wH{sMRT53D6O!y2IGGM}P7vC(H?o`%k^<~zFyhZ!) ze|S@+BYs+~X}TYZng$glmGj={40WgtNZ&tW%MKaqS5`@Tc#A6vrB6D>Hdc2>_!HFD z$$%nGg6k>IZERT#kXQ!vM{J(1`WIM7&8R6cqEYnWU33{kP8yyLWDXt54b5#Sx`dj* zB87mj32STIpb%Psj^*cf*%3@K@d@~7#~rJh_a<9G(OwcJB8_WDGotu7PSwr}vCn9th$M~rbNCBQt~ zqk|lf$_j@L7x_nhrSSm=>S_(SaCKAdCak_zM8o)Lo2C)cZ`E)5MHr=@k$OLY)^&5b z5a_rBbqI0Lin;cX(zrOsHZ7o^52*JRfLZ+#u!Mebj}6uKO>zT@Y}jgc%!b_FIj9Cu zHgzb2REy@%(r`k3{HC{629k`CSsDW0Upu3vNTSvTJ}m(#;{c6ShSTlx%qi!A8k~WU z2~;bU{XyOYK*e^1?WKp4&`-}wf?KV)YlHi3lND3k<1+SbWsv4U$-dps37I0cQgY!g zxc1SlVJ5CK+RG{e3VxW)CgfFtB~*ytPJYl%>th{{V>-@RzHQH`pczo`gRsbN8kPNFn&s+VIOh#p(Gpw}p1n=++-A!1?qNrcDIH7hjsx%O^W$dSO0v~= zY8_Zt=*!7iN@01-_qASOFsn07W4d^7V{ez_y;T2ibh#j-VXRA41B?0 z4^d49!b&JX;IsGcL|6@PKJXnf>!$X|H)d$fzK&**G-;!EPU%@5CHY7A`BgQEGg?ND z9+0^Co65NIU;Hub^ul7aTVquwbW5Moo~fg%AgEZm*&D|YL!oh628O##RqTBsSh-i)#Bt9c@ms&`n+LT_rj1r@JlAfq^{*f7S3(0 zVM>lXZYJ~(RDG&Ud&gSh+4k#RzN5JvUp^a1(SR?S1l)H?KH^wfT>JQRwNH6SN4~+Z z!G4(OkeEV_7FHO{9dt4X#C-F2mQ~(}w<#Ol`}-EVs|~YYAcSUopAhTn@WM;+Qyg{h zF}XFaGLr*)&Zkvt3Di_x*8Ez`A^YMEWE+i(3?!@Vo;K~h7f|+Qm(fr&WD7EXowu#gq%7)QG*lw7W?S2<=?&x7pt1S2zymc+}N@yS)&?I4X z_In7Q93%MPIB;yq`b_xU%05kFPyFp3x?`!NX7Z;$kBWfF z#i3gX)_&~gw@y|QG|#T+?0E*%Ud~=z+Wp|fim{!+b1I=c;7Mvh3+HKb=E$tH9FuqF z#u+qlkMpjN&E@#BcY9<`cGrkB7ogCV#@lvi&1;aJN%c^m*4`8r27Qn-)3`1vh57yr zfgf#JOPH}JMnhZn{tFj^)2;#CK9SNw0ag6JRAm2n2IK>P-iOhxVhKSxrDCGKH(8BT zBM50>)~Gx26BU#3Yg}$i7Tu4f4VQIvWBW{?!&)TTTp(PT`SsX*|95KLyXGDgTl|A{ zlJ6dzdYn%&DzAdlU^UNLk9B(WpmJSTI;9R>x;Bh61V~;?Ma%`!b@m*C2O?Mj`29h0t#7h132*#ygdw;9>umm^NM8n2c`^_u{U_axkvld3cq- z^4v|#?wy_HaAx$6FXx>fJDydD#ID%3@x(Up+;dxvm9h11LnRrR0vC`Y*3;IZ$d(5G zmSQi=8%Z;&grua)YrhnP|I<<@vy+e0+fE{y_7 zvSvxU+Gc5{`|O*_A1n+c45OEN2jDT8YoDm^)UH)jJpO#n(QdNm9?7Lx0L3XBx>WW( zE}C_BRA$@EYwdlec|Jc@YoM0)ygQ=uJ7lZaelzV#iC6ZQACJ2aUU}X|OM7zYypK=v z-(M_6y1fS+e{}?DfO%MB|@4Q8M6saVAIsYI1G*em0=A#bgqjKWFbn>}( zzM#+L*AG-gAGfJdc>0b$_xlwIKl+p@p}LWu$gH0436k>-tyYZ5eBR>l&M1 zD5Z<<%|p3|ZI|Fxt75}dt&L^hoRALxDyAC-q!(bmrnq!D8f4JO?o!b0zBp}?^ds=X z3Gkb_Vf$1YfRweg8=j5!l1u|N76Ct|t=)US`$1$dJJEW&wGtAh-E_FZ)4DNe6ngDa z6>&5Ha!0=ka(|ZVQ=pCgFIPtTbneiDa6pODU$L-*>Dfhd=xj=LmM}#_6j_sk&Kd5-M+JpG91Z!>y456h zE}|EMoT#GOzTVuiCvd8CkK_&>jm3_4g7clXP-B4d==)rz8JUJ8HG#c+jjnO=`JYtTgl_xgc}8S&vahp z;W8+u?hPmUWoiaNTWOg~S4?$R1A?W?1xGi77nQ@zNG5G2``{+ko~+`m7-PWus?~&P z=y8+cK^i5_G{M^GM5p4RCLPjx^MHiB z7>OF$=Vi}e?Ed;37ZU@PFnE=czUQA=OC3p=l;C5$8aJh9W@a`Dw^(+U0Mfs&rRwQj z{XyN~4-xAz_(F>+B(Xj6o&MP20&Y*6&DTE974=*fcyi@Z;1YvU1;m%jsw=Pi(t=B8 zad%sY-QSPfK4vfrQ6_SG#Pi)&=gi9HYhQZ!Fi2<>W&W_{aWz<_Sy+Eg(>Fr?llQcp^uYxyR0&4@f`6+KjxY-AzD0kg z6qV0=FshAdp?i4Ht3P#(EFQy8I%|9Pi~U2^<2&qsFCFJ8O|u6dn1CR7{l^?CldXq~ zw+x9*MiN=EX|yT6lVnfX8E5dJYQ7)g?K?H%fM2(LrccBzY@_6K2*(GFRYMzO&H&B0 z+zHrTkK_tbb_xu`25k9;EYULd(~QmQCtS&}7fq?_nwsk~z?nyVT=uXGa103&53 zSMN=YdXfAsqk_`@rZJ?dhL6>Vxd3qtZ&$$96aMu%gHnO>*(co{nj(&wLkur~XIiIw zUF^{M;Kvu+#gkzu{(-8;Y_6Ot@)HmE8h|nAl%scfat=n(=jV^<&cOa8s>X%lpHQ z-SE73m!u}u+vU^{RBaVmp7-^1_TplkXmXIua0PvVn9QZQu-YNep20VnIGss?toUHCj8z?-{upPTY!HT@ zZ$FkiPx7T>7)WdfJ=Y79=htb&co^7`T^JR$PotwQ}za1S*cSY7o2l`oHhp-jN)@8kicg%?5wCqY^n#US0f1yL&N>X_o9)Xv77pe@B^Q(~}eGB-)j*<2iOB@)! zOs}y2b10g}D~AhcG*@ab)*Hiin5j&3s=ac8@!_! z2Ns@`3Cud;M%w_O9nl{Xt4Qhi(&j*%^bwZB@g(8J&cI29(ZxO4crVrgYQHw;j*0tZ z&}nHt96h70_NStkke(12Huzr>SR));T{ROO&leB`{?vi36)@5~cVH!dlwv>C-L62o zXBN6-wcNo664<^!Hy!^Ik6eUY?z|Vh1F&&Wpu6E_o})cczN{jabQBk zd6Ca$=tSpz{7z#15WG0Jp4dSPNh^nFv1zG)%>9?KPc!nP3vfU~ zucFQY_I@Je(#7CX0GFA-54;iBb)#P4beo^)n^U)Lr3V-9o%|=HP1L`)UYH?i^bE>yXq z8{F=!f|W_vaY0%Q?wl~6SMIG;k@0a)SbVfQC5x*y9(AQ%)}A`4LsL+$oNv_mnh?0s zaGe518IpR9n-0% z5?O)zq`iVj#@je7fIjdQ{%0*c;L7&O88Zj_Y52N@dDo0#^u3M=-B;M%%Ie&`eAZf% zViCFCTWT833V#YVorsv)+OBpj&)KpajUdcQ$!qf~ znfEwe!W3#`vDPYM3Ur>It#vyTCiry^YbP1Uf1W=A926GKKt^cZ(JKIs&Ssac?GeUr z#ke`1)&0}S1k4jx^R;45xcYtKj!xLC9E6e3jT08<);eW*xCgRBPMzc81;In^h$u71 z{PJ_q4dVkYHijWS-_q5oLBt2A+!}p%JiI#mx!~?S1N_^vHJq>Ki2)A*95^S1ddJ|u z2$X*94p=~L@f86No|o9B)v3NaNCTp(&6ehmDOcrgyQF!qkMQL)4gFr4`N3CSAoKMG zuhph1_c`Tadl{M%bTvYQV7+*La^-x#+2ts1R)i}Nvpt=SponeM;KlFX3Tj4g*Fla3 z_8abiK5X``KQmqX~`&D1$9lAjoLAGqw9Pqw~#9SBTcm3>s<3^lWIw<+^VBr>*Ek zZx5064)4f%SzFG!9)%#aJGmrhga8_0bEbxH@!OalE9k(zfM{$xrelFq+9fS6_}jtj zarn?;&lx8y&Y52frF`oBdud=)gPIDpwS)f9$;jTV{~%#24>q)~suL7dU&UB-fiH~= z`$Z?4^`1Qabwe$`z+iXhsj0POYo@m4%Nd zBA38u-5L&c?xht393w3lSl`ykd$uKT_tigm=?q;H7{!jEASh2Urz-;G>$&ZB3n430 ze>`a_%X63K`Gnc|Z146M?=XPMKpMbws*WwdTM=v6PhQY$SBm-oqVK+lcwWXK>R|P!5(DjOsP35NIeLfv zPyQ2AxaiU)jj!le&2?-Duz zi;wfwnwj#&N3db%E8bIH@J#9ltPk;&0jwK zjE~nv64WoTDi(XK7B*upS-R@tER>I&ol^)$Wh`WeR59po(JRDHDER)eG2Gg1_#kyR zb&RtSdVXm$)o0HJV$Y7onFl}9z3#&3kNvHHE6L4uZt;4D*x&tgL%w#P+4^e0qoAD+ z-=~?7rrlYo0e(dwbh{res~IIqw5(kG8rzp=CV@RzKj4_k?@5S`m@j8OqgfpH%$YiTD`&~CQA zs4MAMsbdUBsb5r>j6|6XplV}ZhhpW{pFnionS>){c`I$C9Pr*k?;F^M08*7!xn_SD zBB2z)SW+OTtP zjl1RiSFcoQwc5Z2_>ifH;|DO#jpv%%ah~lM+@icx#FF#er7y@G8)E3=6xvsw2A|^( zg^~P>wfCIMf_Lb8moZBdw2uN@JP=dw`FRB;{%*FGrF(dbF|uU~UBbs3J7@Wt%;`RW z5|^6Z@U>7+c1F@Qem|byp7p)&RVQ7OnV7F>P0hXQOSFYIbdVviXqlJ(yRYVR~r(QH9jg>6IwqBRbm`3c>~V+*Hn` zeC0*d>`(h3swck`2s)-F$KZVjuSM3WDAEV5{Sa-!LF+f>TZekD3~r}|Wb%~m+dTie zKbRJ`BojXOFD~#XdrI;b&Zc~DQMm^t3fSKN)9$>OL@Y*RHMFzTFXr`aK#^ZPkz+<9w zo6kOR2`Ah8N!Kx^+& znwpfTEB9E$^K@n9`pJnGXB)G8Nh+-;-v^G|bJ^kggT}n7L%Soi6hLfo;-E-7mx8 zYLFi)F&96XANxZrQ8SJNdWJdZ7A3Cj%~Hw-tSm`;M{e`S7JJ7KCe7vzfngSk3hL#s zYdod6o%F0u07p()QOuLyw?EKUucFQ#{V`9V6_fCnKGI5o(ZSw5Lck#RSNnp)Sdb2F z4Z<9U*opm_ZH?5*yT5J-^NICeEQT7qr1`hLdy}&GE-sGrc^vTt4X}7%=>jeeSbMQ~ ze@=rknzn&(Tj@#L%UKFHF&G?1J^Aj~Y!_kKUJ#*)!lfNhjS~H+4fEHRZ^hpsbo_Xs zZn>|&J%nNitsYj^yE%jwT(miq8;}i5WpkkRL5pCz1nz!JKxdr)E=H>jR% zf1gZi*6b*LdkR!rnlJ&}+M}<5Vfg9-wfJ?@uFO4G;IW@J4D-3qfsfB>8YlJ+nitLm zkDTCpMu_|z-=X6m<{!L5nVFA6;YMe-pPu%6ikX?`btyWE@aN=g&PbH_67iwN*u2KK zHjtbSKRc%V!rZOTF?3TXqNwwlg1l;~(_Bt@7;hF@)ek|ka zoA|@8CV6|(>*Pus>Ds`PCCzifN3F4kfy{<~p%>U?Hm@6E+MBRGkMXpvHZC$hYe$y) zI2TWY37v=o#UK{`%Vt9D&$OwFe8qF~b>Mj%N-jwuE+fKHq{C(h4C>D8yaAkJ-h2~s zgCs-@-5f2W+q|ROmk3hZ)_ri=-nf1W?C=@Z zf!t6>6;Lw;iES_T+T(uaj!7l_xnw6!X6d@jZ}sp5sR?(eg{N###1!I^n!}yz9?oT6 zGSx@YtrY47&M_`L6Bs^mJ7L-MtJEcD-T2_IU8()Ta^S0j$d`#6!hYLB*}gcoj`S=; zad9Vpd8b*l>YtU0h@@<;zbRmcXZ6qrE+}4XI9|!{2fr27+FN5K?(nG3xva=9`%XMo=(nP{jisk(Q}I?&je>qw;A#Fc9sEzF6`45sYTjVg3=^zR+Pc1 z_!RB!1j+b|(*J}cH_g?gsj-qxt0lD$-%=jwa4Cr&eNrRH&6?!rOuLM`F?NC91vt9m ztlpv<8Y)z&Hz6a=@}Fe)S0iQpeNmd9;Y&_DyZfz&?OV`;M`yyWamEu)vT6;P?%1p{5FD+9J8bbH+5 z)3u9+GnhcO>@KB~$dAzE7tK<3>o&#EB1a=XV-)PIbDDKE?*$eJh#bZ4yi_-g+RH!7 zC~ZyBxscSHMHt3Nji)Mz91S_l4}w9fea)IFss2wCPWxh8(!(#;xIBU4TW`F-7`(VH ziBxJ^mlEQfd_YhhAFUfG*_`zb6Di^;07_rAlYbPASD}I#jGg1BrT{Q zy58^b=ixtuKM}wZAiaFctOP-^IE_5j=&x|G=4b8(*hQViBp$aL%2I!(!E6yFyN@m$ z`IpQ%I6!^z0q}LdAE%s_`oiwt(*BQL8We>nRZbX%P~PIa+@9pY?vaAb4Edva^J)|Y3Zo&LW>0qhBVy9PU?eDPJ(!}!k^R&xbSvShd*ydK! znA&|gE_j=R?=*I=e$d&o@^eBM_-f1%u7gcoN)L;9ks>& zYfKGWKZx2WIZ}pM9p#V?=AN0wO6iYN@UJ|nK1}x~SLbuLEH|7Vl*UyCxjB2TeU9L z(F*Z`V5W?8xAL@}DL}ImdYgB_{No0Z{@Q!Q=&-d)sdT=_^Eq?&G>MLlBgm{7WRA-2 zULuh8Dv$)&6FGULqkVLEZaG$f5pJOz5WUkQbQIf0FArMN9w$AVx(T0%dX%RT(d4Nx zF6(~!bzw$)JV(5#T0BVp)KhnRYmLj-5~S&Kz*5ysN>?fHwc+gPP9m`*@=aJzA;-_t?D zf5IIr0gaVoy+(F3Tg*mpSg`z>sz_(*R;#Fwpi!@zx=$ z=M>C-j~w#dxEcO6V(+aUioSmQC4L;FqI^6@9U-asst5zL-^7b!PtKb{8Ll678JJh4T_j5@GwwykKE=mx; zuq}$2O}qndPK5feHpGKCMkL&$>$_Sa#*2)n`?dKSxWu*b?>5U8cSXLnxrf*+oH8f; z^0xt~52}X~VOL8F-G6f-w^7hA>C?k^mdDg{zlk+a!SE)aaPJD{SOgiCpNo>(%e4$ZWl^4|9Cfa=<+aAm7<)DN#?a*PG>S-F@J5Qgm%!f3pu3=kR%GAJwiguCld3Ol|N+f(M5Q)h>ou*tOCg%DAK; z`>*o%^d2#iuBeX5O~W^dKIgkFiurKnF=I@Ke-rMZ7Pwow_(VMC;bW{we4N28F8E2V zvy2eN?8PKU@xC06?yA{{K8Xqt)y4B7app&<<+`UQB1J@W6$*wd@pa6frO56d+;*kr zVb#5(X~+NJJlw3MQcFbpgeVn*{%G!=aYA5GKyzOokCl{lII7{iEivIcM_bAVXWw4!CvjJfM^kHa@3Z>_op{#Pke=L#S$M%y?sEKFnQdXRc3d1M%ty{ntRyX+ZK98; zkF*v$n0(2lO!$s|jvr;H!Fa0`vWtL&Q>;zP+=6UC>-Y;;HaDu#mz( z#BUdtZ@B=nQD!yBacAYz0fxg7^1YI4O5M7}0Thi#f(eHk3t`kO_SH+kN{KmQT?Eo*%p|htI zqbFihZ-kg1_uP5Ec?t|N#=Q|N+Dzd_cUzso(SAuY{zK&h?%Xb~L?Aj6b6)0^)?i2`2c( zpgfjSQS@`GeZ|0QyjEAfPfc=PZn#s3f7D^o_Y=8g;qb+3j&;ML&^sb)`W1d8JfI%- zh$lHpUG|NU>TQtxLP2iUUiVbCg%g0|hFkbIV>!;p_vgiV!c-)8ZD0scG6ySbAe2_7=v!>cYg7AW_&m!+Ec(aly2%o48L-_jIbktfE(;y%L@2W!0uu1WDfTSuJ#zgd z8KlR0?r|Dx)8$u4*~G7)1HTHX4_t(wZqb50Q(X+BuU~+g8AOwROysh0e%BndE=6-L zzEl|oRq!Ujwx14t9`ckiIM7Dz27T%11gm6?7I|AA0Z$K#bPUP0sVS97?e5n5=21%q z2dw{CQ@UPh*M+d?BOsazM+apw(<9p8mN+~kbSVr0JThGg^ImQ}u1hWhDROiI81o1p zfU~DGmh#DaqvkjGy{3R|QI>#4_1;n76MnR+3Ig$5Cy>COFu?9{y2s+gG??~4o3u25zSGsX~ z8O&lBcMi9;>+MJSJ;rfM5D5_wUKPn^hfu`z^U_=X8VvO=Ug%@#`DVMty4d&I=y=|e z;4p-74t+m8N4`5xs=-QE#%-Ltyw7~rR|mfS(=NWx5db^4D$~g$uwk5cl0C!(jyUOH z?C*bgD`DYpZQ@ZDuzzpq?UfG;Cc8jSNIJ{+wi8lr+Eb^Hmh;+_rueaqpZrK!ySY-S;Dc^i%Mz^muVNded^%v#HT77_#t z(&S0B;D-Cq^07Y{l+^>!#|{pot_i#u#*;2W7HmbUU4McZRq%S$~-=gJp`<*K<3d|*aez>neX z2XX!Y@KNXqZ_Xkx-q{)NPjyPrT(PXPSh$$421TZ1UX>vwZQlTruoV_J60L?)0@JsEm!^2v+nlN{5bc9)}(H7A!(p9@9q2w&%n z$SSTpPWGv~bY-gR2y1o&IXU0G94q*<*iBnLdkeZ1OExcc_5CM*e>9>q*97h@cM3=} zEuAU;vKdGgUdaJvO@V#Kd6-pwGRcjqmMo(+mIn+Lvqh^kz@^u;F4&!Jie z@q%$5xL+vBgtVpaw44%@*w3xMqsuyfE+NJ^NfLBriQ}CzeHE~}>pm21g0B@=wbEbu zgoQ0Pykr#%hmZaTg0R+b>1ovkySZiosHk)wKf2cDA;YJ`)wI;myDZC}SR7YtxMS`z zwG#JADFH%ph)S-U@heBH=+>5-z-H^KSuF=rW`+dPt&xMT(D5`ZSM+sDgFyk(o*`MB zAWBg0Q8=vWx?7Y&eg!xv!L@vSPM<^@?yWzuF*CqBh|ZOM_V@HKitQRdrOc>!9?i4G z;Bvsmk9F84w?wFNGagon;@!UAWhm-ZWKZR>pDVy~*?->NQc*+1PvRr*y)V z=`hj@LDMsV6bH_Vh4lf6om-QXKfi+L3D9JB?y2)jSGTbyBHiY3<39z%v&}Jd@-MW& zezgMgSy20K_DeLcc(0EA?}Jk;N0EDZw}Ja>U>6(BZEQD>^IF-YPgK>^N}1rv_oq39 z-2Iuh2))`4Jq?42aOIG0olI6f6pUWo3Fi3z>DV}ymKk;lUMo$v}H^Xq?|z;Z}`2mz6I znr(p_VaC`G0gX{5ZMUp*7C8=`fTtJ5PR$RzkV8Hiks14*6Os8aA+$2ij#c1GxV!z2 zFmpV+A{CX)wLfX!G2UL#*7USqunb-8P0`>>uK9+8l}c{0!X!^P&?*Iig$@mR>#4=% zexRTOAS{P~)JORAKy>?1iVr}6B7X4~ZIx%wE^(SS|J82vPg6xQNY2gQZ+KFvv?NMhejveKPYr|$5rKVwc4#cpqgbVeOW>d?)t&}&e zhDqNSkL&D(1-i1C_)OYlhnoUzexUn}a6aF8J=rf8%^Ql7|9jSR$x|ExKj1mENJ510 z8gqT}deMtEsJU6Ju!BNLGMCGI(CAgpdAW#v^ z7iV>lWq~K@{6}4${7)sl7-1ywBQ`e<)qnH_;fCnnbL;wVezwH(a@JM^J1x9I@G4Ri zl-uw3ST5&fu|Bfk9rDlOoVU)M&<=*@&p0xHbCxI+s1bQBlF}c?R!$;YDGZA^84fA6<|C>&L0g6{EH-^UtyV-OrFPEhLY()~2O7qTx=_?TpBnu2{;n zkKgsu>^iPM>&EbakFo1|^=GSu08#ro!B7@;#jhE1r^KKyX{)?(>jHxd*DdbC^o6kM zO~f@`eQUK4l=(4v-1J3DAUzPiK)?RjSTYC*fl)~@#<*6W=EvtZ7FxWHhgs#-m__&L zE55NsRb;VU|7hlLgdaehIxslMUg)qv9TRa=X7|6Wfm_d#7oXKuw?$aP3z-22ljVcj z`)ehDW^int(XRUimv>)A)q8F`?NtX1C=Q0Ea>P4IBd?2-R=#tyeo5;skFp`GpmV=4 zyHLGyxG5biVs@@4(t55na_h16^NAe62Hmv5boL8F#}~E8aqDR3LP&O?MK~mO1}{mRtabbrAP{ z-5fj%I^L|CjiZb^tUwE+oz>2HAW2*g7SH4_G$D(y<$R3nNNQHtm(Pmjbk{o7)z$kU z73m_*6He=_Z^pgc8Ii`%JEg#P+4(1^p`wje*$hO+wZS)OQcK0#rV}_!+meDHOHVNX z^{KJEDq!|+fGZ>1DExyg&ZwU^Dz*<{9Nv5PzMUJqa3d`bRNpa{ z8&v~_L;p0dDDkJ(smizRhB-t$JhoH>vq`ZZI$GFFeLDhd&zioY*x(}!VV72d5Fwui zrGKVbA8gBE<3$|~-kKNAl-+OLfEa&lcmJ_quV&p@kMN8N*tZ@O= zgx4)P`|f6`twwbp7h&?eih07k_hMhGM%R8J3@GP)wf~nZCtP-k-@PHCR)8XW+RMV2 zVQ)h9v<{i>PUud62Ajtb1lT=mP((iZnnEOxg{e$$7$0?-@!5X~-NRYK?2%1NGpq`M zDX&WlWkU^{1o$fIq)pVh&YnV!Uu-C(&H~i#3#`>eY-3JmuYByY_cspNL);87y zID!|-l3hCg+qy~EGsTZQOD_O9pT%A0h=cOvFLKx$s7a@>-m4{$o1Xv{TUcxuzaDvg z@5Pk>KVcc96Y%TvmA@}UZY+f7+Rx79b4gQ|zk`?PYsOO^VK%oY|gwvwf}&$?Oy9LFQr^6-?+h&zco z;J)hG24oOD3sjGqP;jeH3883jH@1HA2Q1x1h~Q_`mz4c>$9bd$%RRsSY12(D#YDX3 zlXg-=1%OC_0eqb|iPSaaoK8Eb&4!lA_dL0xeqWy{Jf4Y^LsFlJc#oM%Dryy~|CuW@ z_cITeIP+exNbe`7pG9ij{9hdh<2R`lrExdkVZT&=?YXI8f>uqK9O%>{@y;63X3Q$|`z0r24ucf=&^8sEL@|~#nLw?{V&DzyG zN`gv|=zsiV22*Q-Byz_M?%sv6O}Sf{LJ;o{3zvs$HRv?i&C%(x2t>8Dvu0=7 zbx!yD?rGWf1&7FeE|5J(i$@`B(Ch%hSP-i_EV`0}Q9LA_eL!!ubuEuuOP3;*_La+6 z%x0N8dE-O(@EHRMyK{4CaK_@njQkhenY#PsFX9ZR8#}I|EGXlTK$)7xB*j6NW3zn_ zfI1#;<} zR_AKsjcrnC#zKFTXSd$pXxO|F6b-oZD#d6+0YvTZGV)&+m>$Pvwf8c+<6#8uFWo04-yUS&+%}N5 z_GX(&A5>z{NyCYg+3h4}kWGTo0*}d1 zX@KtHwZ(Y8T1mmUQj-O|blQYHVnZ`83&g-oo>i1yVkxB+R5m^}d}-bTAIbvP`&z?}Uy6|(pyn10ZGAXlu|!`>Gy6~0QBKVQ_Y@U=mcQE$ z{#IKu#&?!O5$q_XwLKYm8{C>zX)LwILv<40R7$am>@`_Uwx)q4rsm_tvVcc4ao^l5 z^by)(!hTR8&6T{V?C|&tzaa&uC?~x!%91?i?6R3q8LX$kFR-S3QR}wmc4QFEdVeCp zIZo_6M_Tv4(62+|wrUzU-VDf|#q6EI#%9s@?n}w0+b*X47w@|#sh2#z$zh1~UYb&P z{T=+m>HN`uPGEs2!)Y1ej$lMG&?~neK)z+84t<*dPR{!;;NFePlBPNyc}>rs+xB;Z z4lV0@qzs}TNE-ZA!L~PVRgu``GGxAV2QW7XL{`M6emzcmA%WH}u?u$PtikN%dM>&6 z-3t;Y(wy@&SoL}osE%GpO1`LG7rw&h-9vOX%aS~- zNYVnCo8NLD#g|n7zENbkgwdNht?`ERH;ME6aOV#pSG^16L7Ekt==j~Ap70#A{DI;x zPR?F1`LM_O0fgvgpwyFT-h6CDz@J)8FJZ!%T@c6Ch1XDT@06bpDCcf4!vIeRx~8u2 zzhI?&y5XyeZ%%p8daoY$+1 zXpK*GIo)zQb0y^A1K+1Q&+wvr7RVu;6#!meF8F^rS5Hc(9uFce2w&U(er0MbkSuqg zVs0EW_;f~(Nnt5Matx;!E7^4nb z_r?noO985C$tg3yU)ZBOb$0xab!6Y|aB&{~`w!r>>m~Z#fL~IJxb)$$#iT3P0TK8D z0e#1bx*(ekH(y!N7yKGk%DH!{mlNjuo2$wk>ucBXHEtDnKkk(mzoX}1wy&a}l&{|` z({;+Ram2GfsgQ|w{rx@ecHR}hWEbDG9p%-!?gb*HYEeONefsWxL)Xop)Xg%(gK}CD z=U@pLjiYIgLmDy00}4gG4*n?Ek3g|=8gskp>Cc`Z?;Gb(D=0s9;_dNulF?q4!ZwR{ ztlNg6yWh*7{>&(Nfg?;!+V8kuInP%w1R*v6T}D0LphcVanw%yO*rkyb5O{uTC$uv- z;!g`l?FA&~gBLs+DK`E-=@sAjep0Jy&U%+3q)a8WyJI%*<@gPTvM<);t(teDS@sj{ zc+3vgt}eDLK)?DN%vnASU0b8{EIZ51{oO_C$lsg(#?>bN<-~YnqKbq~8l|`IkMms> z`ua~C|A(W{wQzi4RP_rR1UR>QkJGpV`rjbSPL@2;*WJe=X2BoIB)=z&~iy@m5d3{!BXWX*Q0%B z!Q|E}&xeMWTwEu_l(xjM$6W&Nc%*^rb*Xu+omZ3hXIa6QWR%=bQ+GHmVpvvPx1?U>r z)u6}qPg61fhUg6be6)ABhfn+L{`1+%_#cgiiolIn&P?o`wmRv52z?`TrE0UYRFR-E z>Ju+DBmL#(>{zz0@%IGEyLNEkVe)7o@nuhLADd-B^fr{8>w83y&|o^1NpGrF?pb-$ zf}nXkkic)zp(e+qli}WJn}E@rZa=Al{WWVvoqD$>c0$2)jIo(>7rH0%bR*C$H_--N ziRy@t7jx@%!=4JvdM6q3sk^B&Qy=^IDe`QqD0WD2GwCfe4fsyT>g7se{RRsEBz$k` zK`%F3djw*V?#62*sB*z2b+o;BFI_T{MFma7@>d8>Be4K@8>=n%FmI+kw$U)zOqb!W z!HI1*X?-{5zT7~-UFn88@&%5Y&C-% z$1MZ?iTvL)2PDE$0zL%!>P%|cbJigQYjdWb?5tu ztt$}|(_FFIX~Ol4vBRJi5qJ-7WL)>e#uZze2Sc)uPn+?>i9n5J)8fUYj0Xpg(IK^7 z)`*r3D?3Xu^UqIz<|*mZ?DBf7R11&u`Xd^KYHgby%m)=?Jdgot(Z0$6>9JXF65i+s z)biGj_q;H~;eG=pVRvxdt_*w^l;xB_nRYgTBWmjh&&Dy|yis2qij=>a8_>_(50R+) zHB!2%_134{uqosP7$6#}A@Obh*Vn1f1|F}@ZhKtCogze*YyP2SdwF+9=EtbtZtN-E z3|bO~^tuLavwtjJkqdP)@LqZ5tp)S`a<+Vo%M$ANGssEz z6zn8xmF`iVYKz&o#iRW|{)njCqz4XvlFr7FrWLOEoOlV02hr3O4}Q6+7O+fX2ktez z-NoX;pa6&6?P&`@ofKLwe7^is6}q4PAwBxV7H#qN6_kr9wf+-S(L28+;6SH*FI}%* zeT5Ihc>;qi!68J&(u|dp3efmk&*jnM8LR>!Aio6doktwF`aSNo?zux>_l*HXPTS8} z36sm&nd^Sa3XtZoGBh?K5xU!@0}?omQJeV-EJZ2oxSn>oD@+EZLeEQg%GvkH8;bDm zeOp3)NM>v?{0W@gVXi7AAL+U{9$mp zFS>IkfwI=AQ?2BH?8)u7V(njHTKR}eId5r7tk^z|O$dIz^$h#>y*Pr1&0N!yt%B>f z(5QJbII^>`{lh#0TP6q@OeZTRz{?d0mJ$K*-L5eaUraY*H>=q;j-8BA6AVys1`dZ| z>Tstn#JQF$VT^?lSK#&fwrT)ky7ymqtiGym^FYKIGDh8Z*?)k6gmuXU@^?-AdZL`( z|1=YH;xTL5xLl`w%|Z(x334V(c?xZ{{%Y%*40MK6c9@Oq+HYA=4Uc!;prkTyxeXzX z6i;W~E;=11WgX;tJpNsq?$18-L~s3c<7TDbbP8nUjD%d^)A&e4v%5&wG|qr~{a!=3 z?-*rTu(WGR^|7ut`jd#hm(mf+gQHJOfQ70*gyQLm#rZ0 zBjy_p`1|`o+5yZUX0ZX;k(gX%Y(4oB9Ma5~9G zFWfs1{94$E`d(&3-$`46*c5fxymfGEFXle|Hs)X)DRe*!HY++xs@Y4^KkPUn2^}c| z4x>8bcNJZHB)L$cFtiDmZ(CUG&Se`8sh0}lGxMYA|53RQ)<9A{whDhs-Ld~9*v50)YM~X73 zzwY6iop=csd#>hxfmogc+Q#F&h*GvQ#?WBI3%-2Nn~$j0j9)DFa8CvLt@|CyVpg#KO9-kQxX%iZY;bJ*eh3|7ysebK9Q4(8ZWRCGea`U+?Hc z?dLB~a!Ap?;3)2+78t`4$e%;Du!s@kiZ~PI2HG3aI*>e+dX29ERVW}Bhh`^w5c{M= zkeB~=O+dpbDdk+f{0+fzPkKppz`k`Zg-zo_nyi=k`&Fu=q{o>3UK-oE-cW7r-__(5 z`S1^(`P$<|TU<U1ImS3*M_p$#wulUhLk=Q0I6Ot4d_DJyekR~c zM-`^H*5asgozT5}Q7U9DvqxcDW({#9I~+=Bc5C@@FAgeaqfCzaMSBFb-oIDvf}Ldr zK@8C6$yu#$i4$q|9n}cEd)uRels&(COl=A)Us<`Qp-%IdFp-H~vHrdpz_cu!-N2zl z@~6mn6UqLaXFSmT#XmCMp+%a1SeUu58I=3D-H52~X*Ssy;i!EJt9 zi(4OD(bC)4 zNE&VOD}tR~PE%Y|2OB90Lu!IFZp#N)&3UMRVah~2@UYGCc3t&`zTvs1&js0?#*>Yr zJo}?XQRvVm`cf87(_1{Zsq1nd76*?!e^h5kzBd4qhyI04asQw7nqAz{4=ma3u%*I7 z*Vf?7luzC9H!es}dfy8W?`(~))O3yZhdk+oK!S82m@&56Qbc4;=1)n)Z9XTDBjA4--4;JJK%4f z+miodU+a+FXXm7{TflJ?g*xi@~ULq-?28Vv6zNDc#DV1iKOP{ ze-G?O#zaSgKisRGl36|Myr=rIho@w}!E;zu9-(Qo>%76Hx5;DFnrD0GZm!}X2Iq%- z2nP0d=N0#~2m^wr1oqw?PP_CB?qZ-&vau=s2-x=G4n-4eeS(0=8L=J4<;H!xR(8 z@{p}3+UiMuL_Hg1c7wn8orIeH;q3TI*t(yq74&Cgl{#rY-=S<+W{9zj@^hJyEElR{o&|B=$^G#c95dx$?s0$ zx1TtiODaYWsehU%9@1-BPc98`^*lgl`w_e_IK)OrYU@N=k)CycqSoKofd<-y4BSS4 z-Pk$b3EdC#3+gjDT1ZM=d=aiT>MZZcwDz7XH9kmd(6WUiT)pT^Z|&U7n2KZ!DQ~5# zEQDvJeXXPRmx?DO-#V)AeL{uuo!&8Qok}?+L+Af!I?J#o-@lC$3I?H~g3_XdhzLjz zhVl~x1O%jGgp_nMU>k^nNH<7Kl#uR@Q4*sYHo9x{Ml5*d|2Uq#+^fZXU)Ob?=lT7d z*=W8rKPz0Q<8Oxt*gE_8if6V2^?+36lyor%MZ|>9o^8F~d+W7)D^h}eP;u_(yXGN< z^_;tHrd_lbETcLjw9SKI1oit@S*!Olqj?%b5OyXQ;Pzc?OKjN4x{U|QQc(66KDln76V_pn zk-%EO%*Mi(#cQ2&gw0yBm42mPV%=jIe|nu^sc>HOQ--3bB6%HiL4wx0bG^GatyztM z1ba^J)>OClgbMo(cRS?cOOsQyH%k6bnvB-oA>SLk% zM{U38f3DKYuN6OUdS@?qUWk*NFt(QL(?8Fwz@z>FN83){qu11o;f~Q&LY!%w6+k_h zAyKgg@0pOO4TGmcv5EANjK#%8ivCANjYo-gloN*TFw~L$u-ZY|yIQE4 z&Jeu)>hA+-&dzLhY*s(5z%fZ0vnpS){RB};dIsDhJu|xN+!HU(wjm&Al6CdMp~OS{ z)-;5_lr?mt+x}G@ACHZtDrxW%yKuQr8-1j+u*^6y3BQoQGE28xR0i)+W-~ByJ*|Xi zCI#bS8DXpI8EbR$SoRI1QD?8fJ&NON~6$q^Mzmagzm3?!?@8-oME7 zpK+~Y9r&1%TaC@wae{-+s+cz?$avo~^|QLgP&JWeJ%*|??NeUaLGf;%(F;iyDB zDov^^dcP%Lp$Ve}4^l~As{g=jVvoR3wVDxa828lU1Fzxa7H;gY<3ti!*Spbj}%t;M6h*r=YbGGcg!lCTZHY-&Ve z8x749uF;P^-=(KHFchmd0<_5=_^-&&vBQ%HEKBfLDUk*3RP>?r#8K zAumwYjUn5uQzG`vEp+EUF-hCZeuL;%_4-c9?(3_?YGAL5clZqjEX)`*7R6%01a(dj z*;@s)!wHXoG~GovGs^9Cn#*y~LVSBC3phT+S&cou+J6^UTmZzURw%ac-G_)C{d7bs zvU4tqkw#%cnqc1}Y-p3HHuB=*T45u@gv85uQWaJpd2PG8rbjTZ|CSR5*PA1ZRBV%8 zxwHH(H4RroPq4Rr#*QYH<1W_h_?{eF88m2aJ;TEO3=j2qdsOrPX}nkX@azXVYmpC_ z8qLIc-V>?@gmxEkk{twzUOt+h_`TW7c4m%)s;oMVn*ToDG%fO3w|Uq@-9z7wNMfbt zEoge5*$bslXtey0XtYb3s80d~NLUmTxsRlA*RGn0(7Tq6t z<`yK0YFm$eT*K1Q35eOiW+;DQmWOTCOwA0o`v$@JBA}3mqsG>irI{iC$OE3j{+Q?_ z7u7~9l-F*SOef`c0P%i76D8Bp?6A94-ZY~!0g|%HC3g1PEO7R(ZY^ZGtmA>hLuh-cOIl) ziIEE0eU2)-$!dkd93~i*dPYPhjA$IWBZf)>tV3C6nAjfK)VtcxCM! zACdl%Z*+MPPwk~~I%e=Cmmi}N5_)T~S!QVNufPPOG=Wh0Lc#L~^i$jtR6iHax+J%o zzPECATk{)UR>=511g5?#V4r``^J(Hf2vbyG`-fn3wz#X5);7S!1V*y(Wf~u04cFpI z+Bs*`M=PKrUGpV`hewKdp}&%zO)Xk`G%XnA4+*s#(br{;vLP5Vy-B`>qZ7oMOWH!R zDe;bufK;F`sMvO4hi%RB@q`lR-1xpa_98%vM)T4*Le$0lJGdNlJ^-@gFD$mky!TG+ z&rcZPs6DaQWxa4!=%zPDD%1}xniiUKYY8b3QT%@&D5s)+&0S1R&LO`XP| zPAZ`<>OZt#_Buk`KJ%rUe9PGUR?70ad}%T?zQWL^xwr8I;<~u3g2r?oTu|wR75eoZ z)GGm!mtLi&NR4p2EM9r1Zs|n2^>Qaq9x|8h>{x!=@e#{k{My+T<{t_s?cZFg__dVy znxa0)$#ufvtr+3K%10add6@#8XlYEbz=WLHkm9l z?nKl^PQ>yGV`pg9%4~F>w8@t!UNP!DcDpZs6!Z?|;$)D76;OP@D)=1uKT`#9iAR*~ zn^s+}pJg>&*jE;Ji=J<@{ctuykX*J)FD%!=l$kTp`*V%@F7i5=G6Tk!xtRBt+IGt^ zEKe5PQY3?BVq0?OQ*Z)|IhPf~6mo~vvoc0$Nqv%~O`hLe z&g(~NT<~5N;i0$ zqFPDb^S4wWVEd%LCY)H*(U1_2n=wkBLYd_(=+{c$Ermo&+Tj zIRk+AA2(Ztl!jDWncd(tUe?khKuB%I$nOZttSe2+3hKe82M%#b5i~4yDe3N(#ADAK zxL~%;y$T)A)N8S-b7I70rMamY)!&%{SH=|B=IOJgE7`C1w1qdO(z%PW!JEl-TQ`Q^+# zXi@I%$x5d_B6*HWfO^0$4z`7_G44OEW38hJMx2Es3{w8&0VHOhvzMx)Y30q6B!A$n zx~!bPn}7$VWMl7*jk6YT&Y)i^a~)EkO~7(wgxku2$qM0gm#^r6hwE>3XyWh{%8a_1 zJV&Qx@(>D{U_qI8+H%^Qc=QGYtLZjCw#bZk<3`nlC*T(q3-i~=YpV7~Y)(#(oos%9 z9r=ksJwXBk`doK1u>sT4@=2@@8&6w7SPcUJ z2bN^I|0DjBZgvwAKWW~8|2H4mbhOLKvo+P=g)Z^JUaT@v?>;&W`@e7fq{dC6NVvo@Btv!!6v z$!|^lG<#vMkTU@fXZ#HBX`50&=ao;=FY)D!4HqAEG}BO7yAQQN{>B{BzH_T6Rp2_` z&dG|(gJ6$Wp;F&7Y8D%XbtU@78zr9dR;A(T_4Pz)JP=EbBz{f9^5BgSx&X58lRv>3 zr^bG&qd#vZP)Pg~7gbcO+4QdZTWl!6amXx2QEI}etEy67um2Wfr%(&Y0v|z$-n5yDwoBH#i*GTxm+adq|gG zJa4@>gsP*Ks(E$KyN>=tp(-v?-O&K?!LeQ;uvBn_H(sUI((6JiTHa)g8RN7(CcgQN zk<2RrzPgIggk6kz9Z)4@F?bFYymq0)J1Jk%fib?g*yJ#HlgpGblOBwVzZH z8c1Xj;@vifl=PA(IAhvv?>z*bugMHGt{WV7Zv%OU6JldL)aX{-pm<%7UEfAtYZ2Wl zp;n$M@(N;6B&a|7(a(kCgEUd9Fic1jF2935!%_HReWcgj=}uiIh&rjqJi0Z*8(mIk zTzJR36-B-lk&OOU@zC0{*5vN*egD#9L7>>BGl$E1~#2@|!x-Bt$u{fV!?9ShsXhqdWDVY3mmW8Gl_XaL2GEIwt@yknpgZ&ZomIdHnGfu55F?2F7B5<_tT3=ewuf?^tD=!)XPR^ z4O$+CDnX*uZ~$9pB9vt>f|>Zqyj(@b&c9!u-KbCRW}aWp5wZko;gR`C!DZc~8$Oe9 zG~%k*?ryg?Rq^Jy?0y_j(#$+gOEWl90Z0{j%f@c=rQ1(H7E4*m>ZOxZf zh!e507+upB#O5DX%KXK|;P2lbA7DbnOwEq_QysHh4~A(+X4a9T2tpGb4+TYiIAHLsZ{7%;YE%=fLz0SZ}hz)VEs92s^MNyeJhVX`R2Ok6U`((aSs-qd=F;bAX*&c zheRC3GNyy8n_{A22j3;Ji?_cWeeRq(HLV2FuUufks@D>KXfD;X=FHJoQ^HLFsUefmhx=2z=SPBH-J zai-;R4P&-@flREtQJBtk?F&a7U)LMGg~Q=6xce{^l}hY|O5uio6*5>|p?t}=g|hB9 zSDPuv$uX!*{LS=UiUlQ}+^etZZ6ST)Iks{vtiAaOvL)<2W=lpjnlJ8)!I!hm8UCLI zaNa+VZGyj(e3Dn4Y+Z}*yS=_u60m|Ot>HS@`2G^9o%uT+9Q~>f&iQvq4nwDAq7lY;cdNTeH5ku` zpn|GP6?y!JF<$1WUNFj>5_h$sq&mFGVdH)oTk1JV1GQ6zlSk8&1mNe~^$F4@=1 zhnS`(cckEGjE`|ha$Wf8jKxQDd+P3tNcp>Q0(1uyzzZ>AopGBC%qK@m$BBdW^sk2! zGi+Nn(nMr4878I8sF&rl=ehsdV@r~mS|fcXZgBZlz8E29r@9|l9Yp;|!fb}J+{p30 z=1h{_9M%0WT+Frh*cG6E8F0Dd+DH*f3f zv`G|&z)O|$`b2u%3FNKUPj$s*MS?DdbJRFlI3%A>uUc3WPmMpZfcgChiqn%k#*ng5 z6O;Z0;KM~5dAyrH_d&`u12!Adtu!UstHot&Ntr}{MP`$*kc&0 zq>z^2Yi5L=a*8&X*33T2IhZR72G9PFLGdysgYvakR(&+oK`jlLI>mXM{Emrf(4Pu+ zJ_yvatTeZu`TX$kjz>PBvaPgBP4BAiq@%h>=$m&woPRN0pW!4=(s$ABH5_}6 zo~DDB?xIVoE_LNu473c6Ed%!DnLpGw|C8PdLNf09y8_(mDBkhT#eLMjpl9!)jPG!S za3mQ#doULGCNg-n^LH`bGxcRvGqCSF7D(LI7m>bLP1#j+c0eCuvdK4)RddqBXy124 zgQfm`%y^^Ttb~)Kl$cpy)^d%h}z=5(q)Fh=y@Gl^@r{04FVH)7QQ{UmPfWfProEO8P+n*T^tB4!q z;+C^du+5H8QAy-=LiutAF(9xo@`U+;B$EDCJ5P1hkP@n~6XJH8k@=D9Ww-B=Ad*G6 z^QPg+Z0DPzoT+bl26Q7-#%<;JO$Yo9A?AQTg3vHoYw|NKboRGF8jX)xhWEkKR#n8& zmow01wf~X?A3bdxW!T%j-L4D;ixK}nRC4?;t(0lzpVc^Wl$3we=o6T>{(c}@U*Ah!7O`*IA3Tl86#_uod{ zGOJp>O3oSsw;-&kDZ{(xi4&PJ_Ix|(V;siy=|8E>NZ^@Qxg1Ub@5prORsdl`ZZQ?yn7A0 zX)XD+q*HQTQM*Or?DR!qhZ*Y2C7G8#+eB_bL!`drmE8B6YTQQt4<|e!POW{B+HmB& zMV<*Vrh6bv_cl!ISSsFq-R0jq3`K3n5(knTwcIM*jL1sRIz)K^D{MV7F=!w!15uH6 zO7#v!8lQV0$9N@5>IXMa(U579$EPXofNCJ!5>HJ6lfi&~;_Yq&YzgqBtW9|D=cE;( zqY29PYamZMbo%>EgR*+AAUww8Yzc`NuN2x=ExoN-&Z5|+oPPeKJG=idV5(T~D}I+u zvniG5XNtQ+N#&~j;Pa;z&%-o0DZ6Q`wB=oy|5Q33@;4b?8?Rg?^`3Nh>l*XKT$B#x zD{W=#LRAa@_8g|@zH!bEFYSAb$;0YQ;rJ)YvbopAb*GB;S;d}~=-{0~asRm~EK^jt zcPB!{WXIT}b^16nYAxPa%rC#e+ld@}p!0z@H z3-ZC5Ks@BUbR(v6XwFF|kzS4lCL9&Fkgck2TqEZ4tfTJPAY_W%us2Q06W*v<2tCeO zn!%M?vGKU_#zYF^Y++h~zylx5MhS+Uy4GtuySZPia|TQ!u{oAJSvu8blUhW~{@dNO zHoe#~l&B3D_IzXX{NoX&x@A-(-4`8+mzRAPN$2DUQ;mL8)^a}*cyY4Rr)&-fuc!XK zYBi9;J&&rt8-SZ(aK#l)ET$7@RxF8&H}(g^g=!rc?+Q~^XE}MNpNb(rAJUs6CLKwG#i%U+(y%SZJm+Vxss&BSBquB15T6f5##JR z=(6QskzZw)!<}s?djvo~Km9CCflo*Z)hZ42o5YIzmnUThLI#=VfS%{@JsRvYz5Z5u z*!T4x$qxfYgwYi1Y4bv-OCua3|LpQ3v-k1Tw{IWeu4pOAGHm8Y)2-EGCw>>JrVH;HJLiBgRE;s5;%uXu|M-8%vrOp4*2Q=R7Z;NowRUX~Vva4Z z=F;QYSt?*(#*(mUd>A9{&+&x3DY8*T=vcXN*dCr_qex!-jFq5^5+L-Vuk=RBkVxji z7>EhFH#%jC8tvA}gRIc(?@?_4IP&JB6fbOn_J{VzXCFDQ+A^c0v@!U# zSaHf8gsj6Zf@j5_91h~}NWLz5GwF8X^%a^^L5`biBR-A1vo-dGzHaO%6GlzPL;CV- zNZ`k|i@}>u4!ZRroM%|G!2NbP>(4#5!3gi;ol63Cz@Ky=w-(sE(v?i>*ZRrsk5V)e ze&M zzMEE*P{-wds;h3fz)FRnDcY11ou@Fs_6_B){(3WX8dlziEaY=QN{*@nKHuv;PB$4XrSn z`7W)80tprv7xOGSeCjAez_H>{e%jGd_qM>lZmRo@Q!Th^@!{?cW|!e5w|EcMGqh&( zZU3lH<0#IEF>+EzC5a2M{R^J+u}^3SJ^5*bptm%V6rZfTSo+-c>FEj?zuq$JLkf~iJJLQMoz!=# zB{=ki-*&pnc?WR+X<57I!W-H_K>7z|z(gVPkd`EF#rpna@B8r-xp?#;r~-)BwRUSh z{z?vhPyxktHNR}h4wDuck)!?Yj|lVo#JvI5J|>PwZeMm9sCDmtb5Epi=jQ#d8yE~S zy$;Lcd&p-J%cINT*|nouz^+j@gBWzyeVulBro|7G-m7XDMGdJwkhp)NVfia!T39ar z(scV>GURh~#%Y6HvL^YYPmSt2ncxh^a=5; z$;IlbfQy-o9_ZZKGjXWTvl3Gu9aUH0B0XMg`as-Y+4_3bw*Iz79{@keo%1Z%pvN)o zga>nSSOGYlidAoh?0Q(86UZym7&)VhUVc(?h52A6;DWL=8ZJ6j#wZUqX}iLva*!G* zEAo;nhad!P+~Jm{lx+P$JT)mFB)wtX1(BNvU7X3a$)E|=XvBFMq8_}Jll(LVsep#s z%(vLLXm(csULQ=y@JXBTkL6j-2$`lcedA`@{+Iv6+Jx}!7WGr=bM*VJK*?@R!-Z+U zgwt`}_i|F^XV}><;NnKt*^;un1pQkuKqD(7Z#9@@MQ3?es<;$vvYNppw|>Yh%MX3A z@9TV_>)I7fjv)KW*%2ov4R&?lkmG5?smW;>%~w%1Bk%`#_Lax70gb$D-fqt>4l4Fv zM0@;waT;d6Cp&6ju?6^#71LCT3GJE7m8M#xCR3#ZpPBZm&MMCS6v{P0K1+YR1q%t~>Ti0Z#=Rsu$=50omMaR0tIGJ&Y_hd+ql)0@|FAUW zo++`nqJ>zqS28Kz8#RTjjVnAcKF?~xa6Se7B@el-R$osP&Pj*Vq~G$RR3{7F+bPM9 z_Cwy8-Ab5A_~fGlIdL44kf<5SfhK#3EtaYF+$*BnHCKvr=k9q7;y6#TovD70|Jr>Y zu<5hdulXwFj}-JpS#V_?3Rrrz5K^Tx`v7>Y>@!eO2Jps#FA)C+wjhB4k;9Ciy^jN7 z`76BpgTLUZyZV;FfZitjsz4>%53Fv^nN{l1s0g^0 zVsQLl25GyK(PV4LX;BzEXn$$oduov_{5~qQ`-?)a(_$%OIR8@ryk`<%nmnD51 zHI*Xzl?LBAdd!&1PU7xp<2S?R4vu!bL8{pfz(vR7aiVnm z9vvyzwm#O37E06eaYMZ+QQPYBcez67|7i?Ww8h)z%*X>t;NypD-n=AM~%( zM+qlCx|s`s1Rn+`*R98a=bMo?IG>k2?v7P!TOP*T^5)! zv4%R66;*ejU14;D2Qd`^)j1l=9}YQpE?d@GyTKgzwB;rjpky^{cf|$vmvP;v zMeTdb0AVn?_5uG02&-3Ze9kT1mt%!tn31K0F27q?51I4P-$qD%3nv)MC{s9g(l*V; z#0<3@190a*L{DElUc>Kx2+F6!+YePZWaHFC+*;`5pWj-Nr|EwH4A=l!MwCp~;;)d( z?7@?vyVbd!!ptdQm5hPp;=+BP@7#_VkhKT)o);f2e{n%hKOJXXFfA}lmniE0rvF9r z^;%x+&#uqeYmWR+=6a_f^eG3XOZO-p6!wwyUL|q0xh`7=M9Tcbe zBE4?jtE8w_oRyR5(6Z2|7a+^yV?8-Op=&r%UFh9aHTnIXpymE7zVF`cKTVi&MK`O3 zyJMqh4dRU^Pb-HFp_d=4+Pm)XkI`=>?~BYKS~CXSWIlXJ`%Eh@$-?oTLJ4r-WUIf= z8b1aBmvpaj)N06jBBUV(OOGK8zoEdN6a>oqFG}znMG!njsT9h&8?uo-QbpXZ<9uHh z4RQtS)kV9OxP`8o&J4%rO=&B}DG5k@wP_EuVnW&$LdQ|PI{(G$kjyt zy_NFg7N%z+u~_0+^=To9_-Qv=S$g4XUh9HcQKP?+V|3))6hPnH1@NrbAxLj@uQub; zw9uS}yN0_ohqf<&r8Jc=W;U-`ZNtswRO|Gzt{my}OD)c8UjD4CEj}j4p@yRE{ ztIDcFVVi3ZoA8aOJ#IE3qDtl8S5@7(!!ys#fbFsj@Lt+#ow?tc5Vcvism6SKKozc) z7t;8Ckces=e*T<6E|jt^E3}KR#xq^ipAb8h^k(@w(GKH?5ArxL+cVvVT(UGBhQnP% zhhg}2mp;WggO)$y#LVWwz2@XA6iA)Cha<0pIzOK7xsH2o7esY~Df_}+fLC+~0^Ru< z=KqDHbLp8D=it&AS*pZeaNCr)1H1f_6HwUqn1ne;h1Z8c@IPp-?3$g8XY zT>ZBVIM2ia=V)u-kMRIiV+g$nj%A9}Zeqf=_k*r%zyhV5?}GBRXWA*FSo9FJhF5hb zqIb(m5v9j&Qzc;3@X4SDDr>EAb_=?B@e>`DBsx|jTC);VQmWaf7QhF!GkVaN6>6JD zo!aw|Z$H&GQ{Z3l=7trs3vd!2%)mts`RGguNWuzvykuc~a#00MrTbc2OMXtmz~mSj zz&@EsqqFXj=WS53BTZjx)CyEMdL1@UuUVO|j#nJe@ScB)^<8DdotYDk*xDgq8W?Y$ zd0eu4`$xOqomTwL?CUrWdQF=KP{B=Wf~Ms;fRG0Xc+!Z>3*Y1gdE#SfNW++?yyDq; zIYhX;89ca`l!VuFe&o<-VT(q&U64PVC(->_UWHrYkj1CbNqCQQ{z*EXb|F0YlH>!c zJy&SuWIX#AaGVCyE2-p7uBQ%Fu(Rp>;U_Ntg+IhxhZY~k{V_#k`bl2Md;-s1z4`Zg zlfU%o0aB&aVAjx*97*^w zUt+aq{4#!RPI%$594>B19li1+f80CP#rgy@mE^?i19DXM811{LSy{(`Q217OcU%4( zPV%V{-on-;(^B>{=SK@1W-?Z_K`uKLf}M46F5|z4F8ZJDv0pm~Rd*B)_WO~`9o$hX?=Y(kQagBl#VcM`1z9~`ZLL>nujOCb!0s2O5|I(le7&u4UDEos9OG^p}!%tj-# z63nrbdAMCz+T~G$al3^QZh;N7NW7~{x};?vc0FpgfU zDUNVpd+_sE+vNHFY4R9p{w4d8)Qr=)O4O;-ZVk#T0nNj~<$3@kfi6$i3GJ_I3wPH9 zeJ?Vux3DZL0v;bpd~uGniAAO}y!|X%fz7(X^W1`4lQU3(=9XdX)3=|WEoP}Em$6mn za9k@=W}?r36*F<=>+QN9E)uUx&{A5emoaDk-{VlaQeUnQyV%%By!OQ19x>9NYxwUC zxRPOJ`8V}^zNGWn*{>^HS&CBELaCV-g)15v%Xj`Hde%pMV2ynLp*}I2?|GzI-|Ovb zuO^wAwF=n;ysK|C5>yIa3I2-F4KvoRU7#NSm9bytv_ks{bT-KMB{ZJ3R*tw^ff3-$ zEhj*mOQKy(X6l-fx{uIJbDhOQ&UVH>h)0ncQh=zr7(sAsH4BH0k)pNjlFfG`@!69R|MPpns zQ*$(F>()%qW5-gh9aTGMXwRXAX@>VTjCbhyyD81ubD@J!S_w5%*Q(ZUL4PKr{6~Cb zO&NdpV}KFl;!)bxg@3UH7R7(b$G*`~?FjnSnLXKFZ^Yhzr`gF?dE{>Z@sA@$b)3zp z!!8qa|yu>czU7}aL>0>{B)gmQN{o)tfg;mpEE2`95 zK5CgZ83_D`&Kl?x@N3~(@Li$rL7rajoOZ0VHLBY}A|Jh~#xqWdhw*eD&ac^CYR1XP z!+?O|>}H45Sq^Rt^J9sPo9=NA0ml1gE3z{IrAN7`E$qN5R@XLK2j&@Tw1WU{pC?z2 z-ls-kVR9Nhb(h-;m01Mk+ENpT059vZ?ZuSQ3{8ZyzvM=$Z?cSZkRLsEXE7a$YznME zwhE3%i>5cfr*?A#gg95y8b-d_7tCr>Z2ICx|MbA)Rd3EV@ia7vkDBgwv+ zfMlj$!J5IaRYf!v8J?Sj4whjZG{2&tiNXCf17VI-Vr{msFP|?N-kB~Sv!Glf9ZC| z^}+6(ojG^T2Y?pCx{l~EaWch`PNfq2kEa*iYO|`-CqbR%sUUi8^mINiB-sLZz=ZNkw0^D!`ti|&H!?XREnvw>nMomSUXUA8}uO7o`| z2rZ8rt=Z~k3~Mldyc+t_JOfa?R-1n-vc0e@iT0jSjKAgf4Sl&D=jGTNsKo;7hegwW zjKehxt}yl^^_y?~(sxhvO$`(73GF*NVx2EDRCJ@ch`Mt-J3~L*``YIp4Zo{-HLjjT zut1i7@v=?6jG*6hhmaZ?<&T)8seJnmeO?Q6Ho5T86*#wMu?+4xl6^ zMr+-~u*Nk`b2i%3d1|te0`HS{>hi_!&Rh)uTR&;ihmQrnt?S(Ri;%mhKv!7IYKKZk zWrgFXz>#fSBa)DGun44WoN~_F#b=>lglg zCcAL1Q51xRwMvwB=y7gH|L1&}-R~#+lIX11_hsH~$0F6q?&0gPwmwEavV$H;E7H_X zf%TDzX|s^lkY)6zOj%wU>|6RLDVFgla0PM&P-vMwT@)`q>~78$j`mEOnq<21uD82t zd*Vml)n8?&%gdH`(Jc(dna}{qmyk?8@qsgmGADmDlo)g9!PYgb0on4#{O1$1R!n<+ zfoay~j606m2YvGMM226Qc81iE^!N1Y!r!L4V@TU+vCnxmq)hfu0@EVp2#L0W)UZo9 z1R-$#qc6VzYF($hYVdB3_?7W`_T-w|;PhE#1G5mfNX3qNkBtU(sgYhBuQSJTUiaYr zR`2N|xw>dND6VVhD#5g$;Mp_bU+eIXxU6%Q}RQL(Y`v;fz5aUQUYZ9MH7%dp#T5*KqRK+qgZcKC!Z za@PIm)?=PRLfC^NdNA84rz`RfDHcz=Y&#uGovucy{z+fvgvLfxOv%3oyV|_T;80<0 zHk#pbW&a(Qe&e=A)wpH6SG(Tu>HydEa!yHeZ}k@JjL@8d{5R&wO534GsL1z`K+N!Z zNfD^>xI1)YYQ~WL)$DKs<%o42F|;?<;2>hv5&ojNL*8qlfu~rzUCu^6S=N)(>1Kdd z#@DM{lC_O!`Cf5B(06Xd=+iaK_&z%Eci$wbB9~7v8#Gr-6j^6}i=_WAHR4JYw5GPtcs_V^gMYP7&S}nf{`^&cntxq0g&K#)y2UQ#)5GOZTB>=!MoLnD zG~i?t-DoP9;64bQOBxA5k3=}Q^zEEEZ@tsZKu_#2Um0VXN5Fu)?-~!wKB}WK7{^b7&tKdJgM>0@;AATM+uy@@(y z3u1U-SSkOA!$;xDFMs={D@;T=+Gd39t*wSV)TU>b3_Iv;S{aa?Q zcKip+;f?3eT?k&!BXShBz+*z2(NBH@lAMH(*{bCEbUC~$F%-Y1y}aK<(MQ-*IAyv} zn5bL%!$0`5eP|>vs19guG;XE-s=t3&$z*w!i_0-vg0tplHpi$r$HulD)I>693oBKM zyJ?`qtsL-OD(X3xKKma{pGSc7SXM1_DJ_9a&xGNvdyk4l-8{v^Z)Iu(!{b|>z*2niA~KnID2=oC9%%~kl#xT8ALO^CcI4@+XU3=B zG5-qnA*t2LSmnM^u5e7!FV2P6m4D@b z49`|i;tNCB-N@NR9ejh|1mk|ovGe)4@Y93S?bD7lalgEWvO5)e51h*l3w~;j#V+|K z{#^aoqR|@m&3s|7OFf)|;ev4*aB%pw*X;&DybEPrRV}{K$G4ksNVO#%0hpLtDO;Pf z_R>*V#~DbY{(6%C?Q`o}uHQM!zKPvS6sQ=U){BtMjak;}qJGG?;F7+YR#Hq$BE8}; zvlY)G;*;XJttDb_ci|_CeuCUwUScIcYQm0Vb$lrOd_I3wn<7lRij*(ELx#H zC(Mw6&^?OJ2sU-pM;BCITbo966a$zJpM}wi=%5CuO&wMw=8>|Ij6&v(R)Uula=t`P z!2`a<$Y6cv#O~O6sNdTSVCDq4c<42N^sDu&25lg1wyS(d5-DGzu(S7F1t-X)nIr-=>ybtuk9)-OkSV-uLD9=tFI-l7Kl0 zONvTuoN6|}8|v=r|=?TF3hfYRuyBh9$FkgAKCGs`Pa zuzMMeRHTEV)sXV{E!d+zk-zzvTJ_(JqbFQ}h^(lYObJXK23^x`?PS*=;o<u9pZIE72QUTi;(1gb%tjy^&**<2cnU(D0;$dy$L!xzeTz{Q&s1e za!7YmN35U8%v-w~D&!f4^LIW3MMpFzZT5o&K;S_*i?Dd$)6C_iWFlFnhY?-;{R3{} z@;IjF31r4efClH(Fs6pIg1R~_$#7=X?;B9^n>_(N4_#cLL^B2q z$(@?;bzHn!KvqUbFd9uc$%n4{)OW~VYKT4?%370R<6}hCKm&m#_8ji8OZ)=x&Vh2X z{J9(XC87akGnb}dNXFA%@hs3osTmar#^aIcF|Z&i*~y_J?m-<;$(Gn>8g!R z8Up)Y=S+kNd#UpjqoW5fVO?ikl^o`sD~%KEsCdy9w71-#ls9hckevZ=MCh0gfFGGy z`ln42JFu>Pj@1-3yXYHFj{q9#V^J<>wA#b!xPhtlj4rY+<(>EC@PW73LEe%XX!2M$ z!-x3lC)MgryCu2Ic!tMD!ZB~(n6z?du;e_t>E1>Wm*vR9ORNQBwB~U;9*bu9rFzFG#eTBw}>RNfoz;3!i%U99G zbfAvSdUe!%>ajI$_p4~-PvJ*7lD0z$;z2M6s_W9!&+Z=7_P$}I;EEiQ_*0)H&8=MZ zwduvr2m{JiqleqBzt1pfhzXQ!(blPTF*y5;0ag$o{Bq7bQDIq@y)o-m$djCw)h{DE zc{-c$^Y^YNV@U}gleAnyk|uk90){LQ4s`s2*rhSPghV8!W|aRIk3*jn+;Dc4283i? zXP^r7JFYcy(6Cy4Qk->`o~vDH^F(;pm%6Kmi5ft2Ia+cOw4)YQ6N;JFOl#ouw)DHY z&bckCx_C5Va>CYa!HyqKW!S+@hgcR_Bx=2(3qo-GMwS~#(8cG#aeWoCZGIF z27TEu;Cbl>{sWpW;)v5kn&X6JyRtHVXsE1QK=rx=+Sj16<$%=-2Lz)g#N z(iw-ci~Q?8pXnsb6Zw)%H*iTMh_g!G_~E9J^g2&8C+!1=z>I&wmnEvy-ngNLofwcu zq^8(%m?}vuC40$-cSy_O!d)kica*Lj*lJG7A52YR`Q3J~{Gu8+goPs<;}k)a63jzS ziY$6P9nrl+4+AHhlx)!jLm|hmz5ha;n^osLX=(j&4eG++-s@7eD#w3Od* zmYd!IV36DMk$v7@YkU!}G*z>(lD4nDw>GQULd3Yxa!rh8ykuq5^LJG2`m@hBPd|aP z381FXW@rWz=vGh2UNHt+<&ElCC3)(CMnS|dm`oa?qnPL685?1j*@bTE zjQZgS*ZLw>)~wATDWnGZvPXP4Ys;VD)RiEn01ud$x_A2)#WIC)9kH^3gUM;*VAU8T zP`T4*?TvkvdT&wkx9{!6TEEMZRs^2vf+L|qHIoAPm6alJ3CmX&-Ef7%oBG97!Qb&S)feEG2?--hUr;~ z;?ceE7u%0-{LGfIy}~xCCy-6cV4@2QXT}0Q5yhN)7A__QseXl&6g-MZyGkv2-jf<| zWo~u3%?zaz8oDakdfS)T-i+3`$4{z2Y>dZET3)0v+#M1q1m>csG?});Q8F* zhRD84u6L>H4?+|NjhKjcLQR9mDvvUJRt4H0em^?#$JOt=qP#y#3Hv{q&N`~;|KZ}J zK?D?0q`?9NoYFBEh;$2rbazSj29kn=bazU3GZ3VEGOkC?I&uZ7B!$Yq06A@49KS|F) zl7F^&^O4h}ewCpe^e72=;WKKQMWxYJT!Umk(lYepGnhH*`I(tWDXA-%XqbJ7tazF5 z$wXE}C(--ww;hiew$*CIdB#(FpULNgO=_l&DgndwRIsV}3DZB$Q3a2qRIQOC?w_7A z?t|Q{CpA8tFy!nKeLl-~uRG7qm2)kpQn3)A$PtxX@nG z1zcpnc87K1vldJYPU(DZjR3(9zYWobmn971y<2%?PM>&CcecAFGIDB14tjS4FjlA7 z>%WHVRSje9d`C}}0NDGH9N+OiG}Tl=LBTJ`{>9mv#_oHRcRG4|==@Avj9FuO>DK)M zdkoh1+HVg1&2J9LztwU41pQ2z=Hdvexto}bCE+5xV-9HBj>X9=-WJG>+>MyBZo7N& z4t*xC2)(<{^P;)fI3|a-Qtst)0QCG*Z97?+px@lJvaMe^gFW3cUb=%@(LT`L*n`earhYjTsZxgm>Dn6L9JM;-X@=%KtpN4yNl3KR6q zBuv9|NusaEfE-HmO4Xmf4YP?qGvZjbtHnA(8e$ z-W1-S=80SV7cb{$>(Y3dR(`sCtxTDU(y_1O(J@E9T{<}IN??4JefVac=ZFZ| z?--Nq5ZYzW>^P{P7s0g2FY(}~xWW65isBIm~8JG6u z3$|fr)JuS~uD2Mu9Wg(ce#IDO{Kl1ruDI=NMi*xfc7J!XiZeI)tzb~YZdtfu6pD;#MP)V)e+CYG@gtO*a97+e`apdq*0=`G^R$!;pjwBo33#c?; zb?{hz;SnJBziY(yo;%ZWHj9*NqLOaAtB8Uj!#a=e*L06fYIv$?zxq&GjarH1ps`(i zDCYb-iSUKrt5<5qUsK#&XfdVx<}VQ`MR0Z*9L6lQPkvq5(SyknQE5gzIh59G%E_M1 z+K0?6Ug0i0o@*oroo3=kI!?nh`) z3O0=1aV;MrzPCmlDXUVGc%}S4SAPMY2~o8)&q3=>R|aqL+B%0oe!cEB?-jBgvEJPg z!Mz{t&pX?2gz$hAiwT9-iTtdnh2-N>ZXeC-im|=q*^!C3xwdDuj6V^~zc$qC?f@Ps zP*cz_<5*7@kT^%R0s*NlHCc?B3>Tic?nr~Sa*k+w;F*?m;J zg)VcILsy$l#2G_jjaTnZNFSPWjUy%-xQAu7yEn))mP7ha<~O@*84MLro>@yRu?NEG zMA0bb^#Ypgs1hB!-GEspiYCPkf#{u#{aKXnY^dVDwx27Jhl>Xgff=aHl_Dv?+=veF z;5tyO7$qly;D>|lnbblS(E%1K(bQ7#)Vue4?#XVVqvv(}MVSryb95BEQR*we;X_%b zxzs0gbeFa50~fJmZB@W`??Pmzrc0OffR&*TC|Z+cwic^oltV?U1Q^xkT4A3E(aV+P zDlKStc!zsBGO>YmjN^`_Bkd^v$gyRyANtwamjU}}AlzQaDcZ$di_r7TFL*J*i;1=` zRB@;p1OH})W5;uOM0a21b;a)08Bny%AOZkA_+H`X`EoSXZ#>^PjvprnACNQ7j@x66 z{E2^ne?7uo@38?%@%qNvhT-4${mj3=@EMaR4)ZaWpz|IM4$T69z0Pq?y&9J_IEzwd zP^G)9QoE0 zZjI@Q7*{+Ig+G*0?yJP@YMHd;sN!|&n5fx}4%M13g$yAi*G??l1+vBjce%75w27kA zjib8wgTH;8+g`cLe>229Dj|$x?fII9?%xlRxFDR6w!092@ZU8;tUpX3>iU6Sl29~0 z6B_g=k0`WT5sjg_u74oFsTML^Xiuf`+muv)!vzvD*Sbr$p=(8B z^z?}3`OgZ-_$91lu^e);>1ZM^BJx9jRwrDm?tEU`e!mMx_w?7t zPJ_#s-RJoBpm3DTOvYmOZvNqVy37v(#?-d+~ z0z;$)KStVnT;Q=>JXJZf4`3Tq^!U7oK0j^kba%RYC7g7?R|nc%l|Y<36mixI*EyZE zC{NyklFqs{$<6awk1ni{!ic7gI=3?~b{A2*#6Lr{{!BoJgZ2vpkO+V8TVdwpq)6H&2iEU;<{AY;ZxA4uk76K5jIP{Au`2iW#BV<{svUPyd;gwzjk=r z)9|X2;Lcq{5~l-h3Vmjj9(_`0mhO_}*w=Uyc?1#OY(ya4X)s?Ip-J^epSBK*h-9@D zdxO}CpjCm7*+xkHzC+E#Nox{75;&F0p!2x|4`sNwC0{x9H^*;=>fQvW_74t8#}Dqd zQulpSP#7-iF1yqRWuaPfc<(5w`e}ykFKm0>xU*jd^;~(;scU@(;?$^ zOIiuu<|fN?i%gwrijQq}U6XAoF{ zHpO$rGcsm;C$$g9sI26*&BbZ(Z;9gS5uz7s{p3!+N%fat^JZKO+SKzOWtg&SqaMnc zwq9-@fA-&zHNW8o(;CQ?J?3`hJ(jcJNfnkNCsIea^qE$i;or^iZtO4mY~)4H&xoOK zM-ES0-|5JO3hdG0etfx`ojv^yZl*4?o5Uq|XCyJ#Z~P!M;rFi(A0fk(84Nb}MkjR} zY=FO1h9DQ6?C8RCcwgC-OhrYdklp@`kUs}7azP7J-|07bQ2Ela^X1!>b5L&bkG(`k z5y@@PzjaevpX~ZhrVVrf2oGLM?K$ChO=y({|Mh;Z^NWYYr)wakOI^D6j%fsb57hFGn7-k~? zJ*imrGcwaT&2$$9DU*E@iCkLHGWo%dv$!^Mee%`btFXPjPXb(7z3nu5n;toQh(RIK z>rSF1k>rvx$e?eBaZq1Tf0!q7m2}l9N}etg`RJz9vPFhKgb_}GOdN!M`C!RfHerQ~*d2O9 z!TUNY@%yu*yC;{86@~+|1b~X#olwvnVN&M1z@m!3&5(U(?GzD1&3S^asQVAMTFZJ) z&XTvX>ORZ9JRWhkxuEP!A7zSXv+IZo!*$N*{c&H9N|pngOwiv}Yhm zk;jScsMb;Ot~nU7$s>(l-JZyUf3x>&heUX)@c@;`|7a09!%;X~4A!Ko0aigFm@!tl=F=&m@NUbYOGj^aTSriv5mGJ)M zh0kPCO?&@ve<63dJ&{)EXxT3rzc(HBkljyb(s$yL_(=qZr1P(s&$(l{)$`KwJc+6K zdwZqDG%QXZwaq_qTIVLrStS~(hQM;ODPSvi`-V_0O z8W1VNK|$l^UBti`%C8a_H8;dB!!!vRKV!;n_u<|U%W=H)oxZvXZ^rlkgVh}U zv&fV?&NvuHI}zUplTr_!p=Q^_jv^g>^FY`s-Ng$M-%SFmGpc^|m9a$dTopERVCv%! z`){5HtKzY)PfcB&tJ%e`4hRwQx;t+31De*Fn)T|OYBhL5!QAr#{*0OTz=@oq7Ob0w zoM~XN-nZpUz{!AC)j_x_z1*LqLIvtn9+2^`)@?D30q2$!{s4Za-@R{xO{_QxJ1iJG zcEIcp&WTL$f~UeC4$WshE7EK5?-NqUtz-OqXS{T4<|AT%2Yr1pdCPfRKL8HXnA4e}qoG8Ku+IvJQ5;oe#YN%I>b=KEci=HD*jYVPK- zkE=ASXI?ZSvT0%iWQ1Ij&3JN zXBJ2U#3V333)A?=Ydl?7y6x&X{;OrfvJm8dGqN+80Mub}`um&RhK#}bld#W#k*&f1 zZvnj4eh7HFPLSKBS`sKg*{`lZ%vO$3`=ku0pZILe^eKTqNYhy`4v*czlApR_ikE#V ztSUjA^^7b8r-shi(T3}HBs| ze&rTD6Y1l)O>8SkI?Jh{=a^Ud9dk#PxA|P0iG0ia_gmUjGv)hQXvQhr@7h{Hce&x< zN@~dV<^w|vk^m*6)=W%W zM@Gh0Op-Gm)F7W8qU?$E7&k@>Xv0Np1KD<`^%(uWi-8Y0 z1ur1>7IE_)Ion{3Si_2>1J)cRRnER1fcN#l==E$3P9wBe(Y4C#f!L_7i+27~py1$~Ppovg5Cy(O2cBSacmN1U5D)OtQKwO; z&uiI1eSV=t?RR}^!ZGO!_xhsm_O{-kn?eq&YCFqOU+gw{k7o8gFr@29}-WzC%gQ9iN?LW1*Bn>;G|( z{=E(ow6#m=<^CnnZlL~{*-Y)cAsxbSqtu9=ul$J>|BWxLk+`jE)^gWG;7f_Qj2k}% zmpS`=l+WB5le8b>!Q5ge6BREh5PPV&evC$#YeAV9iHytZL6n? z;cqh#_b~MPxG;+gtl5@@(RRkUhr~P|#V^SXsEKe74}0Rz4qz=*9ZHlkNW#ldEHR+o zmT6)E4uzK5Zqy=Mx_b8u?@Op@-39y#-qCXU$bVaSWhL#G-Cw^;={-pI{=7g*Vv(k` zf%h`ZLq;j+*2bczmFQUk;!n2YD~%hGB6wwKc1;BH&5IZH41DDFteqrwDV>ZfSLw?9 z-6=SV(Jp*{K4w|frUzWJT{B<5xanGZEwQ~9tuzl+Z&*%;dnf9^YuMUg4QdXH%~}q` z+jnCZOTZJ$(F8|Kiu=)YygUDmksfOFk$i8Yt{9|=a9z*<1M{3=}f#p_6l%{qRylD0O zSyj88M=_cBW5)pSWFf0-Iwmpew2rBKU#7&?R$$M8`8NgT%FK`yr+0fD|TCv=w{3JD#TX|9uZSwZz1u2B>>(}x2HV8#ZX3PyK zfU1xEklI4*toYjmFd6{97F4FyR@+n6_AP(!m?F!_!5PIb{os2e$3 znOz$c_Bvg?-O3v~z{nYMcuWf6st-~@WPxu%K zak{Q<)K0r+@G8qQPaIM4_VmYFFAY!exSm@`bAo?!>nj&jO0aTd6PhC+LS`o{;WIv=!|uW(=K8J| zYrpBn9p4LRS>SUfc(o_9(f9wC7fYfkua*6Z-&QeZyC{XDiapBMxQ%v9SjM34IWOu9 zmq~#gkNlV6I>3c_+NvOaS}|IE)MoC1@#1W^p>q);U{iE z;cW29+&0=+&veOdLh8Ddf=MIhjH#5$jzP0Wg#FKE^>86BX{F{%XbG^x4R71NDY1%IR)F{LJ*m%UseTfO(r+(J74qXn-e}`2GeIDgnB5B~ zn+E|v?0%y%-gZpP@SR@E=VwzY9~hcyg+_Atgi&)USzzW)P)_!*iDBlE4ky?I2ijN! z`F_7UvDYcu+%u}SkLlW_0r+;UP^_ih;oiDw8kZ65C93q!Q9);AOx;{ZXrF1T%V*&_ zce>sFM(uC4q3y-9OS&Sspiiq|??j{5ZG#Fe9oJZ1Z%OTR%IWRRMZGdwW@7*U<2_NR zj`Gs!rx2fz$3;JH=!=lzm)PoZ(t+=m$kB0E{7Zk>xqtK%z+jqB9Y90jruaznUM9gU z{c_Rax)iF2dzbA3KKCl*5=DFKfTP_i9`6GIi}Cf#MGdW9g(EXWIb&-!X?@LZd$W?w zS*C0#yoybv{ag}Ew*zaeW>k}1(D`H^Nm5?Wg2unT2w@8H6-`GRO-KjziMqSeQ}BW= zaRBxnp!=_+8F<35q;v$-@!SzDwP3wB;B0uuGBSpWZ!~Sc7u^#>rafbg*6CaZ_h>91 z%CD8v8!^XF(WZrLy6K-!bt%2+A_fHEU_GnHfPiN+^}qURu-K|y7ERPux!-XIpfh?X zeda37(2vdkV_ohTAHF0nZu8p^OEZo9yl$Kp+4#a2If{iy6}{c>ZL3|2R_n#)Q$vr* z=q3T;E5QwfmjbMZ2S43!pI(M;Egv^?Y|N}Edfo5Kd!c$|%=Z`m9*-p5D|l^Q*Vb$6 ztpI3AFgXtmpd=Xf=(M`u1m3H_p%Y^ep)FfHlRhbxgo#I3q=qMjbaHHq^NX-T{dsG? zKwO48-77lWnBy1UqrP80-~1(&X|*E&!k8pk1bEis##-Q{YSyXO7CI&oc?^b(j)Yzi zi0x3#1raf?EEg6^I^tqV?n`j0NDewA0MH#{P2P5I!j*$EkP3k?85MRBO2@E?`C#Z| z11xq~+;*pOF9}z+95TdW{Wf0TIty})KWeQYxy&2;O8t!)*ws`uEp3RYd(k4iC;Jvj zj$dk*iGR; zy(J!wtEhM5W1gOM4F?Zx^jdlhfp1Z;1hTU+j%B}k(9K_&^f%a!QhO^(vc)}Tk11~dP*FP7cA4oeNOn1sclY!ly%kcSm%}ih4ND)x5 z9V4ipTABK?WgVU-+Xc*2tQGeroaFwK8n|UPPSXuxT9IYy>-g5XnA!b6|DeeUNpz<} zF)Ow#2tgRN$e~j-#N?J<3Hgk8v{!_lF1C8Cy$*24a#>&$2Vl5%2mJ7g_mW5nHLpk? za}Z2z5T;)YE2bea z^r7JKY5HdOwO85A4b@6Cs!yHSkIAvJ#M)sN;#MnqJ_KVDLuMXDEebt9SeO+$&x1oe zb8A>v@Q~k3JbL*uRUr^Nf#8$&ZIbr`rnV-w-TcbI9WXd`<_8lgUziX>UqkzM|P9wKM z;Rw4r+i;c!^rX+6rWxB*w%zhO_+k5vVn9p$yWtP7<9W=kgBjPRn}qX3ULZhv{@>g} zPZ-<@_+IFQORt|<>v~o3ZPc^PraUQr<&PI#8|k9**BhE;#~Ba3SvP1Ffad7=?38Xy z)&k=rk}4Cu0yK|(%EYC~IsN4MAu1%8VC6{#g;%{SLvQh)mz@S_^B&J{nuB&IFXO1p z3pwZB)_>|VN@@?q)Mt!yfK@v4nWKbX0#CoI6b;sGIpHcPzI+a85qZ3BS& zs^-q36f9ug1ANtn!DKv$2-QYM+! z2%(=6IbS~&GFwXmp={8}$5PWj8|-W^TFq^LA8<04UmJ;o0jIlN)N?}k zs5l6K(|nNc*56ON&sm=_2~e2@(&KXUV`jepQ*g{$iIHl)#!!EOXu4VshFseQT4UiE zxbCGYPqqu~t@U*r(}G@4(hm+(hC1;?fvEE4g1)|n=Lw}S1=laQj*5`yAP44{M+fje ziJVP{6Pq(iGA=vhZ3z0&IymAWOZ|@40!oub9$ zRE?y*)QvjVt+6bi3i#Ib=WHeP7PV?UjvL6ub>;%KHteUSre5oqoD{WLKtnWy`hG0i zzuCKZazV4VM0BT!y305}KS%P7T$|`B?>S^68UMBkI@43P9?XtLm%=!yZ=40|GO>7# z4?TuHTmj%q#KD4C*40f83bh5^*_nAa7wcrNqOiBO^?aM{;wm3$4?}118tAr~+TMTL z^IlMiyHxU^Rc-+ApZ;Jts$16{WUNrMzIX?dHO5>V@D;6r(IS^6h1X&QBcg%;Amuma zkE7$`bjGfD(5I(Qig|$8J1U{I+UKCG@SI%Ct8uu0%~4t$Kh2kzk@%6Ui}B-8flrxX zOhT8qIc)>?j zKN=?AUsx8ZWrn~bbv}%gMT=Fdl_^LHW`RT=mpGnMv03>X8I3PX(KxanyEan<#b&w(2@ND?I2 zJ8|wNZrIBi>Sn0}G=O03vkhCr8=Yo%w2s!y7Ax7Ke@xFjSwhEZdM6H89R=*?qZh2V zb{f-o8#daU)}+e_{x;mO@TmsdW>x#}UwG|}PW8>~N9%^> z#osqw4>^l2F*MkpAuO>@z%6AO^KNtRMU|6p`NKZ_EO?QzPIf(M1HQjWo6m?4q|I#5 zx^;8G!5(6>R{jjT*Xho>yv9Jmi#>H&v`})qE00xiaW}<5{(7X#y`Z3 zi;dTAsw`j5Z%WzkKZg65D~bjL-I`|!0&qVd9$m(*#tV?Hu&Qn^gmi`x;WDo8Xkjxq z!`takn5(Pa8~||w+b$)+xR`?NMX0;c()N&8cIP%rfrt)m_Aw%g#eTNREYd6iKJoSi z-g=!yzzf{78GPx*v{qHIH0o`qvn%JTA?Rm|N{}w&XgU`MuH4K9O;{203x76ef9u^6 z-%S(YmxPgjrhd@AQ~=Q*ekvaRDdoJLmj%{auH1E0j{TKzg~R{&=}OqcYj~&O?7?)R z(+8Y|fw(8*(Qb5jR+Qt7KeXo2Dg=V7J01dU_ZEDSuF|F~prNU;=5FBGddeF6ne16U zP6OFf+hSMo$QlB`=Q&+|{m01{s-3a3y6LcMyXH&G=M=cZkS%V;pUt?*M^;RrK=oe6nA;r_^HGG1&k-Z3G9VZ*xcuB4h+X7EIdXcQ`P5iJev z=$zZYHk)SLGKkFK6PryCDV2T+ZC%EcA||9x=XuSdmul}mHr9P)vQ0!pYQ2-;K`+^8 zO6zLb7M=EcBFY1Wsum;jK9C|pQADpbIxds1Pyj|5p`gx|g=6gM5wV=hb-}!~!LH}T zSM0(3e}#y_=~698{0;h`M9EZdl>jj3(Io{kL+p^^VOuhs2-DeV!3lV=U)onWkvIKK z@6=9rz%N7JqWT8u2xAa0g{s=_D4Sr|Zb(~QDo;F#RxH|TZ{A$IcU|k~tB%VQNyzHy zK&qrQEdxMDc--z;r-2BFS=KSuVcXls$~~{BorB}n_8|CVyN>@2uKQM>I`)6lh2sLn zMF;eo-=&CGrCY`;ZyYE#eX{yJ031N+t+}3{d;TMkdJk}0x1ZGo?qrxb6REw+PS#@eLzb{_m;aWJ__QV6PnxU9 zzHFLty!txKDmRViC>wD)$X1V2aOkgNu4Nd&1c085b!hOv(+5)E6n6@gI2Z%o%T|q)M4Z>r396Qg;DvJv!*Ju&ER4{lP ztI2e{K?i(1Xd=&P*tOlmyZBX787{ZA57i{Z#qi_vCy1oR=3oAtiA|gCeawTKW+D$X zTwwv5zl0V)I@&z!+|`LSw@TU?$5Z7XNF)jadE}(~ZIYVrr#>s0)`>`?&U%MJn7uB{ z#}y_?Hopb?&z@GrOC24?ePS`9d7CLRFbSMzvi3kF86()-236F)s7az&pVBwjXcV~i zMU(x@a<7L@hJFCliv2-GH&p=d{;lZX@NUskCJT^;Rk&d+_PG=80zZr0%ldUG&+ig> zne-wec2#ti8Oq=^!m^s>97DfDGIH0$#jX3RpE3G7al56K%;`is>C;t}WwmPX^W8;^ z(s;Gkz|RmgXWa`|^!K}=N}~P28LugBHZ{(FTHbybjF+%}B(=CWB6upFrWI~hnx7)R zW)&YdDGFaR$QH?E|Jk&-4R#pJLz)YxieoG4@%0<)8H`A5d@-r0H)cz!-`*p?uFn4M zoKMlx8kv|kGrq=5YxpVMWF2<}n>?}fM zVqn4^c0Ul0fh>pcX|43jIIu6!P5NP&Gg|rmd&%Hntxix#~ z?Yoj?Fc>ST_N0c^eF6|?S`KZ!>(f{k@`rI4vQdoba||8(>X@T>yhX4W+$(c-@X_-l%CPHB`$t^S`jH=}k*BqEfGi-f#rk0(+!6YLl{_GJDF|zR#44<_S>7X$vVY zy$C`)vBi85eTY#bT3J?2n5wmjLHwF7Nqt-q0a7gSy_IS3*DQ|x{7XKqn{hndDIbjY z>ung_Gkn4wjVQCi&6axIq$2XZ!TW2QhE72~SvHT5c-byPT6*ozl zP(Ub#=uqYp(X5mnY54pa_q8}vcL(uDwo{q5kRG>W2f=-wWr2HayiD7%BL?tsPVYOY za^xTIZD?Jhb5=gP?a+XTXhWm8Ezlo4v-GFXz;tw@++H`$5$NZwuvpPOGk#_wNj}*i zVr|gVhXajg*y={R%ibLIuILoq24QR1k-&XRdM=p#wl4^Cc-jpCc3hgYE!3YDzKn(g z|Mhq6W0h45egCRA#izLsRFemE$ZkK|n>D9-#IkE&!GOI;k@nV11>?mw)=*IN&_mSg zrZHjTD${}b$eT8pq0+$(owf2spd?&q!M-)?lQ44JzHy65oC?f~1H#U9Ek6*?uRkcU zx3A8SL=K(@2DW|6R!gsULmNMQ^jEa#3=>#6hMYkpIqGaR)~T2*oPR^=w${0CWd<&a zF6A7Y==8=tLMS(MtrUTu9A3oFsFw;XeT`E(@c#t5zSv^lmtL>l97X13 zeM0u{%u)Sl60;JteGoKAMEbe{h+CqBxJ6(ZwldPK{;mS}f=;;nBV$(b z>`(Z$;VMQ?)MW)Wv>WaQd{&JKw*^?MtR)N}&0a)CadvQaE!4r3YLKUvL4qy35WUS- zR%90le*ss~+Td&c6K`04)abR7!tJurTyr=~S^zrx+4i2G#l)vjw{}#|U%{lOVR|no zY_dNp!wT>8ge-ZmcJ}k?lu=K5mCkI1gqgEhveGvS3#^6Y3OawE3TH6Lo5N=~nn%2Z+z5nJZ^PPEwDD3WZK^Z>^r)&a%t$lB0?~t?#`2 zlgcFVdS4dFn{w6@16W2(Ty)sAQHtoJXdfL4_@J-2V~AD={hJE$`!<<(frX^qW07xq zWMo5QvO4YJi{IPqh-s9W_9tzm=z=9zWR>TV)7S7Zf16ZcKJpJKtN=J@YE6&4sG~Id zC?BVXnK@*N0>eU)XI%b^f_5CC=!hTG=7qyW8$WAXhoTg=`I#CzDjLyvjN$EItIu+l(iTU^7(g)-mjA!$^jxS<+jrT9q`Vr?bijD zd6w#iTSpqs`4%NmE|eSdy>nyy>#b>VylWY8-D{bz886kyqZN8Z0cBn{4IT(=AQ?(& z-;%^X&$#K-Qm?YS-?99j;8IT1jtR*T04_fwdJA|yfdifX*h%H|O&#YFzKL^!Fk4yZ z4dkw5??@9^j&i%T;3NCR-cfcVz#*(p;+-=ap{dxsj-?xwYuT}wYtFv}9&_RNCiF_^ zrptyX^pdDA5lcoVn(6Ler^;88$P-r?Q6m7!yc-@$sPuBuOI=vU*O~RRx-xc{KjVkh z&vk)-yHx8A*)BrdxsUW;)Ro%hVwh91s5FUx(LEga5bB-(JFBkSm9mjbeJh-Q3_k;q zcihvbd{g^CR_7h54%|`G2p%F1BlAkKCmzpe&f}va*sl3Ss_t|2z%2dYSq-D#Yg@>p zw~T!;9I-iZCX7t&k1ELK!!n>+8*U9R#%h#sDqU2DPE@ktn+aP(h-MCRp_x>?7PF}m z^1WxQYX3-t|GFAov+i~^Oszb*(H$FiNUlMs?R^Rv2;kfuc;ECzJPUA5aL9@*;d9Dx zV)-L;vX&Zw3g)|=qNq6m0b2MEldmw{pQk8nvwR=XZ4Q&hXY{Rc&y1}Py|F>uy)5)o zr!YJEb=rkgv3#7k9aj8_Uwy2v1zL*0n10EG(&6}niy)pA!v=m8c9~k>VyGtHE%p^* zXh14EnRWfX9dr3vk(ui2hN z2o?}#+Zm#EzO@DIjMd-Sw|YJ{Vm0ht{BKt~nYPEzAJ2O<5j#1MO))4)(~X@Gs+PmI zCBebyPf6R8l9Ik*_+>gjoRYG?1Vv8C`U4YNL1!G=58Rl2tKvN@8>TJ^~#r0306X80= z&{2)j#Iof zn0%(LwYW2QzMV(@!g3;^F{L|~wpqK0-gwl7V1bLIo?$4}B`9vdmN zkkm0Dwt94Ru(9qgS8$GFnu1?{JcC99OLS4a7mliqsRO#^S;_4mEdoG?s^*w=JI~B@ zoWK)0jfePA@23UQO4D$-F9i;%UkrrFY8HFOg?p|PKBn8{tphN`vwO4WHbmpQxqj;R zNV)FKW|9&YR$R1r866zjI4I6&fkNa5TX*0oeaL`IGm_%wZQ>h^y!X?LQDz;oaZ3>D zUhVm=F)lpOTXDqa@OX}R{L8ssFYp%wbmJ;?c4Or_seUHce>NE3;E2~W?nhPWrE|HI zL+|>u8{la)Df4d$Flu{ZKRoocK6P^4P(KPUYTMjwwkD?R+{xaa_*9{jPx6&aQm5>z znN!n?>gAS9OI#-iA)0Xt$DyxGRrNGA*L~0YY^Cw}qJG{z zUYksLE{~ovS{iSz==f^9W$0y8VQ6xF=3-7xp?Eehm@NyR?+@1S*g6qvAz?*E7FWoWe#y?+;&GUZW~Q@BCIu zmiO5mMm0)97;YNYgYgeIKwMrdNAW)wLCH#Prj2S2sTE{)9q{-*>q!r~T4m0fyPu+c z=+&W94gj<_Yv^c&hvDOold4@JO)Y%U3v%UNlp*G?Vb3Twuhf6|)x#>Um0*_ z;&T;^e!JClg50m`=6A~M6E$yuS@(;Oha#P)T68FoW5(btUf{|S+SSRaX_H2rYBtHs zI_@gE#V=at-nc%{yNZd`Xbewqp>hI#d z-1&31D(_MIsFT7#mkb+r@aXhORa-#kzT z3yYZ6KD(?P0qyHX4`Exif14UJvZ#1k+8ai&k;g;$+(LJzEP#@BqJ~JoOq`5Nydb58 zE{&MjGuekt^~Ne;5(ll1r8pd>bBL(tOH9ZxU**P8ABQu6J4r zGu}B8OLrqx)Kzdwh5i0U)BK_GAN{iQ{z<`cp~SB-{5$RpM0Q|Qh0e9U zHXS}*BGT{DoTt>1=b|0=K~4|w+YZwekK)0-e%BBGj2afb+4zj#=Fk(ugnQ5X`ngf~ z8Fmun`Sy~PRKNNjKrt+!_N{c28(nXP`VV0O-LvcvzK?3_QUzjVitKn4;EIAX&*$N) z*$jH|-E_>Eogn_w9WVJ7Y{Qbi&Wm?FyE@d-?ZgnI$oiJHne5O zI^uIxgehQzE&nlS{}J$J5RTntB1&B%y$mI?nCRuO^9&@~q*edN$LA@!`~PX z*vsPSTXpFA8|JUd=9tp==pPxTP*_(U60oXV|f6h7QkQeuaP`}?&YDl9e@yVzFmZ@v5rzf@&z!6?*G8^1afh? z0mDxzuHc0i1~+rqsdc3`f3FL$`K(lXkHPOHQh}0aH35i%-L})th$S@M9w(|}+b{`A` z7j~U@KvwGt4~dQ%i%3^%+42mg_g#=NZh{V0Zu?Hi)-p?q3WY}91>Y{}-uNtBF|Kzo zXE{apy$%fkqwH?dmUFHcQkOQA!8D zJF8DRgW7JBzk4Q@v|Tuo(0jw;Rq*9~F@4<715F`y(LbkzSq*jpU|oSs$uDBQj9=v9 zthzeh_Lk|-#aL$Y43CrY0i<_?@ zVP|0Gxcc>j>O${})>V88>no1xF4w)}pCvm5bVKF_BA25}Pm*s2S_^!y4d%yFom~)o z=f3`GxUK}4X@qStGdW_M@s`(ol63kwP}b#iC$Ng$gZ8Bn2TtX2v2XTHekpZDJlVV` z=pK*}Z}4=53N=jP`}dB7%~&m<3N*!DiFcQ4vyKOIYN{BHDBF%V);?E^pL#>X|LMPsNX}n&FY2~buMWna>jm_+zv%f7Vb~Dx4kmQL?22`qvsL`Tg0F*TK*oVKOa<6tz z5tW)6DqUXj&i%Pr;g`abAA%xjU%(mGe^R6J_xe+zHAj9KrCV8(4nt!Jxh1o~^}zb` z7tEI}g&mbYGIyq5w(80Rf5~*+9Lr46!(WKsX`C85i)N$dUB4uZ^80Z^UywOUMPasg zIDkh33(_mbL zoCR0cf}{9uJMPXZ`*ffU)EnrDO_$0e3bLY3L)(JDhzsxY>!zd087fF^jV>VmTi=o!O^0W{h2)1EZa8*O6aSn?Bj#&706|>R5?=u0WqOj?-dm2V4sZOAs1f#qs z$Lix}D-X)(6Q4SXopML_E%&RTB0ztUCjWMOI3EPtfC9_2y54t?50QO{^U`{|keIp!|`M9}q6^sk43pi2|)lENsP@Ph@( za#mJH*zp9^symUwBroymDYlR6AG3p;Pa=6h1l4?WEi6pwuwyA-OVAyY7%8GCqfHmu zQBlvf;wYuAr1egZBMmoWGt*0r4yqTepOj+rV7temjwH7*@`w{zw?*R~wX5E-+FCZ| zCTw?BHA-V~psGxpQlCyo(Q<;TAgeRm*J4NGN7?KjV58=#S7F2O*JtDBj28WNs!5Vv z;brF2|0C+Gqnduhzdr_ufG`yWrG_FUrF0KPK}A3X=~g$`Aw3rNQwvwm&f>=K0C}EfS%h^_=`{sMh zCqE5tKU9R@j=V~V(mV)QTvt3gt@w1wyW7Dc?T<*LsmDKcqB@3Qk;3r}ffjiQD;{&C z7Rq(+6W$$xU0H-*uGM&ariBM=U2(#*9enrX_6?o`m+^*P$&Tjm+}Wpip=*!2euGOP z*=}t&%+1V1OH3tiVzZp?at{%FX0mr5rqY^V52R@Bb&rW#{+L47auwP>#f}e)ao|=uqNr1w;k_n?kR4<@Jx|Ada#1-cMTfT(>BEbc8o$kltOJ z{cV)Whqb6DWY5;abibB?tfZkco+LG>a(yVSVRA9M&pS?a&^VY`FPOT|wGo1P7xb#$ ztnn$SOB}tML50(bEO)MvFdDpVV04{?vioi(JM?#+o{uvzOaXtrHP>vgied^Ix)t8B zs7tnOv{oW-hz-qTJ>OX&vO-jv4+oSNtrzD*{VTnN2tTx3IpWd)lz}Wr+(+OSz9W?E zV&gzqGqtXsKioMB_j;$p`_$h(DG@~B_d8Ve-yg-Yr`eDp6QQHb&1y@Kw7xwvYS-PO-dEexA=PfnctEbX38CNL)wt8|ajRFxOL)dxi-g=nrqV0voj#WN zX=<0J>avUS9a<~yU^b_5>S-YrH1w7Z@aOC(ZnHZ#38Op@MKV707n%8JabQ0ilqKBi zh4)-G%GH@J-)Pr8Pc>@km-~3{HOs3|0Bk1PNI%3O$s;)>IO`FNl`61wia}PTnkorZ z_-jgXY`zu_ypi>D_k*KWq1@ROAIAkqj`fdep-q&>_Cs&k5PkVkmcZBL{aNCmaR#pB zED`TXtE&LQ$I2Xvv1*C$TJ&o3L}rRvU=A|UyT+vjlHqznbFryB zbZRU$YSqc_Y~1%20x6qM++zQI~9l z_sdR<{lLI>D- z<>J}~NGZduWwhk&3zY8lol$V&LYygLw#iBns%)Hj$jDQ-TZjrQuUnPIYGoG8rR=@b zm^>`>ij_tZ+p~$?iy~Nmg%+1!{WRkHp*HX-;x#5Qg!S;UmjdMKnP(_uzQFtRWdsxo z(g3^K1Y@D7cK-^uDDrH-;Eod-mx4aqtL16RtD5`HIm60&`mQ@u?|Il;e&JwqsnK5^ z``?|D!`(SfYGR0$zeScaS#eowe%mfizr|0ZPs9p1*|14uIYs-aN!B|9^4lNoPo(;ussUu+(TNRJtL1XiQ}wuyUTdcUGuxf? zi;LQ5{Mw$&DtXU{Y^E;0uQ1wrKfj#AaT8IJes?pLl@OI)tT&mtCiut-$AHn|=2Vwn z+4j~Y%NB^VdIK8p5b?B`!jB@YRlxMMeJHzr<2u0mZ`Miv!?$DcKgUa7OZ7Sj4*B2w z;@acL)Rib3_^87#=(F|r>tTrh{_h-!1QQiX^}yUrB8MzJp*Y_bH5)B5S!vB0WFqDM z2dBheD*tvnTnFdaA!ixYB-hmbK~0=SZI)ZI#|B)nW)U!{+0cv4A3r+v23m8_wGMPs zXx*qG+FFIDqKH1r@A5T24ES7p+<5llWu*J19=V+N-=xic>W!m}Q)Pd!(}%ps=Zods z92xL+;d%L4wdx#A(liaN!qB8YIGNhU@t*&67m~b;dwfy8zAy<6VZ)$C0{DiSh6wed;pO26T zb>2Pi{{eR6%R}f9F%NB7K=fIo9`-@JNovtBs+NUFeIx=t)uDA?gCS;<+tlj+9rZ#Y zV6!RSBZf?e0CS-F0gv^dG@$K7ar4eJrf|l#sqUDT5a{m`>hq5h&>U;#GQ5oTI@>hd za|+pp2BquF$e!0T&;(H1U}#prgx}ub^d6bCoa9HG%M1&H%-JQri%b4~=bQiLLx zs0fOS6OXv}+ow&`Iia_N`Q>Ed)pEJG4E%Cw-~6mB@BSr2Wln5<_>(W}Rpxw0_|X+O zv!9%*{@#F->8Ac9>b(l(3n0$!Z}On|T~TRM^rd~N@yFMtoi&1pEXX-WtC^>Cx4#rS zKY1qh#+1zsf6;VP>)6$tmXP!JH*Pk3H(~$a^ z`z(g`eml@z8fetBncI9)Q~Rm`o%>6&Aj^H)<)#;ZFGFMyQ-ED=+;u89Z9Q{j?d~8G zA^5jz_pDIb%jH+G{`n@N9KyQv(yHq_t?^<(#K;Bjvawrbex!axBOZ zR?h4icW`rZK}WHi!@_81O&K9_v`*JHfcjn=g7w>3QReqRD(W0q#OuvRp8?_blYw9lKvToX>e&Z=00eSP`8vgnB85Io|>P7x$JuK&- zpMT0Fdfo!Hl*O*3@gBYVG&o_{f6Ch>MZDalSw%hC)|`C5*OU7 zGCq8iKkG7ua6piRB6-aSK1~&f!IM_l9LzId?A;rpO6<^yrX0ClHNuk{yM9KMX_(o< zZpqb^eZ?F+;C;8VeV~`w1=H3FJ@*WRAhQ<4Ewc9Si$8kpI{43#8!9$MG=RQpZJ@);seIi`T#6_K&CNQ~=3!UDJ^jk@Q`<}$Waw{R2% zPEz$D;k)xgL4cr7-HV5oZcNnkemTq=$Er-k8k!JxTBLI4L*%P3Oz&8@ZMC~s+y(LR z17c?$y(rmJx7Sg2MSU&_(D4;F!q~nRlg3Rb1n)gh$zn6+pO%KlFMhPY{OHjwLvT?g z9Zml0uq!WyxLbY&)ruI%%ve^574Tn?Ud47VU#eK9V4j;yDtUXC9u(+M>6U6%h65Hc z{X$c8bV1z?+Zqgf`MzVhPr7lKFY)byOlseyPJ0$#6o0xRtlHcF@+$ z3k_+W9&Qavm-x#j9#y?s*{$Q&uY(A$SO1&))7xP@DH+mb%`{Nz(KTq`@r0cuyBRQ~ z@E~Pr&7~^hRq73D!Yu^9(}sMlb84X`G^ibz!jgHOs&X%DQpOcfQ1yGj>Ul%H-$-9SdL2R`w>UZ%ZJT%I<#SC-)K;WSK$Foir@eqLb< zhgrKYKeJLrzObwh$~M;zFx*t+cL`FH^f0n0HjA{YR3=g@j+tBvxx%v>71tJY5cVlo8x8^+vh3me@p zOWG_@+wwbYXHpHZg&|}eFbI#H+=(W{pzdbw$Rs{;erzyG-Y>%MDz=VGQF(glsYD%_ z+m_jiwiXh2LCsVNM|I&jkar6*Lrk~jBS>@@tA6c&&XJ)b0 zZm%{Q6zP2y%wb^}>{j0p6WCKX-@hMUxf?q_;wH3wC($OZRR=2O$ptrZqa)+ z3(6J$zOxnr@mGq`-6h~b11iZQdg4&j=zd3sua@^ir7Q=LGP)8yo-9;K?!dELnGIHSeCNvr~e=zYv1rSt;s zzrRTI$N%A#+ygLJq+ETVEG#+$JleyVHb7xDA$~CN36Qe?qN^gzJv$wuY&6j0#t0Ht z8OEBv*;PDdDF(%L7xvV$R=zJsJq2# zNS7#L356qn_sF0I9x<_{o<9Y*k?>1HB7v%vNBH|4l;p}X&&RoyJ$7;8v zDsh5OeSSphNHYY-K%T1?EdgU3#W7%)KGmU5ye>Gow7>(s-nANzRp?Yfi6-jqN9}?($@go&^15tuc`aK>f@;mM@f$nlJE;W_{6Y zgZ!Y9`%P4>^mM_#j?m^QF&Eut{6g@e7X^os?7BVqZvNSDMa08`I8*$xDa3DQFU*;4 zQdQs59X;WDn|OG6NH(Au)Irt^HJRY50sO69rDy1 zd|L!tryr+gsz_c`JAigKrFroL=oge2A(Fh;2VxA?)OdQ*M>^jPUsp9FQqfR*^%I6J zxaE-nLkCg!An5d;vvCwR?5OUc6wPv8XDBaDC2-!TDEh0}vj{3>9>~idf1x>$8_4;@IpMbprxqn`I z+~w`aOnTtb+8WZU8`ok6P!1w_pWBo{=Sty+kuE&-{=Jy0G`o{_p1@ef1>3u~+p-)3<>NZC*_t>hlTFLa6d`JCjVZyK#2@RND2MD!Q}Ovg9!|Iu^_xI)yR(_ZP71++MmyF#aV z?Qv-5Ep5<1RRF0c+?x{H+()-k9>S-NA1GLDZtmOAha(qXCKmd#9+s&)f1OdVEV?a1 zxoo3YMt3pf>h6L6uSEHgZhmpI?%Ju-uzU-IvqmJA&~)-x2N~K}%IImzA>5tPmIXip zQs`tD;ixFiS^nxzp9k(_DOCh~x-vHQlYx}Cn>_&Os*e|rq9U6yaW1YE+bW_L>Zh4J9c46_j3mvBu9gg1icJpmZ!6i()XhYZbS-P;(w++1$;y0n>fp;s zrlFx=x0(>LWI2g^2G=WqCO;EP*gB$<6Ylz%_Qzx(iRS&5(wDxCK>I z8e8(4pXSyI(q}Svn)%Nk6`ZvDQ$fcQ1Z;V_;m|I&-izW?FVAe z!iRH!T2%rv#yXZag=g1)_eIrlnADPqQRZfYPD8VeJAx{Ap>DJDV`v7-MmXg+mm)NC z^eBMYT3Z(#QNIre@#gs-Xkh?#e-JG)2stNx28_nN)ph!_?D1@zxyE(yB!Z#&9AIu0 zxS9y~S&E!p-fnYB2G?OLj_c-Kg(meJiHE9v5^1|2k2UWpoXLb=_GVpf;J02^(8I2V z^SPE_>S!S4B$j;hoP@Pk+SykNFhAi8jB&g>jbaf-ow-Jm$%ypr8%$d%poqSlR- z=N(*iXAm?P4LirW67^X#R!=lg+f@C?LJNJ!`J!rH6KN@65uEw^H?i#m-E!2Cn=Z2y zk?T<@L7mGtd)~6#baD+KIbo*{LEW~Y-g)T`s`bh`~-YM-N%@-`tsYKaJb-YkJ({h05v7=xpV1wpu&Q_&x|dYzZiN z0iZFsZo)VxU-vylXt1Xlr7t9%m0)##5ZZ7YP}BXhJY7xIs{A6MsZ;82Lywo?qUY9xv+{iYiDF!e8iPNlfyXul;Z#ZHg$K^=L`AJwRfrw1@%^wRVGW+f>C-9Io=g^G-JD=c!~t~??Qa@S`E8p|;7T(YCw zvi-Tl4>R$694&J;81uoLB03QBF>l(tl8|Qkm31E~f!RN-glaJaZ@h?8T-Bk+{Av^i z@3zrtBekcm{h$La!!@6U%fH_xgB)bt2!6^^SOcg;+A8c zZ;zfq&KKiXErLT%`tZ?{Re{}Oe;t$#;)8%7@t(W)&@(n)D+!^LqORv?6!8)QqQC+W;l z3?fQY#73L0ztGxP+);j}61Xst8Omk46-*q~JjJfD(ZF0*7yfBB)HS}`yZFQ^QI^jo z6p;aWO&Q#`5!jU}8LBo7(XJzcz;N=sckzb!J-Z0nD**#$YjBDxgEVSDShe16&Y zKdS(MHuMkGG3c2eVnn*57}QLhDn}jtpBxTW8yZ5#*40`z5`VhgVZ!Q|Mj>!<>sb_J zB=XfgB65A2=(Yk7h>=yu;<6~gHtj5p@| zr~o4VACqpbq%X$T8NI1B43SVt)e}ReFj(STP)4W;pR$E?e{Lv#-S@z~p+U9IBP%4c zLxthV;Ww>~9`C@>S$}BoDMQ|D2}xdj9@pl7V_J$rX4sg(O~K&qzSz5Oaiw)L>oBuG z!x*xq3XGY|`8hb)V-_KQ_VxAbOe7p7)cv}pEVZ{8!X`bf7 zkyhjb%hMgocibc2{fQO|JBJ{O-r_$+3i02xSKv!+b_c;;(xc2*%+}Y{@5JbPC~z*_ zW|0g{Fc=Mw<16)HHA12gtNe>oZwNEMdB+bo(!Vv*0YH zeSb#8)Il^nge4I{x$Lu_9jq)IH4Ly$jM2cm)09_a>k^>;mf6;&c@f$Q7UYQ{>)AbQ zLEh}UADv}!zF&4Y-aR~AnR#Q9>Sm}dy_xVS$D%FecV(*pvsBnqF<|EKLKIwMhpp?u zm4>56n#dfBL=N@ZA}<%yKmG5q2h%B1YT_@RO8uNmIGT+CA3kg1KhxQ2%PWmf(zF)C z&;J;W?B&MZs))>++-a$oXmirXpkv_=vJ-Eag_knQ*_;}cosV^GNW>HdX)DcM%D=sl zl>Ire{+Z5%fXCJM{vQt#uXsOGlY#$z1JvuP>GOYPeKvQ(wwoAO;EJX^j|kd$WOsu9 z&YN#*$yoNr`K4ahjpOeI&^)b{+ZKuNeUI2g#M=Y>a6d5>f?7S}C;NghddJPadj_Wv z%8~8q0vGj$&TEaUenhB}1T*o?i7`j%+a2_|D*F3n_YFR0G(a3G&*-PsOk*`JE6T|* zc_IJaPioD&tL(64BMP*Y_r>%VAGO(tau+|eIssCE&+`}Jkt!ll<=gU)hkTVeK`*Nz zyD>9|#r=@JiqpmLaH@_`9J><1vbm>~rg;`gJiB@itEH0!v3cv(z;-U!kUJvzwi%3d zP*dIGfk-qeh=pcpSqinG7vlu~F&?%RpnxQCaq+*Z7x%jBba%mOlfmAe<^dn{-l8Jp zsc(Ow(toj*-g{0kHE={|Dt-bsAF?kXfA~Oc(8fb?NG)P97=d%k()?&~UfAs6l4@s* zuB6A_@a+}T2J5^@IYudwA46f9JFi2JX33UgznV0OxsJ1@vsmF7j;FItZfaTaw>T1b1l?|7ux>fw1Fl+r48xD6Ci2vKj-0o>ssXmyC2sj}bJ zcKTX+QTn|nJ;hzZBMIaomJGX!#UIRf0j2zUnbR6PbFBRa zqzgxlF0UpSvJCt|%y2ZvkKBUgw&z~l(a(5vv&ndkG2s4{$t2cf;|wz~ z>MYR@O*vG+&|*CF`JTW-fy%f?Ch8yw!O-K^LO(TuydS>hwZltxi!ZrXJg@x6-!$Sw zE@{g;`C4+hvRb0!PfX=-?VlrM{%4!OuP)zsdc4fq7Ct4JBb>94ZZsA89?c~J1swDW z{au?VWAeLh2E$Lzy5pb5G(fa~d!xz%V_~BQOBXuyEdI7#OY7sgU+#DoFPvZgi?!nC z{BZqKj9yeHHOPWoYQz8})z+ep*J|tlQFZdL8x72OWD5hDi3=*~_u>2#Dla^;;&S2os7j&W_btWHWo_tY*8ZFN6zDMd;CrwV_oIl$ zKHUWA^|f9zk4(vRy+QVA?F&D64+RN5hKC%P@w!h8ptK}51BF~N`|sAV5aCMryg3zX zcOP58;l45tgaxr6g5sawbbh@)#vSy$^RSCS92{>WT|8f|E>dN`a=%-un8= ziVYfj&A3BHM)nJ|>H?M^X22u}?hyrw()J*~X>^z*1c{vGmZHx>bJHq$un_rD#8fi9}wG@bA^aC!thLv{bL`ekx}S^F0K9(M8$rL=R0fAL_4;Y(C8}P_kNR ztu~fmE>z&Z=VU2-6@&iJdk0{bIR-w~@pyHe5Z>~s08ac3G&7BZUss7GeF zin>B%9b!`KU^CD2mYrT1ghpT^5K6*LZONougLydu7j86Up|Mbc# zoHM%X@1PU1X&uR&yjJ65W>*tU?AuAuO|g4j7gX?$!`jQw$So~y#h#E%!9nyA=YLoT z>-qfXj0F@FiS8#_(CCVOXSO+xsJTg`DNbn%@lKJFw^lc?l6l5iHs;44z0t3Ac2LrK zAQ@1I0|P1X4HSWmWbdfF*5R(Q8Y$5zq`opr$zavqgt!%#=h$#OS9yY8wg%C{h8KGu zeGv7iUSF{`j$nV{7DtDJ25mn*#l-mwxR`8ZT79Nk$ek>EX`Y>;DJvnT)bx{M&7rsX z2!O>C4xXJZeLCT8tb4WR?1bIiWapTulO(1 z^v~dFinsw!KA{PBQUnEf6wl#U(qgkzHmov7RCq6iypRUZQKg(Us}!86DyJ-uAJP$$ z`S{y?9R3xa4YPk73pxT|KIE~SRgj3wxnNj}d8oIU%jy>KMF|7GIgkImuxYuCUrHvc zo8y$W`RbbDe*|Okzb>1m)5D> z9)2}Uj2Ih;xh@RF3|7LZo|UD+W1dZeIiI?+uSyKvQ4%3)^cm$7VCYF-E3{+_*?3pCn4lT z5KN(ZeY@Q`6ly?zdD1KnqJiA0>aYoD&>XqvD1-soJDL;SF%t?P#PF8GQUPl zMlcN!8}|4`T;86hvqcJi?&~dhc?26Z7B@e2efRB zo+r{t_AX2eNWw3TTy2#%MHhemma5^4g6z7S>{(p^5FRDji(};_Fp^0G&6~Ze7*y&- z2GSMUZ!%R^7CFIgy9^(HyhmcLSUfSzW(%?C9xx06dj5H@|8w-iQM~|PvWCFgWHS9q zrB7P8Y9%Xv96q39@{N3^Pg5xmPBxp-bJv14dfJqmU&i{sL_HZ4@B6iyS1QRt$24$p zg$g)Z2p3w#XU%=_qV7D4Zhvc6412~wbw9K;7v|9GPpX>n-mC8Y+tbhKy)!Eu{4BBj zg~Jic0~v{tG5NwyYAJdERe|YhL(zA=J)rU@r@>NzrbJYKqIg(E(=q@y#z5%8xqMt< zHvBf{J8qYk9sP{MIaW~P;7?tA)z#Z~TkO2LQy$^?85<7uDys#=clHc09=GAhL@!fz z*fI!_oHz)H9!*>~;!U~ zb2Dx)@LmIMl>^_K-W^I>XsGfK>x1OM_H2 z$bzx3gWX?6A*_cLCho$kV%*h>R%zp{$w2F_1#(oS2p=~lP9NsY>nOpuAN037&NG9p zP{8N=xaJGUspR8|$#BH~t@*akWx=8Cwz^)?Ax%Z0S$bXMpD?mHtjhFJtg*RTC`kce zY-Ubb5rRZAgqYT60bqz{+tKR*>`y^`;nZ+^{WR!2Xt;wBTZfFcw3EQ$TX)euBwxr$({Hl!ax{-1CxXFXIQtV+Ue zzJm)v$~*O{@a}FMMV6zzRw`z1%pKxg{-PO%Zoq3OrFEep$TMBsNfLZ@6CWz< z7T9wL4;L?BvV`8Fak>0WI2SN2)-)agX+s|aC`l+7nY;_2@D>i( zS#00#xX7Yi`Sf&V0`Xi#rG!pB|8dy$b-FVP6ZpQ% z@1M4;EmRZDCCpi9z8~fbG0!jDkYt~7P?>F)uUFxC6)S(T09rwo<;4JjG)i~t!~UWl zgdt~ePfl_ISEoQTp8--LmxG>UbV`i^$i+3_HfkoSTjgWM4r9Z&ilvRL{~}dj43w1D z1h85>W2~f3;6kLA#m{*LAVsbDv@qlyRnt2mwR1mAYqau?+0e*5^9;ZvVO73?jVE`psDq+vJ~^^RoazehtJf# z(*&$UpXJP-{@UKrvlDJiZ*Kp2*022mP#|k!sg`azmVMPDNq?VWA_CB*AqiaE&TDlH z0+0?~IEF!1|NYQ`#~(mEtFP-A8XDBv^Ak_3umY|87J={TpMExQV>HMbk_s%9(DQ&y z{0p&46v{fcj3^Cxty>1UTa_l3%|Otn3CQjz73~(kobg=-lBbZKfzSeT4h7<-P7g6k z%ao#GnY7SUXd`df8oyxwhzdGQ7xA#V_ER2G(vW*!WMM+Swl_EN7*_;Gg46=};(c;R z(|GidT53VBfKDZS80=lIceHrG?~=+bIAm%0cQShB=>17^NJ+Fbn6C2zR$fhCoO(0< zypHWAT|8ay_{!z-wgDY~Aes8*h0GpTh2n2?zJtZxfbM}1taV+U4oojiEox7zZ!>i5 zDXHNOMzPzzRjkMnykq(5KqtAXYt)-@@A_qa2PEdt_jQ`hOd%N;DEIYN(A_V&1Cpc+ zs>A&FT1obyf)e4|zn{DPA#k_JpQ}9Ue$D&Zm3xTeX%inV&9bzsMZ;#d-%v-O=Lko-`Gv1lE zSx>q%V>R0gzVm0Ck_? zy;H5-2^yQ;xZ?2U$;FxBiBAz)(~i17!9?ZVgSxh&R-Z?F!?h#;;P>UxJ4_fo;@5r; zCPLGpi3s>yQ#;h|Kxn%{BurYPEvt8}^E-#GE1i(I@`uL`ra8}Zx=sIju6ovqbpx@bfWnd)+RK>zvMN*E zyV3>BrdmO|$Hm)Vea(hiO{#zo8@&FGYkS6}9KCM+Y zngD+zdArCW!Esr)d82`hRMAO^ObH|3pdBvLv#8h8CMK5UsDzVINsr_>ch$S#1rw3F zU(3ELMP7h96ZhZEz7(H8{fKAgmOt(~6!@b|Rx_?(Ww@k$!ghz<{RU z?vbk)kAoJZ@EfI-<==4RI3o>ggkEO(8~^w&i1fHCwkpmLxr| zSec_7(FeYXi5353>jZxjzW1>ah?QcnGejk!$&%g9L>aY^k`s9aL_2&=D2nN@S{3;* z6sOw zwYBt|?umK^d*E|V$u-V4^axi0ic1Qi+W&~{@=dts7fqzIwDE`@{+c25*PUkpBcC8+xu<(DqTvfHAy;gI9|W#@(FHm^tL-?~U&5t6?Kgv#iK-I~nTN>SbT z#MH9%gs8sw2Bc2`pA)*~4-Rru{UJA$h4!|ewjIWUE{QRFLfbaCYdnv%gH?Fwb!R!u zx7$Nf^x}fMGGJrm|DyLD2nXiVO*(6(T=~da8j(fbaX1LYQVj*{u9Y#mVREdO;_($7*^R;*wgoLJR`Hf3?s{m$cKU6Uo03 zb*p-c5?%Ojn}uii9CChvnf=kIR~5Rq$0o^)NbVMW_0wOKAaP#3L&|hUU&~BBk#5nm za~?6H-hjH^4SU~n*;krGk&%ST4dr={raKWk{x@%K7`a{udaI|^KRv40p~{(<<&?>= z3(m*SFm)@IoQ+@<9Y4E>TyB|!V#;U*k zg*G&lMi|w*aGA3r{M!q55DksKjB2*br3;Gv$*agipfr0yes7>jn#BliSYA&j$zQTB zX}_h17e4xccIV#AYLkHxu2O#mOOLI~>0q8(_IR$|HSy8E_j{3k;1{PO zoe%~rL(ZbM-J*r>9Y*M~l@jP4Zp4llXywdz?NUFKOXS7L+(bHDi z53!U}JM&E+2{C0)msV;~3^N~6F?wdEq@ux)7;@@aLyFVeOMo>{Dni6C`?0ZKE%f*N z{POy`-|s}T?kOlMTMRJ5TW-S{x21IVTf{FXcL=IAH<`LK5puap^_UwnM!#Y7N2aG! zoM>wFSNs1uZMrr#m*urhzO88x#(YtFc+I|KyZY*#Uluf0C6&$1k|@;tp+}N5`UzH(@WPqv;ZzTo491isxW4*%R4xO+c3ie$=oEeZl8K{(j-r+6Ng;>ga$cUUG&8 zD-?w+6Ivac;5Q*bO?a6JTurc+^l9_q1z2Tsf~*_BZFrOLGK!yjnaw^0Qb~9Nehf#( zA%hGA?~Fo-qoS)hVj{lPl_xLf5@iL5Z(}1?UB!G2B`4(TP#PH%q~Bun=Mg6t=0