From 6d31c73216e8267f0a08ac54d4340b7c8e0c99b2 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Thu, 15 Aug 2019 11:05:24 -0700 Subject: [PATCH 01/56] style fix and remove unused variable --- examples/DeformableDemo/DeformableMultibody.cpp | 2 -- .../btDeformableRigidDynamicsWorld.cpp | 12 ++++++------ src/BulletSoftBody/btDeformableRigidDynamicsWorld.h | 3 +-- src/BulletSoftBody/btSoftBodyInternals.h | 4 ++-- 4 files changed, 9 insertions(+), 12 deletions(-) diff --git a/examples/DeformableDemo/DeformableMultibody.cpp b/examples/DeformableDemo/DeformableMultibody.cpp index e947a5585..d32cd67a7 100644 --- a/examples/DeformableDemo/DeformableMultibody.cpp +++ b/examples/DeformableDemo/DeformableMultibody.cpp @@ -49,8 +49,6 @@ static bool g_floatingBase = true; static float friction = 1.; class DeformableMultibody : public CommonMultiBodyBase { - btMultiBody* m_multiBody; - btAlignedObjectArray m_jointFeedbacks; public: DeformableMultibody(struct GUIHelperInterface* helper) : CommonMultiBodyBase(helper) diff --git a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp b/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp index 3b3b62edc..80c77ada1 100644 --- a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp +++ b/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp @@ -64,7 +64,7 @@ void btDeformableRigidDynamicsWorld::internalSingleStepSimulation(btScalar timeS // /////////////////////////////// } -void btDeformableRigidDynamicsWorld::positionCorrection(btScalar dt) +void btDeformableRigidDynamicsWorld::positionCorrection(btScalar timeStep) { // perform position correction for all constraints BT_PROFILE("positionCorrection"); @@ -140,7 +140,7 @@ void btDeformableRigidDynamicsWorld::positionCorrection(btScalar dt) { c->m_node->m_v = va; } - c->m_node->m_v -= dp * cti.m_normal / dt; + c->m_node->m_v -= dp * cti.m_normal / timeStep; } } } @@ -149,19 +149,19 @@ void btDeformableRigidDynamicsWorld::positionCorrection(btScalar dt) } -void btDeformableRigidDynamicsWorld::integrateTransforms(btScalar dt) +void btDeformableRigidDynamicsWorld::integrateTransforms(btScalar timeStep) { BT_PROFILE("integrateTransforms"); m_deformableBodySolver->backupVelocity(); - positionCorrection(dt); - btMultiBodyDynamicsWorld::integrateTransforms(dt); + positionCorrection(timeStep); + btMultiBodyDynamicsWorld::integrateTransforms(timeStep); for (int i = 0; i < m_softBodies.size(); ++i) { btSoftBody* psb = m_softBodies[i]; for (int j = 0; j < psb->m_nodes.size(); ++j) { btSoftBody::Node& node = psb->m_nodes[j]; - node.m_x = node.m_q + dt * node.m_v; + node.m_x = node.m_q + timeStep * node.m_v; } } m_deformableBodySolver->revertVelocity(); diff --git a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.h b/src/BulletSoftBody/btDeformableRigidDynamicsWorld.h index de5eb7ef4..6efbb204b 100644 --- a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.h +++ b/src/BulletSoftBody/btDeformableRigidDynamicsWorld.h @@ -38,7 +38,6 @@ class btDeformableRigidDynamicsWorld : public btMultiBodyDynamicsWorld bool m_drawFaceTree; bool m_drawClusterTree; btSoftBodyWorldInfo m_sbi; - bool m_ownsSolver; btScalar m_internalTime; typedef void (*btSolverCallback)(btScalar time, btDeformableRigidDynamicsWorld* world); @@ -49,7 +48,7 @@ protected: virtual void integrateTransforms(btScalar timeStep); - void positionCorrection(btScalar dt); + void positionCorrection(btScalar timeStep); void solveDeformableBodiesConstraints(btScalar timeStep); diff --git a/src/BulletSoftBody/btSoftBodyInternals.h b/src/BulletSoftBody/btSoftBodyInternals.h index 80545ebad..a39394e0b 100644 --- a/src/BulletSoftBody/btSoftBodyInternals.h +++ b/src/BulletSoftBody/btSoftBodyInternals.h @@ -998,7 +998,7 @@ struct btSoftColliders if (!n.m_battach) { // check for collision at x_{n+1}^* - if (psb->checkDeformableContact(m_colObj1Wrap, n.m_x, m, c.m_cti, /*predicted = */ true)) + if (psb->checkDeformableContact(m_colObj1Wrap, n.m_x, m, c.m_cti, /*predict = */ true)) { const btScalar ima = n.m_im; const btScalar imb = m_rigidBody ? m_rigidBody->getInvMass() : 0.f; @@ -1006,7 +1006,7 @@ struct btSoftColliders if (ms > 0) { // resolve contact at x_n - psb->checkDeformableContact(m_colObj1Wrap, n.m_q, m, c.m_cti, /*predicted = */ false); + psb->checkDeformableContact(m_colObj1Wrap, n.m_q, m, c.m_cti, /*predict = */ false); btSoftBody::sCti& cti = c.m_cti; c.m_node = &n; const btScalar fc = psb->m_cfg.kDF * m_colObj1Wrap->getCollisionObject()->getFriction(); From 10e819db8e1abec2b1eefc9820d596cfe80b4489 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Wed, 7 Aug 2019 15:21:16 -0700 Subject: [PATCH 02/56] add grasping with joint motor example --- examples/ExampleBrowser/ExampleEntries.cpp | 1 + examples/GraspDeformable/GraspDeformable.cpp | 525 +++++++++++++++++++ examples/GraspDeformable/GraspDeformable.h | 20 + 3 files changed, 546 insertions(+) create mode 100644 examples/GraspDeformable/GraspDeformable.cpp create mode 100644 examples/GraspDeformable/GraspDeformable.h diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index 481d36c5d..030f4eef1 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -197,6 +197,7 @@ static ExampleEntry gDefaultExamples[] = ExampleEntry(0, "Deformabe Body"), ExampleEntry(1, "Deformable-RigidBody Contact", "Deformable test", DeformableRigidCreateFunc), ExampleEntry(1, "Grasp Deformable Cube", "Grasping test", PinchCreateFunc), + ExampleEntry(1, "Grasp Deformable with Motor", "Grasping test", GraspDeformableaCreateFunc), ExampleEntry(1, "Volumetric Deformable Objects", "Volumetric Deformable test", VolumetricDeformableCreateFunc), ExampleEntry(1, "Deformable-MultiBody Contact", "MultiBody and Deformable contact", DeformableMultibodyCreateFunc), // ExampleEntry(1, "MultiBody Baseline", "MultiBody Baseline", MultiBodyBaselineCreateFunc), diff --git a/examples/GraspDeformable/GraspDeformable.cpp b/examples/GraspDeformable/GraspDeformable.cpp new file mode 100644 index 000000000..b291dbafb --- /dev/null +++ b/examples/GraspDeformable/GraspDeformable.cpp @@ -0,0 +1,525 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + +#include "GraspDeformable.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h" +#include "BulletSoftBody/btSoftBody.h" +#include "BulletSoftBody/btSoftBodyHelpers.h" +#include "BulletSoftBody/btDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h" +#include //printf debugging + +#include "../CommonInterfaces/CommonRigidBodyBase.h" +#include "../Utils/b3ResourcePath.h" +#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h" +#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h" +#include "../Importers/ImportURDFDemo/URDF2Bullet.h" +#include "../CommonInterfaces/CommonMultiBodyBase.h" +#include "../CommonInterfaces/CommonGraphicsAppInterface.h" +#include "../CommonInterfaces/CommonParameterInterface.h" + + +///The GraspDeformable shows the use of rolling friction. +///Spheres will come to a rest on a sloped plane using a constraint. Damping cannot achieve the same. +///Generally it is best to leave the rolling friction coefficient zero (or close to zero). +static btScalar sGripperVerticalVelocity = 0.f; +static btScalar sGripperClosingTargetVelocity = 0.f; +static float friction = 1.; +struct TetraCube +{ +#include "../SoftDemo/cube.inl" +}; + +struct TetraBunny +{ +#include "../SoftDemo/bunny.inl" +}; + +static bool supportsJointMotor(btMultiBody* mb, int mbLinkIndex) +{ + bool canHaveMotor = (mb->getLink(mbLinkIndex).m_jointType == btMultibodyLink::eRevolute + || mb->getLink(mbLinkIndex).m_jointType == btMultibodyLink::ePrismatic); + return canHaveMotor; +} + +class GraspDeformable : public CommonRigidBodyBase +{ +public: + GraspDeformable(struct GUIHelperInterface* helper) + : CommonRigidBodyBase(helper) + { + } + virtual ~GraspDeformable() + { + } + void initPhysics(); + + void exitPhysics(); + + void resetCamera() + { + float dist = 20; + float pitch = -45; + float yaw = 100; + float targetPos[3] = {0, -0, 0}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + btMultiBody* createFeatherstoneMultiBody(btMultiBodyDynamicsWorld* pWorld,const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool floating); + + void addColliders(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents); + + btMultiBody* createFeatherstoneMultiBody_testMultiDof(btMultiBodyDynamicsWorld* pWorld, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical, bool floating); + + void stepSimulation(float deltaTime) + { + double fingerTargetVelocities[2] = {sGripperVerticalVelocity, sGripperClosingTargetVelocity}; + int num_multiBody = getDeformableDynamicsWorld()->getNumMultibodies(); + for (int i = 0; i < num_multiBody; ++i) + { + btMultiBody* mb = getDeformableDynamicsWorld()->btMultiBodyDynamicsWorld::getMultiBody(i); + mb->setBaseVel(btVector3(0,sGripperVerticalVelocity, 0)); + int dofIndex = 6; //skip the 3 linear + 3 angular degree of freedom entries of the base + for (int link = 0; link < mb->getNumLinks(); link++) + { + if (supportsJointMotor(mb, link)) + { + btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)mb->getLink(link).m_userPtr; + if (motor) + { +// if (dofIndex == 10 || dofIndex == 11) +// { +// motor->setVelocityTarget(fingerTargetVelocities[1], 1); +// motor->setMaxAppliedImpulse(1); +// } + if (dofIndex == 6) + { + motor->setVelocityTarget(-fingerTargetVelocities[1], 1); + motor->setMaxAppliedImpulse(2); + } + if (dofIndex == 7) + { + motor->setVelocityTarget(fingerTargetVelocities[1], 1); + motor->setMaxAppliedImpulse(2); + } +// motor->setRhsClamp(SIMD_INFINITY); + motor->setMaxAppliedImpulse(1); + } + } + dofIndex += mb->getLink(link).m_dofCount; + } + } + + //use a smaller internal timestep, there are stability issues + float internalTimeStep = 1. / 250.f; + m_dynamicsWorld->stepSimulation(deltaTime, 5, internalTimeStep); + } + + void createGrip() + { + int count = 2; + float mass = 2; + btCollisionShape* shape[] = { + new btBoxShape(btVector3(3, 3, 0.5)), + }; + static const int nshapes = sizeof(shape) / sizeof(shape[0]); + for (int i = 0; i < count; ++i) + { + btTransform startTransform; + startTransform.setIdentity(); + startTransform.setOrigin(btVector3(10, 0, 0)); + startTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.)); + createRigidBody(mass, startTransform, shape[i % nshapes]); + } + } + + virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const + { + return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + } + + virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() + { + return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + } + + virtual void renderScene() + { + CommonRigidBodyBase::renderScene(); + btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + btSoftBody* psb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i]; + { + btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer()); + btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + } + } + } +}; + + +void GraspDeformable::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); + + m_broadphase = new btDbvtBroadphase(); + btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); + + btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); + m_solver = sol; + + m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); + deformableBodySolver->setWorld(getDeformableDynamicsWorld()); + btVector3 gravity = btVector3(0, -10, 0); + m_dynamicsWorld->setGravity(gravity); + getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + +// // load a gripper +// { +// btTransform rootTrans; +// rootTrans.setIdentity(); +// BulletURDFImporter u2b(m_guiHelper,0,0,50,0); +// bool forceFixedBase = false; +// bool loadOk = u2b.loadSDF("gripper/wsg50_one_motor_gripper_new.sdf", forceFixedBase); +// if (loadOk) +// { +// for (int m = 0; m < u2b.getNumModels(); m++) +// { +// u2b.activateModel(m); +// +// btMultiBody* mb = 0; +// +// MyMultiBodyCreator creation(m_guiHelper); +// +// u2b.getRootTransformInWorld(rootTrans); +// ConvertURDF2Bullet(u2b, creation, rootTrans, getDeformableDynamicsWorld(), true, u2b.getPathPrefix(), CUF_USE_SDF+CUF_RESERVED); +// mb = creation.getBulletMultiBody(); +// +// int numLinks = mb->getNumLinks(); +// for (int i = 0; i < numLinks; i++) +// { +// int mbLinkIndex = i; +// float maxMotorImpulse = 1.f; +// +// if (supportsJointMotor(mb, mbLinkIndex)) +// { +// int dof = 0; +// btScalar desiredVelocity = 0.f; +// btMultiBodyJointMotor* motor = new btMultiBodyJointMotor(mb, mbLinkIndex, dof, desiredVelocity, maxMotorImpulse); +// motor->setPositionTarget(0, 0); +// motor->setVelocityTarget(0, 1); +// mb->getLink(mbLinkIndex).m_userPtr = motor; +// getDeformableDynamicsWorld()->addMultiBodyConstraint(motor); +// motor->finalizeMultiDof(); +// } +// } +// } +// } +// } + // build a gripper + { + bool damping = true; + bool gyro = false; + bool canSleep = false; + bool selfCollide = true; + int numLinks = 2; + btVector3 linkHalfExtents(1., 2, .4); + btVector3 baseHalfExtents(1, 0.2, 2); + btMultiBody* mbC = createFeatherstoneMultiBody(getDeformableDynamicsWorld(), btVector3(0.f, 7.f,0.f), linkHalfExtents, baseHalfExtents, false); + + mbC->setCanSleep(canSleep); + mbC->setHasSelfCollision(selfCollide); + mbC->setUseGyroTerm(gyro); + + for (int i = 0; i < numLinks; i++) + { + int mbLinkIndex = i; + float maxMotorImpulse = 1.f; + + if (supportsJointMotor(mbC, mbLinkIndex)) + { + int dof = 0; + btScalar desiredVelocity = 0.f; + btMultiBodyJointMotor* motor = new btMultiBodyJointMotor(mbC, mbLinkIndex, dof, desiredVelocity, maxMotorImpulse); + motor->setPositionTarget(0, 0); + motor->setVelocityTarget(0, 1); + mbC->getLink(mbLinkIndex).m_userPtr = motor; + getDeformableDynamicsWorld()->addMultiBodyConstraint(motor); + motor->finalizeMultiDof(); + } + } + + + if (!damping) + { + mbC->setLinearDamping(0.0f); + mbC->setAngularDamping(0.0f); + } + else + { + mbC->setLinearDamping(0.04f); + mbC->setAngularDamping(0.04f); + } + btScalar q0 = 0.f * SIMD_PI / 180.f; + if (numLinks > 0) + mbC->setJointPosMultiDof(0, &q0); + /// + addColliders(mbC, getDeformableDynamicsWorld(), baseHalfExtents, linkHalfExtents); + + } + //create a ground + { + btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(25.), btScalar(150.))); + + m_collisionShapes.push_back(groundShape); + + btTransform groundTransform; + groundTransform.setIdentity(); + groundTransform.setOrigin(btVector3(0, -25-2.1, 0)); + groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0)); + //We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here: + btScalar mass(0.); + + //rigidbody is dynamic if and only if mass is non zero, otherwise static + bool isDynamic = (mass != 0.f); + + btVector3 localInertia(0, 0, 0); + if (isDynamic) + groundShape->calculateLocalInertia(mass, localInertia); + + //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects + btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); + btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); + btRigidBody* body = new btRigidBody(rbInfo); + body->setFriction(0.5); + + //add the ground to the dynamics world + m_dynamicsWorld->addRigidBody(body); + } + + // create a soft block + { + btSoftBody* psb = btSoftBodyHelpers::CreateFromTetGenData(getDeformableDynamicsWorld()->getWorldInfo(), + TetraCube::getElements(), + 0, + TetraCube::getNodes(), + false, true, true); + + psb->scale(btVector3(2, 2, 2)); + psb->translate(btVector3(0, 0, 0)); + psb->getCollisionShape()->setMargin(0.1); + psb->setTotalMass(1); + psb->setSpringStiffness(2); + psb->setDampingCoefficient(0.02); + psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + psb->m_cfg.kCHR = 1; // collision hardness with rigid body + psb->m_cfg.kDF = 2; + getDeformableDynamicsWorld()->addSoftBody(psb); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); + } + + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); + + { + SliderParams slider("Moving velocity", &sGripperVerticalVelocity); + slider.m_minVal = -2; + slider.m_maxVal = 2; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + } + + { + SliderParams slider("Closing velocity", &sGripperClosingTargetVelocity); + slider.m_minVal = -1; + slider.m_maxVal = 1; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + } + +} + +void GraspDeformable::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + +btMultiBody* GraspDeformable::createFeatherstoneMultiBody(btMultiBodyDynamicsWorld* pWorld, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool floating) +{ + //init the base + btVector3 baseInertiaDiag(0.f, 0.f, 0.f); + float baseMass = .1f; + float linkMass = .1f; + int numLinks = 2; + + if (baseMass) + { + btCollisionShape* pTempBox = new btBoxShape(btVector3(baseHalfExtents[0], baseHalfExtents[1], baseHalfExtents[2])); + pTempBox->calculateLocalInertia(baseMass, baseInertiaDiag); + delete pTempBox; + } + + bool canSleep = false; + btMultiBody* pMultiBody = new btMultiBody(numLinks, baseMass, baseInertiaDiag, !floating, canSleep); + + btQuaternion baseOriQuat(0.f, 0.f, 0.f, 1.f); + pMultiBody->setBasePos(basePosition); + pMultiBody->setWorldToBaseRot(baseOriQuat); + + //init the links + btVector3 hingeJointAxis(1, 0, 0); + + btVector3 linkInertiaDiag(0.f, 0.f, 0.f); + + btCollisionShape* pTempBox = new btBoxShape(btVector3(linkHalfExtents[0], linkHalfExtents[1], linkHalfExtents[2])); + pTempBox->calculateLocalInertia(linkMass, linkInertiaDiag); + delete pTempBox; + + //y-axis assumed up + btAlignedObjectArray parentComToCurrentCom; + parentComToCurrentCom.push_back(btVector3(0, -linkHalfExtents[1] * 8.f, -baseHalfExtents[2] * 4.f)); + parentComToCurrentCom.push_back(btVector3(0, -linkHalfExtents[1] * 8.f, +baseHalfExtents[2] * 4.f));//par body's COM to cur body's COM offset + + btVector3 currentPivotToCurrentCom(0, -linkHalfExtents[1]*8.f, 0); //cur body's COM to cur body's PIV offset + + btAlignedObjectArray parentComToCurrentPivot; + parentComToCurrentPivot.push_back(btVector3(parentComToCurrentCom[0] - currentPivotToCurrentCom)); + parentComToCurrentPivot.push_back(btVector3(parentComToCurrentCom[1] - currentPivotToCurrentCom));//par body's COM to cur body's PIV offset + + ////// + btScalar q0 = 0.f * SIMD_PI / 180.f; + btQuaternion quat0(btVector3(0, 1, 0).normalized(), q0); + quat0.normalize(); + ///// + + for (int i = 0; i < numLinks; ++i) + { + pMultiBody->setupRevolute(i, linkMass, linkInertiaDiag, - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), hingeJointAxis, parentComToCurrentPivot[i], currentPivotToCurrentCom, true); + } + pMultiBody->finalizeMultiDof(); + /// + pWorld->addMultiBody(pMultiBody); + /// + return pMultiBody; +} + +void GraspDeformable::addColliders(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents) +{ + btAlignedObjectArray world_to_local; + world_to_local.resize(pMultiBody->getNumLinks() + 1); + + btAlignedObjectArray local_origin; + local_origin.resize(pMultiBody->getNumLinks() + 1); + world_to_local[0] = pMultiBody->getWorldToBaseRot(); + local_origin[0] = pMultiBody->getBasePos(); + + { + btScalar quat[4] = {-world_to_local[0].x(), -world_to_local[0].y(), -world_to_local[0].z(), world_to_local[0].w()}; + + if (1) + { + btCollisionShape* box = new btBoxShape(baseHalfExtents); + btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, -1); + col->setCollisionShape(box); + + btTransform tr; + tr.setIdentity(); + tr.setOrigin(local_origin[0]); + tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3])); + col->setWorldTransform(tr); + + pWorld->addCollisionObject(col, 2, 1 + 2); + + col->setFriction(friction); + pMultiBody->setBaseCollider(col); + } + } + + for (int i = 0; i < pMultiBody->getNumLinks(); ++i) + { + const int parent = pMultiBody->getParent(i); + world_to_local[i + 1] = pMultiBody->getParentToLocalRot(i) * world_to_local[parent + 1]; + local_origin[i + 1] = local_origin[parent + 1] + (quatRotate(world_to_local[i + 1].inverse(), pMultiBody->getRVector(i))); + } + + for (int i = 0; i < pMultiBody->getNumLinks(); ++i) + { + btVector3 posr = local_origin[i + 1]; + + btScalar quat[4] = {-world_to_local[i + 1].x(), -world_to_local[i + 1].y(), -world_to_local[i + 1].z(), world_to_local[i + 1].w()}; + + btCollisionShape* box = new btBoxShape(linkHalfExtents); + btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, i); + + col->setCollisionShape(box); + btTransform tr; + tr.setIdentity(); + tr.setOrigin(posr); + tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3])); + col->setWorldTransform(tr); + col->setFriction(friction); + pWorld->addCollisionObject(col, 2, 1 + 2); + + pMultiBody->getLink(i).m_collider = col; + } +} + +class CommonExampleInterface* GraspDeformableCreateFunc(struct CommonExampleOptions& options) +{ + return new GraspDeformable(options.m_guiHelper); +} + + diff --git a/examples/GraspDeformable/GraspDeformable.h b/examples/GraspDeformable/GraspDeformable.h new file mode 100644 index 000000000..fed8cb03e --- /dev/null +++ b/examples/GraspDeformable/GraspDeformable.h @@ -0,0 +1,20 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ +#ifndef _GRASP_DEFORMABLE_H +#define _GRASP_DEFORMABLE_H + +class CommonExampleInterface* GraspDeformableCreateFunc(struct CommonExampleOptions& options); + +#endif //_GRASP_DEFORMABLE_H From 94aeb4657b7a5e751beeb37bb840d951fff8f72e Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Wed, 7 Aug 2019 15:24:26 -0700 Subject: [PATCH 03/56] add comment and initialization --- src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp | 3 +-- src/BulletDynamics/Featherstone/btMultiBodyLink.h | 2 ++ 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp index 1be76ad86..f5a7a7f1e 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp @@ -588,15 +588,14 @@ void btMultiBodyDynamicsWorld::solveExternalForces(btContactSolverInfo& solverIn { if (!bod->isUsingRK4Integration()) { + // avoid damping in external forces (e.g. gravity) const btScalar linearDamp = bod->getLinearDamping(); -// const btScalar angularDamp = bod->getAngularDamping(); bod->setLinearDamping(0); bod->computeAccelerationsArticulatedBodyAlgorithmMultiDof(solverInfo.m_timeStep, m_scratch_r, m_scratch_v, m_scratch_m,isConstraintPass, getSolverInfo().m_jointFeedbackInWorldSpace, getSolverInfo().m_jointFeedbackInJointFrame); bod->setLinearDamping(linearDamp); -// bod->setAngularDamping(angularDamp); } else { diff --git a/src/BulletDynamics/Featherstone/btMultiBodyLink.h b/src/BulletDynamics/Featherstone/btMultiBodyLink.h index 1cd6b8c07..565bb6b3e 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyLink.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyLink.h @@ -157,6 +157,7 @@ struct btMultibodyLink m_parent(-1), m_zeroRotParentToThis(0, 0, 0, 1), m_cachedRotParentToThis(0, 0, 0, 1), + m_cachedRotParentToThis_interpolate(0, 0, 0, 1), m_collider(0), m_flags(0), m_dofCount(0), @@ -179,6 +180,7 @@ struct btMultibodyLink m_dVector.setValue(0, 0, 0); m_eVector.setValue(0, 0, 0); m_cachedRVector.setValue(0, 0, 0); + m_cachedRVector_interpolate.setValue(0, 0, 0); m_appliedForce.setValue(0, 0, 0); m_appliedTorque.setValue(0, 0, 0); m_appliedConstraintForce.setValue(0, 0, 0); From deb7c152c41d3b3111338d96bbbfb5f64862985a Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Thu, 8 Aug 2019 10:14:18 -0700 Subject: [PATCH 04/56] add corotated model to lagrangian forces --- examples/ExampleBrowser/ExampleEntries.cpp | 2 +- examples/GraspDeformable/GraspDeformable.cpp | 5 +- .../btDeformableBackwardEulerObjective.h | 1 + .../btDeformableCorotatedForce.h | 143 ++++++++++++++++++ .../btDeformableLagrangianForce.h | 3 +- src/BulletSoftBody/btSoftBody.cpp | 19 +++ src/BulletSoftBody/btSoftBody.h | 4 + src/BulletSoftBody/btSoftBodyHelpers.cpp | 1 + 8 files changed, 174 insertions(+), 4 deletions(-) create mode 100644 src/BulletSoftBody/btDeformableCorotatedForce.h diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index 030f4eef1..ae40afec9 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -197,7 +197,7 @@ static ExampleEntry gDefaultExamples[] = ExampleEntry(0, "Deformabe Body"), ExampleEntry(1, "Deformable-RigidBody Contact", "Deformable test", DeformableRigidCreateFunc), ExampleEntry(1, "Grasp Deformable Cube", "Grasping test", PinchCreateFunc), - ExampleEntry(1, "Grasp Deformable with Motor", "Grasping test", GraspDeformableaCreateFunc), + ExampleEntry(1, "Grasp Deformable with Motor", "Grasping test", GraspDeformableCreateFunc), ExampleEntry(1, "Volumetric Deformable Objects", "Volumetric Deformable test", VolumetricDeformableCreateFunc), ExampleEntry(1, "Deformable-MultiBody Contact", "MultiBody and Deformable contact", DeformableMultibodyCreateFunc), // ExampleEntry(1, "MultiBody Baseline", "MultiBody Baseline", MultiBodyBaselineCreateFunc), diff --git a/examples/GraspDeformable/GraspDeformable.cpp b/examples/GraspDeformable/GraspDeformable.cpp index b291dbafb..7d42ffa43 100644 --- a/examples/GraspDeformable/GraspDeformable.cpp +++ b/examples/GraspDeformable/GraspDeformable.cpp @@ -332,14 +332,15 @@ void GraspDeformable::initPhysics() psb->translate(btVector3(0, 0, 0)); psb->getCollisionShape()->setMargin(0.1); psb->setTotalMass(1); - psb->setSpringStiffness(2); - psb->setDampingCoefficient(0.02); + psb->setSpringStiffness(0); + psb->setDampingCoefficient(0.04); psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects psb->m_cfg.kCHR = 1; // collision hardness with rigid body psb->m_cfg.kDF = 2; getDeformableDynamicsWorld()->addSoftBody(psb); getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(2,2)); } m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h index f87f7f509..2f44bf016 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h @@ -17,6 +17,7 @@ #include "btDeformableLagrangianForce.h" #include "btDeformableMassSpringForce.h" #include "btDeformableGravityForce.h" +#include "btDeformableCorotatedForce.h" #include "btDeformableContactProjection.h" #include "btPreconditioner.h" #include "btDeformableRigidDynamicsWorld.h" diff --git a/src/BulletSoftBody/btDeformableCorotatedForce.h b/src/BulletSoftBody/btDeformableCorotatedForce.h new file mode 100644 index 000000000..f4d42453f --- /dev/null +++ b/src/BulletSoftBody/btDeformableCorotatedForce.h @@ -0,0 +1,143 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2016 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#ifndef BT_COROTATED_H +#define BT_COROTATED_H + +#include "btDeformableLagrangianForce.h" +#include "LinearMath/btPolarDecomposition.h" + +static inline int PolarDecompose(const btMatrix3x3& m, btMatrix3x3& q, btMatrix3x3& s) +{ + static const btPolarDecomposition polar; + return polar.decompose(m, q, s); +} + +class btDeformableCorotatedForce : public btDeformableLagrangianForce +{ +public: + typedef btAlignedObjectArray TVStack; + btScalar m_mu, m_lambda; + btDeformableCorotatedForce(): m_mu(1), m_lambda(1) + { + + } + + btDeformableCorotatedForce(btScalar mu, btScalar lambda): m_mu(mu), m_lambda(lambda) + { + } + + virtual void addScaledImplicitForce(btScalar scale, TVStack& force) + { + } + + virtual void addScaledExplicitForce(btScalar scale, TVStack& force) + { + addScaledElasticForce(scale, force); + } + + virtual void addScaledDampingForce(btScalar scale, TVStack& force) + { + } + + virtual void addScaledElasticForce(btScalar scale, TVStack& force) + { + int numNodes = getNumNodes(); + btAssert(numNodes <= force.size()) + for (int i = 0; i < m_softBodies.size(); ++i) + { + btSoftBody* psb = m_softBodies[i]; + for (int j = 0; j < psb->m_tetras.size(); ++j) + { + btSoftBody::Tetra& tetra = psb->m_tetras[j]; + updateDs(tetra); + btMatrix3x3 F = tetra.m_ds * tetra.m_Dm_inverse; + btMatrix3x3 P; + firstPiola(F,P); + btVector3 grad_N_hat_1st_col = btVector3(-1,-1,-1); + btVector3 force_on_node0 = P * tetra.m_Dm_inverse.transpose()*grad_N_hat_1st_col; + btMatrix3x3 force_on_node123 = P * tetra.m_Dm_inverse.transpose(); + + btSoftBody::Node* node0 = tetra.m_n[0]; + btSoftBody::Node* node1 = tetra.m_n[1]; + btSoftBody::Node* node2 = tetra.m_n[2]; + btSoftBody::Node* node3 = tetra.m_n[3]; + size_t id0 = node0->index; + size_t id1 = node1->index; + size_t id2 = node2->index; + size_t id3 = node3->index; + + // elastic force + // explicit elastic force + force[id0] -= scale * tetra.m_element_measure * force_on_node0; + force[id1] -= scale * tetra.m_element_measure * force_on_node123.getColumn(0); + force[id2] -= scale * tetra.m_element_measure * force_on_node123.getColumn(1); + force[id3] -= scale * tetra.m_element_measure * force_on_node123.getColumn(2); + } + } + } + + void firstPiola(const btMatrix3x3& F, btMatrix3x3& P) + { + btMatrix3x3 R,S; + btScalar J = F.determinant(); + if (J < 1024 * SIMD_EPSILON) + R.setIdentity(); + else + PolarDecompose(F, R, S); // this QR is not robust, consider using implicit shift svd + /*https://fuchuyuan.github.io/research/svd/paper.pdf*/ + + btMatrix3x3 JFinvT = F.adjoint(); + P = JFinvT * (m_lambda * (J-1)) + (F-R) * 2 * m_mu; + } + void updateDs(btSoftBody::Tetra& t) + { + btVector3 c1 = t.m_n[1]->m_q - t.m_n[0]->m_q; + btVector3 c2 = t.m_n[2]->m_q - t.m_n[0]->m_q; + btVector3 c3 = t.m_n[3]->m_q - t.m_n[0]->m_q; + btMatrix3x3 Ds(c1.getX(), c2.getX(), c3.getX(), + c1.getY(), c2.getY(), c3.getY(), + c1.getZ(), c2.getZ(), c3.getZ()); + t.m_ds = Ds; + } + + virtual void addScaledForceDifferential(btScalar scale, const TVStack& dv, TVStack& df) + { + // implicit damping force differential + for (int i = 0; i < m_softBodies.size(); ++i) + { + const btSoftBody* psb = m_softBodies[i]; + btScalar scaled_k_damp = psb->m_dampingCoefficient * scale; + for (int j = 0; j < psb->m_links.size(); ++j) + { + const btSoftBody::Link& link = psb->m_links[j]; + btSoftBody::Node* node1 = link.m_n[0]; + btSoftBody::Node* node2 = link.m_n[1]; + size_t id1 = node1->index; + size_t id2 = node2->index; + btVector3 local_scaled_df = scaled_k_damp * (dv[id2] - dv[id1]); + df[id1] += local_scaled_df; + df[id2] -= local_scaled_df; + } + } + } + + virtual btDeformableLagrangianForceType getForceType() + { + return BT_COROTATED_FORCE; + } + +}; + + +#endif /* btCorotated_h */ diff --git a/src/BulletSoftBody/btDeformableLagrangianForce.h b/src/BulletSoftBody/btDeformableLagrangianForce.h index eb4d032bf..2146d4ec5 100644 --- a/src/BulletSoftBody/btDeformableLagrangianForce.h +++ b/src/BulletSoftBody/btDeformableLagrangianForce.h @@ -20,7 +20,8 @@ enum btDeformableLagrangianForceType { BT_GRAVITY_FORCE = 1, - BT_MASSSPRING_FORCE = 2 + BT_MASSSPRING_FORCE = 2, + BT_COROTATED_FORCE = 3 }; class btDeformableLagrangianForce diff --git a/src/BulletSoftBody/btSoftBody.cpp b/src/BulletSoftBody/btSoftBody.cpp index 86a48bf62..f65851dec 100644 --- a/src/BulletSoftBody/btSoftBody.cpp +++ b/src/BulletSoftBody/btSoftBody.cpp @@ -854,6 +854,7 @@ void btSoftBody::scale(const btVector3& scl) updateNormals(); updateBounds(); updateConstants(); + initializeDmInverse(); } // @@ -2811,6 +2812,24 @@ void btSoftBody::setSpringStiffness(btScalar k) } } +void btSoftBody::initializeDmInverse() +{ + btScalar unit_simplex_measure = 1./6.; + + for (int i = 0; i < m_tetras.size(); ++i) + { + Tetra &t = m_tetras[i]; + btVector3 c1 = t.m_n[1]->m_q - t.m_n[0]->m_q; + btVector3 c2 = t.m_n[2]->m_q - t.m_n[0]->m_q; + btVector3 c3 = t.m_n[3]->m_q - t.m_n[0]->m_q; + btMatrix3x3 Dm(c1.getX(), c2.getX(), c3.getX(), + c1.getY(), c2.getY(), c3.getY(), + c1.getZ(), c2.getZ(), c3.getZ()); + t.m_element_measure = Dm.determinant() * unit_simplex_measure; + t.m_Dm_inverse = Dm.inverse(); + } +} + // void btSoftBody::Joint::Prepare(btScalar dt, int) { diff --git a/src/BulletSoftBody/btSoftBody.h b/src/BulletSoftBody/btSoftBody.h index f2934c94a..0ee9e827d 100644 --- a/src/BulletSoftBody/btSoftBody.h +++ b/src/BulletSoftBody/btSoftBody.h @@ -292,6 +292,9 @@ public: btVector3 m_c0[4]; // gradients btScalar m_c1; // (4*kVST)/(im0+im1+im2+im3) btScalar m_c2; // m_c1/sum(|g0..3|^2) + btMatrix3x3 m_Dm_inverse; // rest Dm^-1 + btMatrix3x3 m_ds; + btScalar m_element_measure; }; /* RContact */ struct RContact @@ -1023,6 +1026,7 @@ public: void applyClusters(bool drift); void dampClusters(); void setSpringStiffness(btScalar k); + void initializeDmInverse(); void applyForces(); static void PSolve_Anchors(btSoftBody* psb, btScalar kst, btScalar ti); static void PSolve_RContacts(btSoftBody* psb, btScalar kst, btScalar ti); diff --git a/src/BulletSoftBody/btSoftBodyHelpers.cpp b/src/BulletSoftBody/btSoftBodyHelpers.cpp index d0a9921d8..b3c5c88a9 100644 --- a/src/BulletSoftBody/btSoftBodyHelpers.cpp +++ b/src/BulletSoftBody/btSoftBodyHelpers.cpp @@ -1221,6 +1221,7 @@ if(face&&face[0]) } } } + psb->initializeDmInverse(); printf("Nodes: %u\r\n", psb->m_nodes.size()); printf("Links: %u\r\n", psb->m_links.size()); printf("Faces: %u\r\n", psb->m_faces.size()); From 26983b05e2a9b2fd8fe7a6b69063fc187f89c357 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Thu, 8 Aug 2019 14:25:01 -0700 Subject: [PATCH 05/56] modify constraint setup so that contact constraints are persistent in a single CG solve but motor constraints are applied only once --- examples/GraspDeformable/GraspDeformable.cpp | 4 ++-- .../Featherstone/btMultiBodyDynamicsWorld.cpp | 8 +++++++- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/examples/GraspDeformable/GraspDeformable.cpp b/examples/GraspDeformable/GraspDeformable.cpp index 7d42ffa43..68a52be7e 100644 --- a/examples/GraspDeformable/GraspDeformable.cpp +++ b/examples/GraspDeformable/GraspDeformable.cpp @@ -402,8 +402,8 @@ btMultiBody* GraspDeformable::createFeatherstoneMultiBody(btMultiBodyDynamicsWor { //init the base btVector3 baseInertiaDiag(0.f, 0.f, 0.f); - float baseMass = .1f; - float linkMass = .1f; + float baseMass = 1.f; + float linkMass = 1.f; int numLinks = 2; if (baseMass) diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp index f5a7a7f1e..602c94926 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp @@ -375,10 +375,15 @@ struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager:: m_islandAnalyticsData.push_back(m_solver->m_analyticsData); } m_bodies.resize(0); - m_manifolds.resize(0); +// m_manifolds.resize(0); m_constraints.resize(0); m_multiBodyConstraints.resize(0); } + + void clearContactConstraints() + { + m_manifolds.resize(0); + } }; void btMultiBodyDynamicsWorld::getAnalyticsData(btAlignedObjectArray& islandAnalyticsData) const @@ -430,6 +435,7 @@ void btMultiBodyDynamicsWorld::solveConstraints(btContactSolverInfo& solverInfo) solveExternalForces(solverInfo); buildIslands(); solveInternalConstraints(solverInfo); + m_solverMultiBodyIslandCallback->clearContactConstraints(); } void btMultiBodyDynamicsWorld::buildIslands() From 27492887bf8da79cad876e1dd4f425f6a21d092b Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Thu, 8 Aug 2019 17:56:19 -0700 Subject: [PATCH 06/56] move files and update license --- .../GraspDeformable.cpp | 24 +++++++++---------- examples/DeformableDemo/GraspDeformable.h | 19 +++++++++++++++ examples/ExampleBrowser/ExampleEntries.cpp | 1 + examples/GraspDeformable/GraspDeformable.h | 20 ---------------- 4 files changed, 31 insertions(+), 33 deletions(-) rename examples/{GraspDeformable => DeformableDemo}/GraspDeformable.cpp (95%) create mode 100644 examples/DeformableDemo/GraspDeformable.h delete mode 100644 examples/GraspDeformable/GraspDeformable.h diff --git a/examples/GraspDeformable/GraspDeformable.cpp b/examples/DeformableDemo/GraspDeformable.cpp similarity index 95% rename from examples/GraspDeformable/GraspDeformable.cpp rename to examples/DeformableDemo/GraspDeformable.cpp index 68a52be7e..dc7de0057 100644 --- a/examples/GraspDeformable/GraspDeformable.cpp +++ b/examples/DeformableDemo/GraspDeformable.cpp @@ -1,17 +1,15 @@ /* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ #include "GraspDeformable.h" ///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. diff --git a/examples/DeformableDemo/GraspDeformable.h b/examples/DeformableDemo/GraspDeformable.h new file mode 100644 index 000000000..1ce2230df --- /dev/null +++ b/examples/DeformableDemo/GraspDeformable.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#ifndef _GRASP_DEFORMABLE_H +#define _GRASP_DEFORMABLE_H + +class CommonExampleInterface* GraspDeformableCreateFunc(struct CommonExampleOptions& options); + +#endif //_GRASP_DEFORMABLE_H diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index ae40afec9..2beef333c 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -51,6 +51,7 @@ #include "../DeformableDemo/Pinch.h" #include "../DeformableDemo/DeformableMultibody.h" #include "../DeformableDemo/VolumetricDeformable.h" +#include "../DeformableDemo/GraspDeformable.h" #include "../SharedMemory/PhysicsServerExampleBullet2.h" #include "../SharedMemory/PhysicsServerExample.h" #include "../SharedMemory/PhysicsClientExample.h" diff --git a/examples/GraspDeformable/GraspDeformable.h b/examples/GraspDeformable/GraspDeformable.h deleted file mode 100644 index fed8cb03e..000000000 --- a/examples/GraspDeformable/GraspDeformable.h +++ /dev/null @@ -1,20 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ -#ifndef _GRASP_DEFORMABLE_H -#define _GRASP_DEFORMABLE_H - -class CommonExampleInterface* GraspDeformableCreateFunc(struct CommonExampleOptions& options); - -#endif //_GRASP_DEFORMABLE_H From 5b8df6a708b7e13fa50b67bf2182a85797520440 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Fri, 9 Aug 2019 13:39:25 -0700 Subject: [PATCH 07/56] switch to Baraff style constraint --- examples/DeformableDemo/DeformableRigid.cpp | 6 +- examples/DeformableDemo/GraspDeformable.cpp | 7 +- src/BulletSoftBody/btConjugateGradient.h | 116 ++++++++++++------ .../btDeformableBackwardEulerObjective.h | 2 - src/BulletSoftBody/btDeformableBodySolver.cpp | 14 ++- 5 files changed, 98 insertions(+), 47 deletions(-) diff --git a/examples/DeformableDemo/DeformableRigid.cpp b/examples/DeformableDemo/DeformableRigid.cpp index 403ce4907..9268572ef 100644 --- a/examples/DeformableDemo/DeformableRigid.cpp +++ b/examples/DeformableDemo/DeformableRigid.cpp @@ -228,11 +228,11 @@ void DeformableRigid::initPhysics() psb->getCollisionShape()->setMargin(0.1); psb->generateBendingConstraints(2); psb->setTotalMass(1); - psb->setSpringStiffness(1); - psb->setDampingCoefficient(0.01); + psb->setSpringStiffness(2); + psb->setDampingCoefficient(0.05); psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects psb->m_cfg.kCHR = 1; // collision hardness with rigid body - psb->m_cfg.kDF = 1; + psb->m_cfg.kDF = 0; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); diff --git a/examples/DeformableDemo/GraspDeformable.cpp b/examples/DeformableDemo/GraspDeformable.cpp index dc7de0057..15348af26 100644 --- a/examples/DeformableDemo/GraspDeformable.cpp +++ b/examples/DeformableDemo/GraspDeformable.cpp @@ -331,14 +331,15 @@ void GraspDeformable::initPhysics() psb->getCollisionShape()->setMargin(0.1); psb->setTotalMass(1); psb->setSpringStiffness(0); - psb->setDampingCoefficient(0.04); + psb->setDampingCoefficient(0.02); psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects psb->m_cfg.kCHR = 1; // collision hardness with rigid body - psb->m_cfg.kDF = 2; + psb->m_cfg.kDF = 0; + psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(2,2)); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(1,1)); } m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); diff --git a/src/BulletSoftBody/btConjugateGradient.h b/src/BulletSoftBody/btConjugateGradient.h index 22a9f3ada..d7e98761c 100644 --- a/src/BulletSoftBody/btConjugateGradient.h +++ b/src/BulletSoftBody/btConjugateGradient.h @@ -32,62 +32,108 @@ public: virtual ~btConjugateGradient(){} +// // return the number of iterations taken +// int solve(MatrixX& A, TVStack& x, const TVStack& b, btScalar tolerance) +// { +// BT_PROFILE("CGSolve"); +// btAssert(x.size() == b.size()); +// reinitialize(b); +// +// // r = b - A * x --with assigned dof zeroed out +// A.multiply(x, temp); +// r = sub(b, temp); +// A.project(r); +// +// btScalar r_norm = std::sqrt(squaredNorm(r)); +// if (r_norm < tolerance) { +// std::cout << "Iteration = 0" << std::endl; +// std::cout << "Two norm of the residual = " << r_norm << std::endl; +// return 0; +// } +// +// // z = M^(-1) * r +// A.precondition(r, z); +// p = z; +// // temp = A*p +// A.multiply(p, temp); +// A.project(temp); +// btScalar r_dot_z = dot(z,r), r_dot_z_new; +// // alpha = r^T * z / (p^T * A * p) +// btScalar alpha = r_dot_z / dot(p, temp), beta; +// +// for (int k = 1; k < max_iterations; k++) { +// // x += alpha * p; +// // r -= alpha * temp; +// multAndAddTo(alpha, p, x); +// multAndAddTo(-alpha, temp, r); +// // zero out the dofs of r +// A.project(r); +//// A.enforceConstraint(x); +// r_norm = std::sqrt(squaredNorm(r)); +// +// if (r_norm < tolerance) { +// std::cout << "ConjugateGradient iterations " << k << std::endl; +// return k; +// } +// +// // z = M^(-1) * r +// A.precondition(r, z); +// r_dot_z_new = dot(r,z); +// beta = r_dot_z_new/ r_dot_z; +// r_dot_z = r_dot_z_new; +// // p = z + beta * p; +// p = multAndAdd(beta, p, z); +// // temp = A * p; +// A.multiply(p, temp); +// A.project(temp); +// // alpha = r^T * z / (p^T * A * p) +// alpha = r_dot_z / dot(p, temp); +// } +// std::cout << "ConjugateGradient max iterations reached " << max_iterations << std::endl; +// return max_iterations; +// } + // return the number of iterations taken int solve(MatrixX& A, TVStack& x, const TVStack& b, btScalar tolerance) { BT_PROFILE("CGSolve"); btAssert(x.size() == b.size()); reinitialize(b); - // r = b - A * x --with assigned dof zeroed out A.multiply(x, temp); r = sub(b, temp); A.project(r); - A.enforceConstraint(x); - - btScalar r_norm = std::sqrt(squaredNorm(r)); - if (r_norm < tolerance) { - std::cout << "Iteration = 0" << std::endl; - std::cout << "Two norm of the residual = " << r_norm << std::endl; - return 0; - } - // z = M^(-1) * r A.precondition(r, z); + A.project(z); + btScalar r_dot_z = dot(z,r); + if (r_dot_z < tolerance) { + std::cout << "Iteration = 0" << std::endl; + std::cout << "Two norm of the residual = " << r_dot_z << std::endl; + return 0; + } p = z; - // temp = A*p - A.multiply(p, temp); - - btScalar r_dot_z = dot(z,r), r_dot_z_new; - // alpha = r^T * z / (p^T * A * p) - btScalar alpha = r_dot_z / dot(p, temp), beta; - + btScalar r_dot_z_new = r_dot_z; for (int k = 1; k < max_iterations; k++) { + // temp = A*p + A.multiply(p, temp); + A.project(temp); + // alpha = r^T * z / (p^T * A * p) + btScalar alpha = r_dot_z_new / dot(p, temp); // x += alpha * p; - // r -= alpha * temp; multAndAddTo(alpha, p, x); + // r -= alpha * temp; multAndAddTo(-alpha, temp, r); - // zero out the dofs of r - A.project(r); - A.enforceConstraint(x); - r_norm = std::sqrt(squaredNorm(r)); - - if (r_norm < tolerance) { + // z = M^(-1) * r + A.precondition(r, z); + r_dot_z = r_dot_z_new; + r_dot_z_new = dot(r,z); + if (r_dot_z_new < tolerance) { std::cout << "ConjugateGradient iterations " << k << std::endl; return k; } - - // z = M^(-1) * r - A.precondition(r, z); - r_dot_z_new = dot(r,z); - beta = r_dot_z_new/ r_dot_z; - r_dot_z = r_dot_z_new; - // p = z + beta * p; + btScalar beta = r_dot_z_new/ r_dot_z; p = multAndAdd(beta, p, z); - // temp = A * p; - A.multiply(p, temp); - // alpha = r^T * z / (p^T * A * p) - alpha = r_dot_z / dot(p, temp); } std::cout << "ConjugateGradient max iterations reached " << max_iterations << std::endl; return max_iterations; diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h index 2f44bf016..f95cb05aa 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h @@ -73,7 +73,6 @@ public: { BT_PROFILE("enforceConstraint"); projection.enforceConstraint(x); - updateVelocity(x); } // add dv to velocity @@ -86,7 +85,6 @@ public: void project(TVStack& r) { BT_PROFILE("project"); - projection.update(); projection.project(r); } diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index eb8e62237..2b2827e88 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -31,20 +31,20 @@ btDeformableBodySolver::~btDeformableBodySolver() void btDeformableBodySolver::solveConstraints(float solverdt) { BT_PROFILE("solveConstraints"); - // add constraints to the solver - setConstraints(); - // save v_{n+1}^* velocity after explicit forces backupVelocity(); + // add constraints to the solver + setConstraints(); + m_objective->computeResidual(solverdt, m_residual); - computeStep(m_dv, m_residual); updateVelocity(); } void btDeformableBodySolver::computeStep(TVStack& dv, const TVStack& residual) { + btScalar tolerance = std::numeric_limits::epsilon()* 1024 * m_objective->computeNorm(residual); m_cg.solve(*m_objective, dv, residual, tolerance); } @@ -75,6 +75,12 @@ void btDeformableBodySolver::setConstraints() { BT_PROFILE("setConstraint"); m_objective->setConstraints(); + for (int i = 0; i < 10; ++i) + { + m_objective->projection.update(); + m_objective->enforceConstraint(m_dv); + m_objective->updateVelocity(m_dv); + } } void btDeformableBodySolver::setWorld(btDeformableRigidDynamicsWorld* world) From fb6612c0beefdbd9a7eb3c4f0463466729edd552 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Fri, 9 Aug 2019 16:02:44 -0700 Subject: [PATCH 08/56] friction fixes --- .../btDeformableBackwardEulerObjective.cpp | 5 ++ .../btDeformableBackwardEulerObjective.h | 2 + src/BulletSoftBody/btDeformableBodySolver.cpp | 3 +- .../btDeformableContactProjection.cpp | 48 +++++++++++++------ .../btDeformableContactProjection.h | 2 + 5 files changed, 45 insertions(+), 15 deletions(-) diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp index 746048562..09bb9ee2d 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp @@ -145,3 +145,8 @@ void btDeformableBackwardEulerObjective::setConstraints() m_world->btMultiBodyDynamicsWorld::buildIslands(); projection.setConstraints(); } + +void btDeformableBackwardEulerObjective::projectFriction(TVStack& r) +{ + projection.projectFriction(r); +} diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h index f95cb05aa..5de89849a 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h @@ -75,6 +75,8 @@ public: projection.enforceConstraint(x); } + void projectFriction(TVStack& r); + // add dv to velocity void updateVelocity(const TVStack& dv); diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index 2b2827e88..daa85849b 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -38,6 +38,7 @@ void btDeformableBodySolver::solveConstraints(float solverdt) setConstraints(); m_objective->computeResidual(solverdt, m_residual); + m_objective->projectFriction(m_residual); computeStep(m_dv, m_residual); updateVelocity(); } @@ -75,7 +76,7 @@ void btDeformableBodySolver::setConstraints() { BT_PROFILE("setConstraint"); m_objective->setConstraints(); - for (int i = 0; i < 10; ++i) + for (int i = 0; i < 1; ++i) { m_objective->projection.update(); m_objective->enforceConstraint(m_dv); diff --git a/src/BulletSoftBody/btDeformableContactProjection.cpp b/src/BulletSoftBody/btDeformableContactProjection.cpp index 84d35c062..ea88bee49 100644 --- a/src/BulletSoftBody/btDeformableContactProjection.cpp +++ b/src/BulletSoftBody/btDeformableContactProjection.cpp @@ -133,10 +133,11 @@ void btDeformableContactProjection::update() friction.m_impulse_prev[j] = friction.m_impulse[j]; friction.m_dv_prev[j] = friction.m_dv[j]; friction.m_static_prev[j] = friction.m_static[j]; + friction.m_direction_prev[j] = friction.m_direction[j]; // get the current tangent direction btScalar local_tangent_norm = impulse_tangent.norm(); - btVector3 local_tangent_dir = btVector3(0,0,0); + btVector3 local_tangent_dir = -friction.m_direction[j]; if (local_tangent_norm > SIMD_EPSILON) local_tangent_dir = impulse_tangent.normalized(); @@ -395,7 +396,9 @@ void btDeformableContactProjection::enforceConstraint(TVStack& x) // add the friction constraint if (friction.m_static[j] == true) { - x[i] -= x[i].dot(friction.m_direction[j]) * friction.m_direction[j]; +// if (friction.m_static_prev[j] == true) +// x[i] -= friction.m_direction_prev[j] * friction.m_dv_prev[j]; +// x[i] -= x[i].dot(friction.m_direction[j]) * friction.m_direction[j]; x[i] += friction.m_direction[j] * friction.m_dv[j]; } } @@ -410,8 +413,8 @@ void btDeformableContactProjection::project(TVStack& x) for (int index = 0; index < m_constraints.size(); ++index) { const btAlignedObjectArray& constraints = *m_constraints.getAtIndex(index); - size_t i = m_constraints.getKeyAtIndex(index).getUid1(); btAlignedObjectArray& frictions = *m_frictions[m_constraints.getKeyAtIndex(index)]; + size_t i = m_constraints.getKeyAtIndex(index).getUid1(); btAssert(constraints.size() <= dim); btAssert(constraints.size() > 0); if (constraints.size() == 1) @@ -427,6 +430,34 @@ void btDeformableContactProjection::project(TVStack& x) } else x[i].setZero(); + // apply the friction constraint + if (constraints.size() < 3) + { + for (int f = 0; f < frictions.size(); ++f) + { + DeformableFrictionConstraint& friction= frictions[f]; + for (int j = 0; j < friction.m_direction.size(); ++j) + { + if (friction.m_static[j] == true) + { + x[i] -= x[i].dot(friction.m_direction[j]) * friction.m_direction[j]; + } + } + } + } + } +} + +void btDeformableContactProjection::projectFriction(TVStack& x) +{ + const int dim = 3; + for (int index = 0; index < m_constraints.size(); ++index) + { + const btAlignedObjectArray& constraints = *m_constraints.getAtIndex(index); + size_t i = m_constraints.getKeyAtIndex(index).getUid1(); + btAlignedObjectArray& frictions = *m_frictions[m_constraints.getKeyAtIndex(index)]; + btAssert(constraints.size() <= dim); + btAssert(constraints.size() > 0); // apply friction if the node is not constrained in all directions if (constraints.size() < 3) @@ -444,23 +475,12 @@ void btDeformableContactProjection::project(TVStack& x) DeformableFrictionConstraint& friction= frictions[f]; for (int j = 0; j < friction.m_direction.size(); ++j) { - // clear the old friction force - if (friction.m_static_prev[j] == false) - { - x[i] -= friction.m_direction_prev[j] * friction.m_impulse_prev[j]; - } - // only add to the rhs if there is no static friction constraint on the node if (friction.m_static[j] == false) { if (!has_static_constraint) x[i] += friction.m_direction[j] * friction.m_impulse[j]; } - else - { - // otherwise clear the constraint in the friction direction - x[i] -= x[i].dot(friction.m_direction[j]) * friction.m_direction[j]; - } } } } diff --git a/src/BulletSoftBody/btDeformableContactProjection.h b/src/BulletSoftBody/btDeformableContactProjection.h index 64d448b5e..0827554bb 100644 --- a/src/BulletSoftBody/btDeformableContactProjection.h +++ b/src/BulletSoftBody/btDeformableContactProjection.h @@ -36,6 +36,8 @@ public: // apply the constraints to the rhs virtual void project(TVStack& x); + // add to friction + virtual void projectFriction(TVStack& x); // apply constraints to x in Ax=b virtual void enforceConstraint(TVStack& x); From fa5741d07edee8ca9466dc86c2ab030d2debb782 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Sat, 10 Aug 2019 11:11:18 -0700 Subject: [PATCH 09/56] improve dynamic friction --- src/BulletSoftBody/btCGProjection.h | 31 +- .../btDeformableBackwardEulerObjective.cpp | 4 +- .../btDeformableBackwardEulerObjective.h | 2 +- src/BulletSoftBody/btDeformableBodySolver.cpp | 8 +- .../btDeformableContactProjection.cpp | 456 +++++++----------- .../btDeformableContactProjection.h | 5 +- .../btDeformableRigidDynamicsWorld.cpp | 117 +++-- 7 files changed, 245 insertions(+), 378 deletions(-) diff --git a/src/BulletSoftBody/btCGProjection.h b/src/BulletSoftBody/btCGProjection.h index 0a4db2b49..ef902c70d 100644 --- a/src/BulletSoftBody/btCGProjection.h +++ b/src/BulletSoftBody/btCGProjection.h @@ -22,39 +22,30 @@ class btDeformableRigidDynamicsWorld; struct DeformableContactConstraint { + const btSoftBody::Node* m_node; btAlignedObjectArray m_contact; - btAlignedObjectArray m_direction; - btAlignedObjectArray m_value; - // the magnitude of the total impulse the node applied to the rb in the normal direction in the cg solve - btAlignedObjectArray m_accumulated_normal_impulse; + btAlignedObjectArray m_total_normal_dv; + btAlignedObjectArray m_total_tangent_dv; + btAlignedObjectArray m_static; + btAlignedObjectArray m_can_be_dynamic; - DeformableContactConstraint(const btSoftBody::RContact& rcontact) + DeformableContactConstraint(const btSoftBody::RContact& rcontact): m_node(rcontact.m_node) { append(rcontact); } - DeformableContactConstraint(const btVector3& dir) + DeformableContactConstraint(): m_node(NULL) { m_contact.push_back(NULL); - m_direction.push_back(dir); - m_value.push_back(0); - m_accumulated_normal_impulse.push_back(0); - } - - DeformableContactConstraint() - { - m_contact.push_back(NULL); - m_direction.push_back(btVector3(0,0,0)); - m_value.push_back(0); - m_accumulated_normal_impulse.push_back(0); } void append(const btSoftBody::RContact& rcontact) { m_contact.push_back(&rcontact); - m_direction.push_back(rcontact.m_cti.m_normal); - m_value.push_back(0); - m_accumulated_normal_impulse.push_back(0); + m_total_normal_dv.push_back(btVector3(0,0,0)); + m_total_tangent_dv.push_back(btVector3(0,0,0)); + m_static.push_back(false); + m_can_be_dynamic.push_back(true); } ~DeformableContactConstraint() diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp index 09bb9ee2d..f4a3f55e5 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp @@ -146,7 +146,7 @@ void btDeformableBackwardEulerObjective::setConstraints() projection.setConstraints(); } -void btDeformableBackwardEulerObjective::projectFriction(TVStack& r) +void btDeformableBackwardEulerObjective::applyDynamicFriction(TVStack& r) { - projection.projectFriction(r); + projection.applyDynamicFriction(r); } diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h index 5de89849a..3863970c6 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h @@ -75,7 +75,7 @@ public: projection.enforceConstraint(x); } - void projectFriction(TVStack& r); + void applyDynamicFriction(TVStack& r); // add dv to velocity void updateVelocity(const TVStack& dv); diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index daa85849b..be0262842 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -36,17 +36,17 @@ void btDeformableBodySolver::solveConstraints(float solverdt) // add constraints to the solver setConstraints(); - m_objective->computeResidual(solverdt, m_residual); - m_objective->projectFriction(m_residual); + m_objective->applyDynamicFriction(m_residual); computeStep(m_dv, m_residual); + updateVelocity(); } void btDeformableBodySolver::computeStep(TVStack& dv, const TVStack& residual) { - btScalar tolerance = std::numeric_limits::epsilon()* 1024 * m_objective->computeNorm(residual); + btScalar tolerance = std::numeric_limits::epsilon() * m_objective->computeNorm(residual); m_cg.solve(*m_objective, dv, residual, tolerance); } @@ -76,7 +76,7 @@ void btDeformableBodySolver::setConstraints() { BT_PROFILE("setConstraint"); m_objective->setConstraints(); - for (int i = 0; i < 1; ++i) + for (int i = 0; i < 10; ++i) { m_objective->projection.update(); m_objective->enforceConstraint(m_dv); diff --git a/src/BulletSoftBody/btDeformableContactProjection.cpp b/src/BulletSoftBody/btDeformableContactProjection.cpp index ea88bee49..9bdd8323e 100644 --- a/src/BulletSoftBody/btDeformableContactProjection.cpp +++ b/src/BulletSoftBody/btDeformableContactProjection.cpp @@ -57,164 +57,129 @@ void btDeformableContactProjection::update() // loop through constraints to set constrained values for (int index = 0; index < m_constraints.size(); ++index) { - btAlignedObjectArray& frictions = *m_frictions[m_constraints.getKeyAtIndex(index)]; - btAlignedObjectArray& constraints = *m_constraints.getAtIndex(index); - for (int i = 0; i < constraints.size(); ++i) + DeformableContactConstraint& constraint = *m_constraints.getAtIndex(index); + const btSoftBody::Node* node = constraint.m_node; + for (int j = 0; j < constraint.m_contact.size(); ++j) { - DeformableContactConstraint& constraint = constraints[i]; - DeformableFrictionConstraint& friction = frictions[i]; - for (int j = 0; j < constraint.m_contact.size(); ++j) + if (constraint.m_contact[j] == NULL) { - if (constraint.m_contact[j] == NULL) - { - // nothing needs to be done for dirichelet constraints - continue; - } - const btSoftBody::RContact* c = constraint.m_contact[j]; - const btSoftBody::sCti& cti = c->m_cti; + // nothing needs to be done for dirichelet constraints + continue; + } + const btSoftBody::RContact* c = constraint.m_contact[j]; + const btSoftBody::sCti& cti = c->m_cti; + + if (cti.m_colObj->hasContactResponse()) + { + btVector3 va(0, 0, 0); + btRigidBody* rigidCol = 0; + btMultiBodyLinkCollider* multibodyLinkCol = 0; + const btScalar* deltaV_normal; - if (cti.m_colObj->hasContactResponse()) + // grab the velocity of the rigid body + if (cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY) { - btVector3 va(0, 0, 0); - btRigidBody* rigidCol = 0; - btMultiBodyLinkCollider* multibodyLinkCol = 0; - const btScalar* deltaV_normal; - - // grab the velocity of the rigid body - if (cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY) + rigidCol = (btRigidBody*)btRigidBody::upcast(cti.m_colObj); + va = rigidCol ? (rigidCol->getVelocityInLocalPoint(c->m_c1)) * m_dt : btVector3(0, 0, 0); + } + else if (cti.m_colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK) + { + multibodyLinkCol = (btMultiBodyLinkCollider*)btMultiBodyLinkCollider::upcast(cti.m_colObj); + if (multibodyLinkCol) { - rigidCol = (btRigidBody*)btRigidBody::upcast(cti.m_colObj); - va = rigidCol ? (rigidCol->getVelocityInLocalPoint(c->m_c1)) * m_dt : btVector3(0, 0, 0); - } - else if (cti.m_colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK) - { - multibodyLinkCol = (btMultiBodyLinkCollider*)btMultiBodyLinkCollider::upcast(cti.m_colObj); - if (multibodyLinkCol) + const int ndof = multibodyLinkCol->m_multiBody->getNumDofs() + 6; + const btScalar* J_n = &c->jacobianData_normal.m_jacobians[0]; + const btScalar* J_t1 = &c->jacobianData_t1.m_jacobians[0]; + const btScalar* J_t2 = &c->jacobianData_t2.m_jacobians[0]; + const btScalar* local_v = multibodyLinkCol->m_multiBody->getVelocityVector(); + deltaV_normal = &c->jacobianData_normal.m_deltaVelocitiesUnitImpulse[0]; + // add in the normal component of the va + btScalar vel = 0.0; + for (int k = 0; k < ndof; ++k) { - const int ndof = multibodyLinkCol->m_multiBody->getNumDofs() + 6; - const btScalar* J_n = &c->jacobianData_normal.m_jacobians[0]; - const btScalar* J_t1 = &c->jacobianData_t1.m_jacobians[0]; - const btScalar* J_t2 = &c->jacobianData_t2.m_jacobians[0]; - const btScalar* local_v = multibodyLinkCol->m_multiBody->getVelocityVector(); - deltaV_normal = &c->jacobianData_normal.m_deltaVelocitiesUnitImpulse[0]; - // add in the normal component of the va - btScalar vel = 0.0; - for (int k = 0; k < ndof; ++k) - { - vel += local_v[k] * J_n[k]; - } - va = cti.m_normal * vel * m_dt; - - // add in the tangential components of the va - vel = 0.0; - for (int k = 0; k < ndof; ++k) - { - vel += local_v[k] * J_t1[k]; - } - va += c->t1 * vel * m_dt; - vel = 0.0; - for (int k = 0; k < ndof; ++k) - { - vel += local_v[k] * J_t2[k]; - } - va += c->t2 * vel * m_dt; + vel += local_v[k] * J_n[k]; } - } - - const btVector3 vb = c->m_node->m_v * m_dt; - const btVector3 vr = vb - va; - const btScalar dn = btDot(vr, cti.m_normal); - btVector3 impulse = c->m_c0 * vr; - const btVector3 impulse_normal = c->m_c0 * (cti.m_normal * dn); - const btVector3 impulse_tangent = impulse - impulse_normal; - - // start friction handling - // copy old data - friction.m_impulse_prev[j] = friction.m_impulse[j]; - friction.m_dv_prev[j] = friction.m_dv[j]; - friction.m_static_prev[j] = friction.m_static[j]; - friction.m_direction_prev[j] = friction.m_direction[j]; - - // get the current tangent direction - btScalar local_tangent_norm = impulse_tangent.norm(); - btVector3 local_tangent_dir = -friction.m_direction[j]; - if (local_tangent_norm > SIMD_EPSILON) - local_tangent_dir = impulse_tangent.normalized(); + va = cti.m_normal * vel * m_dt; - // accumulated impulse on the rb in this and all prev cg iterations - constraint.m_accumulated_normal_impulse[j] += impulse_normal.dot(cti.m_normal); - const btScalar& accumulated_normal = constraint.m_accumulated_normal_impulse[j]; - - // the total tangential impulse required to stop sliding - btVector3 tangent = friction.m_accumulated_tangent_impulse[j] + impulse_tangent; - btScalar tangent_norm = tangent.norm(); - - if (accumulated_normal < 0) - { - friction.m_direction[j] = -local_tangent_dir; - // do not allow switching from static friction to dynamic friction - // it causes cg to explode - if (-accumulated_normal*c->m_c3 < tangent_norm && friction.m_static_prev[j] == false && friction.m_released[j] == false) + // add in the tangential components of the va + vel = 0.0; + for (int k = 0; k < ndof; ++k) { - friction.m_static[j] = false; - friction.m_impulse[j] = -accumulated_normal*c->m_c3; + vel += local_v[k] * J_t1[k]; + } + va += c->t1 * vel * m_dt; + vel = 0.0; + for (int k = 0; k < ndof; ++k) + { + vel += local_v[k] * J_t2[k]; + } + va += c->t2 * vel * m_dt; + } + } + + const btVector3 vb = c->m_node->m_v * m_dt; + const btVector3 vr = vb - va; + const btScalar dn = btDot(vr, cti.m_normal); + btVector3 impulse = c->m_c0 * vr; + const btVector3 impulse_normal = c->m_c0 * (cti.m_normal * dn); + btVector3 impulse_tangent = impulse - impulse_normal; + + btVector3 old_total_tangent_dv = constraint.m_total_tangent_dv[j]; + constraint.m_total_normal_dv[j] -= impulse_normal * node->m_im; + constraint.m_total_tangent_dv[j] -= impulse_tangent * node->m_im; + + if (constraint.m_total_normal_dv[j].dot(cti.m_normal) < 0) + { + // separating in the normal direction + constraint.m_static[j] = false; + constraint.m_can_be_dynamic[j] = false; + constraint.m_total_tangent_dv[j] = btVector3(0,0,0); + impulse_tangent.setZero(); + } + else + { + if (constraint.m_can_be_dynamic[j] && constraint.m_total_normal_dv[j].norm() * c->m_c3 < constraint.m_total_tangent_dv[j].norm()) + { + // dynamic friction + // with dynamic friction, the impulse are still applied to the two objects colliding, however, it does not pose a constraint in the cg solve, hence the change to dv merely serves to update velocity in the contact iterations. + constraint.m_static[j] = false; + constraint.m_can_be_dynamic[j] = true; + if (constraint.m_total_tangent_dv[j].norm() < SIMD_EPSILON) + { + constraint.m_total_tangent_dv[j] = btVector3(0,0,0); } else { - friction.m_static[j] = true; - friction.m_impulse[j] = tangent_norm; + constraint.m_total_tangent_dv[j] = constraint.m_total_tangent_dv[j].normalized() * constraint.m_total_normal_dv[j].norm() * c->m_c3; } + impulse_tangent = -btScalar(1)/node->m_im * (constraint.m_total_tangent_dv[j] - old_total_tangent_dv); } else { - friction.m_released[j] = true; - friction.m_static[j] = false; - friction.m_impulse[j] = 0; - friction.m_direction[j] = btVector3(0,0,0); + // static friction + constraint.m_static[j] = true; + constraint.m_can_be_dynamic[j] = false; } - friction.m_dv[j] = friction.m_impulse[j] * c->m_c2/m_dt; - friction.m_accumulated_tangent_impulse[j] = -friction.m_impulse[j] * friction.m_direction[j]; - - // the incremental impulse applied to rb in the tangential direction - btVector3 incremental_tangent = (friction.m_impulse_prev[j] * friction.m_direction_prev[j])-(friction.m_impulse[j] * friction.m_direction[j]); - - - // dv = new_impulse + accumulated velocity change in previous CG iterations - // so we have the invariant node->m_v = backupVelocity + dv; - - btScalar dvn = -accumulated_normal * c->m_c2/m_dt; - - // the following is equivalent - /* - btVector3 dv = -impulse_normal * c->m_c2/m_dt + c->m_node->m_v - backupVelocity[m_indices->at(c->m_node)]; - btScalar dvn = dv.dot(cti.m_normal); - */ - - constraint.m_value[j] = dvn; - - // the incremental impulse: - // in the normal direction it's the normal component of "impulse" - // in the tangent direction it's the difference between the frictional impulse in the iteration and the previous iteration - impulse = impulse_normal + incremental_tangent; - if (cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY) + } + impulse = impulse_normal + impulse_tangent; + if (cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY) + { + if (rigidCol) + rigidCol->applyImpulse(impulse, c->m_c1); + } + else if (cti.m_colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK) + { + if (multibodyLinkCol) { - if (rigidCol) - rigidCol->applyImpulse(impulse, c->m_c1); - } - else if (cti.m_colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK) - { - if (multibodyLinkCol) + // apply normal component of the impulse + multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof(deltaV_normal, impulse.dot(cti.m_normal)); + if (impulse_tangent.norm() > SIMD_EPSILON) { - // apply normal component of the impulse - multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof(deltaV_normal, impulse.dot(cti.m_normal)); - if (incremental_tangent.norm() > SIMD_EPSILON) - { - // apply tangential component of the impulse - const btScalar* deltaV_t1 = &c->jacobianData_t1.m_deltaVelocitiesUnitImpulse[0]; - multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof(deltaV_t1, impulse.dot(c->t1)); - const btScalar* deltaV_t2 = &c->jacobianData_t2.m_deltaVelocitiesUnitImpulse[0]; - multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof(deltaV_t2, impulse.dot(c->t2)); - } + // apply tangential component of the impulse + const btScalar* deltaV_t1 = &c->jacobianData_t1.m_deltaVelocitiesUnitImpulse[0]; + multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof(deltaV_t1, impulse.dot(c->t1)); + const btScalar* deltaV_t2 = &c->jacobianData_t2.m_deltaVelocitiesUnitImpulse[0]; + multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof(deltaV_t2, impulse.dot(c->t2)); } } } @@ -234,19 +199,7 @@ void btDeformableContactProjection::setConstraints() { if (psb->m_nodes[j].m_im == 0) { - btAlignedObjectArray c; - c.reserve(3); - c.push_back(DeformableContactConstraint(btVector3(1,0,0))); - c.push_back(DeformableContactConstraint(btVector3(0,1,0))); - c.push_back(DeformableContactConstraint(btVector3(0,0,1))); - m_constraints.insert(psb->m_nodes[j].index, c); - - btAlignedObjectArray f; - f.reserve(3); - f.push_back(DeformableFrictionConstraint()); - f.push_back(DeformableFrictionConstraint()); - f.push_back(DeformableFrictionConstraint()); - m_frictions.insert(psb->m_nodes[j].index, f); + m_constraints.insert(psb->m_nodes[j].index, DeformableContactConstraint()); } } } @@ -301,41 +254,12 @@ void btDeformableContactProjection::setConstraints() if (m_constraints.find(c.m_node->index) == NULL) { - btAlignedObjectArray constraints; - constraints.push_back(DeformableContactConstraint(c)); - m_constraints.insert(c.m_node->index,constraints); - btAlignedObjectArray frictions; - frictions.push_back(DeformableFrictionConstraint()); - m_frictions.insert(c.m_node->index,frictions); + m_constraints.insert(c.m_node->index, DeformableContactConstraint(c)); } else { - // group colinear constraints into one - const btScalar angle_epsilon = 0.015192247; // less than 10 degree - bool merged = false; - btAlignedObjectArray& constraints = *m_constraints[c.m_node->index]; - btAlignedObjectArray& frictions = *m_frictions[c.m_node->index]; - for (int j = 0; j < constraints.size(); ++j) - { - const btAlignedObjectArray& dirs = constraints[j].m_direction; - btScalar dot_prod = dirs[0].dot(cti.m_normal); - if (std::abs(std::abs(dot_prod) - 1) < angle_epsilon) - { - // group the constraints - constraints[j].append(c); - // push in an empty friction - frictions[j].append(); - merged = true; - break; - } - } - const int dim = 3; - // hard coded no more than 3 constraint directions - if (!merged && constraints.size() < dim) - { - constraints.push_back(DeformableContactConstraint(c)); - frictions.push_back(DeformableFrictionConstraint()); - } + DeformableContactConstraint& constraints = *m_constraints[c.m_node->index]; + constraints.append(c); } } } @@ -345,64 +269,15 @@ void btDeformableContactProjection::setConstraints() void btDeformableContactProjection::enforceConstraint(TVStack& x) { - const int dim = 3; for (int index = 0; index < m_constraints.size(); ++index) { - const btAlignedObjectArray& constraints = *m_constraints.getAtIndex(index); + const DeformableContactConstraint& constraints = *m_constraints.getAtIndex(index); size_t i = m_constraints.getKeyAtIndex(index).getUid1(); - const btAlignedObjectArray& frictions = *m_frictions[m_constraints.getKeyAtIndex(index)]; - btAssert(constraints.size() <= dim); - btAssert(constraints.size() > 0); - if (constraints.size() == 1) + x[i].setZero(); + for (int j = 0; j < constraints.m_total_normal_dv.size(); ++j) { - x[i] -= x[i].dot(constraints[0].m_direction[0]) * constraints[0].m_direction[0]; - for (int j = 0; j < constraints[0].m_direction.size(); ++j) - x[i] += constraints[0].m_value[j] * constraints[0].m_direction[j]; - } - else if (constraints.size() == 2) - { - btVector3 free_dir = btCross(constraints[0].m_direction[0], constraints[1].m_direction[0]); - btAssert(free_dir.norm() > SIMD_EPSILON) - free_dir.normalize(); - x[i] = x[i].dot(free_dir) * free_dir; - for (int j = 0; j < constraints.size(); ++j) - { - for (int k = 0; k < constraints[j].m_direction.size(); ++k) - { - x[i] += constraints[j].m_value[k] * constraints[j].m_direction[k]; - } - } - } - else - { - x[i].setZero(); - for (int j = 0; j < constraints.size(); ++j) - { - for (int k = 0; k < constraints[j].m_direction.size(); ++k) - { - x[i] += constraints[j].m_value[k] * constraints[j].m_direction[k]; - } - } - } - - // apply friction if the node is not constrained in all directions - if (constraints.size() < 3) - { - for (int f = 0; f < frictions.size(); ++f) - { - const DeformableFrictionConstraint& friction= frictions[f]; - for (int j = 0; j < friction.m_direction.size(); ++j) - { - // add the friction constraint - if (friction.m_static[j] == true) - { -// if (friction.m_static_prev[j] == true) -// x[i] -= friction.m_direction_prev[j] * friction.m_dv_prev[j]; -// x[i] -= x[i].dot(friction.m_direction[j]) * friction.m_direction[j]; - x[i] += friction.m_direction[j] * friction.m_dv[j]; - } - } - } + x[i] += constraints.m_total_normal_dv[j]; + x[i] += constraints.m_total_tangent_dv[j]; } } } @@ -412,76 +287,80 @@ void btDeformableContactProjection::project(TVStack& x) const int dim = 3; for (int index = 0; index < m_constraints.size(); ++index) { - const btAlignedObjectArray& constraints = *m_constraints.getAtIndex(index); - btAlignedObjectArray& frictions = *m_frictions[m_constraints.getKeyAtIndex(index)]; + const DeformableContactConstraint& constraints = *m_constraints.getAtIndex(index); size_t i = m_constraints.getKeyAtIndex(index).getUid1(); - btAssert(constraints.size() <= dim); - btAssert(constraints.size() > 0); - if (constraints.size() == 1) + if (constraints.m_contact[0] == NULL) { - x[i] -= x[i].dot(constraints[0].m_direction[0]) * constraints[0].m_direction[0]; + // static node + x[i].setZero(); + continue; } - else if (constraints.size() == 2) + bool has_static = false; + for (int j = 0; j < constraints.m_static.size(); ++j) { - btVector3 free_dir = btCross(constraints[0].m_direction[0], constraints[1].m_direction[0]); - btAssert(free_dir.norm() > SIMD_EPSILON) - free_dir.normalize(); - x[i] = x[i].dot(free_dir) * free_dir; + has_static = has_static || constraints.m_static[j]; + } + // static friction => fully constrained + if (has_static) + { + x[i].setZero(); + } + else if (constraints.m_total_normal_dv.size() >= dim) + { + x[i].setZero(); + } + else if (constraints.m_total_normal_dv.size() == 2) + { + + btVector3 dir0 = (constraints.m_total_normal_dv[0].norm() > SIMD_EPSILON) ? constraints.m_total_normal_dv[0].normalized() : btVector3(0,0,0); + btVector3 dir1 = (constraints.m_total_normal_dv[1].norm() > SIMD_EPSILON) ? constraints.m_total_normal_dv[1].normalized() : btVector3(0,0,0); + btVector3 free_dir = btCross(dir0, dir1); + if (free_dir.norm() < SIMD_EPSILON) + { + x[i] -= x[i].dot(dir0) * dir0; + x[i] -= x[i].dot(dir1) * dir1; + } + else + { + free_dir.normalize(); + x[i] = x[i].dot(free_dir) * free_dir; + } } else - x[i].setZero(); - // apply the friction constraint - if (constraints.size() < 3) { - for (int f = 0; f < frictions.size(); ++f) - { - DeformableFrictionConstraint& friction= frictions[f]; - for (int j = 0; j < friction.m_direction.size(); ++j) - { - if (friction.m_static[j] == true) - { - x[i] -= x[i].dot(friction.m_direction[j]) * friction.m_direction[j]; - } - } - } + btAssert(constraints.m_total_normal_dv.size() == 1); + btVector3 dir0 = (constraints.m_total_normal_dv[0].norm() > SIMD_EPSILON) ? constraints.m_total_normal_dv[0].normalized() : btVector3(0,0,0); + x[i] -= x[i].dot(dir0) * dir0; } } } -void btDeformableContactProjection::projectFriction(TVStack& x) +void btDeformableContactProjection::applyDynamicFriction(TVStack& f) { - const int dim = 3; for (int index = 0; index < m_constraints.size(); ++index) { - const btAlignedObjectArray& constraints = *m_constraints.getAtIndex(index); + const DeformableContactConstraint& constraint = *m_constraints.getAtIndex(index); + const btSoftBody::Node* node = constraint.m_node; + if (node == NULL) + continue; size_t i = m_constraints.getKeyAtIndex(index).getUid1(); - btAlignedObjectArray& frictions = *m_frictions[m_constraints.getKeyAtIndex(index)]; - btAssert(constraints.size() <= dim); - btAssert(constraints.size() > 0); + bool has_static_constraint = false; - // apply friction if the node is not constrained in all directions - if (constraints.size() < 3) + // apply dynamic friction force (scaled by dt) if the node does not have static friction constraint + for (int j = 0; j < constraint.m_static.size(); ++j) { - bool has_static_constraint = false; - for (int f = 0; f < frictions.size(); ++f) + if (constraint.m_static[j]) { - DeformableFrictionConstraint& friction= frictions[f]; - for (int j = 0; j < friction.m_static.size(); ++j) - has_static_constraint = has_static_constraint || friction.m_static[j]; + has_static_constraint = true; + break; } - - for (int f = 0; f < frictions.size(); ++f) + } + for (int j = 0; j < constraint.m_total_tangent_dv.size(); ++j) + { + btVector3 friction_force = constraint.m_total_tangent_dv[j] * (1./node->m_im); + if (!has_static_constraint) { - DeformableFrictionConstraint& friction= frictions[f]; - for (int j = 0; j < friction.m_direction.size(); ++j) - { - // only add to the rhs if there is no static friction constraint on the node - if (friction.m_static[j] == false) - { - if (!has_static_constraint) - x[i] += friction.m_direction[j] * friction.m_impulse[j]; - } - } + f[i] += friction_force; } } } @@ -491,7 +370,6 @@ void btDeformableContactProjection::reinitialize(bool nodeUpdated) { btCGProjection::reinitialize(nodeUpdated); m_constraints.clear(); - m_frictions.clear(); } diff --git a/src/BulletSoftBody/btDeformableContactProjection.h b/src/BulletSoftBody/btDeformableContactProjection.h index 0827554bb..331e1df6d 100644 --- a/src/BulletSoftBody/btDeformableContactProjection.h +++ b/src/BulletSoftBody/btDeformableContactProjection.h @@ -22,8 +22,7 @@ class btDeformableContactProjection : public btCGProjection { public: // map from node index to constraints - btHashMap > m_constraints; - btHashMap >m_frictions; + btHashMap m_constraints; btDeformableContactProjection(btAlignedObjectArray& softBodies, const btScalar& dt) : btCGProjection(softBodies, dt) @@ -37,7 +36,7 @@ public: // apply the constraints to the rhs virtual void project(TVStack& x); // add to friction - virtual void projectFriction(TVStack& x); + virtual void applyDynamicFriction(TVStack& f); // apply constraints to x in Ax=b virtual void enforceConstraint(TVStack& x); diff --git a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp b/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp index 80c77ada1..900ca9d8c 100644 --- a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp +++ b/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp @@ -70,78 +70,77 @@ void btDeformableRigidDynamicsWorld::positionCorrection(btScalar timeStep) BT_PROFILE("positionCorrection"); for (int index = 0; index < m_deformableBodySolver->m_objective->projection.m_constraints.size(); ++index) { - btAlignedObjectArray& frictions = *m_deformableBodySolver->m_objective->projection.m_frictions[m_deformableBodySolver->m_objective->projection.m_constraints.getKeyAtIndex(index)]; - btAlignedObjectArray& constraints = *m_deformableBodySolver->m_objective->projection.m_constraints.getAtIndex(index); - for (int i = 0; i < constraints.size(); ++i) + DeformableContactConstraint& constraint = *m_deformableBodySolver->m_objective->projection.m_constraints.getAtIndex(index); + for (int j = 0; j < constraint.m_contact.size(); ++j) { - DeformableContactConstraint& constraint = constraints[i]; - DeformableFrictionConstraint& friction = frictions[i]; - for (int j = 0; j < constraint.m_contact.size(); ++j) + const btSoftBody::RContact* c = constraint.m_contact[j]; + // skip anchor points + if (c == NULL || c->m_node->m_im == 0) + continue; + const btSoftBody::sCti& cti = c->m_cti; + btVector3 va(0, 0, 0); + + // grab the velocity of the rigid body + if (cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY) { - const btSoftBody::RContact* c = constraint.m_contact[j]; - // skip anchor points - if (c == NULL || c->m_node->m_im == 0) - continue; - const btSoftBody::sCti& cti = c->m_cti; - btVector3 va(0, 0, 0); - - // grab the velocity of the rigid body - if (cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY) + btRigidBody* rigidCol = (btRigidBody*)btRigidBody::upcast(cti.m_colObj); + va = rigidCol ? (rigidCol->getVelocityInLocalPoint(c->m_c1)): btVector3(0, 0, 0); + } + else if (cti.m_colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK) + { + btMultiBodyLinkCollider* multibodyLinkCol = (btMultiBodyLinkCollider*)btMultiBodyLinkCollider::upcast(cti.m_colObj); + if (multibodyLinkCol) { - btRigidBody* rigidCol = (btRigidBody*)btRigidBody::upcast(cti.m_colObj); - va = rigidCol ? (rigidCol->getVelocityInLocalPoint(c->m_c1)): btVector3(0, 0, 0); - } - else if (cti.m_colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK) - { - btMultiBodyLinkCollider* multibodyLinkCol = (btMultiBodyLinkCollider*)btMultiBodyLinkCollider::upcast(cti.m_colObj); - if (multibodyLinkCol) + const int ndof = multibodyLinkCol->m_multiBody->getNumDofs() + 6; + const btScalar* J_n = &c->jacobianData_normal.m_jacobians[0]; + const btScalar* J_t1 = &c->jacobianData_t1.m_jacobians[0]; + const btScalar* J_t2 = &c->jacobianData_t2.m_jacobians[0]; + const btScalar* local_v = multibodyLinkCol->m_multiBody->getVelocityVector(); + // add in the normal component of the va + btScalar vel = 0.0; + for (int k = 0; k < ndof; ++k) { - const int ndof = multibodyLinkCol->m_multiBody->getNumDofs() + 6; - const btScalar* J_n = &c->jacobianData_normal.m_jacobians[0]; - const btScalar* J_t1 = &c->jacobianData_t1.m_jacobians[0]; - const btScalar* J_t2 = &c->jacobianData_t2.m_jacobians[0]; - const btScalar* local_v = multibodyLinkCol->m_multiBody->getVelocityVector(); - // add in the normal component of the va - btScalar vel = 0.0; - for (int k = 0; k < ndof; ++k) - { - vel += local_v[k] * J_n[k]; - } - va = cti.m_normal * vel; - - vel = 0.0; - for (int k = 0; k < ndof; ++k) - { - vel += local_v[k] * J_t1[k]; - } - va += c->t1 * vel; - vel = 0.0; - for (int k = 0; k < ndof; ++k) - { - vel += local_v[k] * J_t2[k]; - } - va += c->t2 * vel; + vel += local_v[k] * J_n[k]; } - } - else - { - // The object interacting with deformable node is not supported for position correction - btAssert(false); - } - - if (cti.m_colObj->hasContactResponse()) - { - btScalar dp = cti.m_offset; + va = cti.m_normal * vel; - // only perform position correction when penetrating - if (dp < 0) + vel = 0.0; + for (int k = 0; k < ndof; ++k) + { + vel += local_v[k] * J_t1[k]; + } + va += c->t1 * vel; + vel = 0.0; + for (int k = 0; k < ndof; ++k) + { + vel += local_v[k] * J_t2[k]; + } + va += c->t2 * vel; + } + } + else + { + // The object interacting with deformable node is not supported for position correction + btAssert(false); + } + + if (cti.m_colObj->hasContactResponse()) + { + btScalar dp = cti.m_offset; + + // only perform position correction when penetrating + if (dp < 0) + { + if (constraint.m_static[j] == true) { if (friction.m_static[j] == true) { c->m_node->m_v = va; } c->m_node->m_v -= dp * cti.m_normal / timeStep; + c->m_node->m_v = va; } + c->m_node->m_v -= dp * cti.m_normal / timeStep; } } } From f7cd1edf4af9f53b078357dd758b064d1e343bbb Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Sat, 10 Aug 2019 12:00:48 -0700 Subject: [PATCH 10/56] code clean up --- examples/DeformableDemo/DeformableRigid.cpp | 2 +- examples/DeformableDemo/GraspDeformable.cpp | 4 +- .../DeformableDemo/VolumetricDeformable.cpp | 3 +- src/BulletSoftBody/btCGProjection.h | 44 ------------------- src/BulletSoftBody/btDeformableBodySolver.cpp | 5 ++- src/BulletSoftBody/btDeformableBodySolver.h | 1 + 6 files changed, 9 insertions(+), 50 deletions(-) diff --git a/examples/DeformableDemo/DeformableRigid.cpp b/examples/DeformableDemo/DeformableRigid.cpp index 9268572ef..6cc3d7b4f 100644 --- a/examples/DeformableDemo/DeformableRigid.cpp +++ b/examples/DeformableDemo/DeformableRigid.cpp @@ -232,7 +232,7 @@ void DeformableRigid::initPhysics() psb->setDampingCoefficient(0.05); psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects psb->m_cfg.kCHR = 1; // collision hardness with rigid body - psb->m_cfg.kDF = 0; + psb->m_cfg.kDF = 1; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); diff --git a/examples/DeformableDemo/GraspDeformable.cpp b/examples/DeformableDemo/GraspDeformable.cpp index 15348af26..6596c07d7 100644 --- a/examples/DeformableDemo/GraspDeformable.cpp +++ b/examples/DeformableDemo/GraspDeformable.cpp @@ -331,10 +331,10 @@ void GraspDeformable::initPhysics() psb->getCollisionShape()->setMargin(0.1); psb->setTotalMass(1); psb->setSpringStiffness(0); - psb->setDampingCoefficient(0.02); + psb->setDampingCoefficient(0.1); psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects psb->m_cfg.kCHR = 1; // collision hardness with rigid body - psb->m_cfg.kDF = 0; + psb->m_cfg.kDF = 2; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); diff --git a/examples/DeformableDemo/VolumetricDeformable.cpp b/examples/DeformableDemo/VolumetricDeformable.cpp index 74d9678a8..22755856b 100644 --- a/examples/DeformableDemo/VolumetricDeformable.cpp +++ b/examples/DeformableDemo/VolumetricDeformable.cpp @@ -234,7 +234,7 @@ void VolumetricDeformable::initPhysics() psb->getCollisionShape()->setMargin(0.25); // psb->generateBendingConstraints(2); psb->setTotalMass(1); - psb->setSpringStiffness(1); + psb->setSpringStiffness(0); psb->setDampingCoefficient(0.01); psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects psb->m_cfg.kCHR = 1; // collision hardness with rigid body @@ -242,6 +242,7 @@ void VolumetricDeformable::initPhysics() psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(.5,.5)); } // add a few rigid bodies Ctor_RbUpStack(4); diff --git a/src/BulletSoftBody/btCGProjection.h b/src/BulletSoftBody/btCGProjection.h index ef902c70d..9dc416cdd 100644 --- a/src/BulletSoftBody/btCGProjection.h +++ b/src/BulletSoftBody/btCGProjection.h @@ -53,49 +53,6 @@ struct DeformableContactConstraint } }; -struct DeformableFrictionConstraint -{ - btAlignedObjectArray m_static; // whether the friction is static - btAlignedObjectArray m_impulse; // the impulse magnitude the node feels - btAlignedObjectArray m_dv; // the dv magnitude of the node - btAlignedObjectArray m_direction; // the direction of the friction for the node - - - btAlignedObjectArray m_static_prev; - btAlignedObjectArray m_impulse_prev; - btAlignedObjectArray m_dv_prev; - btAlignedObjectArray m_direction_prev; - - btAlignedObjectArray m_released; // whether the contact is released - - - // the total impulse the node applied to the rb in the tangential direction in the cg solve - btAlignedObjectArray m_accumulated_tangent_impulse; - - DeformableFrictionConstraint() - { - append(); - } - - void append() - { - m_static.push_back(false); - m_static_prev.push_back(false); - - m_direction_prev.push_back(btVector3(0,0,0)); - m_direction.push_back(btVector3(0,0,0)); - - m_impulse.push_back(0); - m_impulse_prev.push_back(0); - - m_dv.push_back(0); - m_dv_prev.push_back(0); - - m_accumulated_tangent_impulse.push_back(btVector3(0,0,0)); - m_released.push_back(false); - } -}; - class btCGProjection { public: @@ -104,7 +61,6 @@ public: typedef btAlignedObjectArray > TArrayStack; btAlignedObjectArray& m_softBodies; btDeformableRigidDynamicsWorld* m_world; -// const btAlignedObjectArray* m_nodes; const btScalar& m_dt; btCGProjection(btAlignedObjectArray& softBodies, const btScalar& dt) diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index be0262842..8361abfe5 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -19,6 +19,7 @@ btDeformableBodySolver::btDeformableBodySolver() : m_numNodes(0) , m_cg(10) +, m_contact_iterations(10) { m_objective = new btDeformableBackwardEulerObjective(m_softBodySet, m_backupVelocity); } @@ -46,7 +47,7 @@ void btDeformableBodySolver::solveConstraints(float solverdt) void btDeformableBodySolver::computeStep(TVStack& dv, const TVStack& residual) { - btScalar tolerance = std::numeric_limits::epsilon() * m_objective->computeNorm(residual); + btScalar tolerance = std::numeric_limits::epsilon() * 1024 * m_objective->computeNorm(residual); m_cg.solve(*m_objective, dv, residual, tolerance); } @@ -76,7 +77,7 @@ void btDeformableBodySolver::setConstraints() { BT_PROFILE("setConstraint"); m_objective->setConstraints(); - for (int i = 0; i < 10; ++i) + for (int i = 0; i < m_contact_iterations; ++i) { m_objective->projection.update(); m_objective->enforceConstraint(m_dv); diff --git a/src/BulletSoftBody/btDeformableBodySolver.h b/src/BulletSoftBody/btDeformableBodySolver.h index 94102afa9..206354f52 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.h +++ b/src/BulletSoftBody/btDeformableBodySolver.h @@ -37,6 +37,7 @@ protected: btAlignedObjectArray m_backupVelocity; btScalar m_dt; + btScalar m_contact_iterations; btConjugateGradient m_cg; From cb7257d27b0b5855f5b912b927d68bed41ac451a Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Sun, 11 Aug 2019 15:51:49 -0700 Subject: [PATCH 11/56] add reader to create softbodies from vtk files --- src/BulletSoftBody/btSoftBodyHelpers.cpp | 101 +++++++++++++++++++++++ src/BulletSoftBody/btSoftBodyHelpers.h | 6 +- 2 files changed, 106 insertions(+), 1 deletion(-) diff --git a/src/BulletSoftBody/btSoftBodyHelpers.cpp b/src/BulletSoftBody/btSoftBodyHelpers.cpp index b3c5c88a9..e30f5af58 100644 --- a/src/BulletSoftBody/btSoftBodyHelpers.cpp +++ b/src/BulletSoftBody/btSoftBodyHelpers.cpp @@ -16,6 +16,9 @@ subject to the following restrictions: #include "btSoftBodyInternals.h" #include +#include +#include +#include #include #include "btSoftBodyHelpers.h" #include "LinearMath/btConvexHull.h" @@ -1228,3 +1231,101 @@ if(face&&face[0]) printf("Tetras: %u\r\n", psb->m_tetras.size()); return (psb); } + +btSoftBody* btSoftBodyHelpers::CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, const std::string& vtk_file) +{ + std::ifstream fs; + fs.open(vtk_file); + btAssert(fs); + btSoftBody* psb = CreateFromVtkFile(worldInfo, fs); + fs.close(); + return psb; +} + +btSoftBody* btSoftBodyHelpers::CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, std::istream& in) +{ + typedef btAlignedObjectArray Index; + std::string line; + btAlignedObjectArray X; + btVector3 position; + btAlignedObjectArray indices; + bool reading_points = false; + bool reading_tets = false; + size_t n_points = 0; + size_t n_tets = 0; + size_t x_count = 0; + size_t indices_count = 0; + while (std::getline(in, line)) + { + std::stringstream ss(line); + if (line.size() == (size_t)(0)) + { + } + else if (line.substr(0, 6) == "POINTS") + { + reading_points = true; + reading_tets = false; + ss.ignore(128, ' '); // ignore "POINTS" + ss >> n_points; + X.resize(n_points); + } + else if (line.substr(0, 5) == "CELLS") + { + reading_points = false; + reading_tets = true; + ss.ignore(128, ' '); // ignore "CELLS" + ss >> n_tets; + indices.resize(n_tets); + } + else if (line.substr(0, 10) == "CELL_TYPES") + { + reading_points = false; + reading_tets = false; + } + else if (reading_points) + { + btScalar p; + ss >> p; + position.setX(p); + ss >> p; + position.setY(p); + ss >> p; + position.setZ(p); + X[x_count++] = position; + } + else if (reading_tets) + { + ss.ignore(128, ' '); // ignore "4" + Index tet; + tet.resize(4); + for (size_t i = 0; i < 4; i++) + { + ss >> tet[i]; + } + indices[indices_count++] = tet; + } + } + btSoftBody* psb = new btSoftBody(&worldInfo, n_points, &X[0], 0); + + for (int i = 0; i < n_tets; ++i) + { + const Index& ni = indices[i]; + psb->appendTetra(ni[0], ni[1], ni[2], ni[3]); + { + psb->appendLink(ni[0], ni[1], 0, true); + psb->appendLink(ni[1], ni[2], 0, true); + psb->appendLink(ni[2], ni[0], 0, true); + psb->appendLink(ni[0], ni[3], 0, true); + psb->appendLink(ni[1], ni[3], 0, true); + psb->appendLink(ni[2], ni[3], 0, true); + } + } + psb->initializeDmInverse(); + printf("Nodes: %u\r\n", psb->m_nodes.size()); + printf("Links: %u\r\n", psb->m_links.size()); + printf("Faces: %u\r\n", psb->m_faces.size()); + printf("Tetras: %u\r\n", psb->m_tetras.size()); + return (psb); +} + + diff --git a/src/BulletSoftBody/btSoftBodyHelpers.h b/src/BulletSoftBody/btSoftBodyHelpers.h index e433558c1..927cb6781 100644 --- a/src/BulletSoftBody/btSoftBodyHelpers.h +++ b/src/BulletSoftBody/btSoftBodyHelpers.h @@ -17,7 +17,8 @@ subject to the following restrictions: #define BT_SOFT_BODY_HELPERS_H #include "btSoftBody.h" - +#include +#include // // Helpers // @@ -140,6 +141,9 @@ struct btSoftBodyHelpers bool bfacelinks, bool btetralinks, bool bfacesfromtetras); + static btSoftBody* CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, const std::string& vtk_file); + static btSoftBody* CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, std::istream& in); + /// Sort the list of links to move link calculations that are dependent upon earlier /// ones as far as possible away from the calculation of those values From 991be526813a8675360bcbd7d59255141351186e Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Mon, 12 Aug 2019 11:08:11 -0700 Subject: [PATCH 12/56] add more volumetric meshes for grasping tests --- data/ball.vtk | 5681 +++++ data/banana.vtk | 5524 +++++ data/boot.vtk | 5457 ++++ data/bread.vtk | 5459 ++++ data/ditto.vtk | 23419 ++++++++++++++++++ data/paper_roll.vtk | 5057 ++++ data/torus.vtk | 9917 ++++++++ data/tube.vtk | 5051 ++++ examples/DeformableDemo/GraspDeformable.cpp | 71 +- 9 files changed, 65625 insertions(+), 11 deletions(-) create mode 100644 data/ball.vtk create mode 100644 data/banana.vtk create mode 100644 data/boot.vtk create mode 100644 data/bread.vtk create mode 100644 data/ditto.vtk create mode 100644 data/paper_roll.vtk create mode 100644 data/torus.vtk create mode 100644 data/tube.vtk diff --git a/data/ball.vtk b/data/ball.vtk new file mode 100644 index 000000000..a5007a034 --- /dev/null +++ b/data/ball.vtk @@ -0,0 +1,5681 @@ +# vtk DataFile Version 2.0 +ball_, Created by Gmsh +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 600 double +-0.983023465 -0.0964612812 0.156077221 +-0.983023465 0.0964612812 -0.156077221 +-0.934172392 0.303531051 0.187592313 +-0.934172332 -0.303530991 -0.187592283 +-0.851981342 -0.0839028731 -0.516805649 +-0.851981342 0.0839028731 0.516805649 +-0.851980925 -0.499768227 0.156077191 +-0.851980925 0.499768227 -0.156077191 +-0.850650847 -0.276393682 0.447213203 +-0.850650847 0.276393682 -0.447213203 +-0.738584518 -0.432902843 -0.516805708 +-0.738584518 0.432902843 0.516805708 +-0.73858422 -0.655845523 -0.156077221 +-0.73858422 0.655845523 0.156077221 +-0.639950216 -0.568661451 0.51680553 +-0.639950216 -0.207932755 0.739748478 +-0.639950216 0.207932755 -0.739748478 +-0.639950216 0.568661451 -0.51680553 +-0.577350318 -0.187592313 -0.794654369 +-0.577350318 0.187592313 0.794654369 +-0.57735014 -0.794654608 0.187592268 +-0.57735014 0.794654608 -0.187592268 +-0.525731206 -0.723606944 -0.447213262 +-0.525731206 0.723606944 0.447213262 +-0.395510972 -0.544374168 -0.739748478 +-0.395510972 0.544374168 0.739748478 +-0.395510912 -0.905102789 -0.156077221 +-0.395510912 0.905102789 0.156077221 +-0.356822073 -0.491123736 0.79465431 +-0.356822073 0.491123736 -0.79465431 +-0.343073279 -0.784354985 0.51680547 +-0.343073279 0.784354985 -0.51680547 +-0.343073219 -0.111471429 0.932670832 +-0.343073219 0.111471429 -0.932670832 +-0.2104855876170211 -0.964206637039642 0.1581990558083625 +-0.212030917 -0.291835517 -0.932670832 +-0.212030917 0.291835517 0.932670832 +-0.212030917 0.964718938 -0.156077191 +-0.183480024 -0.836209893 -0.516805649 +-0.183480024 0.836209893 0.516805649 +0 -0.982246935 -0.187592283 +0 -0.894427359 0.447213143 +0 -0.67288357 0.739748418 +0.003206644697647349 -0.6069040358667548 -0.793866965776601 +0 -0.360728621 0.932670832 +0 0 -1 +0 0 1 +0 0.360728621 -0.932670832 +0 0.607062101 0.794654369 +0 0.67288357 -0.739748418 +0 0.894427359 -0.447213143 +0 0.982246935 0.187592283 +0.183480024 -0.836209893 -0.516805649 +0.183480024 0.836209893 0.516805649 +0.212030917 -0.964718938 0.156077191 +0.212030917 -0.291835517 -0.932670832 +0.212030917 0.291835517 0.932670832 +0.212030917 0.964718938 -0.156077191 +0.343073219 -0.111471429 0.932670832 +0.343073219 0.111471429 -0.932670832 +0.343073279 -0.784354985 0.51680547 +0.343073279 0.784354985 -0.51680547 +0.356822073 -0.491123736 0.79465431 +0.356822073 0.491123736 -0.79465431 +0.395510912 -0.905102789 -0.156077221 +0.395510912 0.905102789 0.156077221 +0.395510972 -0.544374168 -0.739748478 +0.395510972 0.544374168 0.739748478 +0.525731206 -0.723606944 -0.447213262 +0.525731206 0.723606944 0.447213262 +0.57735014 -0.794654608 0.187592268 +0.57735014 0.794654608 -0.187592268 +0.577350318 -0.187592313 -0.794654369 +0.577350318 0.187592313 0.794654369 +0.639950216 -0.568661451 0.51680553 +0.639950216 -0.207932755 0.739748478 +0.639950216 0.207932755 -0.739748478 +0.6403071758249252 0.5681663036852607 -0.5166876297130185 +0.73858422 -0.655845523 -0.156077221 +0.73858422 0.655845523 0.156077221 +0.738584518 -0.432902843 -0.516805708 +0.738584518 0.432902843 0.516805708 +0.850650847 -0.276393682 0.447213203 +0.850650847 0.276393682 -0.447213203 +0.851980925 -0.499768227 0.156077191 +0.851980925 0.499768227 -0.156077191 +0.851981342 -0.0839028731 -0.516805649 +0.851981342 0.0839028731 0.516805649 +0.934172332 -0.303530991 -0.187592283 +0.934172332 0.303530991 0.187592283 +0.983023465 -0.0964612812 0.156077221 +0.983023465 0.0964612812 -0.156077221 +0.5711142457352039 -0.02117318796408544 0.5475993502453641 +-0.1834416395507999 0.7396783497444386 0.3181062812107694 +0.2106439939202896 -0.2207277428413223 0.4082221439441702 +-0.0539340503386703 0.1205623207765116 0.4836333150598941 +0.2628914088751474 0.7773567891547469 0.09515773339548624 +0.03625912260493044 0.1154490571841422 0.01428072891263531 +0.04533024469518119 0.01305404249175379 0.830501261727119 +0.1985279596222446 0.1026376486066588 0.4134011017099528 +0.2142576018926516 0.2515904542794398 0.6479455601266221 +0.03591460286896146 0.4648677758371071 -0.6570336955526989 +0.5671390851245302 0.5015167065943134 -0.1302515747102941 +-0.4336614400972409 0.6553851050556312 0.01835453816623948 +-0.7093788513188323 0.02333083593137917 0.4009020437778424 +0.3304153126852112 0.3344430393663131 0.4341447817148135 +0.2835700190185853 -0.1109561501157584 -0.03835100901018595 +0.3384894052038657 0.5443598947507846 -0.4660342040261232 +-0.5534428405667881 0.233243177347242 0.4775208239879267 +0.3754426255119463 0.1029385152098835 -0.6464035637317401 +0.4981870246588242 0.6568525523351662 0.03962368739938198 +-0.3224051846001322 0.4144807316899718 0.1313140478558114 +-0.6478232497017437 -0.3106068971239328 0.01838391805257134 +-0.6576204209938942 -0.2352120512243483 0.431309676011668 +-0.05520070934685202 0.3843844699857725 0.5403667230515509 +-0.7319644942494914 -0.1507752387397017 0.1790669502670221 +-0.6189952662241086 0.01441484356622188 -0.4292031591776315 +-0.6262186005325446 -0.1021573130552927 -0.08428654763266503 +-0.6149963655872288 0.1445403524573829 -0.1438974409017034 +-0.7148900485634544 0.2730783119567216 -0.3026754607577274 +-0.7649453896417203 0.2504548103851916 0.09555797780578199 +-0.3715645582539543 0.1330924452813407 0.3239746822760231 +-0.6615658498360117 0.4804724661556226 -0.1782035107984122 +-0.6505392321170821 0.4100942048988089 0.3356868961443531 +0.336318519474418 0.64955921672115 0.141676610967413 +-0.2373043190629461 0.3628706261497389 -0.7212426055441383 +-0.4720367219822728 -0.2703656731060821 -0.4799947601815256 +-0.4838010172770574 -0.4084105827317038 0.02536967576873089 +-0.4820695438460503 -0.3369545734327805 0.2368150044206616 +-0.05526386895500314 -0.6265972416112141 0.5202839866714712 +-0.4578607499769821 -0.1491368316814568 -0.2444009752709367 +-0.4725026890114479 -0.2375671541793563 -0.06095126386351808 +-0.5195546414777057 -0.1755190582509266 0.1209235603722047 +-0.5124729844160486 -0.1633519413558985 0.3519691378163123 +-0.4528539662618702 -0.01654279695323081 -0.5802020170398763 +-0.4008637964178123 0.03833967835098375 -0.2780189568137055 +-0.4045298128199117 0.002479879083573726 -0.006952714925801346 +-0.5016139410945001 0.005830520154651217 0.2427433809520513 +-0.08387994752248742 0.6831638754551344 -0.5090009524768978 +0.09979297173020235 0.6214399756317296 -0.5394454270132362 +-0.5114964260553124 0.2451501439357156 -0.3032535448403038 +-0.5084862441056747 0.2942826463714892 -0.0130907342464313 +-0.5126741910570937 0.2936280836507524 0.1874216510559829 +-0.4823199432566514 0.4941810202203625 -0.3367534291859899 +-0.3772934083386824 -0.5828600711068156 0.05591038990918762 +0.31959038478937 0.6140451281085459 0.4487754251285493 +-0.479509208666884 0.08909312439915772 0.6399726514442271 +-0.5987352168435675 0.484251969256761 0.6021395588401608 +0.5668924718157011 -0.4886889568034963 -0.6283779956613038 +0.639950216 -0.388297103 0.628277004 +0.7459657790000001 -0.06201494095 0.6282770635 +0.7592375082896597 0.03835589427941914 -0.6142001436623598 +-0.289495498 -0.6902920305 -0.6282770635 +-0.289495498 0.6902920305 0.6282770635 +0.2890391134520873 0.6930274692624179 0.6252725821525187 +-0.1954342843662734 -0.7343660690537938 0.6146913268860001 +-0.9175452116087988 0.2925245629145609 -0.1630626342597246 +0.917502195 0.2981147541 -0.156077206 +0 -0.291835517 -0.932670832 +-0.005512644538268026 0.2950789991623015 0.9312507298938767 +0.004756329446631069 0.9636913804870406 -0.1603331621849719 +0.1796931993833944 0.2270906263641855 -0.9332463212503043 +0.2839543240347723 0.8721681798631183 0.3355386774168226 +-0.289495468 -0.870656341 -0.336441435 +-0.2824861689252822 0.8686566398371635 0.3475001356528549 +-0.9088421251404275 -0.001564412629376344 -0.3594565782347531 +-0.9203312242053348 -0.003164966157839524 0.3264860119713744 +-0.09774266951051733 0.5555167174787097 0.05788528891157628 +-0.7959907918282177 -0.08211319339975402 -0.2053910711192425 +0.03999856928576947 -0.7162839095211453 0.3099013009429171 +-0.202249908345953 -0.5058539092504294 0.1161823685420006 +-0.3148245980164619 -0.486917647454533 0.3203107592281709 +-0.2982953732069865 -0.5180797069493416 0.5498719423954977 +-0.3594062555305886 -0.3476011575009336 -0.6363012624107233 +-0.4028820318916886 -0.3603563062649521 -0.3178933311462525 +-0.3832569634790784 -0.3515629954201686 -0.1608643060189855 +-0.4216489709933123 -0.3683521042712592 0.5299835001681149 +-0.3195340547884118 -0.140458944668357 -0.6767753179600076 +-0.2872190492198003 -0.173107228026045 -0.1073851967440021 +-0.3380772476234242 -0.2306023291143007 0.1015223234543294 +-0.2354645404631943 -0.01847107181770858 -0.3779481679535365 +-0.2339023084221015 -0.01296643920890605 -0.1988671494631802 +-0.4987959292068802 0.5466275984665788 0.3553392545012639 +-0.2993944553011925 0.1160085292182497 -0.5451195709408356 +-0.3180663905624121 0.1816410244317394 -0.3429709835741863 +-0.2984496076861362 0.1731311801956928 -0.1197266002465337 +0.4687659597810016 -0.2609182020629837 0.6456947938158271 +-0.4055380501868786 0.3360296110081572 -0.1690284861777329 +-0.3933493850310362 0.3799269361927073 0.4612899972994972 +-0.6111316600192891 0.5629118916990601 0.2058136799792555 +-0.1835444972768308 -0.2503244747191174 0.6894847407095083 +-0.3286465144478981 0.5109703139291987 -0.4955986563887662 +-0.004524729044751769 0.5061287162879585 -0.4068364833826668 +-0.2086130206014155 0.6253776096440031 0.1785871149235653 +0.07445582966821258 0.7328882912340795 0.1563893347189518 +-0.2415260834301355 0.6855613573510219 -0.1635365387199929 +-0.1928500407563954 -0.7485795663723692 -0.08958998919100135 +-0.2440533359827937 -0.761435917282856 0.1477089760778446 +-0.1323263255053054 -0.4702260860235108 -0.4985941389931162 +-0.22737749859913 0.4085551242737154 -0.1336398432333173 +-0.2222732982258658 -0.2445988685511035 -0.4900209146071922 +-0.1866052001617161 -0.3328028942391639 -0.3051094150744377 +-0.2137502620263282 -0.3303845535191539 -0.03786939554681432 +-0.1395435470476703 -0.1430048503387833 -0.7860101332846771 +-0.1661517739966091 -0.2049543828386332 -0.6361077629093909 +-0.1017630055389408 -0.1670464911194232 -0.3764157164282813 +-0.1109262933335437 -0.1818459499504256 -0.175842010364428 +-0.2161513648114311 -0.1313699938541844 0.1374374024081151 +-0.7811637926694741 0.03047292067867113 -0.02077792430430652 +-0.1418259415916119 -0.02690292354447475 -0.5424026029815623 +-0.1662287378662191 0.1595605701931951 -0.4695541301881394 +-0.1728767079413297 0.1908071514581589 0.0615239831543104 +-0.1248750586000535 0.3373311231905142 -0.5554664407645996 +-0.14774927995634 0.3063479780977638 -0.2971590655764376 +0.317116356473119 0.2636782785377943 -0.517452462149712 +-0.2394625555723072 0.2531091923781731 0.6835180344331175 +-0.1679730860372385 0.6368995083228546 -0.3448914412206089 +-0.1837756206218147 0.8016555747753288 0.001376073021788904 +0.3451586896859973 0.4434648907403473 0.5896671438737594 +0.003912050757982196 -0.6827793661450405 -0.2655034195677201 +0.05117827517194013 -0.4435365454492594 -0.6820128265394876 +-0.193753047436954 0.4669909734707379 0.3562881914225061 +-0.09133017258798415 -0.3710555026643473 0.2211949880926304 +-0.03705517642456098 -0.3967684449657486 0.5575378871330299 +0.004882513238944297 -0.09563858312228475 0.4646605164348893 +-0.06034179915165584 -0.2072440902334313 0.8115716909884921 +-0.01502779929022804 -0.1349339192206479 -0.5198216229754721 +-0.06170726596266114 -0.03300790193827988 -0.3521591664732798 +-0.04024251802528552 0.005316680619917384 -0.1720644173805807 +-0.05170363143209005 0.1443521662120487 -0.3084341261872872 +-0.01322903563459284 0.2892392261133912 -0.1423042447860729 +-0.006197885268519417 0.7257559254287651 -0.117604568649597 +0.00766263881206371 0.6713927509871588 0.3773690346367958 +-0.2765102001377094 -0.1450045556428195 0.3700566231624965 +0.2934780115174567 -0.2895974752147772 -0.6869405692235921 +-0.0646204301881949 0.7678706524307314 -0.322313732124793 +0.1983578642321666 -0.6692184654722374 -0.3806422137534514 +0.1896536071268709 -0.7783794014092489 -0.1543701154216221 +0.04814811832475203 -0.306957222624095 -0.3920233494555808 +0.130872993428573 -0.2614789390432524 -0.224930457969755 +0.05389397376507032 -0.2123135609868312 -0.0456044035096165 +0.1511164622406309 -0.1940120025982684 -0.5486948695672719 +0.08753891237885909 -0.1517419059418617 0.2085053703494517 +0.1573315106118656 -0.2063105176207875 0.7159593163722718 +0.1550574248229858 0.04460639168602056 -0.1632815974459763 +-0.09138953766989316 -0.4558122872772558 -0.2134181647417048 +0.2200403617095288 0.07018008050263533 0.1855545431154388 +0.1745720918276096 0.2964164757364657 -0.6869932450671804 +0.1552374192338686 0.2846877060298754 -0.2720285722263412 +0.5793485990688858 -0.4281363848214862 0.159228937020492 +0.1842995827528208 0.380858358573093 0.2335724355465266 +0.4560445866155982 0.1596898570065349 0.5987060162239723 +0.1897142363072325 0.6801377880530463 -0.1902732043843415 +0.1901803121038665 0.8420330977104334 -0.01077757151453724 +0.3735835590265989 -0.533816093193585 -0.3508145004491201 +-0.2333532313517916 0.1770127404954969 0.4648197664473095 +0.4181266969831226 -0.6618380482497811 0.1445372622865072 +0.3540133290923644 -0.6599343730878077 0.3758436212261005 +0.3333915829314644 -0.515513798024383 -0.5694349617782053 +0.2972094522201416 -0.5540869081361335 -0.1452966914102986 +0.2485136095544038 -0.6516874642731798 0.03570321982604948 +0.4160373989187208 -0.4753541308402521 0.3172453979902219 +0.2504742106226169 -0.3318321328184352 -0.4555861371925892 +0.3482752365168776 -0.3103663015204521 0.5103815503896095 +0.363152181432955 -0.09509648738396842 -0.3986768381978469 +-0.06840482657418301 0.05308915763389212 -0.8176348399056567 +0.7133486872755079 -0.1421207717732033 -0.6548609400718425 +0.7136162202406232 0.139291053558023 0.6556126973517143 +-0.7106270713040959 -0.1410901777337968 -0.6583856211814568 +-0.7240001684667472 0.1373968881268417 0.6443478150910714 +0.657967418 -0.310247578 -0.6557300385 +0.657967418 0.310247578 0.6557300385 +0.3779418925513292 -0.01593005867563534 -0.167519838453102 +-0.6392793337542173 0.2794427660700018 0.688823162263437 +-0.5065672941465678 0.5379795210271793 -0.6419662140897575 +0.4983861445 0.5298925935 -0.65572992 +0.2932328291895358 -0.06287549989074649 0.5654605252776161 +0.349947676 0.6377393605 -0.6557298899999999 +0.3106772736351038 0.1522421239459671 -0.2847040964404556 +0.3619016076579907 0.1233667417260152 -0.0445398112121507 +0.3684048064067006 0.2305894720953906 0.2839597151092496 +-0.3487589772923571 0.638136180858714 -0.6557480128856027 +-0.4871324826293567 0.3638301270017998 0.7677279552997338 +-0.9585979285 0.1035348849 0.171834767 +0.608650267 0.01017022099999999 -0.7672014235 +0.608650267 -0.01017022099999999 0.7672014235 +-0.6024376177446233 -0.003711788266030136 0.7714069934328189 +-0.6042447734847533 0.006687585073746893 -0.7701420626251527 +0.3849066454986819 0.3232513751465138 -0.3587201583300489 +0.349947646 -0.3012975825 0.863662571 +0.3483476961081615 0.3176425081266358 -0.8582847161038692 +-0.349947646 -0.3012975825 0.863662571 +-0.349947646 0.3012975825 -0.863662571 +-0.3946906175 -0.239713915 -0.8636626005 +-0.09671645922550712 -0.455556329131489 -0.8609885293111011 +-0.1060154585 0.449448809 0.8636626005 +0.1060154585 -0.449448809 -0.8636626005 +0.2912864408393545 0.4360741369068572 0.03666708387193633 +0.1060154585 0.449448809 0.8636626005 +0.9585978985000001 -0.1035348549 -0.171834752 +0.1784110365 -0.4259261785 0.863662571 +0.1784110365 0.4259261785 -0.863662571 +-0.1784110365 -0.4259261785 0.863662571 +-0.1784110365 0.4259261785 -0.863662571 +0.4485607805444057 0.0274412363049529 0.8699508680135298 +0.4602117685 -0.03806044200000001 -0.8636626005 +0.197755486 -0.5757181345 -0.7672014235 +0.1875170285645086 0.572125542956834 0.7717238126591888 +-0.197755486 -0.5757181345 -0.7672014235 +-0.197755486 0.5757181345 0.7672014235 +-0.4983861445 -0.3495282455 0.767201394 +0.500733827029852 -0.3429494372899287 0.76820165259275 +0.4984777918937785 0.3440639152388975 -0.7690320795564272 +-0.4983861445 0.3495282455 -0.767201394 +-0.893076867 0.19371696205 0.352198981 +0.893076837 0.19371693205 0.352198966 +-0.893076837 -0.19371693205 -0.352198966 +0.197755456 -0.9436748619999999 -0.171834752 +0.197755456 0.9436748619999999 0.171834752 +-0.1821617266157461 -0.9467164087685083 -0.1730772900272592 +-0.197755456 0.9436748619999999 0.171834752 +0.1784110365 -0.582003653 0.7672013639999999 +0.2040914871099653 0.5689224150578829 -0.7711529358179858 +-0.1784110365 -0.582003653 0.7672013639999999 +-0.1706458392315522 0.5873889545945985 -0.7646290951570205 +-0.7146655325 -0.6472114175 0.1718347295 +-0.3946905285 -0.879686773 0.1718347295 +-0.3826992263243234 0.885549985338254 -0.1672278852813028 +0.4151318255287663 -0.8705468821272369 0.1688179381681522 +0.3816176964913821 0.8846414226634638 -0.1740180681064438 +-0.091740012 -0.909228414 -0.352198966 +-0.091740012 0.909228414 0.352198966 +0.091740012 -0.909228414 -0.352198966 +0.1089846745012238 0.8993400783200778 0.3711736160872028 +0.6605850764739363 0.7218724255144597 -0.02082643400756409 +0.6051372878400938 -0.6836471993845313 0.3532258537403473 +0.4583870346619611 -0.4209981570445642 -0.1711038550931559 +0.408350076952553 -0.5098359751664326 0.01900175426181287 +0.608650178 0.6816580295 -0.352198899 +-0.608650178 -0.6816580295 0.352198899 +0.45648501097621 -0.3834349647647116 -0.5239930356657895 +-0.1042226204554116 0.9733574426023197 0.01329700120380936 +0.1060154585 -0.9734829365 -0.015757546 +-0.4932432547533117 -0.8454431013474896 0.02391297713720811 +0.541956875235316 -0.3767605104076648 0.4856263302575095 +-0.486430526 0.8498786985 -0.01575752350000001 +0.486430526 0.8498786985 -0.01575752350000001 +0.48061420171132 -0.2281208781151917 -0.2153453641230161 +0.4284248677084959 -0.1138731139101116 0.2768188947161023 +0.4891608441455692 0.04285741068612015 -0.2392536176845577 +0.5028450662469833 0.1744824366837791 -0.3552556460455714 +0.4918009675321204 0.1992321909831743 0.03932374300364145 +0.4173683137353702 0.1629270449975743 0.1505109990808487 +0.5887669952330052 0.2351015203098686 -0.5092344915592217 +0.4725694558703502 0.3409692333818932 -0.2300329801651423 +0.5014632353682689 0.330522856036409 0.5277466676480008 +0.5887046726367641 0.4133518205028979 -0.3564640791626207 +0.5031963258450896 0.4082414396977185 0.1108730627916911 +0.2436600679212088 0.1449343977100464 -0.8027510085861623 +0.2661692629564029 -0.4161860961116939 0.6778322933520385 +0.5389336922228024 0.1297001439188301 -0.6793540746793117 +0.6190312172756546 -0.4853355389423176 -0.03823594414065377 +0.6213611290860127 -0.3654585732207788 -0.347839611365611 +0.670070540631135 -0.3304850044928141 0.3075176279985078 +-0.6312346450457121 -0.4270283138376362 -0.1407213056076125 +0.6730006361713489 -0.2300717412324852 -0.04015617222070676 +0.6324119311658877 -0.1685265550881164 0.47278684240569 +0.6718515317701345 -0.05261279391738263 -0.3476589343402736 +0.6546114519167675 0.01675368673195545 -0.08995678553058238 +0.5666475744692999 0.01576403308009006 0.1090301993966335 +0.7263519144247657 0.2057950395874256 -0.2835024210938008 +0.6292624093999444 0.1466102513984335 0.3296682045884995 +0.6539040382194233 0.4373423551522446 0.2973447396401895 +-0.7643904657784308 -0.3270157704006694 0.1507235781129556 +-0.3983099956439372 0.6820166389351584 0.1935158435411442 +0.1454606949276961 0.3560515065805233 0.4574558148114424 +-0.01767048188895652 0.3492544118967844 0.06334264290988761 +0.7646550963318656 -0.06248067496257166 0.1786710643635689 +0.7930174579354851 0.1693865451645832 0.003272865232918417 +0.01099307050411781 0.02194760905610892 0.6477401853065817 +-0.1771759356058517 0.03015440844192887 0.2473680276008317 +-0.5356149458936418 -0.00801003630796797 0.4864425417428122 +0.1872786676121908 0.2172773256198141 0.03050623571169319 +-0.3987986696634189 -0.4946354289051259 -0.4439894573386592 +-0.5888927087817538 0.4747743064772978 0.04104831404680311 +-0.4694703441665588 0.5798300713339117 -0.1603835011744431 +-0.8294116489724226 0.4943369061879145 0.1673151208721621 +-0.8285092954478688 -0.4943369061879149 -0.167315120872162 +0.08601788431546994 -0.4744118786476427 -0.4369039278327513 +0.4268144290850234 -0.7056612795120653 -0.09119225644388079 +-0.235911498660543 0.2496733507810339 0.2926911520456563 +0.04659252556510694 -0.5220086048051136 -0.03190513921165003 +-0.7464064032657043 -0.5811252752524934 -0.255439270284655 +-0.7257250063463581 -0.5604577921412572 -0.3346302417443242 +-0.746406405436403 0.5811252774217315 0.2554392724872807 +-0.7257250063463581 0.560457792141257 0.3346302417443243 +-0.005212278065876854 0.1920171302444726 0.2672071089672988 +0.01121553754032911 0.4522189791379762 0.2930005482030935 +0.2839230991990829 0.4622075315499078 -0.3082127476279448 +-0.4946697047593434 -0.3557726340191656 -0.7662271305074406 +-0.7138890554715793 0.6476333650493602 -0.1727963078701259 +0.5625564905082746 0.01892208994219046 -0.5555981537279906 +-0.09297651214053022 -0.0615660465312691 0.01339996495471615 +-0.8038254879010522 -0.01152003924077081 0.1729691168589109 +-0.2579234662149842 -0.5521401609060735 -0.2660064486766345 +0.7006944775450153 0.3370390934389887 -0.1608815100660374 +0.7914465127578063 -0.2741122939862151 -0.5140873673583262 +0.7888851699703932 0.2780931631132194 0.5168056818287339 +-0.7952829299999999 0.25840285805 0.5168056785 +0.4915117175 -0.159702092 0.836209655 +0.4915117175 0.159702092 -0.836209655 +-0.320482407164663 -0.4333159822567259 -0.8217963374496685 +0.3037709445 0.4181048425 0.836209655 +-0.01265687939189167 0.8375532314178935 0.5137773422349819 +-0.4952171247940293 0.6753533752031967 -0.5140018615193953 +-0.9824696345558724 -0.01113430460937868 0.01032097863238671 +0.983023465 0 0 +0.2984464834261905 -0.9359684011346607 -0.0001635690412845059 +-0.3037709145 -0.9349108635 -1.499999999210466e-08 +-0.3037709145 0.9349108635 1.499999999210466e-08 +-0.7952825725 -0.5778068750000001 -1.499999999210466e-08 +-0.273800906277004 -0.8767913403461751 0.3346302417443243 +-0.4754992136879836 0.6456701396731745 0.5683147406859165 +0.4713001299770969 -0.6411723922906573 -0.5765449053642733 +0.7424826560371693 -0.237850575465973 0.5980659213001208 +0.00551055714916493 -0.7645400515392027 0.6175047879190813 +0.632157862 -0.5782548935 -0.482009485 +0.632157862 0.5782548935 0.482009485 +-0.632157862 -0.5782548935 -0.482009485 +-0.273800906277004 0.8767913403461751 -0.3346302417443242 +-0.6443169789210386 0.5642532597966963 0.4817704764478887 +-0.8529292054160453 0.09169119062812325 -0.478939318374926 +0.852032273325431 -0.08033786692739198 0.4834552999970668 +0.8513160945 0.09624540444999999 -0.482009426 +-0.8513160945 -0.09624540444999999 0.482009426 +-0.3515619224043152 0.7829670991881906 0.4779156773553317 +0.354605615 0.7799084185 0.4820094555 +-0.1648899015864478 -0.2546360153139223 0.9278156620360043 +0 -0.1803643105 0.9663354159999999 +-0.916837156 -0.1864274816 0.301645212 +0.916837156 0.1864274816 -0.301645212 +-0.1715366095 0.0557357145 -0.9663354159999999 +0.1715366095 -0.0557357145 0.9663354159999999 +-0.1648899015864478 0.2546360153139221 -0.9278156620360043 +0.7453005315000001 -0.4225275665 0.4820093665 +-0.7453005315000001 0.4225275665 -0.4820093665 +0.7453005315000001 0.4225275665 -0.4820093665 +-0.1060154585 -0.1459177585 -0.9663354159999999 +-0.1173073419684945 0.157376424596409 0.9630408543723834 +0.109959547888504 -0.1576493649126376 -0.9636288252903217 +0.118687913334654 0.1555536665238542 0.9628678827087409 +0.1715366395 0.839391172 -0.4820093065 +-0.1715366395 0.839391172 -0.4820093065 +-0.460621059 -0.8143548665 -0.3016452415 +0.460621059 0.8143548665 0.3016452415 +0.632157713 0.6897262335000001 0.3016452415 +-0.632157713 0.6897262335000001 0.3016452415 +-0.1060154585 -0.9295731485000001 0.301645167 +-0.1060154585 0.9295731485000001 -0.301645167 +0.8513158860000001 0.3880809545 -0.301645197 +-0.8513158860000001 -0.3880809545 0.301645197 +-0.470377170221815 0.3308692980874088 -0.5346461516515045 +-0.1378971466884762 -0.05872417041574372 0.8245819610452255 +-0.6636097440568927 -0.4820470659935153 0.1441924221159884 +-0.09924075389872836 -0.2639529564994283 0.9372760024704234 +0.3428052246626204 0.3101314782608706 -0.7114897127700051 +-0.09924075389872844 0.2639529564994281 -0.9372760024704236 +0.2497212303585584 0.4759065639172987 -0.634785469991164 +-0.5018582142373347 0.7913357212282524 -0.2936758927309688 +-0.1836056077381358 -0.6567713801098206 -0.4817652775425123 +-0.2470453184003564 0.6526313165075527 -0.5021591169140639 +0.1776571780252803 0.5609861185411928 0.3505695105209232 +-0.06475380565392276 0.6107809085531266 0.5638166510217938 +0.2735253005670124 -0.8762404997642916 0.3346302417443243 +0.2708187524123817 0.8746241813427392 -0.3400836120249706 +0.6171031044747036 0.2521419060127235 0.1499066624088571 +0.4764939378534095 0.4593821606547799 0.3433921458186807 +0.7257250063463581 -0.5604577921412572 -0.3346302417443242 +0.7257250063463581 0.560457792141257 0.3346302417443243 +0.7001310961221709 -0.6616508216673254 0.1759751935031104 +-0.4840866932637082 -0.6121700368985139 -0.1501069607555149 +0.489348674378097 -0.3619183235336728 -0.7671171736051364 +0.1440253661317507 0.3895705948950923 -0.5116461636673226 +0.4946697047593433 0.3557726340191655 0.7662271305074408 +0.7464064032657043 -0.5811252752524936 -0.2554392702846551 +0.8285092954478688 -0.4943369061879149 -0.167315120872162 +0.7464064032657043 0.5811252752524934 0.2554392702846552 +0.829411599676636 0.4943369061879145 0.1673151208721621 +-0.3526508796440742 0.6262207041656306 -0.3288568676190132 +-0.0310745620977699 0.4969617889406759 -0.1761210085106677 +0.9074384118554124 -0.2394964387055004 -0.2895170798756234 +0.9174609659449906 -5.551115123125783e-17 0.3346302417443243 +-0.9411115744202567 -0.1064871788113919 -0.2265040935376754 +0.2076585869786285 -0.6593725678856036 0.2099765396705036 +-0.9248774506368126 -0.2767315414789368 0.1481069821184871 +-0.9608377633517635 -0.1905018186427999 -5.551115123125783e-17 +-0.9598400361758898 0.1938991361849407 0.001978364046988118 +-0.9009246315621086 0.3824345339992005 0.04567887866379172 +-0.8941131900717569 -0.3991747520142159 -0.02009175298266276 +-0.8468161346461875 -0.3613128783487702 -0.3346302417443242 +-0.764674133349585 0.03626511617036607 -0.6086059259490402 +-0.7488125245903672 -0.05809673420800637 0.6252838165775659 +-0.7470301189491562 -0.533868944883471 0.3346302417443243 +-0.7470301189491562 0.533868944883471 -0.3346302417443242 +-0.8001267099090277 0.5711394866640385 -0.01333475398259278 +-0.7371909513941939 -0.5034384621332837 -0.4053005277811758 +-0.6706594551458225 -0.32955793745861 -0.6338583417611625 +-0.8309969453659541 0.3731133554126599 0.3590941679249 +-0.7404349180221135 0.5072093490563344 0.391480111932217 +-0.657984249270295 -0.7252353702830132 0.01572114045120625 +0.1716397495004564 -0.520493295642469 0.4114520704611611 +-0.5633540339641707 -0.7831576632145403 -0.156077221 +-0.657984249270295 0.7252353702830132 -0.01572114045120619 +-0.5954559207000718 0.759834284989988 0.156077221 +-0.4946697047593434 -0.6742138297313394 0.5168055006382355 +-0.639950216 0.4085518317838012 -0.6157588733492543 +-0.5998918291693639 0.6967399145036977 -0.336298137399878 +-0.5237505581750362 -0.502706610838997 -0.6564133188224507 +0.01571896257416014 -0.6311969310402367 -0.506967405792985 +-0.3668821572994054 0.5028341068058905 -0.03428236487469615 +-0.2791390631868537 0.09909319471286901 0.9308043434985912 +-0.2737977646360331 -0.1017366076864576 -0.932670832 +-5.551115123125783e-17 -0.964718938 0.156077191 +-0.1241942773737781 -0.762168056508469 -0.606583644747047 +-0.0100337821037552 0.2805783147871246 -0.785522469281193 +0.1648899015864477 -0.7264596185416647 0.6325962642028151 +0.2395466931977362 -0.3847973404532145 0.1987252323797588 +0.1527941100557161 -0.2485787627082534 0.932883326713121 +-0.5150830027579768 -0.225458908235314 -0.6414400992740774 +-0.1648899015864478 0.7264596185416647 -0.6325962642028151 +0.1648899015864477 0.7264596185416647 -0.6325962642028151 +0.1120997896845222 0.9729512646430574 0.005333115449487641 +0.2905600608752268 -0.8710022476126034 -0.3346302417443242 +0.2733518164848321 0.08333433799291456 0.9340806351506195 +-0.2186876832761552 0.1355551725632875 -0.7514080414631757 +0.5883533537861093 0.7646147491588572 0.1573500293575232 +0.657984249270295 -0.7252353702830132 0.01572114045120628 +-0.283151721891854 -0.2697271334462735 -0.7677817901486564 +0.3923587771881114 0.643044977255366 -0.2358683228539508 +-0.4406098886950756 -0.6391326817605969 0.3190304651144633 +0.639950216 0.4085518317838012 -0.6157588733492545 +0.7429325497058085 -0.5022358480759658 -0.3926503031839971 +0.8149411764884267 -0.3823966170795073 -0.3882821740004315 +0.7385844337468173 0.4959351597049497 0.414817375227283 +0.8893080805939757 -0.4106472579246842 -5.551115123125783e-17 +0.7397023528267623 -0.5327068054158335 0.3516701384263012 +0.9049514139222521 -0.3367420363845999 0.1560772031267084 +0.7453150012885376 0.5372878022233248 -0.331485378105409 +0.8468161346461875 0.3613128783487702 0.3346302417443243 +0.9574021488411723 0.2026759276143504 0.00969656983529274 +0.8941131900717569 0.3991747520142158 0.02009175298266304 +-0.957709450127873 -0.1150537272727258 -0.1655405539330506 +-0.4845984888036726 -0.5261166943379729 0.6692604834886484 +-0.3506172103503078 -0.6234596794029414 0.6692604834886484 +-0.4753746993073021 0.7937918318749986 0.3346302417443243 +-0.4840505109308432 -0.7014906573711918 0.1445905231917857 +0.2707633919962071 -0.7081297721928731 -0.6163457072825573 +0.2720567874572617 -0.1070947872842641 -0.932670832 +0.4606355048509909 -0.8086249801719713 -0.3147570083320652 +0.3506172103503078 -0.6234596794029414 0.6692604834886484 +0.4096770803439219 -0.761789534681282 -0.4708113795533366 +-0.5608864967343244 -0.5002524898810411 0.2796298810577725 +0.6115251132961432 0.5648777306174195 0.1603831698017203 +0.3112910443022733 0.005653668058812759 0.7497519303946486 +-0.326223368851062 -0.090716640529712 0.6409736602035725 +0.5603757281700371 -0.5518103791561476 -0.2623215125048247 +0.110531317716949 -0.06212769157402307 -0.7090846736271308 +0.7066528525432456 0.3857452961775781 0.06466039034313326 +-0.2870284024040223 0.3993456525073666 -0.3603438608047557 +0.4073544778967688 -0.316613713703684 0.004045726126147522 +-0.7885700713375572 -0.2499228280367138 -0.07471496532949348 +0.4402160867874776 -0.1218990893552541 -0.6831289812200559 +0.6646971797773117 0.2583486777982067 0.4739581945577929 +0.2738513407524434 0.3723478719915778 -0.1410164250591326 +-0.6097271098386507 0.05789107466758828 0.07196260058945804 +0.6233549523511848 0.4703431892808756 0.5916864408666598 +-0.2252612501639656 -0.6585131146906121 0.3735728487626422 +-0.1952039515635032 -0.4206871829507813 -0.675228105140974 +0.1112955484387936 0.5127300343494182 0.6032043578325359 +0.4251068484948444 -0.2312900141676994 -0.8520679447903731 +0.4535650605864477 0.2229142033935338 0.8414200303719319 +0.4482113831635415 -0.5098491617575793 0.7088642783123628 +0.06209713868688906 -0.6846150787542344 -0.7006190068735234 +0.0375335915419611 0.2478879406402632 0.7891168376389351 +0.9674071119541455 0.03415884376465241 0.161696170936081 +-0.6465554288694874 -0.2733596096316241 -0.3223698881350392 +-0.6342918131897257 -0.5058841359687427 -0.2738551387910891 +-0.346614458255896 0.6520192716236507 0.3646333695986975 +0.04578829671120705 -0.1403897385186038 -0.2562642746637507 +0.2476581831353243 -0.3872670587268629 -0.2083650025354314 +-0.3003935458321194 -0.1749983686001565 -0.3188893171939637 +-0.727709338623766 0.1540042504308398 0.2424727027908384 +0.1159640558706719 -0.07081091511933212 -0.4108053950654383 +0.5452822968143677 0.2416746102773027 -0.1075963602108601 +0.003220736745420392 -0.2941661607341402 -0.6318213160745906 +0.02250441915388015 0.1375631176366774 -0.5374998591515358 +-0.6090663507680694 0.3444698098995285 -0.1186274894911475 +0.2198027106802337 -0.3850323513976263 -0.003955119313183036 +-0.2539815602932239 -0.1830537221569612 0.9302432470180022 +-0.2539815602932239 0.1830537221569611 -0.9302432470180022 + +CELLS 2536 12680 +4 386 189 123 142 +4 231 167 297 194 +4 221 114 215 255 +4 232 397 194 471 +4 371 315 377 89 +4 233 380 255 95 +4 297 124 252 194 +4 179 136 137 207 +4 202 391 240 222 +4 0 494 495 115 +4 176 223 233 190 +4 0 115 495 403 +4 212 192 595 482 +4 0 415 403 495 +4 367 440 370 368 +4 106 279 348 369 +4 90 377 299 88 +4 489 297 573 252 +4 125 281 191 324 +4 112 131 585 117 +4 268 585 10 506 +4 251 285 563 92 +4 87 491 432 371 +4 216 192 235 231 +4 373 494 115 570 +4 371 369 378 377 +4 139 49 530 101 +4 576 539 197 326 +4 472 39 232 93 +4 22 383 453 163 +4 9 156 119 7 +4 337 249 361 569 +4 186 276 263 243 +4 532 332 237 236 +4 525 60 41 169 +4 69 67 218 427 +4 265 595 534 203 +4 269 381 104 108 +4 3 498 387 570 +4 3 570 499 168 +4 581 344 559 263 +4 168 499 585 570 +4 337 249 526 261 +4 578 218 100 375 +4 402 240 244 106 +4 211 228 229 97 +4 415 208 120 591 +4 218 427 575 476 +4 129 323 172 553 +4 569 526 348 242 +4 50 235 192 252 +4 505 10 585 428 +4 469 518 332 38 +4 436 162 145 53 +4 484 542 541 362 +4 368 440 378 91 +4 309 295 472 48 +4 570 387 499 364 +4 206 239 240 391 +4 267 271 251 73 +4 89 567 475 548 +4 5 166 314 104 +4 5 104 434 166 +4 201 200 238 388 +4 329 124 96 252 +4 205 226 592 238 +4 10 126 383 517 +4 17 414 191 274 +4 75 150 366 92 +4 328 70 64 389 +4 197 539 144 555 +4 111 121 390 188 +4 9 1 168 119 +4 532 236 237 259 +4 504 497 122 384 +4 9 168 1 165 +4 11 108 123 147 +4 151 86 401 266 +4 220 262 388 306 +4 85 334 562 79 +4 437 225 190 598 +4 36 282 215 19 +4 22 24 428 383 +4 23 587 422 182 +4 208 115 570 117 +4 242 597 106 569 +4 27 217 374 345 +4 27 374 320 164 +4 315 584 377 89 +4 377 584 378 89 +4 520 215 98 462 +4 32 46 462 520 +4 564 121 255 233 +4 33 134 177 534 +4 34 196 197 522 +4 34 457 522 197 +4 270 266 264 367 +4 537 204 577 203 +4 153 472 221 93 +4 36 520 215 583 +4 36 295 583 215 +4 86 367 401 266 +4 86 367 433 401 +4 98 379 225 462 +4 360 76 284 410 +4 360 410 284 305 +4 162 65 96 318 +4 194 162 96 318 +4 234 270 72 571 +4 234 270 571 264 +4 111 193 587 221 +4 201 174 175 590 +4 86 367 266 406 +4 333 194 51 318 +4 437 225 302 190 +4 437 225 44 302 +4 56 412 580 583 +4 57 231 252 253 +4 57 329 253 252 +4 58 563 409 243 +4 97 230 382 244 +4 234 579 571 72 +4 401 571 305 284 +4 56 580 533 583 +4 68 560 565 423 +4 68 426 423 565 +4 67 427 575 218 +4 51 93 320 217 +4 196 319 418 26 +4 454 110 562 124 +4 454 455 562 535 +4 454 455 476 562 +4 125 461 212 191 +4 324 125 212 191 +4 57 50 451 252 +4 252 474 451 57 +4 422 182 587 221 +4 80 148 362 270 +4 571 284 72 305 +4 401 266 571 284 +4 57 235 50 252 +4 88 362 485 365 +4 65 96 253 329 +4 377 88 546 365 +4 90 88 546 377 +4 280 371 476 105 +4 401 433 353 367 +4 321 223 44 300 +4 300 359 321 223 +4 429 470 488 31 +4 452 31 470 429 +4 429 216 488 470 +4 452 470 216 429 +4 270 264 266 571 +4 479 249 256 335 +4 250 476 297 124 +4 250 476 124 471 +4 215 114 379 95 +4 496 497 120 156 +4 496 156 208 1 +4 192 398 107 252 +4 25 282 188 215 +4 366 186 424 75 +4 67 145 218 154 +4 120 142 141 384 +4 162 145 471 124 +4 368 299 490 91 +4 367 91 86 440 +4 398 102 356 538 +4 241 264 234 566 +4 575 476 81 572 +4 427 81 575 476 +4 467 107 277 530 +4 404 480 453 196 +4 151 284 401 360 +4 151 401 353 360 +4 23 430 182 422 +4 450 533 583 56 +4 98 533 583 450 +4 169 391 170 222 +4 62 289 359 300 +4 141 118 136 574 +4 25 309 215 153 +4 153 188 215 25 +4 23 456 182 430 +4 200 205 209 180 +4 360 410 109 312 +4 360 410 305 109 +4 76 360 312 410 +4 313 125 461 534 +4 53 145 471 162 +4 16 313 461 534 +4 16 534 461 134 +4 349 347 367 368 +4 347 365 367 368 +4 140 187 568 143 +4 143 187 568 385 +4 129 510 222 223 +4 156 7 497 122 +4 367 490 86 91 +4 101 530 467 322 +4 49 322 530 101 +4 489 231 252 192 +4 231 235 252 192 +4 118 120 156 208 +4 204 173 577 200 +4 204 594 200 577 +4 251 572 371 355 +4 572 407 548 81 +4 496 120 208 156 +4 0 166 115 403 +4 166 115 439 0 +4 176 552 172 28 +4 16 534 134 33 +4 12 420 509 480 +4 420 127 112 463 +4 385 21 122 512 +4 147 282 188 25 +4 432 82 424 366 +4 495 3 168 570 +4 498 112 420 364 +4 353 76 83 433 +4 324 49 101 303 +4 523 38 469 152 +4 243 276 379 563 +4 449 566 45 447 +4 443 524 125 534 +4 443 125 524 303 +4 295 298 578 48 +4 30 539 576 326 +4 57 231 531 160 +4 116 16 445 461 +4 497 384 120 596 +4 497 120 384 386 +4 161 290 358 59 +4 236 388 589 254 +4 164 39 93 331 +4 4 165 168 116 +4 165 316 4 168 +4 283 314 120 2 +4 28 223 190 302 +4 145 476 454 69 +4 186 359 263 581 +4 311 359 186 581 +4 194 318 253 531 +4 72 270 266 571 +4 179 202 178 207 +4 270 266 367 406 +4 389 565 254 259 +4 300 527 243 44 +4 44 527 243 225 +4 168 208 570 117 +4 256 337 249 361 +4 461 183 568 184 +4 413 53 232 333 +4 98 243 379 563 +4 98 563 379 100 +4 161 524 45 358 +4 420 463 373 6 +4 420 6 325 463 +4 420 480 364 127 +4 6 463 460 502 +4 6 502 325 463 +4 325 20 555 539 +4 347 365 361 362 +4 336 361 362 347 +4 347 367 365 362 +4 528 116 126 134 +4 190 223 224 243 +4 207 178 402 202 +4 65 110 124 346 +4 346 535 65 110 +4 116 117 585 130 +4 570 585 112 364 +4 570 117 112 585 +4 112 127 364 131 +4 230 192 489 248 +4 117 136 116 118 +4 115 137 132 574 +4 115 137 133 132 +4 531 194 231 253 +4 194 318 531 51 +4 499 585 316 168 +4 119 122 461 503 +4 120 142 384 386 +4 503 122 461 143 +4 122 384 596 385 +4 229 592 595 278 +4 595 248 214 482 +4 212 482 101 192 +4 132 179 137 233 +4 132 179 136 137 +4 223 263 510 94 +4 103 217 193 167 +4 116 119 140 461 +4 116 140 184 461 +4 591 574 403 208 +4 314 283 120 591 +4 166 314 591 283 +4 403 166 591 283 +4 522 260 54 342 +4 422 221 587 153 +4 587 153 221 93 +4 93 587 153 435 +4 348 365 249 569 +4 232 578 471 53 +4 368 369 378 475 +4 242 348 246 99 +4 26 196 343 418 +4 177 204 203 209 +4 199 568 489 213 +4 382 230 573 248 +4 230 248 489 573 +4 144 171 128 561 +4 144 127 128 170 +4 317 332 40 237 +4 117 136 131 130 +4 126 200 177 134 +4 127 364 131 175 +4 127 202 175 131 +4 127 144 175 202 +4 130 134 135 590 +4 131 179 136 132 +4 131 178 202 175 +4 131 175 130 178 +4 270 340 362 264 +4 270 367 264 362 +4 347 362 264 367 +4 136 135 118 185 +4 136 130 135 181 +4 120 123 142 386 +4 137 108 142 591 +4 137 233 380 121 +4 189 384 374 142 +4 137 233 133 132 +4 134 183 200 177 +4 135 185 140 118 +4 118 140 596 187 +4 118 136 185 141 +4 140 187 143 596 +4 140 568 461 143 +4 482 398 214 107 +4 143 568 191 488 +4 141 385 384 519 +4 170 245 202 391 +4 222 240 242 391 +4 167 232 221 397 +4 232 221 397 114 +4 504 512 384 122 +4 302 225 243 190 +4 598 462 564 32 +4 232 53 162 333 +4 242 224 94 99 +4 144 175 202 404 +4 172 223 171 176 +4 181 228 227 229 +4 233 121 255 380 +4 173 177 200 204 +4 225 98 243 379 +4 175 178 590 130 +4 202 222 207 179 +4 202 222 179 170 +4 142 111 121 211 +4 130 135 181 590 +4 128 233 133 176 +4 177 209 183 200 +4 136 178 181 402 +4 136 207 402 380 +4 489 248 192 398 +4 183 534 209 177 +4 183 209 534 210 +4 185 402 211 136 +4 297 110 124 357 +4 512 345 103 385 +4 187 111 185 199 +4 187 185 184 199 +4 111 199 211 185 +4 233 564 190 224 +4 233 190 223 224 +4 222 242 233 223 +4 568 187 184 199 +4 187 199 519 111 +4 585 174 364 383 +4 586 364 383 585 +4 263 186 344 366 +4 153 39 472 93 +4 232 472 413 39 +4 114 232 472 578 +4 48 472 153 39 +4 188 153 215 221 +4 188 255 390 221 +4 221 153 215 114 +4 188 215 255 221 +4 175 201 590 178 +4 178 201 590 206 +4 401 571 109 305 +4 297 252 538 573 +4 141 185 187 111 +4 141 111 187 519 +4 576 170 171 222 +4 576 169 41 457 +4 198 388 594 200 +4 198 201 245 388 +4 201 245 206 202 +4 201 245 588 206 +4 501 15 113 381 +4 204 594 203 566 +4 205 227 180 206 +4 205 227 209 180 +4 206 180 181 227 +4 207 242 402 380 +4 203 566 209 204 +4 209 534 210 595 +4 180 227 229 181 +4 180 227 209 229 +4 327 21 468 385 +4 516 400 503 122 +4 564 462 379 215 +4 222 526 391 242 +4 242 99 246 396 +4 401 360 305 109 +4 185 213 230 229 +4 185 211 402 228 +4 211 402 97 396 +4 369 368 365 106 +4 106 348 279 246 +4 564 215 95 255 +4 233 95 564 224 +4 3 387 499 570 +4 364 174 480 383 +4 495 403 115 208 +4 495 208 115 570 +4 208 117 574 115 +4 403 208 574 115 +4 380 255 396 390 +4 133 381 104 113 +4 381 104 108 137 +4 133 137 104 381 +4 197 169 196 170 +4 542 541 362 80 +4 200 590 201 205 +4 174 201 200 590 +4 193 587 221 93 +4 295 472 578 114 +4 139 467 482 101 +4 482 107 214 467 +4 404 174 175 201 +4 229 592 278 244 +4 409 186 92 75 +4 163 196 404 453 +4 163 196 453 26 +4 246 280 348 352 +4 219 391 40 237 +4 12 586 480 22 +4 169 522 391 493 +4 251 280 105 371 +4 422 188 153 25 +4 280 357 475 352 +4 594 234 262 220 +4 594 262 388 220 +4 201 238 588 245 +4 245 391 238 239 +4 170 202 222 391 +4 245 391 206 202 +4 527 438 98 225 +4 462 98 438 225 +4 402 244 228 97 +4 142 211 121 136 +4 137 121 136 142 +4 218 145 578 154 +4 154 307 578 218 +4 307 412 100 218 +4 227 592 595 229 +4 228 229 97 244 +4 402 106 244 97 +4 402 228 240 206 +4 595 524 212 247 +4 229 244 248 230 +4 47 524 49 303 +4 247 595 214 482 +4 212 482 247 101 +4 351 475 368 593 +4 212 595 247 482 +4 230 382 244 248 +4 146 255 564 121 +4 474 538 451 61 +4 198 388 518 220 +4 43 198 518 220 +4 469 43 198 518 +4 397 396 376 250 +4 566 265 595 524 +4 595 265 534 524 +4 47 466 45 524 +4 561 176 171 128 +4 192 451 139 50 +4 267 150 92 87 +4 267 92 572 87 +4 232 471 114 397 +4 18 268 528 134 +4 287 18 134 268 +4 408 273 108 11 +4 271 81 407 572 +4 269 19 146 273 +4 274 281 461 29 +4 540 275 107 77 +4 556 258 388 236 +4 63 275 277 467 +4 306 556 258 388 +4 529 31 281 470 +4 474 538 252 451 +4 36 25 215 282 +4 218 145 375 578 +4 578 307 100 218 +4 237 219 391 259 +4 237 389 417 64 +4 120 2 496 283 +4 151 76 284 360 +4 285 75 92 150 +4 302 323 28 223 +4 19 32 286 146 +4 286 146 269 19 +4 169 257 493 510 +4 289 62 359 311 +4 312 290 465 63 +4 388 594 238 262 +4 198 388 200 201 +4 238 262 241 592 +4 239 106 588 240 +4 391 526 597 242 +4 391 260 597 526 +4 526 510 94 223 +4 291 598 564 32 +4 92 186 366 75 +4 432 424 150 366 +4 75 149 186 424 +4 310 32 564 15 +4 435 23 587 422 +4 435 422 587 153 +4 592 262 241 264 +4 43 294 220 296 +4 588 264 244 106 +4 295 48 578 472 +4 296 158 234 55 +4 296 55 234 66 +4 56 583 298 412 +4 159 56 583 298 +4 236 388 254 258 +4 110 562 124 357 +4 102 110 357 562 +4 321 223 42 44 +4 202 402 207 222 +4 202 206 402 240 +4 73 285 304 251 +4 304 73 251 580 +4 154 307 218 67 +4 246 348 279 352 +4 114 472 153 309 +4 99 100 105 375 +4 75 311 186 149 +4 248 278 214 288 +4 29 125 461 313 +4 461 274 29 313 +4 29 292 125 313 +4 246 382 352 279 +4 250 167 194 297 +4 13 512 384 504 +4 62 359 321 300 +4 559 359 321 62 +4 107 61 77 277 +4 107 77 61 538 +4 325 509 555 20 +4 326 197 421 34 +4 217 37 327 419 +4 539 14 339 514 +4 328 256 389 417 +4 51 93 331 320 +4 331 194 93 51 +4 331 333 194 51 +4 232 53 471 162 +4 334 79 535 562 +4 339 539 30 20 +4 539 339 325 20 +4 376 199 489 230 +4 376 199 167 489 +4 65 318 253 96 +4 172 28 553 323 +4 576 223 172 129 +4 217 341 320 51 +4 217 51 531 341 +4 467 107 530 139 +4 27 374 513 345 +4 179 222 207 233 +4 179 222 233 128 +4 170 222 179 128 +4 254 565 423 362 +4 259 336 254 589 +4 259 565 254 336 +4 260 337 259 597 +4 260 389 259 337 +4 260 597 526 337 +4 260 337 256 389 +4 337 597 526 569 +4 329 538 71 346 +4 262 347 264 589 +4 262 589 254 347 +4 262 362 264 347 +4 589 347 336 254 +4 514 576 30 539 +4 183 180 209 210 +4 183 184 180 210 +4 426 80 148 362 +4 589 264 106 347 +4 589 336 347 569 +4 597 569 337 259 +4 360 353 312 109 +4 43 306 220 518 +4 441 534 203 265 +4 348 369 365 106 +4 279 351 297 352 +4 279 352 369 351 +4 352 297 280 357 +4 296 234 220 306 +4 294 577 220 594 +4 158 594 220 234 +4 297 351 279 593 +4 280 371 348 352 +4 119 140 461 122 +4 122 140 461 143 +4 201 205 206 588 +4 590 205 206 201 +4 55 579 234 66 +4 288 354 398 573 +4 288 107 356 353 +4 16 134 461 116 +4 375 218 105 145 +4 239 589 106 240 +4 214 312 353 109 +4 63 247 467 301 +4 247 101 467 301 +4 482 467 247 101 +4 401 360 284 305 +4 571 72 284 266 +4 359 263 510 223 +4 594 241 262 234 +4 594 566 241 234 +4 88 490 365 299 +4 310 552 176 28 +4 561 14 502 339 +4 472 48 53 413 +4 590 206 180 181 +4 590 178 206 181 +4 389 256 361 337 +4 259 532 236 254 +4 413 472 232 53 +4 496 208 415 1 +4 336 361 569 337 +4 186 92 276 409 +4 347 264 349 367 +4 328 256 417 54 +4 42 155 323 129 +4 44 42 323 223 +4 264 367 350 349 +4 129 223 323 42 +4 279 369 368 351 +4 348 369 279 352 +4 92 87 371 572 +4 351 593 368 279 +4 350 370 353 356 +4 350 367 353 370 +4 351 352 369 475 +4 348 344 363 366 +4 352 371 369 475 +4 366 344 363 424 +4 351 475 369 368 +4 348 352 371 369 +4 572 315 87 371 +4 593 567 102 357 +4 476 372 81 572 +4 103 111 167 193 +4 374 554 182 587 +4 225 243 98 527 +4 119 118 140 596 +4 144 245 404 202 +4 169 473 257 60 +4 375 471 250 397 +4 41 169 54 522 +4 251 92 348 371 +4 111 211 199 376 +4 371 491 377 315 +4 593 370 405 378 +4 368 490 367 91 +4 368 369 377 378 +4 74 559 261 257 +4 116 16 134 287 +4 500 16 116 287 +4 371 372 548 475 +4 567 102 85 405 +4 136 380 402 211 +4 402 396 211 380 +4 217 167 231 194 +4 124 476 454 145 +4 436 162 454 145 +4 385 327 103 195 +4 454 562 476 124 +4 476 562 357 124 +4 137 380 136 121 +4 558 532 389 254 +4 64 532 389 558 +4 123 142 188 108 +4 132 233 128 179 +4 173 177 204 537 +4 594 238 262 241 +4 114 375 471 578 +4 114 100 375 578 +4 389 532 237 259 +4 83 433 370 353 +4 367 353 370 433 +4 251 105 218 355 +4 83 440 370 433 +4 370 440 367 433 +4 100 105 218 251 +4 112 131 117 132 +4 592 241 566 264 +4 573 382 376 230 +4 489 252 231 297 +4 46 98 438 462 +4 46 438 464 462 +4 402 106 97 242 +4 536 361 479 84 +4 536 479 361 256 +4 215 98 462 379 +4 278 350 214 288 +4 288 350 353 356 +4 288 353 350 214 +4 288 354 350 356 +4 278 350 288 354 +4 233 380 95 224 +4 560 258 254 423 +4 560 254 565 423 +4 116 16 9 445 +4 16 431 116 9 +4 445 9 116 119 +4 134 528 177 126 +4 116 130 135 136 +4 309 472 153 48 +4 172 223 176 28 +4 342 417 237 260 +4 260 389 417 237 +4 396 97 382 246 +4 218 476 145 69 +4 408 314 507 591 +4 179 136 207 178 +4 95 396 375 99 +4 396 250 397 375 +4 211 97 402 228 +4 230 211 97 376 +4 98 442 243 563 +4 98 442 563 533 +4 344 74 261 363 +4 74 261 363 545 +4 335 545 261 74 +4 115 137 104 133 +4 348 366 363 377 +4 32 520 146 19 +4 391 260 259 597 +4 288 356 107 398 +4 422 147 182 188 +4 430 147 182 422 +4 430 123 182 147 +4 515 461 274 17 +4 17 191 143 461 +4 298 578 307 100 +4 242 569 106 348 +4 263 92 276 186 +4 289 359 243 186 +4 106 368 365 347 +4 4 116 500 431 +4 504 7 122 497 +4 176 233 133 564 +4 199 167 489 195 +4 13 189 456 395 +4 400 512 504 122 +4 400 7 122 504 +4 20 539 30 326 +4 89 475 378 371 +4 430 11 123 147 +4 564 233 255 95 +4 566 264 214 592 +4 214 264 278 592 +4 566 109 214 264 +4 222 402 242 240 +4 240 106 597 589 +4 97 106 382 246 +4 480 404 174 175 +4 480 174 404 383 +4 480 144 404 175 +4 354 593 350 405 +4 350 593 370 405 +4 367 593 350 349 +4 350 370 593 367 +4 278 349 350 593 +4 308 577 411 24 +4 173 411 577 24 +4 304 409 58 563 +4 126 134 130 590 +4 585 126 174 383 +4 90 584 416 377 +4 559 257 510 261 +4 44 464 438 225 +4 109 410 305 358 +4 388 201 245 238 +4 104 591 108 137 +4 202 240 402 222 +4 258 254 340 262 +4 254 340 262 362 +4 136 121 380 211 +4 390 221 396 211 +4 158 203 447 35 +4 524 247 566 358 +4 358 109 247 566 +4 592 264 278 244 +4 376 297 382 573 +4 160 217 341 37 +4 375 471 145 105 +4 301 524 49 47 +4 498 570 112 364 +4 337 526 249 569 +4 597 106 569 589 +4 66 148 258 423 +4 154 436 145 53 +4 377 348 92 371 +4 480 127 144 175 +4 364 480 174 175 +4 364 175 127 480 +4 70 257 328 60 +4 391 259 589 597 +4 245 388 391 219 +4 205 588 227 206 +4 85 102 71 547 +4 255 95 396 114 +4 89 378 549 584 +4 116 184 134 461 +4 461 183 184 134 +4 450 583 159 56 +4 448 583 36 159 +4 520 448 583 36 +4 174 590 130 175 +4 93 435 39 164 +4 254 558 532 560 +4 251 100 276 563 +4 200 383 201 174 +4 195 327 103 217 +4 217 419 327 345 +4 252 398 573 489 +4 250 194 471 124 +4 124 297 252 538 +4 411 173 399 24 +4 596 187 143 385 +4 385 488 568 143 +4 385 187 568 199 +4 385 519 187 199 +4 28 190 176 291 +4 94 348 261 526 +4 94 348 526 242 +4 371 548 89 475 +4 526 249 348 261 +4 142 136 141 185 +4 520 564 146 215 +4 116 184 135 134 +4 132 131 179 127 +4 106 368 272 279 +4 382 106 244 279 +4 106 244 279 272 +4 94 263 348 276 +4 403 115 574 137 +4 571 305 557 109 +4 566 557 109 571 +4 245 388 219 518 +4 479 249 361 256 +4 479 84 361 249 +4 196 245 170 391 +4 404 198 201 245 +4 211 221 396 376 +4 564 215 255 146 +4 566 571 264 234 +4 566 264 571 109 +4 396 246 382 250 +4 566 557 571 234 +4 85 405 157 550 +4 405 567 378 550 +4 85 157 405 459 +4 560 556 236 258 +4 461 212 534 125 +4 142 211 136 185 +4 267 407 87 572 +4 572 371 548 315 +4 409 311 186 75 +4 285 75 409 92 +4 16 292 534 33 +4 411 293 537 35 +4 294 203 35 577 +4 307 412 218 67 +4 257 335 261 74 +4 551 415 168 1 +4 256 335 261 257 +4 237 317 64 417 +4 34 196 40 418 +4 422 147 188 25 +4 76 353 83 446 +4 541 426 362 80 +4 427 81 476 372 +4 543 427 372 81 +4 229 192 248 595 +4 388 258 306 262 +4 388 258 262 254 +4 87 432 150 92 +4 87 491 371 315 +4 410 290 465 312 +4 434 15 8 113 +4 38 22 469 152 +4 38 469 22 163 +4 436 145 454 69 +4 69 145 67 436 +4 527 438 46 98 +4 524 47 161 45 +4 434 113 8 439 +4 45 441 447 265 +4 442 58 527 243 +4 82 444 424 363 +4 445 503 461 17 +4 515 461 17 445 +4 446 356 353 83 +4 46 98 448 450 +4 557 566 449 55 +4 41 473 169 60 +4 107 451 61 530 +4 50 452 138 235 +4 50 452 235 458 +4 78 565 477 68 +4 79 478 455 562 +4 455 79 562 535 +4 458 235 50 57 +4 545 84 363 82 +4 387 586 505 499 +4 585 499 586 364 +4 548 372 487 567 +4 129 525 169 510 +4 525 169 510 257 +4 583 114 578 100 +4 412 583 298 100 +4 357 476 372 562 +4 583 578 298 100 +4 160 217 531 341 +4 85 334 102 562 +4 272 347 264 349 +4 106 264 272 347 +4 92 251 267 572 +4 275 540 214 312 +4 540 214 353 107 +4 119 1 118 156 +4 275 107 214 540 +4 1 118 156 208 +4 1 208 168 118 +4 9 1 119 156 +4 408 123 11 108 +4 507 408 591 123 +4 583 379 100 98 +4 583 114 379 215 +4 520 98 215 583 +4 429 195 458 217 +4 129 223 172 323 +4 172 223 28 323 +4 219 237 332 236 +4 250 194 124 297 +4 231 194 252 253 +4 598 225 190 462 +4 462 225 464 598 +4 507 314 120 591 +4 460 128 113 561 +4 463 561 509 144 +4 287 134 116 268 +4 456 554 182 374 +4 93 232 193 194 +4 469 577 198 43 +4 202 402 206 178 +4 506 126 116 585 +4 109 465 358 247 +4 333 162 194 318 +4 525 510 223 359 +4 247 482 214 467 +4 49 324 192 138 +4 49 529 324 138 +4 167 193 221 232 +4 472 221 232 114 +4 263 366 344 348 +4 263 366 348 92 +4 587 554 435 164 +4 467 139 530 101 +4 116 130 134 135 +4 500 287 116 268 +4 5 104 269 501 +4 286 146 501 269 +4 334 535 346 110 +4 345 513 512 103 +4 461 515 274 313 +4 356 338 538 102 +4 559 525 359 510 +4 561 339 502 325 +4 547 71 338 102 +4 267 285 92 150 +4 282 273 108 146 +4 296 158 220 234 +4 163 219 196 330 +4 164 331 93 320 +4 495 168 208 570 +4 415 208 495 168 +4 415 208 403 495 +4 120 574 591 208 +4 496 415 208 120 +4 291 190 176 564 +4 291 564 176 310 +4 524 125 534 212 +4 270 340 234 481 +4 270 148 340 481 +4 313 125 534 292 +4 148 258 340 481 +4 234 481 340 258 +4 470 216 488 191 +4 138 470 192 216 +4 203 204 577 594 +4 467 322 277 63 +4 470 191 324 192 +4 324 470 192 138 +4 482 139 192 107 +4 49 139 192 101 +4 167 232 397 194 +4 129 525 510 223 +4 188 111 182 221 +4 519 103 111 167 +4 454 535 562 110 +4 142 188 121 111 +4 439 373 115 113 +4 498 373 112 570 +4 373 494 439 115 +4 270 264 234 340 +4 285 73 267 251 +4 100 251 218 483 +4 580 251 483 73 +4 296 66 234 306 +4 298 412 100 307 +4 383 200 173 126 +4 126 177 200 173 +4 302 223 243 44 +4 258 148 340 423 +4 190 223 243 302 +4 186 263 344 581 +4 559 263 510 359 +4 522 169 54 493 +4 387 498 364 570 +4 362 485 361 565 +4 548 567 487 89 +4 382 297 352 279 +4 234 579 557 571 +4 119 596 140 122 +4 136 207 380 137 +4 26 453 480 196 +4 6 373 460 463 +4 213 229 192 230 +4 229 192 230 248 +4 206 391 240 202 +4 74 344 559 581 +4 115 104 113 133 +4 534 177 183 134 +4 534 183 461 134 +4 42 129 223 525 +4 42 425 155 129 +4 42 425 129 525 +4 522 196 391 40 +4 391 260 522 342 +4 522 342 40 391 +4 391 237 342 40 +4 391 342 237 260 +4 328 256 54 473 +4 126 590 200 134 +4 343 144 509 555 +4 293 528 399 177 +4 579 481 234 66 +4 100 483 218 412 +4 458 195 235 231 +4 195 235 429 458 +4 57 231 235 252 +4 197 457 169 576 +4 302 190 28 291 +4 294 594 158 203 +4 296 294 220 158 +4 189 374 456 182 +4 199 185 213 230 +4 476 280 297 357 +4 485 362 361 365 +4 116 118 135 140 +4 116 140 119 118 +4 383 198 577 200 +4 13 456 189 513 +4 199 488 195 489 +4 385 199 488 195 +4 385 519 199 195 +4 13 189 384 103 +4 13 103 384 512 +4 103 512 385 384 +4 242 348 106 246 +4 195 216 231 489 +4 65 124 96 329 +4 573 398 538 102 +4 398 252 573 538 +4 384 385 103 519 +4 233 380 242 207 +4 16 313 515 461 +4 16 445 461 515 +4 279 382 297 573 +4 336 361 347 569 +4 29 461 125 281 +4 577 220 43 294 +4 294 43 577 308 +4 177 534 209 203 +4 209 203 595 566 +4 15 146 564 381 +4 15 564 146 32 +4 396 242 97 246 +4 107 356 538 398 +4 261 344 363 348 +4 5 104 408 269 +4 348 377 369 371 +4 89 371 378 377 +4 585 130 174 126 +4 585 175 174 130 +4 368 416 91 378 +4 309 295 114 472 +4 170 245 144 202 +4 388 391 238 245 +4 34 418 197 196 +4 34 418 326 197 +4 197 418 343 196 +4 197 418 326 343 +4 222 510 391 526 +4 174 383 201 404 +4 108 215 146 255 +4 255 95 114 215 +4 230 229 211 185 +4 97 229 230 244 +4 116 135 118 136 +4 168 119 118 116 +4 593 378 567 475 +4 116 135 184 140 +4 137 121 142 108 +4 108 121 142 188 +4 269 273 108 408 +4 271 407 267 572 +4 294 577 411 308 +4 223 243 44 300 +4 322 101 49 301 +4 44 323 302 223 +4 65 124 329 346 +4 40 196 319 418 +4 217 419 320 341 +4 576 539 144 197 +4 496 283 415 120 +4 551 495 3 168 +4 495 415 168 551 +4 194 252 253 96 +4 513 456 374 554 +4 15 552 176 310 +4 506 528 399 18 +4 506 528 126 517 +4 52 38 332 518 +4 85 71 102 334 +4 15 310 176 564 +4 15 564 176 113 +4 16 134 287 33 +4 275 107 467 214 +4 149 186 344 581 +4 344 263 261 559 +4 546 365 88 544 +4 570 373 112 115 +4 378 157 550 549 +4 195 235 231 216 +4 383 480 453 404 +4 22 480 453 383 +4 558 254 389 565 +4 559 261 344 74 +4 17 414 143 191 +4 414 143 191 488 +4 35 293 537 521 +4 232 472 578 53 +4 518 582 38 523 +4 302 437 190 291 +4 316 3 168 492 +4 491 584 377 315 +4 432 150 92 366 +4 434 104 113 115 +4 434 113 104 501 +4 151 433 353 401 +4 151 86 433 401 +4 450 583 448 159 +4 520 98 583 448 +4 518 219 332 236 +4 427 372 478 543 +4 428 393 586 505 +4 426 565 477 541 +4 430 395 123 508 +4 156 122 596 119 +4 9 119 168 116 +4 503 7 119 122 +4 459 370 405 356 +4 373 460 128 113 +4 463 127 509 420 +4 420 509 480 127 +4 548 567 475 372 +4 212 101 524 125 +4 212 324 101 125 +4 303 101 324 125 +4 301 247 101 524 +4 524 301 247 358 +4 561 509 144 555 +4 328 389 64 417 +4 329 124 538 346 +4 346 110 124 538 +4 537 399 173 177 +4 399 528 173 177 +4 411 399 537 293 +4 580 100 483 251 +4 73 271 251 483 +4 167 193 111 221 +4 121 255 390 188 +4 115 403 104 137 +4 374 587 93 164 +4 374 587 193 93 +4 374 193 587 111 +4 587 374 554 164 +4 389 532 259 254 +4 289 359 186 311 +4 581 344 149 74 +4 167 232 194 193 +4 193 221 232 93 +4 211 396 97 376 +4 230 573 489 376 +4 489 376 297 167 +4 114 471 232 578 +4 223 94 224 243 +4 297 194 252 231 +4 376 167 397 250 +4 489 231 167 297 +4 106 365 348 569 +4 198 245 518 388 +4 472 153 221 114 +4 162 65 454 124 +4 138 216 192 235 +4 138 192 139 50 +4 570 117 585 168 +4 131 175 364 585 +4 374 103 513 345 +4 343 480 144 196 +4 480 509 511 343 +4 423 560 258 556 +4 45 466 265 524 +4 9 431 116 165 +4 9 168 165 116 +4 327 385 468 195 +4 103 327 385 345 +4 103 217 327 345 +4 330 40 196 319 +4 163 330 196 319 +4 469 219 330 332 +4 315 548 572 407 +4 283 403 415 591 +4 129 41 169 525 +4 250 105 280 476 +4 99 250 105 280 +4 463 502 325 561 +4 409 92 276 563 +4 563 92 276 251 +4 18 506 528 268 +4 528 506 116 268 +4 528 268 116 134 +4 269 146 108 273 +4 165 492 316 168 +4 186 149 344 424 +4 186 344 366 424 +4 15 564 113 381 +4 440 86 367 433 +4 342 417 260 54 +4 54 256 417 260 +4 238 589 239 391 +4 367 91 440 368 +4 378 370 157 440 +4 118 156 596 119 +4 503 9 119 7 +4 434 501 15 113 +4 16 500 116 431 +4 533 98 100 563 +4 583 98 100 533 +4 271 251 355 572 +4 483 251 355 271 +4 445 503 119 461 +4 563 304 409 285 +4 498 112 373 420 +4 420 463 112 373 +4 373 112 128 463 +4 471 145 105 476 +4 529 281 324 470 +4 596 141 384 120 +4 384 385 141 596 +4 496 2 120 497 +4 255 221 396 390 +4 406 367 490 86 +4 406 362 490 367 +4 297 593 102 357 +4 297 593 573 102 +4 447 521 203 441 +4 450 533 442 98 +4 456 23 182 554 +4 23 182 554 587 +4 50 529 138 452 +4 525 425 129 41 +4 139 50 451 530 +4 547 459 356 446 +4 460 14 502 561 +4 401 264 571 266 +4 353 151 76 433 +4 75 150 424 366 +4 266 367 401 264 +4 22 24 383 152 +4 145 124 162 454 +4 163 383 404 469 +4 196 522 391 169 +4 450 98 448 583 +4 449 566 447 158 +4 264 109 350 401 +4 264 367 401 350 +4 401 367 353 350 +4 401 109 350 353 +4 370 440 459 157 +4 458 231 57 160 +4 4 116 585 268 +4 401 360 109 353 +4 214 264 109 350 +4 278 350 264 214 +4 214 109 353 350 +4 231 217 531 160 +4 531 194 217 231 +4 244 272 278 279 +4 244 278 272 264 +4 272 278 349 264 +4 14 561 539 339 +4 587 23 435 554 +4 568 213 192 489 +4 404 198 245 518 +4 242 97 402 396 +4 95 255 396 380 +4 257 335 60 70 +4 364 12 480 420 +4 12 586 364 480 +4 458 452 235 429 +4 569 361 347 365 +4 117 132 574 115 +4 117 115 112 132 +4 560 236 254 258 +4 563 304 285 251 +4 317 342 237 40 +4 188 221 422 153 +4 536 78 64 389 +4 470 281 324 191 +4 516 143 414 488 +4 516 488 414 468 +4 257 335 74 60 +4 328 257 473 60 +4 421 326 576 197 +4 468 31 488 414 +4 534 265 466 524 +4 534 524 466 443 +4 163 219 404 196 +4 469 219 404 163 +4 22 383 163 469 +4 383 404 453 163 +4 587 435 93 164 +4 562 567 487 372 +4 562 102 567 357 +4 289 243 359 300 +4 142 188 111 182 +4 182 111 142 374 +4 508 386 123 507 +4 300 359 223 243 +4 537 173 577 204 +4 411 399 173 537 +4 537 577 173 411 +4 580 100 412 483 +4 488 470 191 414 +4 414 470 191 281 +4 553 576 514 172 +4 523 43 469 518 +4 523 518 469 38 +4 342 317 237 417 +4 361 389 78 536 +4 536 361 389 256 +4 78 361 565 389 +4 189 103 13 513 +4 12 480 509 511 +4 343 144 480 509 +4 462 438 464 225 +4 441 45 466 265 +4 458 235 57 231 +4 522 41 169 457 +4 455 478 427 372 +4 476 427 372 455 +4 430 456 182 395 +4 430 395 182 123 +4 68 565 477 426 +4 428 586 22 383 +4 12 428 393 586 +4 22 586 428 12 +4 401 151 266 284 +4 291 564 310 32 +4 16 313 534 292 +4 304 533 563 58 +4 598 46 464 462 +4 598 225 464 437 +4 599 441 466 534 +4 599 534 466 443 +4 534 441 466 265 +4 557 566 45 449 +4 520 46 98 448 +4 32 564 520 462 +4 291 598 190 564 +4 199 489 568 488 +4 568 488 489 216 +4 488 195 489 216 +4 489 195 167 231 +4 397 194 471 250 +4 354 398 102 356 +4 470 192 216 191 +4 568 191 216 192 +4 385 516 143 122 +4 142 111 384 374 +4 348 369 377 365 +4 375 471 397 114 +4 396 397 114 375 +4 335 249 545 479 +4 270 406 367 362 +4 537 204 203 177 +4 590 180 206 205 +4 136 207 178 402 +4 49 139 138 192 +4 247 214 109 465 +4 214 465 312 109 +4 374 384 103 111 +4 391 522 260 493 +4 194 96 253 318 +4 402 106 242 240 +4 245 239 238 588 +4 588 592 239 238 +4 206 227 228 588 +4 580 100 251 563 +4 473 257 493 169 +4 328 257 256 473 +4 592 239 262 264 +4 239 264 589 262 +4 240 597 106 242 +4 588 264 106 239 +4 128 112 115 132 +4 498 495 494 570 +4 494 495 115 570 +4 373 128 112 115 +4 365 367 368 490 +4 368 377 365 299 +4 368 416 299 91 +4 128 127 179 170 +4 131 179 202 178 +4 194 217 51 531 +4 179 137 233 207 +4 343 197 196 144 +4 326 197 343 555 +4 35 537 577 203 +4 101 482 139 192 +4 482 398 107 192 +4 420 325 509 463 +4 226 238 594 241 +4 226 592 241 566 +4 493 261 257 256 +4 503 7 122 400 +4 463 112 128 127 +4 463 144 127 128 +4 539 144 561 171 +4 539 555 561 144 +4 260 256 337 261 +4 585 383 586 428 +4 363 249 348 365 +4 385 195 103 519 +4 128 133 132 115 +4 249 365 361 569 +4 112 132 127 131 +4 132 179 128 127 +4 128 112 132 127 +4 117 136 574 132 +4 117 132 131 136 +4 132 137 136 574 +4 381 146 269 501 +4 357 372 567 562 +4 586 480 383 364 +4 586 22 383 480 +4 171 170 576 144 +4 539 576 144 171 +4 126 590 130 174 +4 68 565 558 78 +4 389 78 558 565 +4 144 170 197 196 +4 184 229 181 180 +4 416 91 378 549 +4 378 416 549 584 +4 542 362 490 406 +4 116 445 119 461 +4 135 180 181 590 +4 568 184 210 213 +4 184 213 185 229 +4 127 170 144 202 +4 564 379 224 95 +4 199 213 489 230 +4 213 230 192 489 +4 84 361 249 544 +4 84 546 544 363 +4 122 21 400 512 +4 516 400 122 21 +4 388 391 589 238 +4 524 566 45 358 +4 95 375 100 99 +4 451 50 192 252 +4 283 0 415 403 +4 493 391 526 260 +4 493 261 260 526 +4 215 146 520 19 +4 53 145 578 471 +4 154 145 578 53 +4 244 279 278 248 +4 382 280 297 250 +4 415 208 168 1 +4 382 352 297 280 +4 99 276 251 100 +4 379 276 99 100 +4 379 224 99 276 +4 248 573 279 278 +4 246 280 352 382 +4 507 2 120 314 +4 386 2 120 507 +4 107 398 538 252 +4 316 585 10 4 +4 261 256 337 249 +4 262 254 362 347 +4 254 347 336 362 +4 119 156 122 7 +4 260 337 526 261 +4 278 349 264 350 +4 354 350 593 278 +4 354 356 405 350 +4 288 356 398 354 +4 352 297 357 351 +4 297 357 351 593 +4 357 475 352 351 +4 507 11 123 508 +4 250 167 397 194 +4 8 14 460 113 +4 15 14 176 552 +4 517 10 428 383 +4 426 541 362 565 +4 151 360 353 76 +4 361 544 365 249 +4 371 369 475 378 +4 367 368 370 593 +4 157 378 405 370 +4 548 315 371 89 +4 326 539 555 20 +4 516 122 385 21 +4 521 534 177 203 +4 441 521 203 534 +4 152 24 577 308 +4 59 305 358 557 +4 136 181 135 185 +4 135 184 181 180 +4 137 574 142 136 +4 118 140 187 185 +4 118 141 185 187 +4 140 187 184 568 +4 141 142 185 111 +4 142 111 211 185 +4 108 146 269 381 +4 501 113 104 381 +4 599 534 292 33 +4 38 330 469 163 +4 469 330 219 163 +4 40 522 196 34 +4 521 203 537 35 +4 218 69 145 67 +4 248 398 489 573 +4 210 180 209 229 +4 390 111 221 211 +4 191 568 212 192 +4 248 288 214 398 +4 27 374 217 320 +4 463 144 128 561 +4 117 130 116 136 +4 39 232 93 331 +4 574 591 137 142 +4 35 203 294 158 +4 43 296 220 306 +4 122 143 596 140 +4 123 182 188 142 +4 36 159 583 295 +4 534 595 212 210 +4 534 524 212 595 +4 37 217 458 160 +4 531 253 231 57 +4 252 329 474 57 +4 65 329 253 57 +4 135 134 180 590 +4 135 180 134 184 +4 250 471 105 476 +4 140 461 568 184 +4 143 568 461 191 +4 410 59 358 290 +4 410 305 358 59 +4 469 198 404 518 +4 469 383 198 577 +4 469 383 404 198 +4 581 359 559 62 +4 475 371 372 476 +4 476 371 372 572 +4 200 383 198 201 +4 383 404 198 201 +4 233 380 224 242 +4 432 377 366 92 +4 82 377 366 432 +4 178 206 202 201 +4 200 177 209 204 +4 148 66 258 481 +4 560 565 558 68 +4 553 514 552 172 +4 172 514 552 176 +4 190 243 224 379 +4 190 243 379 225 +4 190 225 379 462 +4 200 204 209 226 +4 190 462 379 564 +4 328 70 256 257 +4 200 226 594 204 +4 190 379 224 564 +4 178 181 402 206 +4 181 206 227 228 +4 335 70 256 479 +4 376 167 250 297 +4 206 588 239 245 +4 228 244 240 588 +4 240 244 106 588 +4 579 305 571 72 +4 113 133 564 176 +4 113 381 564 133 +4 589 106 569 347 +4 275 312 465 63 +4 540 107 356 77 +4 126 173 383 517 +4 232 162 471 194 +4 74 444 545 363 +4 333 162 232 194 +4 536 361 84 78 +4 565 485 361 78 +4 355 476 572 371 +4 371 572 548 372 +4 572 372 81 548 +4 69 455 476 454 +4 487 85 562 79 +4 485 362 484 565 +4 485 362 542 484 +4 368 377 299 416 +4 488 31 470 414 +4 414 31 470 281 +4 556 518 582 52 +4 556 52 236 518 +4 518 556 388 236 +4 306 518 556 388 +4 556 518 306 582 +4 459 370 356 83 +4 545 84 249 363 +4 545 479 249 84 +4 363 84 249 544 +4 547 102 459 85 +4 528 177 126 173 +4 80 406 270 362 +4 131 178 130 136 +4 485 88 365 544 +4 490 365 362 88 +4 407 87 572 315 +4 99 396 375 250 +4 0 166 403 283 +4 251 371 105 355 +4 168 4 116 585 +4 592 244 588 264 +4 244 264 272 106 +4 408 5 314 104 +4 567 405 378 593 +4 507 386 123 120 +4 181 228 229 185 +4 230 97 211 229 +4 561 113 176 128 +4 378 584 377 416 +4 183 461 212 534 +4 183 210 534 212 +4 136 185 402 181 +4 528 126 517 173 +4 11 273 108 147 +4 198 220 594 388 +4 209 534 595 203 +4 514 172 539 176 +4 185 228 229 211 +4 97 382 230 376 +4 199 230 211 185 +4 199 211 230 376 +4 29 281 125 324 +4 385 568 488 199 +4 220 234 262 306 +4 421 30 576 326 +4 595 524 247 566 +4 595 214 566 247 +4 302 225 44 243 +4 324 191 212 192 +4 237 389 259 260 +4 443 47 303 524 +4 208 117 118 574 +4 168 208 117 118 +4 337 361 389 565 +4 532 64 237 317 +4 589 259 336 569 +4 259 569 337 336 +4 312 353 540 214 +4 525 257 510 559 +4 525 257 559 60 +4 279 272 349 368 +4 59 358 161 45 +4 297 573 593 279 +4 117 130 131 585 +4 14 113 176 561 +4 149 444 74 344 +4 365 544 361 485 +4 91 378 157 440 +4 368 370 378 440 +4 567 405 85 550 +4 71 61 338 538 +4 481 234 270 72 +4 251 285 92 267 +4 271 572 575 81 +4 271 483 575 355 +4 92 371 432 377 +4 85 102 459 405 +4 494 439 115 0 +4 480 144 196 404 +4 404 144 196 245 +4 201 175 202 178 +4 404 245 201 202 +4 364 499 586 387 +4 500 268 116 4 +4 420 127 364 112 +4 117 118 574 136 +4 141 120 596 118 +4 574 141 118 120 +4 460 6 494 373 +4 138 192 50 235 +4 563 276 409 243 +4 563 285 409 92 +4 247 467 465 63 +4 247 467 214 465 +4 10 383 585 428 +4 499 585 586 505 +4 506 585 10 126 +4 508 11 123 430 +4 392 586 387 12 +4 392 393 586 12 +4 580 533 100 563 +4 394 189 386 13 +4 563 304 251 580 +4 394 395 189 13 +4 514 552 176 14 +4 555 197 343 144 +4 326 539 197 555 +4 293 399 528 18 +4 186 243 289 409 +4 289 186 409 311 +4 469 22 383 152 +4 490 367 362 365 +4 119 1 168 118 +4 215 309 114 153 +4 21 345 512 385 +4 385 327 21 345 +4 385 21 468 516 +4 58 243 289 527 +4 58 243 409 289 +4 301 63 247 290 +4 465 63 290 247 +4 301 247 358 290 +4 301 101 49 524 +4 540 107 353 356 +4 149 444 344 424 +4 15 113 176 14 +4 33 441 599 534 +4 326 343 20 555 +4 301 290 358 161 +4 524 301 358 161 +4 345 27 217 419 +4 469 152 577 308 +4 469 308 577 43 +4 552 553 172 28 +4 139 451 107 530 +4 452 529 138 470 +4 50 529 49 138 +4 49 50 139 530 +4 293 177 134 528 +4 293 399 537 177 +4 580 533 563 304 +4 41 30 576 421 +4 452 529 470 31 +4 516 488 385 143 +4 516 385 488 468 +4 564 520 146 32 +4 152 383 577 24 +4 188 182 123 147 +4 316 4 168 585 +4 104 408 108 591 +4 408 104 314 591 +4 521 35 447 203 +4 435 153 93 39 +4 513 456 189 374 +4 82 546 363 377 +4 82 84 363 546 +4 225 44 464 437 +4 527 44 438 225 +4 506 116 126 528 +4 439 494 373 460 +4 8 460 439 113 +4 439 460 373 113 +4 439 113 115 434 +4 32 46 598 462 +4 532 332 317 237 +4 520 46 462 98 +4 93 194 217 51 +4 562 476 372 455 +4 524 47 466 443 +4 443 125 292 534 +4 303 125 524 101 +4 25 36 215 309 +4 376 297 573 489 +4 526 348 249 569 +4 94 263 261 348 +4 419 341 217 37 +4 217 419 27 320 +4 390 380 211 396 +4 380 224 396 95 +4 396 224 99 95 +4 472 48 413 39 +4 53 48 472 578 +4 358 557 45 59 +4 451 538 107 61 +4 129 169 576 222 +4 129 576 223 222 +4 510 129 222 169 +4 212 192 101 324 +4 324 192 101 49 +4 311 62 359 581 +4 47 301 524 161 +4 570 499 585 364 +4 303 324 29 125 +4 322 63 467 301 +4 301 101 467 322 +4 234 481 258 66 +4 434 104 115 166 +4 166 403 591 104 +4 314 166 591 104 +4 465 247 290 358 +4 76 353 446 540 +4 312 540 353 76 +4 70 389 256 536 +4 580 412 100 583 +4 580 100 533 583 +4 256 335 257 70 +4 303 292 443 125 +4 61 71 329 538 +4 65 454 124 110 +4 312 410 109 465 +4 579 72 234 481 +4 518 582 52 38 +4 258 306 262 234 +4 540 356 353 446 +4 463 325 509 561 +4 325 555 509 561 +4 294 203 577 594 +4 312 275 465 214 +4 331 333 232 194 +4 331 413 232 333 +4 331 232 93 194 +4 331 413 39 232 +4 324 529 470 138 +4 158 566 594 234 +4 294 594 220 158 +4 159 298 583 295 +4 484 78 565 477 +4 484 485 565 78 +4 476 69 427 455 +4 486 79 487 562 +4 486 79 562 478 +4 548 543 372 81 +4 483 251 218 355 +4 506 528 517 399 +4 78 389 558 64 +4 271 355 575 572 +4 148 340 362 270 +4 423 148 340 362 +4 33 521 177 293 +4 520 462 564 215 +4 55 449 158 566 +4 158 566 234 55 +4 158 566 447 203 +4 527 442 243 98 +4 446 459 356 83 +4 374 217 103 345 +4 374 217 193 103 +4 469 383 577 152 +4 133 233 128 132 +4 485 542 362 88 +4 90 299 377 416 +4 378 549 550 89 +4 92 371 87 432 +4 370 83 459 440 +4 168 551 492 3 +4 551 1 168 492 +4 1 492 165 168 +4 364 387 12 420 +4 498 420 387 364 +4 386 504 384 497 +4 394 508 386 123 +4 394 508 123 395 +4 15 8 113 14 +4 5 434 104 501 +4 501 381 104 269 +4 104 269 108 408 +4 512 385 384 122 +4 501 15 381 146 +4 15 146 501 286 +4 491 432 377 82 +4 173 517 399 24 +4 218 483 575 67 +4 122 516 143 503 +4 517 173 383 24 +4 334 110 102 562 +4 334 562 535 110 +4 553 30 514 576 +4 374 27 554 164 +4 468 488 31 429 +4 163 319 196 26 +4 197 457 421 34 +4 376 167 221 397 +4 111 221 376 167 +4 376 396 397 221 +4 263 186 366 92 +4 155 576 553 129 +4 576 155 553 30 +4 576 155 30 41 +4 380 242 396 224 +4 217 458 429 37 +4 303 29 292 125 +4 64 532 237 389 +4 525 223 42 321 +4 566 557 234 55 +4 566 45 358 557 +4 107 61 277 530 +4 280 475 371 352 +4 475 357 476 372 +4 280 475 357 476 +4 568 489 192 216 +4 558 254 565 560 +4 257 74 559 60 +4 114 375 100 95 +4 97 396 382 376 +4 531 318 253 65 +4 531 65 253 57 +4 61 329 474 538 +4 221 114 396 397 +4 111 199 519 167 +4 297 102 110 357 +4 297 102 573 538 +4 386 189 142 384 +4 424 363 366 82 +4 222 242 207 233 +4 207 222 402 242 +4 540 77 356 446 +4 71 338 102 538 +4 571 109 264 401 +4 484 541 477 565 +4 484 362 541 565 +4 485 544 361 84 +4 92 572 371 251 +4 366 348 92 377 +4 77 547 356 446 +4 550 85 567 487 +4 99 250 246 396 +4 99 280 246 250 +4 546 377 82 90 +4 172 576 171 223 +4 146 108 255 121 +4 248 398 214 482 +4 229 278 595 248 +4 371 491 432 377 +4 229 278 248 244 +4 392 387 586 505 +4 392 393 505 586 +4 566 45 265 524 +4 486 548 372 487 +4 486 543 478 372 +4 486 543 372 548 +4 155 129 41 576 +4 41 129 155 425 +4 217 167 194 193 +4 166 115 434 439 +4 431 116 165 4 +4 545 82 363 444 +4 503 445 119 9 +4 570 498 495 3 +4 377 365 299 88 +4 90 491 584 377 +4 491 82 377 90 +4 316 168 3 499 +4 499 316 585 10 +4 156 497 596 122 +4 363 249 365 544 +4 373 128 460 463 +4 311 186 149 581 +4 523 152 469 308 +4 523 308 469 43 +4 53 307 578 154 +4 53 48 578 307 +4 338 356 77 547 +4 524 247 101 212 +4 325 555 561 539 +4 4 268 585 10 +4 176 561 539 14 +4 327 217 195 429 +4 429 468 488 195 +4 429 327 468 195 +4 460 14 561 113 +4 77 107 277 275 +4 275 107 277 467 +4 320 374 93 164 +4 217 374 193 93 +4 217 374 93 320 +4 217 231 458 160 +4 463 509 127 144 +4 188 182 422 221 +4 562 478 455 372 +4 486 562 487 372 +4 486 562 372 478 +4 189 182 456 395 +4 394 123 386 189 +4 394 395 123 189 +4 223 359 321 525 +4 559 321 359 525 +4 355 572 476 575 +4 499 585 505 10 +4 583 298 578 295 +4 295 114 583 215 +4 295 578 583 114 +4 52 556 236 560 +4 66 423 258 556 +4 211 376 111 221 +4 188 111 221 390 +4 263 348 276 92 +4 348 276 92 251 +4 99 224 94 276 +4 99 251 276 348 +4 374 193 111 103 +4 423 426 148 362 +4 423 426 362 565 +4 539 339 561 325 +4 380 242 402 396 +4 396 224 242 99 +4 105 218 476 145 +4 576 171 223 222 +4 166 104 115 403 +4 251 371 348 280 +4 99 251 105 100 +4 459 157 405 370 +4 366 363 377 82 +4 485 84 361 78 +4 141 111 384 142 +4 141 111 519 384 +4 385 187 519 141 +4 596 187 385 141 +4 28 190 223 176 +4 176 190 233 564 +4 252 192 398 489 +4 99 348 94 242 +4 106 279 369 368 +4 242 94 224 223 +4 519 167 195 103 +4 246 106 382 279 +4 99 94 348 276 +4 591 403 574 137 +4 283 415 120 591 +4 415 208 591 403 +4 197 169 170 576 +4 576 170 222 169 +4 404 219 245 196 +4 121 390 380 211 +4 376 396 382 250 +4 376 382 297 250 +4 175 174 364 585 +4 116 585 126 130 +4 116 126 134 130 +4 99 280 251 348 +4 581 263 559 359 +4 105 355 476 218 +4 371 355 476 105 +4 95 396 114 375 +4 547 338 356 102 +4 106 347 365 569 +4 379 243 224 276 +4 382 97 244 106 +4 375 250 471 105 +4 110 535 65 454 +4 26 480 511 343 +4 511 26 453 480 +4 27 554 513 374 +4 38 469 330 332 +4 49 139 50 138 +4 383 577 173 200 +4 383 577 24 173 +4 254 532 236 560 +4 532 52 332 236 +4 560 532 236 52 +4 66 234 306 258 +4 514 172 576 539 +4 64 389 70 536 +4 343 555 509 20 +4 17 503 461 143 +4 274 281 191 461 +4 17 143 414 516 +4 143 503 516 17 +4 539 176 14 514 +4 214 288 353 107 +4 398 107 288 214 +4 63 275 467 465 +4 467 275 214 465 +4 235 452 216 429 +4 429 195 216 235 +4 429 488 216 195 +4 197 421 457 576 +4 457 41 576 421 +4 234 264 262 340 +4 355 575 476 218 +4 517 528 173 399 +4 457 197 169 522 +4 451 252 192 107 +4 451 538 252 107 +4 54 169 41 473 +4 525 60 169 257 +4 521 293 537 177 +4 521 203 177 537 +4 557 305 571 579 +4 557 358 109 305 +4 55 557 234 579 +4 520 19 36 215 +4 215 282 188 108 +4 215 282 108 146 +4 76 353 312 360 +4 196 219 40 330 +4 129 41 576 169 +4 93 193 217 194 +4 327 37 217 429 +4 243 359 263 186 +4 409 276 186 243 +4 463 128 460 561 +4 463 561 460 502 +4 194 124 252 96 +4 10 585 383 126 +4 218 483 355 575 +4 67 145 154 436 +4 108 282 188 147 +4 108 273 282 147 +4 18 293 134 528 +4 33 134 18 293 +4 474 252 538 329 +4 537 411 35 577 +4 294 577 35 411 +4 577 594 200 198 +4 577 220 198 43 +4 577 220 594 198 +4 109 465 410 358 +4 410 358 465 290 +4 13 189 386 384 +4 386 13 384 504 +4 387 12 586 364 +4 80 406 362 542 +4 408 123 507 11 +4 215 282 146 19 +4 18 33 287 134 +4 33 177 134 293 +4 358 557 109 566 +4 542 490 362 88 +4 467 322 530 277 +4 538 61 338 77 +4 339 514 30 539 +4 538 102 71 110 +4 71 334 346 110 +4 346 110 538 71 +4 298 578 48 307 +4 343 26 480 196 +4 303 524 49 101 +4 412 483 218 67 +4 348 363 365 377 +4 350 356 405 370 +4 562 567 85 487 +4 562 102 85 567 +4 475 593 357 567 +4 475 372 567 357 +4 137 233 207 380 +4 184 181 229 185 +4 203 594 158 566 +4 144 170 576 197 +4 184 185 213 199 +4 568 184 213 199 +4 219 589 259 236 +4 219 237 236 259 +4 588 227 228 592 +4 228 229 244 592 +4 227 592 229 228 +4 228 588 592 244 +4 224 99 95 379 +4 379 100 99 95 +4 236 254 589 259 +4 473 257 256 493 +4 238 262 592 239 +4 589 238 239 262 +4 239 589 264 106 +4 239 592 588 264 +4 585 168 117 116 +4 99 246 280 348 +4 242 106 97 246 +4 248 573 288 398 +4 278 279 593 573 +4 246 382 250 280 +4 250 280 297 476 +4 261 363 249 348 +4 597 526 569 242 +4 162 124 471 194 +4 162 124 194 96 +4 216 192 231 489 +4 195 217 231 458 +4 215 98 379 583 +4 510 391 526 493 +4 510 261 493 526 +4 564 215 379 95 +4 573 398 102 354 +4 310 28 176 291 +4 104 403 591 137 +4 196 169 391 170 +4 368 593 378 370 +4 363 546 544 365 +4 490 299 368 365 +4 221 114 255 396 +4 144 170 128 171 +4 127 202 131 179 +4 170 127 179 202 +4 131 178 136 179 +4 135 181 184 185 +4 135 184 140 185 +4 185 140 187 184 +4 468 385 488 195 +4 368 377 416 378 +4 206 588 240 239 +4 183 210 568 184 +4 210 184 180 229 +4 200 226 209 205 +4 588 205 227 592 +4 209 210 229 595 +4 210 229 212 213 +4 488 191 216 568 +4 238 226 592 241 +4 226 566 595 592 +4 595 278 214 248 +4 482 248 398 192 +4 200 226 238 594 +4 200 209 183 180 +4 120 574 141 142 +4 142 374 189 182 +4 122 385 596 143 +4 126 383 200 174 +4 590 134 180 200 +4 134 180 183 184 +4 183 461 568 212 +4 461 568 212 191 +4 375 218 100 105 +4 578 145 375 471 +4 268 116 585 506 +4 74 344 444 363 +4 424 444 344 363 +4 475 368 593 378 +4 354 102 593 405 +4 102 405 567 593 +4 171 128 223 222 +4 171 128 176 223 +4 128 223 222 233 +4 176 223 128 233 +4 222 526 242 223 +4 223 242 94 526 +4 221 472 232 93 +4 510 263 261 94 +4 526 261 94 510 +4 99 251 280 105 +4 261 263 344 348 +4 561 176 539 171 +4 176 171 172 539 +4 113 176 128 133 +4 137 381 133 233 +4 381 564 133 233 +4 381 233 121 564 +4 402 181 185 228 +4 265 566 595 203 +4 209 226 566 595 +4 226 204 209 566 +4 594 226 566 204 +4 220 518 306 388 +4 245 239 206 391 +4 589 597 259 569 +4 402 240 228 244 +4 206 228 240 588 +4 237 260 259 391 +4 566 247 214 109 +4 196 391 219 245 +4 208 574 118 120 +4 329 96 253 252 +4 156 596 120 118 +4 497 596 120 156 +4 259 389 565 337 +4 404 175 202 201 +4 573 593 354 102 +4 297 110 102 538 +4 130 590 181 178 +4 118 187 596 141 +4 206 181 402 228 +4 386 497 120 2 +4 487 89 567 550 +4 476 357 297 124 +4 123 189 182 142 +4 374 182 111 587 +4 182 111 587 221 +4 519 199 195 167 +4 330 219 40 332 +4 40 219 237 332 +4 522 54 260 493 +4 223 263 94 243 +4 260 417 389 256 +4 113 133 128 115 +4 189 374 103 513 +4 384 519 103 111 +4 189 103 374 384 +4 54 493 169 473 +4 369 368 377 365 +4 200 205 180 590 +4 236 219 589 388 +4 388 589 391 219 +4 493 260 261 256 +4 111 376 199 167 +4 205 226 227 592 +4 205 201 238 588 +4 209 205 226 227 +4 200 205 201 238 +4 200 594 238 388 +4 205 226 238 200 +4 588 205 592 238 +4 222 169 391 510 +4 254 565 362 336 +4 124 297 538 110 +4 249 545 261 335 +4 256 249 261 335 +4 249 545 363 261 +4 357 593 475 351 +4 108 188 215 255 +4 248 288 573 278 +4 278 354 288 573 +4 120 591 142 123 +4 591 123 120 507 +4 167 195 217 231 +4 103 167 195 217 +4 391 589 240 597 +4 240 597 242 391 +4 404 518 245 219 +4 469 518 404 219 +4 354 356 102 405 +4 168 117 116 118 +4 547 356 459 102 +4 405 102 459 356 +4 565 361 362 336 +4 567 89 475 378 +4 89 550 378 567 +4 574 141 142 136 +4 200 180 183 134 +4 226 592 595 227 +4 209 595 227 226 +4 209 227 595 229 +4 595 214 592 566 +4 595 592 214 278 +4 108 137 121 381 +4 183 212 568 210 +4 388 254 262 589 +4 388 589 262 238 +4 353 356 370 83 +4 229 212 192 595 +4 595 192 248 482 +4 210 212 229 595 +4 213 229 212 192 +4 10 506 126 517 +4 212 213 192 568 +4 210 213 212 568 +4 254 423 340 362 +4 262 362 340 264 +4 196 219 391 40 +4 539 171 172 576 +4 108 255 121 188 +4 226 566 241 594 +4 381 564 121 146 +4 108 121 146 381 +4 130 178 181 136 +4 241 262 234 264 +4 272 106 347 368 +4 272 347 349 368 +4 112 131 364 585 +4 585 130 131 175 +4 337 336 361 565 +4 259 565 336 337 +4 99 250 375 105 +4 223 526 510 222 +4 408 123 108 591 +4 461 281 191 125 +4 497 122 384 596 +4 405 378 157 550 +4 329 252 538 124 +4 349 593 278 279 +4 279 593 368 349 +4 391 589 239 240 +4 273 19 146 282 +4 309 36 215 295 +4 189 123 182 395 +4 306 258 556 66 +4 46 442 527 98 +4 450 442 46 98 +4 563 379 100 276 +4 69 218 476 427 +4 24 517 428 383 +4 359 223 243 263 +4 538 338 356 77 +4 107 356 77 538 +4 145 476 471 124 +4 211 121 390 111 +4 373 113 128 115 +4 363 546 365 377 +4 126 174 200 590 +4 45 566 265 447 +4 447 566 265 203 +4 570 115 112 117 +4 373 494 570 498 +4 243 263 94 276 +4 224 243 94 276 +4 96 162 124 65 +4 54 256 260 493 +4 54 493 473 256 +4 328 70 389 256 +4 197 522 196 169 +4 233 242 224 223 +4 349 367 593 368 +4 169 510 493 391 +4 144 196 245 170 +4 510 257 493 261 +4 219 259 589 391 +4 137 233 121 381 +4 379 100 95 114 +4 583 379 114 100 +4 170 222 128 171 +4 573 354 593 278 +4 509 144 480 127 +4 210 184 229 213 +4 121 255 380 390 +4 559 263 261 510 +4 272 349 278 279 +4 382 279 248 573 +4 244 279 248 382 +4 258 234 262 340 +4 258 340 254 423 +4 371 475 280 476 +4 108 142 591 123 +4 120 591 574 142 +4 505 585 586 428 +4 108 188 123 147 +4 451 192 139 107 +4 235 452 138 216 +4 452 470 138 216 +4 549 91 378 157 +4 498 373 6 420 +4 6 494 373 498 +4 256 70 536 479 +4 447 441 203 265 +4 442 58 243 563 +4 442 58 563 533 +4 155 553 323 129 +4 576 129 172 553 +4 469 518 219 332 +4 236 52 332 518 +4 518 236 388 219 +4 582 43 518 306 +4 523 582 43 518 +4 512 513 13 103 +4 107 139 467 482 +4 521 33 177 534 +4 441 521 534 33 +4 32 146 15 286 +4 414 281 191 274 +4 17 191 461 274 +4 334 102 110 71 +4 267 271 572 251 +4 309 295 215 114 +4 300 289 243 527 +4 291 437 190 598 +4 190 462 564 598 +4 443 534 292 599 +4 453 480 22 12 +4 12 453 480 511 + +CELL_TYPES 2536 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 diff --git a/data/banana.vtk b/data/banana.vtk new file mode 100644 index 000000000..e210e9c42 --- /dev/null +++ b/data/banana.vtk @@ -0,0 +1,5524 @@ +# vtk DataFile Version 2.0 +banana_, Created by Gmsh +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 725 double +-0.114051737 0.111051977 -0.00126409391 +-0.1136008866438946 0.1125416473395982 1.000173391591562e-05 +-0.112811992008898 0.1050143081274397 -0.002818488000579707 +-0.1126766781759306 0.1087927864238047 0.001701207127117275 +-0.112563953 0.110402152 -0.00165868399 +-0.1124450160131114 0.1127790787188343 0.001310955468637676 +-0.1123992611666408 0.1002519469778422 0.001220640227638607 +-0.1114217420714711 0.09602479967022418 -0.002262379001488706 +-0.111320287 0.112935029 0.000312530727 +-0.110977925 0.09175443649999999 0.000160303578 +-0.1108043550412968 0.1118265213820596 0.00303850020358509 +-0.1109274601258133 0.1134697765942687 0.001773710620446713 +-0.1100925083407672 0.1059090128878861 0.004031043261968226 +-0.109583117 0.101956733 -0.00394597463 +-0.109548993 0.0885386989 -0.00326827238 +-0.1095068511042773 0.08240754434471335 -0.0002095003683046115 +-0.109267369 0.0967600793 0.00374922738 +-0.108850326 0.113631692 0.003276231119999999 +-0.108956309858666 0.1115120467855114 0.003949692903386587 +-0.1088496395934722 0.1137255891026467 0.002383154566900606 +-0.108746625 0.11384289 0.00306916796 +-0.10862951 0.113609858 0.0026939041 +-0.1086016455421452 0.05525888987522014 -0.001916404486547957 +-0.108595341 0.0664659888 -0.0008088590110000001 +-0.108548008 0.0732978806 -0.0030426241 +-0.10849385 0.0750510246 0.000424304191 +-0.1078813493819049 0.09229631584632425 -0.004391945607731901 +-0.107678019 0.063628301 -0.00734115951 +-0.1077285323486749 0.112735706370635 0.001635951818260356 +-0.10744568 0.0613258742 0.00250348868 +-0.1075224534813596 0.1134169322917204 0.003775870568896788 +-0.1070057492279812 0.07962430633139279 -0.005023396974981076 +-0.1072402631142524 0.1097806031790339 -0.0006083309001901124 +-0.1072392508264609 0.1084469421072674 0.004865189284906349 +-0.1065464864829574 0.1138721757251125 0.003338882502844295 +-0.1065992926505886 0.08857639496018974 0.004080635796822185 +-0.1064186809072021 0.1016377361294261 0.00517828820414278 +-0.10609398 0.0705740452 0.00390446093 +-0.105995163 0.0555767603 0.00465086475 +-0.105985306 0.0789877623 0.0029815773 +-0.105772913 0.113557085 0.00352538005 +-0.105705857 0.0458048545 -0.00280309794 +-0.1052440906671828 0.1116096060433189 0.003759231928780606 +-0.105417989 0.0539664663 -0.0102922758 +-0.1051383196706054 0.09351247370648265 0.004856557320384654 +-0.105099708 0.0498242602 0.00362831308 +-0.1049863530334329 0.07134758156461961 -0.008052810974784819 +-0.1043845915603806 0.111412139510934 0.001315934003048457 +-0.104388282 0.0958219543 -0.00446955673 +-0.104326785 0.0838392377 -0.00557476655 +-0.103935003 0.108312577 0.000190122722 +-0.1038121729825128 0.1128436340919143 0.002999491083116883 +-0.103403881 0.104444236 0.00471720938 +-0.10305196 0.103610314 -0.00194947864 +-0.1027892837399845 0.1091682880539995 0.00309742456804448 +-0.1028587427181362 0.09836130848510805 0.004271721720586552 +-0.1027820874829359 0.08900685565389035 -0.004781886881596129 +-0.102321796 0.0647074431 -0.0116850948 +-0.102200225 0.104322299 0.00191707932 +-0.102199323 0.0448696688 -0.0107371332 +-0.102065496 0.0522785261 0.008293342780000001 +-0.1019610919226192 0.09787713834657223 -0.0009278600457729248 +-0.1021519405528691 0.08837479139865841 0.004545314998268699 +-0.10182672 0.0766540691 -0.00707951188 +-0.1017791014575778 0.1005290156075592 0.002655857099041831 +-0.101563767 0.0921853483 0.00417005643 +-0.101382002 0.0944978893 0.00283863069 +-0.1010123219428869 0.0414181119826509 0.00340800019676107 +-0.1012200886908666 0.09217017884637323 -0.001634216758927716 +-0.10058102 0.08309191470000001 0.00427809684 +-0.100346528 0.0660405681 0.0070979069 +-0.1001472750424556 0.08745636266645969 0.002662176813139112 +-0.0999801978 0.0702699646 -0.0097458018 +-0.0999716595 0.0368879549 -0.00342131662 +-0.0996438861 0.0855282694 -0.00234780926 +-0.0993126631 0.0809905007 -0.00493497821 +-0.0989952534 0.0756540075 0.00546569657 +-0.09870455409999999 0.0461051464 0.00979949534 +-0.09768096439557124 0.080707664925897 0.001801717835405587 +-0.09769105910000001 0.037768282 -0.0109092351 +-0.0971900225 0.0601902716 0.0102019729 +-0.0967295468 0.0433794074 -0.0150171826 +-0.09637343640278835 0.03501019224728508 0.003079233078741565 +-0.09659338000000001 0.0506649651 -0.0167615972 +-0.09524487700000001 0.0589605905 -0.016515566 +-0.0950392261 0.0728451014 -0.008634311150000001 +-0.0948229134 0.0511772744 0.0125985937 +-0.09480095650000001 0.0671963543 -0.0126446784 +-0.09456200164606468 0.06771449881104707 0.008353692107704288 +-0.09348451314960506 0.03885276724462597 0.0101216642420402 +-0.0931681246 0.0314377882 -0.009989637880000001 +-0.09322655180578168 0.02982694175408547 -0.002001053108387836 +-0.09263894709999999 0.0746963397 -0.00298983068 +-0.0924656913 0.0741579235 0.00314810267 +-0.09222440895347464 0.04554786428287758 0.01313761922972155 +-0.0919825286 0.0370452553 -0.0151356282 +-0.09057736951200157 0.03103736207597246 0.005920670210609364 +-0.09000408144304829 0.04620627659915799 -0.01820098872466371 +-0.0887466148 0.0550538115 -0.0177459121 +-0.08816138649999999 0.0599790104 0.0103802811 +-0.0879812464 0.0696046874 -0.00928702671 +-0.08783347900000001 0.0625434965 -0.0148354275 +-0.087033309 0.067857638 0.00703708082 +-0.0867671669 0.0505221896 0.0140988585 +-0.08671910319999999 0.0303294323 -0.0141857136 +-0.0865758806 0.0244262796 -0.00688818237 +-0.08613067119999999 0.07069249449999999 -0.00046836384 +-0.08562295418095843 0.02511251337793172 0.00290257700142643 +-0.0859801993 0.0420435704 0.0144508434 +-0.0853710455868789 0.03520553696399815 0.01240832524624824 +-0.08392000199999999 0.0378322601 -0.0185705591 +-0.08252497759999999 0.028976569 0.0108719897 +-0.08236873153573923 0.06295608073234751 0.008754988550904941 +-0.0809622556 0.0555641428 0.0124617564 +-0.0808979496 0.0508089885 -0.0183463953 +-0.08143418844997431 0.04376974395637605 -0.01943226007004531 +-0.08086945387301993 0.04704155564505044 0.01493127979319375 +-0.0802766159 0.0579927564 -0.0157422442 +-0.07996422419313445 0.065774155257508 0.003635960286105571 +-0.07974053170000001 0.0200297777 0.000658327364 +-0.07973893730000001 0.0248923954 -0.0134307388 +-0.0792114213 0.0664670393 -0.002712755 +-0.07908468690000001 0.0646619499 -0.0107912878 +-0.07825841066874541 0.01966217185466485 -0.007125956663853639 +-0.07808975880000001 0.0226931758 0.00780514535 +-0.0779804513 0.0393797457 0.0152746076 +-0.0776583329 0.0307914075 -0.0180618763 +-0.07727877575199045 0.03260998938227338 0.01480330558251991 +-0.0766204447 0.0589205846 0.009995906610000001 +-0.0757306069 0.02736184 0.0129313031 +-0.0748414397 0.0374666117 -0.0196641292 +-0.07477623896096811 0.04548727511047022 -0.01922722177275916 +-0.07472236725071114 0.05126928487319322 0.01312004844836152 +-0.07404226098316595 0.02090033112017053 -0.01255470670229975 +-0.07244707919918807 0.01543472857130511 -0.001852172768487603 +-0.07314990570707047 0.05356011781941781 -0.01655834157126864 +-0.0728356689 0.0439735577 0.0151419081 +-0.0722530931 0.0170960687 0.00440017274 +-0.07155735395604107 0.06107373018970782 0.00322929311131667 +-0.0719050393 0.0358365178 0.0161508471 +-0.071805127 0.0604844987 -0.0109697729 +-0.0707279146 0.0614537448 -0.00325590954 +-0.07027492909503466 0.05469642747439506 0.01072732330150129 +-0.07055191254266792 0.02537422667693622 -0.01753840394817245 +-0.07044577529065456 0.01671795054975122 -0.01015005901149892 +-0.06912405514624841 0.02690857072318626 0.01497974580131224 +-0.06902165709999999 0.0205107555 0.011822396 +-0.06674306839999999 0.030857712 -0.0196702778 +-0.06787765892807678 0.04027434767868141 -0.01946185601499736 +-0.06629058963395727 0.04801197352701883 0.01320708189472969 +-0.06577267097475874 0.0199002796253463 -0.01580222943502746 +-0.06583652470024837 0.01285111584930967 -0.007254677677989193 +-0.06653501793638865 0.04765121446270951 -0.01743645001047288 +-0.06547333269062999 0.01269432501190274 0.0007298827544402449 +-0.06475524196083957 0.04017216919958858 0.01535625737127572 +-0.0640672967 0.0306881126 0.0160738863 +-0.0639890209 0.0542165674 0.00918609183 +-0.06348066030000001 0.0538089201 -0.0135906236 +-0.0629848312224692 0.05683539148420772 0.002219722076695233 +-0.06317360700000001 0.0574347898 -0.00415055966 +-0.0626117811 0.0135289421 0.00684192078 +-0.0618564598 0.0224019699 0.0150248259 +-0.06133879507030034 0.01443329609688496 -0.01199022767077936 +-0.06038233979000743 0.02388770648600992 -0.01867471076608206 +-0.05983912886755897 0.03503940961689445 -0.0195613133543355 +-0.0595412552 0.0105582131 -0.00564407604 +-0.05866829442356786 0.04858973043997094 -0.01542429883705314 +-0.0588302948 0.0155344559 0.0116496207 +-0.05795713276631482 0.04123081345953303 -0.01822571240460946 +-0.05800644928800736 0.04259611331272521 0.01475666214621984 +-0.058062356 0.0485446341 0.011663761 +-0.0575796962 0.0355568901 0.0167864989 +-0.05768135343522234 0.02809248746428348 0.01708463758813794 +-0.05714657316840494 0.05411134208158549 -0.006780349286282796 +-0.05748603518708979 0.0101364957527641 0.002866730832733535 +-0.0554127254650566 0.02778632351381631 -0.0192453991681546 +-0.05609272506783204 0.01789264748592871 -0.01625764458757824 +-0.05573327206101382 0.05276018590438047 0.005774123109957257 +-0.05403128733792387 0.05132046307055006 -0.01203158006109094 +-0.05449435396902452 0.0531125473374382 -0.000300459253731704 +-0.05430070493436451 0.01093768331084126 0.008189475614259947 +-0.05316014757444319 0.01100817454201737 -0.01099191514205237 +-0.05252068678955198 0.02200698414665932 0.01657544516351135 +-0.0518105328 0.0442024469 0.0133040547 +-0.05158712589087581 0.01402898442584758 0.01302151091579045 +-0.05129078993409283 0.02203537022982282 -0.01904823920581128 +-0.05011899583751155 0.05102610884993711 -0.006439670675582452 +-0.0503631011 0.0356731378 -0.0187367667 +-0.05066628607477953 0.03852360739064972 0.01583159788127251 +-0.05061071350138054 0.03106673749637986 0.01788781210629176 +-0.04841836517417958 0.04787266253896219 0.01002582713487561 +-0.0489770472 0.00640592538 -0.00230537541 +-0.0486579984 0.0451159142 -0.0147699229 +-0.04853799688869628 0.007967583860405837 0.00516442867658792 +-0.04585101915478464 0.02816317901763573 -0.01927105659852297 +-0.0468338318 0.050017301 0.00421916088 +-0.0458148792 0.0105955815 0.0121541303 +-0.0453840271 0.014523332 -0.0162349213 +-0.04520352145219965 0.01677162594980681 0.01625209134702533 +-0.04398109879996284 0.04219600458682213 0.01368603220468977 +-0.04417013192604562 0.04843448774615026 -0.01006181917605569 +-0.04380473376947031 0.04953344475828678 -0.002888439810576592 +-0.04374126556824844 0.02470001528149546 0.01757423193094459 +-0.0435383498182675 0.007349586753594938 -0.009703991872786191 +-0.0420959817876972 0.0343979668547871 -0.01850270966806929 +-0.0422665402 0.0203160215 -0.0187137108 +-0.04049727040793803 0.03408346582549478 0.0170733678666632 +-0.04129025101172593 0.04045695909911076 -0.01617897281643431 +-0.04032767463895483 0.04671428533149048 0.008862834412535606 +-0.039922744 0.00413622102 0.00122563902 +-0.0388036519 0.00706058275 0.007953648460000001 +-0.0384579375 0.0276470818 -0.0191689935 +-0.0384256132 0.0184831209 0.0180218108 +-0.03850952164780469 0.01230169181257753 0.01497224745680193 +-0.0375679433 0.0145521173 -0.0174456555 +-0.03665547660883876 0.04479784832792948 -0.01186015669216877 +-0.03760618611287379 0.009223801546183697 -0.01350293334179345 +-0.0367744751 0.0477754436 0.00166918873 +-0.035479892 0.0470437445 -0.00472489232 +-0.0352141187 0.0403942242 0.0142357238 +-0.03373910402437937 0.03464252359457117 -0.01743021611736518 +-0.0349360146 0.0257716849 0.0190681834 +-0.0332826898 0.00472444622 -0.00808631256 +-0.0327906944 0.0181452613 -0.0189897008 +-0.032027889 0.0165099334 0.0179407801 +-0.0320136547 0.0041693924 0.00610647304 +-0.0308803469 0.0403054766 -0.0146184312 +-0.03097752463672433 0.03290613633374796 0.0173623958186418 +-0.0304363929 0.0121464627 -0.0166639499 +-0.0300168246 0.008193979969999999 0.0130500505 +-0.0297606867 0.00764214713 -0.012931155 +-0.029315358 0.0450244509 0.008045622150000001 +-0.0292481817 0.0291186702 -0.0185923818 +-0.02842306903673929 0.001943341060616327 -0.0003374522975603627 +-0.02765462541375835 0.04493066429705618 -0.006700977147250707 +-0.0273512982466247 0.04557015504336103 0.0001783712036375106 +-0.02750135615863433 0.02519419348813481 0.01921069715108187 +-0.02638039292855646 0.03873551919083323 0.01462509313059693 +-0.02453883669875838 0.03470889183179461 -0.01635919200280662 +-0.02443046312874592 0.004305107976943244 -0.008938531002738566 +-0.0247672796 0.00336881448 0.00639092131 +-0.0253662619633759 0.02334231420049383 -0.0187606169497326 +-0.0240808874 0.0139124207 0.0175858885 +-0.0230385736 0.00886675715 -0.0143878832 +-0.0228405911 0.0167283751 -0.0182557218 +-0.02275328226185148 0.0408737127887488 -0.01322129082557289 +-0.0211166721 0.0316098966 0.0176517889 +-0.0195288478296675 0.04213640560346885 0.01091927587282262 +-0.019309992 0.00134164304 0.00177107076 +-0.02015428511838856 0.02274537387383139 0.01943355572323921 +-0.01896690524447905 0.001886555708547744 -0.005141330219181782 +-0.0181528986269737 0.03044852864580678 -0.01765617593372621 +-0.0186815131 0.0442902632 0.00342694717 +-0.0184646454 0.0075646285 0.0141428327 +-0.0183538441 0.0437417366 -0.00515160011 +-0.01719431959826502 0.03630394879621155 0.01554247779693179 +-0.0168993343 0.0383212045 -0.0140712894 +-0.01554417954204403 0.02144539592919258 -0.01853819368534488 +-0.0162382312 0.00271469355 0.00645302562 +-0.0159593113 0.00576517917 -0.0114322016 +-0.01537890981151984 0.01412919215620267 0.01816691445218831 +-0.0133382874 0.0125402967 -0.0166018605 +-0.01312031485004268 0.02006972435561529 0.01935067427873702 +-0.01253709495317167 0.02678426624794627 0.01899463258945117 +-0.0112033458 0.00086672313 -0.00259883353 +-0.01161471322689774 0.03262413906142276 0.01740619247130913 +-0.01010347402088961 0.03866074590778109 0.01409764314292752 +-0.0107818209 0.042580612 0.00824850611 +-0.0106606958 0.0352396443 -0.0154399844 +-0.0102168918 0.0437435731 -0.0024775553 +-0.008071082145155015 0.028150657073528 -0.01787521630507561 +-0.009804571979999999 0.00449762167 0.0103354435 +-0.009711671620000001 0.00940770749 0.0159354415 +-0.00929959491 0.00139633974 0.0032987718 +-0.008731061668238015 0.04364169891919962 0.003006055023071116 +-0.008912986140000001 0.00312193669 -0.00846305862 +-0.00917714535810752 0.04065595929312391 -0.01128024792929794 +-0.00869166851 0.00662373379 -0.0125971008 +-0.007681948653675115 0.01455715752194286 0.01858753419602688 +-0.006053069468066842 0.02045291377521854 -0.01818220837882895 +-0.005008254711600432 0.02071492450317532 0.01947253876299418 +-0.003758317084889069 0.02737304705944828 0.01887924779327533 +-0.004317203638199386 0.01205681830195021 -0.01643275785483107 +-0.00310213701 0.0346861742 -0.0154968472 +-0.001969603106809912 0.04365235911999837 -0.001316240836097405 +-0.00197649002 0.0333067961 0.0171570703 +-0.001252016023581475 0.002106196467731641 -0.006228966921644648 +-0.00191286649 0.0401224121 0.0123789078 +-0.002319792231715816 0.005563255713344227 0.01209350088378648 +-0.002478214038790718 0.04318275924857944 0.005909177960443506 +-0.00161360402 0.006018552 -0.0118231447 +-0.00060401368 0.0117802061 0.0173396915 +-0.000950992536777889 0.002282544802085986 0.004353648017490263 +-0.00036993227 0.0418592058 -0.009538536889999999 +-0.000363129395 0.0387799069 -0.0133747039 +3.22785854e-06 0.0276072361 -0.0178771149 +0.003078798427084015 0.02019949091304991 -0.01794825459680359 +0.00330328685 0.0201000422 0.0197216831 +0.003903166268209923 0.02817850414840042 0.01899888381757995 +0.00516663585 0.0061012283 -0.0110501414 +0.00517711416 0.0125194434 -0.0165840201 +0.00526071526 0.00364613114 0.008497200910000001 +0.00592743838 0.0335344225 -0.0161430016 +0.0063421973 0.0349959321 0.0165571347 +0.00637653703 0.00258364622 -0.00550256297 +0.00647104252 0.00734008895 0.0136049641 +0.00654121861 0.0419042259 -0.00691652671 +0.00690129912 0.0425271057 0.00871247612 +0.006869313183117642 0.04383481292446845 0.0007363125969336522 +0.00768950023 0.0377592705 -0.0137050543 +0.007925150362733167 0.01358459820271965 0.01769205340984014 +0.008529162341073175 0.002652634462837034 0.003302108264252645 +0.009292948614242626 0.02724635936238232 -0.01776057014300612 +0.01204157932646815 0.01999895326579215 0.01935774208936095 +0.0123681162719429 0.005002333989438702 0.009770208867291351 +0.0122814234 0.0123562478 -0.0153865172 +0.01246684866008367 0.02889460447711264 0.01881662352070369 +0.0126570612 0.00243676011 -0.00127022958 +0.01330489184532292 0.005993399997360749 -0.009782977348011477 +0.01374157579974843 0.04410537656040649 0.004776449592476611 +0.01298936328984628 0.01045019649166554 0.01506560313592625 +0.0131048774 0.0206797346 -0.0180065818 +0.01323068391555313 0.0366285647560731 0.0157697829740453 +0.0145066017 0.0330058113 -0.0165374894 +0.0156523604 0.0437536798 -0.00650669867 +0.01685393725734878 0.04441026273881249 -0.0009662913847590282 +0.0160456188 0.00366567727 0.00454390608 +0.0163637064 0.0430800207 0.00943026319 +0.0171253402 0.03828701 -0.0141017195 +0.0186047498 0.0234314054 0.0193354692 +0.019099243 0.00491793221 -0.00640536239 +0.01788934126814441 0.02803082938519154 -0.01759986016992315 +0.01983772620510506 0.03163654510871074 0.018420231920109 +0.0195339397 0.00623788126 0.00986984558 +0.0196750779 0.014113267 0.017238887 +0.02082172092641603 0.04481353872847039 0.002760508990022895 +0.020773869 0.0166618805 -0.0169365294 +0.0212306101 0.0400626287 0.0142258452 +0.02101086284637052 0.009350006370172194 -0.01259633419562702 +0.02035404433284264 0.02271747646344754 -0.01778850862538321 +0.0233901516 0.00423803274 0.000956238306 +0.0237011481 0.0441019759 0.00818124041 +0.02499375720431396 0.03433717126664652 -0.01613282223973173 +0.0244079214 0.0445832461 -0.004467397 +0.024430776 0.0420512781 -0.011836946 +0.02571920727619268 0.02664333675338492 0.0194665992862569 +0.0260543209 0.0171166826 0.018022852 +0.0264068842 0.0108286943 0.0139747672 +0.0264847893 0.00554576609 0.00588176446 +0.02734785364042242 0.006119631752593333 -0.005569087123163672 +0.02729848533819529 0.03512350992505663 0.0173203253712286 +0.0280050579 0.0458500348 0.00182764546 +0.0281762984 0.0264992453 -0.0175755806 +0.02785413312991091 0.01968449960143727 -0.01722122204370137 +0.028726032 0.0424586833 0.0131679615 +0.0302646868 0.0448487923 -0.008906295519999999 +0.0303494763 0.0141799077 -0.0154678933 +0.0303622 0.0453136936 0.00671803346 +0.0305360463 0.00932488404 -0.0107794115 +0.03117596271414536 0.005435156947331207 0.001865776157706071 +0.03153035589994397 0.02246495829663936 0.01950597020836702 +0.03228446783961818 0.03892118433037444 -0.01446343259990804 +0.0325025767 0.00757192215 0.00890325569 +0.0333169341316644 0.01493380124004088 0.01660622470437735 +0.03274641742534677 0.03033318954450352 0.01877069289886897 +0.0346242972 0.0220167637 -0.017560862 +0.0349714272 0.0464289635 -0.00458746124 +0.0350165516 0.0313316137 -0.0167805888 +0.0354733467 0.0393451825 0.0155258998 +0.0365410510869175 0.04669364476437342 0.00128171103214658 +0.0364774019 0.00750768092 0.00496192882 +0.0366819724 0.0454092659 0.00808882061 +0.0368045643 0.00709279766 -0.0025071362 +0.0383023918 0.0433238335 -0.0125643713 +0.03841367680015341 0.02259152302657078 0.0188992620981856 +0.0398453996 0.013372845 0.014766952 +0.04116571623812505 0.03775694694409977 -0.01556551840767361 +0.04039426876352357 0.03307291498188766 0.01824969454996976 +0.0409615077 0.0154717332 -0.0144360894 +0.04153675423897917 0.01139623646496346 -0.009458208020943167 +0.0416469574 0.0248026494 -0.0172117837 +0.0434931347995678 0.008981135948252755 0.004356104405147658 +0.04357888174419614 0.03225795511425052 -0.01721048274910126 +0.0433636727129388 0.04818056759373006 -0.003637473734780637 +0.0448808484 0.0472434387 -0.00963132177 +0.0450029895 0.0411733165 0.0151776625 +0.04522266555423467 0.02698822026037207 0.01921210985070036 +0.0455205515 0.0487820953 0.0019545306 +0.04587337529156165 0.04682476496112696 0.008779271787431157 +0.04578881344456253 0.04281444989595707 -0.01403728852561119 +0.046402026 0.00972706359 -0.0015060578 +0.0464336202 0.0190062337 0.0171132833 +0.04691194144549375 0.02136398699203504 -0.01671232367442681 +0.047810398 0.0266996529 -0.0175361224 +0.0487265624 0.0121764066 0.010678024 +0.0489669852 0.017151475 -0.014020171 +0.05061454104440424 0.03892893455240178 -0.01625785962555614 +0.04885737904966728 0.03402951277728664 0.0181543562809737 +0.05091911861133105 0.01396341736591928 -0.01019592374437307 +0.0523986854 0.0274757333 0.0187325235 +0.0530002266 0.0493078604 -0.00929273758 +0.05310967079440922 0.05036108131682657 -0.003785246501181473 +0.0531420708 0.0467978716 0.0110234935 +0.053153269 0.0444855317 -0.0141419163 +0.05376529506620305 0.03266471836515882 -0.01752809737121597 +0.0533675179 0.0110052992 0.00295691472 +0.0538544916 0.0249610767 -0.016962735 +0.0543184243 0.0503391363 0.00294281892 +0.054498028 0.0120780757 -0.0034863695 +0.0545213819 0.0176365916 0.0147131979 +0.0548543967 0.0398348123 0.0162701644 +0.0554010347 0.0131984167 0.00813175272 +0.0560664199 0.0197091717 -0.0143852327 +0.05720052979797714 0.03333547742686571 0.01804840081313483 +0.0601324588 0.0253486428 0.0174433403 +0.06085879808170194 0.04027165950361605 -0.01681392038386272 +0.06028195378870806 0.05202649205852616 -0.002831574192920875 +0.0608074814 0.0512592569 -0.00806587376 +0.06153641067055232 0.0311432334871851 -0.01786917877950289 +0.0612438843 0.0166715123 -0.00946522877 +0.06216698766945082 0.04791677918025125 -0.01366515597705591 +0.0618302524 0.0137341451 -0.00199688273 +0.0619205497 0.0447128266 0.0139696822 +0.0619942509 0.0231544208 -0.0166259669 +0.0621569529 0.0184036363 0.0122330068 +0.0622782772292035 0.05076036239469739 0.007512147547378043 +0.0628284514 0.01450592 0.00518588582 +0.0637719184 0.037711259 0.0170023777 +0.06533126765486001 0.05280976674404998 0.0009776047627915942 +0.06622079203018877 0.03137414525613443 0.01754302948539752 +0.0673466772 0.0207098406 -0.0138268862 +0.06833251478074159 0.05331141681481687 -0.005203578428044872 +0.0688039064 0.0242079254 0.0149657 +0.06872069480422398 0.02665953587401521 -0.01738527954854729 +0.0691395029 0.017709069 -0.00829913467 +0.06957291810000001 0.0487165414 0.0121200001 +0.07056589332838169 0.01658999287464418 0.0004634192999927782 +0.06961827451993154 0.04317550162487727 -0.01673111293195457 +0.07042256486553544 0.03617564351289553 -0.01833731568122959 +0.06977339354994293 0.04325278786428565 0.01485546864576196 +0.07083552329999999 0.0520235561 -0.0117781116 +0.0705501977281698 0.05287921192276616 0.005064445727645842 +0.0714384839 0.0185762439 0.00775142247 +0.0721500814 0.0359498076 0.0164267477 +0.0722871235702347 0.05402644540269597 -0.0004160508872610703 +0.0736598894 0.0218374245 -0.013271817 +0.0741636083 0.030591052 0.0162078645 +0.07624816563382658 0.04760646490197727 0.01230842474676029 +0.0761677176 0.028920861 -0.0176278837 +0.0766709074 0.0191256609 -0.00659181131 +0.0770616755 0.054550495 -0.00522641931 +0.07726186509999999 0.0251255203 0.0130709084 +0.0773009583 0.0524023809 0.008152724240000001 +0.07761785390000001 0.0419799574 -0.0175676141 +0.077728793 0.0425962433 0.0144307753 +0.077809751 0.0478065647 -0.0158353634 +0.07851800320000001 0.0187308379 0.00240374799 +0.0789479017 0.0545863621 0.00126891944 +0.0790509433 0.0352232642 -0.0182239078 +0.07992590856450499 0.03630113699953997 0.01527257022295115 +0.0804934725 0.0249493904 -0.0124176173 +0.08097012312166418 0.05238911852539403 -0.01275296248335934 +0.0817756951 0.0218145251 0.00738330279 +0.0830050781 0.0480286889 0.0112593574 +0.08408012989999999 0.0308908112 -0.0166966505 +0.0841493011 0.0538398288 0.00472319964 +0.0843247771 0.0325709134 0.0137142539 +0.0845583528 0.0214127749 -0.0063349288 +0.08468014 0.0273386538 0.011350777 +0.0846964791 0.0547103137 -0.00358114438 +0.084701702 0.0469696373 -0.0158727467 +0.08557409050000001 0.0418253914 0.0130624874 +0.0868452638 0.039044328 -0.0171579607 +0.08845402300000001 0.0228017271 0.00239626062 +0.08873754740000001 0.0534380265 -0.0105227344 +0.08895747971465896 0.02583182545496136 -0.01090829059327477 +0.0891430303 0.0356594212 0.0123840589 +0.0892554596 0.0268291626 0.0087043969 +0.0902603418 0.0500835702 0.00853037555 +0.0905929506 0.0539270565 -0.00246224785 +0.09060554949999999 0.0459265411 -0.0150435511 +0.091622442 0.0240026768 -0.00555973779 +0.0920444503 0.0420676395 0.0105621004 +0.0929391235 0.0339859873 -0.0149719017 +0.09534584729999999 0.0510222353 -0.0123506784 +0.0956979766 0.0389189199 0.00921003986 +0.09608012648152274 0.02900050459573733 -0.00881247983783889 +0.0960012749 0.0533800572 0.00013485919 +0.0967484564 0.0270211212 -0.00182953326 +0.0971835554 0.0318373144 0.00650368771 +0.0972699001 0.0406950898 -0.014138204 +0.09855292114140504 0.04825954413822846 0.006330416870405102 +0.0989532322 0.0537809692 -0.00584771764 +0.100667767 0.0351431556 -0.0113685615 +0.101897255 0.0409820937 0.00579162315 +0.102422468 0.0496410951 -0.0114692515 +0.102486059 0.0536840931 -0.00196843385 +0.103502236 0.0329613127 -0.00502190506 +0.103512958 0.0340141468 0.00194595614 +0.104581229 0.0409179442 -0.0116717145 +0.106261872 0.0482215509 0.00298773823 +0.106378697 0.0535726398 -0.00484610675 +0.1063747463479973 0.03875695647723847 -0.008936833623345443 +0.107711658 0.0506652333 -0.010402129 +0.107752681 0.0407195948 0.00241104001 +0.109060287 0.0378545709 -0.00215689023 +0.109191135 0.0525636002 -0.000231599261 +0.1093260686511559 0.03954309593272445 -0.00625861592353311 +0.110452116 0.0506237 0.00126777519 +0.110844463 0.045697622 0.0012379525 +0.111501828 0.0463481732 -0.0085984515 +0.111746982 0.0523613989 -0.00599241722 +0.111868247 0.0518817231 -0.00322257355 +0.113049246 0.043096032 -0.00139316579 +0.112991235124088 0.04921085674878788 -0.001121831136591144 +0.1132849649411618 0.04307785920440848 -0.005754519569307968 +0.113626279 0.0481025353 -0.00458682561 +-0.01092231361847169 0.02522260121786788 -0.0001730897159843545 +-0.03441059596361942 0.03283384072616163 0.007846900169526754 +0.002401779883681811 0.02978395666807166 0.0006744909168328026 +-0.03834698213722563 0.02906401713821102 -0.0105291274711592 +0.03071955811570532 0.01854928898259279 0.004478675083911933 +-0.08355394791718715 0.05606408011020431 -0.002203600453475583 +-0.03050278701197 0.03170410307445894 -0.005949282049790281 +-0.08795478485560912 0.03776743567531785 0.0002684031461906517 +-0.08930596161141631 0.04784245251411157 -0.009411877164453217 +-0.09255610945858689 0.05050512743499239 0.00352010753411364 +-0.09058832851694783 0.06426132349653581 -0.001000194671873349 +-0.05902704417813314 0.02700188360231915 0.009171450980155387 +-0.002634012272084254 0.03618319005468262 0.005943435204621119 +-0.0682538042873776 0.03111142441459394 0.004359665339393123 +-0.07680186624269664 0.03781720669396579 -0.0113954102240863 +-0.07652356983537831 0.03827336566043763 0.005524950677077373 +-0.07504567573940801 0.050930134140291 -0.009054318340404105 +-0.07386641883864771 0.05210599127790605 0.003215907410014902 +-0.06279627250482542 0.02490654173302122 -0.009837324040070738 +-0.06347611580562533 0.03810284302505331 -0.009908592452778538 +-0.04959754261443537 0.02473256155591715 -0.01061665594671841 +-0.05037828717828955 0.04263215134011838 0.00332019108335166 +-0.03523559164971268 0.0132733754326466 -0.00233742134188962 +-0.0422314030960167 0.03137351895736502 -0.001085625126677774 +-0.02240813292779155 0.02259904091056965 -0.001163589286321974 +-0.02456139384853181 0.01023781164105522 -0.000289611259596334 +-0.02394697403909913 0.02609419395269253 -0.01175445779728864 +-0.02554746423147653 0.02668691455639158 0.01075977081057946 +-0.02078314412946644 0.03572903453154451 -0.005885193584560512 +-0.01297381775368888 0.01088066860731818 -0.001812044374546752 +-0.01059853755106339 0.03022971836297131 -0.009537189943658942 +-0.0119040248733615 0.02732273657316266 0.01067123029294114 +-0.001477419742766834 0.009357818110208164 -0.001858825534193085 +0.0008830670636432656 0.02917663570874922 -0.009694690458305032 +0.01279273997066107 0.01031751672304487 0.0009602101053325898 +0.01260089528673857 0.02441376906053566 -0.0100910206955324 +0.009195840267951082 0.02214474969795697 0.01129509105785812 +0.02628210248080019 0.027386954289592 -0.008750274241572946 +0.02708451039056261 0.02469927950157333 0.01251040852561907 +0.02505679337023908 0.03804328625807699 -0.002599963201148916 +0.03927695651745015 0.02545694157762788 -0.0009284044443443132 +0.03928126143388986 0.02414503802453039 0.01073448572637934 +0.0370502201926533 0.03856359112665766 -0.002107821638751924 +0.05211601823359577 0.01988321760309566 -0.002686866600153209 +0.05325967413028983 0.02437509549501554 0.009113612779492641 +0.04897691197234653 0.04106314674131126 -0.004378936936204025 +-0.03908329356947123 0.02159642778792562 0.009492007856662866 +0.06299916661470012 0.02507495950068745 0.001064344838784517 +-0.07081317231925509 0.04120627568295007 -0.003681100873784661 +0.06267916107211945 0.0429936366417902 0.00237219353695309 +0.07444863332370875 0.02627250126168394 -0.0003130580726575519 +0.07696093994150691 0.03773826910102241 -0.01042484366723835 +0.0894537624382172 0.03585749822866035 -0.001484461026678817 +-0.01518703447043772 0.01998736912379773 -0.008301760289609605 +-0.009625840574258073 0.03623879675257015 0.0003944516324030191 +0.0131981348295673 0.03475363129123801 -0.002887731579891785 +-0.06296964564458182 0.04171006402017211 0.005418873873326202 +-0.06294304772864295 0.02122134293365293 0.002650756040639772 +-0.03328892041211258 0.03947426667308616 -0.002183894851629673 +-0.08096913854508227 0.04563901542917307 -0.002114032842410222 +0.027736632199744 0.01147511036786991 0.0005092154984192043 +0.04009700859857675 0.04301013782476364 0.01209616433404469 +0.08495970155190577 0.04719292890773084 0.001978566727173186 +0.02059997009972326 0.01643020692306375 0.006883169445369788 +0.04888874636833003 0.0282900119709008 0.0007577097980756503 +-0.0338852117292914 0.02410576765961941 -0.0005213264434447172 +0.01276457482106836 0.02202823243876706 0.001464025545818877 +-0.03816055865918792 0.02160777416597316 -0.01143857323046978 +-0.03784327798154182 0.03657486198870281 -0.009679462875609066 +-0.04998726342069369 0.03145310685767266 0.009573582221558624 +0.05570564908372268 0.03399044612126179 -0.0003380287132844221 +0.000297453923834604 0.02923810081964794 0.01114562752120422 +-0.07659624915950899 0.0289366550490384 -0.004814063379771766 +0.06619357591655192 0.0325154279073399 -0.009302319570401342 +-0.09788683169387166 0.05699469529401796 -0.004519722145723871 +0.07168228337340055 0.0357114136399176 -0.0005070507918751775 +0.06650782267085097 0.03301735192344966 0.009529892218824686 +-0.04234159674061519 0.03916762007389672 0.007366549832882003 +0.03360177872778956 0.01705604551183981 -0.006467349195777075 +-0.00336929034500934 0.01867485281396427 0.008403079811178315 +-0.04421923694636813 0.01787684429740002 -0.005925387890777815 +-0.005580235120164435 0.01856330003696153 -0.007734498550205232 +-0.0300297829369998 0.02108449955798409 -0.009976057664183404 +0.04673905040352116 0.03338588276945499 0.009067795431033246 +0.005916165757296593 0.01522725132249416 -0.007365580882098064 +0.02075003197821276 0.02674632450147826 0.001246382211343102 +-0.1067408693773577 0.1049565928324934 0.005020411874885417 +-0.05591972612663118 0.0309687458041341 -0.002042331686823667 +0.004983506865807125 0.01778919096185712 0.002542766781044406 +-0.1054516927106262 0.1065166049145303 0.004861201255330327 +0.02140578503135192 0.01578109778010403 -0.006498661519295235 +-0.1056624406346005 0.1001972986704059 0.001252949862679899 +-0.1023342926135479 0.08315083710534414 4.804208709481498e-05 +-0.1062575446601619 0.0835014516577586 0.003490782401680291 +0.05756311645508917 0.03960286773107863 -0.008684902570827276 +-0.0467245394226038 0.03743487224659591 -0.009290566313511859 +-0.01549327716040606 0.01549302850005239 0.008780709386324028 +-0.1058128154543407 0.09387692782053059 -1.281696491277702e-05 +-0.07091042384904703 0.02271003393144969 -0.001923440619917352 +-0.1051159813589014 0.08797177518256441 -0.0007548251784316361 +-0.106208871577951 0.1052617445338719 0.001868672685061138 +0.046811301638172 0.01772330100211507 0.004235519837837503 +0.1018049814889918 0.04167665012026881 -0.00449130952248786 +0.08302912036645128 0.04649555824690086 -0.006193952789493239 +-0.03943667901804428 0.01568740765288772 -0.01182733907978534 +-0.04899177940415951 0.02524610907676883 0.002309895290648232 +-0.109643694 0.10144538065 0.00393639633 +0.04406814339555582 0.01765208862698166 -0.006771531415131779 +-0.06285946776810221 0.048189251752053 -0.006200020553388526 +-0.05509549735800796 0.04442530837082436 -0.004651362697399586 +-0.111073535 0.1061794425 -0.00280232931 +-0.04290193939874309 0.01324749060400373 0.004105759246252527 +-0.1062278973478537 0.1100715686299029 0.004343035828548236 +-0.1059330913180066 0.1102787510466343 0.001876617064436711 +-0.1096061815151413 0.1040286960869554 0.0003072202443567751 +-0.107839193 0.09244985135 0.00394979643 +-0.03422891091492952 0.01228746226217238 0.006849010863644372 +0.01945265067104895 0.03670196993052624 0.005236352758295424 +-0.05583723160263026 0.02188837993732594 0.004621514305261612 +-0.05236682011583365 0.01660624483935007 -0.0004744601140213432 +-0.1125736808546371 0.105354983713079 0.0015121780897632 +0.04688959373425483 0.03289137876810427 -0.009397918372038084 +0.09421368701478929 0.04608193411161425 -0.003688626111097404 +-0.04206624591026191 0.04199706423032433 -0.003697658960950867 +0.005938915623302768 0.01288069535682142 0.009553517104554087 +0.04598750178056762 0.02364621988633314 -0.01062903424210371 +0.01199285367795478 0.03260122616389747 0.009000565310953456 +-0.02821710077532826 0.01681501874213092 0.008143788694225263 +-0.1059131615665579 0.09784812613163091 0.00509000295037108 +0.0156294064825334 0.01819290681045979 0.01366866042698949 +0.03863310253168652 0.01605448771099142 0.007153335446449087 +-0.1124894027979566 0.1112801698866096 0.001518161223836466 +-0.1044968531082643 0.09613591999454056 0.002503304127103378 +-0.05534624061881979 0.04137869694696682 -0.01128829174933108 +0.02132074837926287 0.02009308653983551 0.01387305233639862 +-0.102943984055017 0.0874984417874685 0.001706095865979671 +0.05607489241406289 0.02718488601202736 -0.009443282143320844 +-0.1091091196453119 0.1112023194203194 0.001844247133032568 +-0.04278645387857377 0.02019614472463952 0.00174375781793838 +-0.05576092777888492 0.03319656360511353 -0.01236685611177493 +0.01086511333221656 0.01597802814744204 0.01337582043421375 +-0.1114872352147683 0.1080628930452143 0.00277021229862497 +-0.1041919820043917 0.08559402241793816 0.004115241508550427 +-0.1076263503759483 0.1109435384220822 0.002348341706677162 +-0.1017224359359822 0.08918213739750029 0.002193943193139914 +-0.02398381350847003 0.03454873746448017 0.003587260443549763 +0.01255198116323408 0.01520693748289608 0.01719595084468047 +0.0360126802519023 0.03654695006779942 0.006639475943065699 +-0.1117173810059402 0.1098429350879581 0.002452644698818752 +-0.1108632743001479 0.1077434748637959 7.55630390727269e-05 +-0.1005505163227177 0.08957777384757959 0.0026288764421573 +-0.1054758942098472 0.09062359257634685 0.002273372408725331 +-0.1065690541720665 0.1101697111194884 0.003216338982646989 +-0.1048211848506821 0.1087667969092068 0.004229945946730755 +-0.02238397762140855 0.01450843746122751 -0.009906468327401797 +-0.113243889 0.1119867865 1.5853495e-05 +0.06849215320076799 0.04386856173034787 -0.006994558258016505 +-0.07741957602419083 0.02872462611833411 0.004033547864764194 +-0.1093060220248247 0.1125614898520532 0.002421347460377496 +0.04953893042500859 0.04075967459515503 0.01001458092871107 +-0.1098090389293397 0.1127889460196909 0.003165332838890691 +-0.1008787286454354 0.0914787468951592 0.0024814984543146 +-0.1080241141351909 0.1088505720279953 0.002395268932334845 +-0.05718820941366266 0.01591270585578396 0.004734699624008916 +-0.1122286352668874 0.1117533108255472 -0.0006073201516319291 +-0.1122573832709412 0.1130067519457083 0.0009242099422828615 +-0.05661611215563907 0.01945680915429563 -0.006865353358187217 +-0.1099175046165722 0.1132374367001153 0.001304306188707353 +-0.100574333837556 0.08948623949027237 0.0002516242052713908 +-0.1107861363203182 0.112078875996816 0.001546341219367755 +-0.1020737814207706 0.09485399927686981 0.004185694324359149 +-0.1065445606254153 0.1119569977789698 0.0028563140651068 +-0.103739097021764 0.09085995652781846 0.004683516483106542 +-0.03282853951230116 0.01441174662663516 -0.01108339274948948 +-0.1029466417467556 0.09093625917500515 0.00189696234902427 +-0.1080918354001368 0.1122417784427192 0.002950265501974746 +-0.1107542769427391 0.1101034039358279 0.0009696354331017162 +-0.1134764766405509 0.1082571478687356 -0.001992090890499993 +-0.1127314827169076 0.1073051929478206 -6.115306395202877e-05 +0.04039274954820213 0.01504108029379518 -0.0005251173568942204 +-0.1103454076426075 0.1091438066439898 0.003639188955334978 +-0.110403994962605 0.1103285409421171 -0.001144748213529259 +0.05699257946342493 0.03697304867848195 0.008951108501266772 +0.03752115076611263 0.02354032762303219 -0.01044925598852527 +-0.1094299337441991 0.1116503525561777 -2.845772043146195e-05 +0.07972003069835083 0.03244894850771408 0.006844024580049999 +-0.1096984238676251 0.1136492787466266 0.002592697969449926 +-0.1073407764097394 0.1112951417237496 0.004249596335916353 +-0.1008930355 0.08993107454999999 0.00347315543 +0.0344740855333594 0.0327883197862325 0.0125417014584337 +0.05145588204283413 0.04202399725766797 0.004250167433536837 +0.1073328094810955 0.04659721372529622 -0.00464084958955067 +-0.1037336778701707 0.09305336002806489 0.002969308734906227 +-0.0616677631950707 0.01633632789632865 -0.002508111162056733 +-0.1132678559539734 0.1097221557629399 0.0002814835175057071 +0.03843780065959376 0.03182822095256005 -0.01007796544077533 +0.01356547753823769 0.01394417187239601 0.008470440145911076 +0.04324742607752676 0.04139546191785541 0.005242885368547954 +0.01820538098770258 0.02605756011940751 0.01062801568939279 +0.04012372566524034 0.03781851241000292 0.0111739226612276 +0.02601901396004718 0.01706299727777313 0.0122899772667361 +0.02778372240531071 0.03311931815313202 0.006563297922327718 +-0.07024123123212393 0.03111871682985411 -0.009791128114604379 +-0.08116027465331531 0.045943190909764 0.007902102085495662 +-0.0496897324650685 0.01871284235740062 0.008485447988136847 +0.1009041038248251 0.04817228371037524 -0.001145137299415997 +0.07520549687042179 0.04414495778707539 0.003763204497485193 +-0.002878485788560608 0.01032400833105909 0.008381796103960646 + +CELLS 2395 11975 +4 356 595 353 607 +4 2 695 637 666 +4 2 6 7 13 +4 2 631 637 6 +4 691 689 65 709 +4 682 11 686 8 +4 6 16 9 7 +4 6 7 13 16 +4 6 623 631 12 +4 7 9 14 614 +4 7 614 16 9 +4 99 112 113 522 +4 18 704 660 692 +4 594 518 540 575 +4 358 607 338 349 +4 358 595 607 577 +4 648 686 682 5 +4 708 505 504 619 +4 579 620 479 639 +4 413 593 429 414 +4 9 616 15 14 +4 686 11 684 8 +4 17 21 19 20 +4 327 634 643 319 +4 14 15 31 49 +4 14 15 49 616 +4 319 634 335 327 +4 14 616 49 26 +4 15 31 25 24 +4 15 25 31 39 +4 15 49 39 31 +4 213 229 633 644 +4 15 39 49 610 +4 645 36 55 608 +4 16 608 36 645 +4 17 18 692 30 +4 376 373 712 638 +4 17 21 20 30 +4 18 704 33 679 +4 394 411 618 561 +4 129 674 127 530 +4 397 410 600 385 +4 478 487 491 639 +4 22 29 27 23 +4 22 27 29 57 +4 22 57 43 27 +4 22 29 38 591 +4 22 591 57 29 +4 501 506 708 512 +4 41 591 22 45 +4 591 38 45 526 +4 22 43 57 591 +4 22 38 45 591 +4 23 24 25 37 +4 23 46 27 24 +4 23 24 37 46 +4 191 193 209 628 +4 23 27 46 72 +4 23 72 37 29 +4 23 72 46 37 +4 24 63 31 25 +4 24 25 37 63 +4 24 63 46 31 +4 24 37 46 63 +4 25 31 39 63 +4 25 37 63 39 +4 37 76 63 39 +4 492 722 708 501 +4 20 34 30 21 +4 613 271 546 724 +4 369 383 387 714 +4 27 29 57 72 +4 27 72 57 46 +4 29 591 70 38 +4 29 57 72 591 +4 31 39 63 49 +4 39 609 63 49 +4 32 50 47 630 +4 708 509 515 516 +4 152 625 166 157 +4 37 46 63 72 +4 37 76 72 63 +4 528 586 622 604 +4 316 715 553 643 +4 38 526 60 45 +4 38 526 80 60 +4 38 70 80 591 +4 38 80 526 591 +4 63 49 609 75 +4 39 63 609 78 +4 39 78 76 63 +4 39 78 609 69 +4 39 69 76 78 +4 63 78 75 609 +4 41 591 59 43 +4 41 45 67 526 +4 41 526 67 73 +4 42 54 630 47 +4 42 47 51 54 +4 43 591 84 57 +4 43 59 83 591 +4 43 591 83 84 +4 44 649 709 614 +4 44 649 687 709 +4 44 614 709 668 +4 45 60 77 526 +4 45 526 77 67 +4 49 56 74 75 +4 50 58 54 52 +4 671 599 542 541 +4 57 591 87 72 +4 57 84 87 591 +4 59 79 81 525 +4 59 79 525 73 +4 59 81 83 525 +4 137 574 615 146 +4 60 526 86 77 +4 60 80 86 526 +4 530 574 146 615 +4 63 72 85 92 +4 63 75 78 92 +4 63 92 85 75 +4 724 301 641 305 +4 63 92 78 76 +4 65 678 691 66 +4 67 524 82 73 +4 253 613 271 258 +4 67 526 524 73 +4 67 77 89 524 +4 67 77 524 526 +4 67 524 89 82 +4 183 190 199 594 +4 245 545 238 256 +4 70 76 88 93 +4 70 93 92 76 +4 70 527 88 80 +4 70 527 93 88 +4 70 92 93 527 +4 482 466 569 476 +4 72 527 87 85 +4 72 85 92 527 +4 73 524 90 79 +4 73 82 91 524 +4 73 524 91 90 +4 674 124 119 615 +4 76 93 92 78 +4 77 86 94 526 +4 77 94 524 526 +4 79 525 95 81 +4 79 90 95 524 +4 79 525 524 95 +4 546 517 613 596 +4 79 524 525 73 +4 80 526 99 86 +4 547 517 598 550 +4 80 88 99 527 +4 80 99 526 527 +4 81 525 97 83 +4 81 95 97 525 +4 82 89 96 524 +4 82 524 96 91 +4 83 525 98 84 +4 83 97 98 525 +4 84 591 101 87 +4 84 98 101 525 +4 84 591 525 101 +4 22 591 41 43 +4 85 87 100 527 +4 85 527 100 92 +4 86 526 103 94 +4 86 99 103 526 +4 87 527 101 100 +4 88 93 102 527 +4 88 527 102 99 +4 89 94 108 524 +4 89 94 524 77 +4 89 524 109 96 +4 89 108 109 524 +4 90 91 105 524 +4 90 524 104 95 +4 90 524 105 104 +4 91 96 107 524 +4 91 524 107 105 +4 92 527 106 93 +4 92 100 106 527 +4 93 527 106 102 +4 95 525 110 97 +4 95 104 110 531 +4 95 531 524 104 +4 95 110 525 531 +4 95 531 525 524 +4 96 524 111 107 +4 96 109 111 524 +4 97 525 114 98 +4 97 110 115 525 +4 97 525 115 114 +4 98 525 117 101 +4 98 114 117 525 +4 99 102 112 527 +4 99 526 113 103 +4 99 522 526 527 +4 99 112 522 527 +4 100 101 122 527 +4 100 527 121 106 +4 100 527 122 121 +4 101 117 122 522 +4 101 527 522 122 +4 102 106 118 527 +4 102 527 118 112 +4 103 720 116 108 +4 103 113 116 720 +4 103 720 526 113 +4 104 531 126 110 +4 104 120 126 531 +4 105 119 123 589 +4 105 589 123 120 +4 396 404 611 638 +4 105 107 119 674 +4 105 119 589 674 +4 106 527 121 118 +4 107 124 119 674 +4 204 585 220 207 +4 108 116 125 720 +4 109 532 127 111 +4 109 111 524 532 +4 109 125 127 532 +4 110 531 130 115 +4 110 115 525 531 +4 110 126 130 531 +4 127 139 530 532 +4 111 674 129 124 +4 112 534 128 113 +4 112 118 128 534 +4 134 615 151 144 +4 112 522 527 118 +4 113 720 132 116 +4 113 128 132 534 +4 507 497 619 502 +4 114 115 131 533 +4 114 533 525 115 +4 114 533 135 117 +4 114 117 525 533 +4 114 131 135 533 +4 115 130 131 531 +4 115 533 531 131 +4 115 525 531 533 +4 116 132 136 720 +4 117 533 140 122 +4 117 122 522 533 +4 117 135 140 533 +4 118 121 138 534 +4 118 534 138 128 +4 589 123 615 119 +4 120 531 143 126 +4 120 133 143 719 +4 120 589 123 133 +4 121 522 527 122 +4 121 534 141 138 +4 122 140 141 533 +4 123 119 134 615 +4 111 107 674 124 +4 124 615 146 137 +4 125 532 139 127 +4 125 136 139 532 +4 126 531 147 130 +4 126 143 147 531 +4 145 139 530 127 +4 128 534 142 132 +4 128 138 142 534 +4 129 127 145 530 +4 674 589 530 615 +4 130 531 148 131 +4 130 147 148 531 +4 131 533 152 135 +4 131 148 152 531 +4 131 533 531 152 +4 132 534 149 136 +4 132 142 149 534 +4 133 535 150 143 +4 133 144 150 535 +4 144 615 123 134 +4 133 615 589 123 +4 134 137 153 574 +4 134 615 119 137 +4 615 535 710 151 +4 134 710 153 151 +4 135 533 157 140 +4 135 152 157 533 +4 136 573 154 139 +4 136 149 154 573 +4 137 146 160 574 +4 137 615 119 124 +4 137 574 160 153 +4 138 141 158 534 +4 138 534 158 156 +4 139 530 155 145 +4 139 530 573 155 +4 140 533 159 141 +4 140 157 159 533 +4 141 534 159 158 +4 141 534 533 159 +4 142 534 156 149 +4 142 534 138 156 +4 143 535 163 147 +4 143 147 531 719 +4 143 150 163 535 +4 144 535 162 150 +4 144 151 162 535 +4 147 536 164 148 +4 147 148 531 536 +4 147 175 164 535 +4 147 536 535 164 +4 147 531 719 536 +4 148 536 168 152 +4 148 152 531 536 +4 148 164 168 536 +4 149 573 170 169 +4 149 156 170 573 +4 149 573 534 156 +4 150 162 176 535 +4 150 535 176 163 +4 151 153 165 710 +4 152 157 533 625 +4 152 536 168 166 +4 153 710 174 165 +4 154 573 171 155 +4 154 573 149 169 +4 154 169 171 573 +4 155 528 172 161 +4 155 171 172 528 +4 155 171 528 573 +4 156 158 177 573 +4 156 573 534 158 +4 156 573 177 170 +4 157 625 173 159 +4 157 159 533 625 +4 157 178 173 625 +4 158 573 179 177 +4 159 173 179 625 +4 159 625 534 533 +4 161 182 528 172 +4 162 165 181 683 +4 162 683 181 176 +4 162 176 535 683 +4 163 535 175 147 +4 163 175 535 185 +4 163 185 535 176 +4 185 537 535 176 +4 306 308 519 572 +4 165 191 181 636 +4 165 636 710 174 +4 166 168 192 650 +4 166 650 192 178 +4 167 721 184 180 +4 307 572 519 308 +4 167 182 184 721 +4 307 519 572 643 +4 168 187 192 650 +4 550 519 601 552 +4 601 551 607 583 +4 169 586 188 171 +4 169 171 573 586 +4 170 177 190 538 +4 170 538 573 177 +4 170 538 190 183 +4 171 586 189 172 +4 171 172 528 586 +4 171 188 189 586 +4 171 528 573 586 +4 173 178 186 626 +4 173 626 186 179 +4 174 636 191 165 +4 174 636 193 191 +4 175 535 185 537 +4 175 185 194 537 +4 175 537 194 187 +4 176 181 197 537 +4 176 537 197 185 +4 177 179 195 538 +4 177 538 573 179 +4 177 538 195 190 +4 178 186 192 200 +4 178 626 192 186 +4 179 201 195 538 +4 179 538 626 186 +4 180 196 193 721 +4 181 197 537 597 +4 181 537 636 597 +4 190 538 208 594 +4 190 594 208 199 +4 185 537 205 194 +4 185 197 205 537 +4 626 612 650 192 +4 186 538 201 179 +4 570 547 517 598 +4 570 547 541 517 +4 187 612 207 192 +4 187 192 650 612 +4 187 204 207 612 +4 187 612 194 204 +4 671 257 570 261 +4 261 257 570 598 +4 189 202 586 206 +4 190 195 208 538 +4 188 183 594 538 +4 191 628 636 193 +4 192 612 215 200 +4 193 196 210 628 +4 209 628 210 539 +4 194 520 211 204 +4 194 205 211 584 +4 194 584 537 205 +4 284 519 308 529 +4 196 628 213 210 +4 197 203 216 621 +4 197 621 214 205 +4 197 205 537 597 +4 197 621 216 214 +4 199 208 219 594 +4 200 640 218 201 +4 200 215 218 640 +4 201 640 218 217 +4 362 647 521 363 +4 362 370 521 647 +4 363 521 555 558 +4 203 209 222 539 +4 582 644 541 544 +4 203 539 222 216 +4 662 523 541 582 +4 370 647 696 521 +4 204 612 585 207 +4 204 211 220 520 +4 205 584 223 211 +4 205 214 223 621 +4 208 217 231 594 +4 208 594 231 219 +4 209 210 225 539 +4 209 539 233 222 +4 209 225 233 539 +4 224 213 563 644 +4 210 633 229 225 +4 211 520 232 220 +4 211 223 232 599 +4 212 221 224 563 +4 224 229 213 644 +4 213 224 563 212 +4 214 216 228 690 +4 214 690 228 223 +4 215 575 234 218 +4 215 207 226 585 +4 216 222 230 539 +4 216 690 230 228 +4 217 218 235 575 +4 217 575 235 231 +4 218 234 235 575 +4 219 227 518 237 +4 207 585 220 226 +4 220 232 238 543 +4 220 543 520 232 +4 221 544 236 224 +4 221 227 236 544 +4 222 542 239 230 +4 222 230 539 542 +4 222 233 239 542 +4 222 542 539 233 +4 223 228 244 599 +4 223 599 690 228 +4 223 543 241 232 +4 223 232 599 543 +4 223 543 244 241 +4 224 644 242 229 +4 210 213 633 628 +4 224 236 242 544 +4 212 221 563 202 +4 225 229 240 542 +4 225 542 633 229 +4 225 542 240 233 +4 225 233 539 542 +4 276 293 571 547 +4 226 545 238 245 +4 226 523 585 220 +4 227 544 246 236 +4 227 237 246 544 +4 228 230 243 671 +4 228 671 690 230 +4 228 243 244 671 +4 547 571 517 550 +4 228 690 671 599 +4 229 542 253 240 +4 229 242 253 644 +4 239 671 542 259 +4 231 235 252 662 +4 231 662 252 247 +4 232 543 251 238 +4 232 241 251 543 +4 233 542 250 239 +4 233 240 248 542 +4 233 248 250 542 +4 234 545 254 235 +4 234 226 245 545 +4 234 245 254 545 +4 235 545 254 252 +4 236 544 249 242 +4 236 246 249 544 +4 237 544 255 246 +4 238 251 256 545 +4 243 671 239 259 +4 239 250 259 542 +4 240 542 258 248 +4 206 202 563 221 +4 240 253 258 542 +4 241 244 257 543 +4 227 237 544 518 +4 241 543 257 251 +4 242 249 260 613 +4 242 613 260 253 +4 242 253 644 613 +4 242 644 544 613 +4 243 671 261 244 +4 243 259 261 671 +4 230 239 671 542 +4 244 671 261 257 +4 244 257 543 671 +4 245 545 256 254 +4 246 548 263 249 +4 246 249 544 548 +4 246 255 265 548 +4 246 548 544 255 +4 246 548 265 263 +4 248 546 273 264 +4 248 250 542 546 +4 248 258 273 546 +4 248 546 542 258 +4 226 238 523 220 +4 249 548 262 260 +4 249 260 613 548 +4 249 548 263 262 +4 525 576 531 533 +4 250 546 264 275 +4 525 576 533 522 +4 250 259 542 546 +4 250 248 264 546 +4 251 547 268 256 +4 251 256 545 547 +4 251 257 270 547 +4 251 547 543 257 +4 251 547 270 268 +4 226 523 238 545 +4 252 254 269 545 +4 596 598 519 605 +4 253 613 272 271 +4 253 260 272 613 +4 613 258 542 546 +4 255 548 266 265 +4 255 548 247 266 +4 256 268 276 547 +4 251 545 238 543 +4 257 547 279 270 +4 258 271 273 546 +4 259 546 277 261 +4 259 250 275 546 +4 259 275 277 546 +4 260 262 278 548 +4 260 272 613 278 +4 261 277 282 598 +4 261 279 598 282 +4 262 263 280 548 +4 262 548 280 278 +4 263 265 281 548 +4 263 548 281 280 +4 264 273 286 549 +4 264 549 546 273 +4 264 549 286 275 +4 264 275 546 549 +4 265 266 285 548 +4 265 548 285 281 +4 268 270 283 547 +4 268 547 294 276 +4 269 571 284 274 +4 269 293 571 276 +4 269 293 284 571 +4 270 279 295 550 +4 270 550 547 279 +4 270 550 295 283 +4 270 283 547 550 +4 271 272 288 724 +4 271 549 292 273 +4 271 273 546 549 +4 271 288 292 724 +4 272 724 596 291 +4 272 724 291 288 +4 273 549 292 286 +4 274 284 289 571 +4 275 549 290 277 +4 275 277 546 549 +4 275 286 290 549 +4 547 294 293 550 +4 276 293 547 294 +4 573 565 625 536 +4 571 519 550 293 +4 277 549 290 282 +4 277 282 598 549 +4 278 280 291 596 +4 699 564 587 566 +4 564 566 592 590 +4 593 564 566 592 +4 587 566 564 590 +4 699 593 564 566 +4 279 550 296 295 +4 280 596 297 291 +4 281 285 298 588 +4 281 588 298 297 +4 282 290 300 601 +4 282 296 601 300 +4 282 279 598 296 +4 283 550 294 547 +4 283 550 302 294 +4 283 295 302 550 +4 284 529 308 289 +4 284 293 306 519 +4 284 306 308 519 +4 285 287 303 588 +4 285 588 303 298 +4 286 549 299 290 +4 286 292 304 549 +4 286 549 304 299 +4 287 289 307 529 +4 287 588 307 303 +4 288 291 305 724 +4 288 724 301 292 +4 301 551 549 641 +4 289 529 308 307 +4 290 299 300 601 +4 291 297 310 641 +4 291 641 310 305 +4 291 297 641 596 +4 292 301 311 549 +4 292 549 311 304 +4 293 309 306 550 +4 293 519 550 306 +4 294 302 309 550 +4 294 550 309 293 +4 295 296 312 550 +4 295 550 312 302 +4 296 300 321 552 +4 296 552 321 312 +4 296 312 550 552 +4 297 298 313 553 +4 297 553 588 298 +4 297 553 313 310 +4 297 310 641 553 +4 298 553 316 313 +4 299 601 315 300 +4 299 318 601 304 +4 300 315 321 552 +4 300 552 601 315 +4 300 296 601 552 +4 305 314 301 641 +4 301 311 549 551 +4 302 552 323 309 +4 302 309 550 552 +4 302 312 323 552 +4 302 552 550 312 +4 303 307 322 643 +4 303 643 588 307 +4 304 311 317 551 +4 304 551 549 311 +4 304 317 318 551 +4 305 310 320 641 +4 306 572 324 308 +4 308 324 325 572 +4 307 308 319 572 +4 307 519 529 308 +4 307 327 322 643 +4 307 588 519 643 +4 308 572 325 319 +4 323 552 554 572 +4 310 313 663 657 +4 310 320 641 657 +4 311 314 326 551 +4 311 551 326 317 +4 312 321 331 552 +4 312 552 331 323 +4 313 316 329 553 +4 314 551 333 326 +4 315 552 336 321 +4 315 607 338 336 +4 315 552 607 336 +4 322 332 316 643 +4 317 551 330 318 +4 317 326 330 551 +4 325 556 335 634 +4 319 325 335 634 +4 634 556 572 325 +4 319 634 572 325 +4 319 307 572 643 +4 524 720 532 576 +4 321 552 339 331 +4 321 336 339 552 +4 524 532 531 576 +4 322 327 337 643 +4 525 524 531 576 +4 322 332 643 337 +4 323 554 342 328 +4 328 323 554 572 +4 323 331 342 554 +4 323 554 552 331 +4 324 556 343 325 +4 324 325 572 556 +4 324 328 344 556 +4 324 556 344 343 +4 325 556 343 335 +4 326 551 340 330 +4 326 333 340 551 +4 335 556 341 634 +4 327 634 341 337 +4 327 337 643 634 +4 155 528 145 530 +4 319 307 643 327 +4 328 342 344 556 +4 328 556 554 342 +4 309 323 572 552 +4 329 332 345 555 +4 329 651 346 334 +4 329 345 346 555 +4 284 519 529 571 +4 331 339 352 554 +4 331 554 552 339 +4 331 554 352 342 +4 332 555 350 345 +4 334 346 347 717 +4 284 571 529 289 +4 334 347 333 580 +4 335 556 351 341 +4 335 343 351 556 +4 336 338 356 607 +4 287 588 529 307 +4 336 554 353 339 +4 336 339 552 554 +4 353 365 554 595 +4 307 519 588 529 +4 671 543 541 570 +4 337 341 354 718 +4 337 718 354 350 +4 337 350 332 718 +4 337 634 332 643 +4 570 543 541 547 +4 339 554 353 352 +4 340 348 359 577 +4 155 145 528 161 +4 340 577 359 349 +4 341 351 357 556 +4 342 556 361 344 +4 342 352 367 554 +4 342 554 367 361 +4 342 556 554 361 +4 343 344 355 556 +4 343 351 556 366 +4 343 556 355 366 +4 344 556 361 355 +4 345 555 360 346 +4 345 350 364 555 +4 345 555 364 360 +4 346 717 363 347 +4 346 360 363 555 +4 347 577 362 348 +4 348 577 362 359 +4 349 577 372 358 +4 349 359 372 577 +4 350 706 368 364 +4 350 364 555 706 +4 351 559 369 357 +4 351 357 556 559 +4 351 366 369 559 +4 366 559 556 355 +4 352 353 365 554 +4 352 365 367 554 +4 356 365 353 595 +4 293 571 519 284 +4 547 571 550 293 +4 354 371 368 664 +4 355 361 373 559 +4 355 559 556 361 +4 355 559 373 366 +4 556 366 351 559 +4 356 358 379 595 +4 530 536 565 573 +4 356 595 378 365 +4 336 554 607 353 +4 356 595 379 378 +4 530 604 535 536 +4 356 358 607 338 +4 357 664 371 354 +4 357 369 371 559 +4 358 372 379 595 +4 530 573 604 536 +4 359 362 370 577 +4 359 370 372 577 +4 565 530 719 536 +4 719 530 535 536 +4 360 558 374 363 +4 360 363 555 558 +4 360 364 374 558 +4 360 558 555 364 +4 361 367 376 712 +4 361 712 554 367 +4 362 363 375 647 +4 362 521 347 363 +4 362 647 375 370 +4 362 370 577 521 +4 363 374 375 558 +4 363 347 717 521 +4 364 368 377 706 +4 364 558 377 374 +4 365 700 380 367 +4 365 367 554 700 +4 365 378 380 700 +4 366 559 383 369 +4 366 384 383 559 +4 367 712 382 376 +4 367 380 382 712 +4 194 584 211 520 +4 368 371 578 716 +4 368 716 385 377 +4 368 377 706 716 +4 383 714 559 562 +4 383 387 714 562 +4 194 520 537 584 +4 370 696 381 372 +4 370 375 381 647 +4 370 381 696 647 +4 371 714 388 578 +4 371 387 388 714 +4 372 696 390 379 +4 372 381 390 696 +4 376 389 373 638 +4 373 559 384 366 +4 374 558 391 375 +4 374 377 386 558 +4 374 386 391 558 +4 375 647 394 381 +4 526 524 525 576 +4 526 720 524 576 +4 376 638 712 382 +4 376 396 638 382 +4 377 600 397 386 +4 377 385 397 600 +4 378 398 395 624 +4 154 139 573 155 +4 378 642 392 380 +4 624 560 408 398 +4 379 624 696 390 +4 379 624 398 378 +4 155 573 528 530 +4 380 638 393 382 +4 380 382 712 638 +4 380 392 393 642 +4 381 618 405 390 +4 381 390 696 618 +4 381 394 405 618 +4 381 394 618 647 +4 382 393 404 638 +4 382 396 638 404 +4 383 384 400 562 +4 383 562 559 384 +4 383 562 401 387 +4 371 369 714 559 +4 383 400 401 562 +4 384 389 403 562 +4 384 562 373 389 +4 384 562 403 400 +4 385 388 402 676 +4 386 561 399 391 +4 386 391 558 561 +4 386 397 399 600 +4 387 707 407 388 +4 387 388 714 707 +4 387 401 407 562 +4 573 626 604 536 +4 388 707 407 402 +4 389 396 403 562 +4 390 560 408 624 +4 390 405 408 560 +4 391 561 409 394 +4 391 399 409 561 +4 392 642 406 393 +4 392 395 406 642 +4 392 642 378 395 +4 393 653 406 404 +4 394 409 411 561 +4 395 398 412 560 +4 395 560 624 398 +4 395 653 412 406 +4 396 403 611 415 +4 396 562 611 403 +4 397 600 413 399 +4 398 419 412 560 +4 399 561 414 409 +4 399 413 414 561 +4 400 611 417 401 +4 400 401 562 611 +4 400 403 420 611 +4 400 611 562 403 +4 400 611 420 417 +4 401 566 416 407 +4 401 566 417 416 +4 402 407 425 566 +4 402 566 707 407 +4 402 699 422 410 +4 402 566 425 422 +4 396 404 415 611 +4 403 415 420 611 +4 404 406 418 653 +4 404 611 418 415 +4 404 611 653 418 +4 611 562 638 587 +4 611 653 638 404 +4 405 560 421 408 +4 405 426 560 411 +4 405 426 421 560 +4 406 412 423 653 +4 406 653 423 418 +4 407 428 425 566 +4 531 565 576 532 +4 408 560 419 398 +4 408 560 421 419 +4 409 561 424 411 +4 409 414 424 561 +4 410 699 427 413 +4 410 422 427 699 +4 522 576 533 534 +4 412 419 423 653 +4 412 653 560 419 +4 530 565 532 573 +4 413 414 561 593 +4 413 427 593 699 +4 413 561 699 593 +4 414 564 432 424 +4 414 424 561 564 +4 414 564 593 432 +4 415 418 438 590 +4 415 673 437 420 +4 415 437 590 438 +4 416 417 431 566 +4 416 566 428 407 +4 416 566 431 428 +4 417 431 673 440 +4 420 673 437 440 +4 418 423 433 590 +4 418 433 438 590 +4 419 421 434 564 +4 419 564 560 421 +4 419 653 430 423 +4 419 564 434 430 +4 417 673 431 566 +4 73 524 525 526 +4 421 426 436 564 +4 421 564 436 434 +4 422 425 435 566 +4 422 566 439 427 +4 422 435 439 566 +4 424 564 442 426 +4 424 432 442 564 +4 426 564 442 436 +4 427 593 443 429 +4 427 439 443 593 +4 428 431 444 723 +4 428 723 566 431 +4 428 723 444 441 +4 429 593 446 432 +4 429 443 446 593 +4 431 440 450 673 +4 431 723 450 444 +4 432 567 451 442 +4 432 442 564 567 +4 432 446 451 567 +4 432 567 593 446 +4 593 414 561 564 +4 593 561 699 564 +4 433 568 448 438 +4 433 438 590 568 +4 433 445 448 568 +4 434 436 449 567 +4 434 567 564 436 +4 434 567 449 445 +4 434 445 430 567 +4 435 723 447 439 +4 435 439 566 723 +4 435 452 447 723 +4 436 442 456 567 +4 436 567 564 442 +4 436 567 456 449 +4 437 438 453 568 +4 437 568 455 440 +4 437 453 455 568 +4 438 448 458 568 +4 438 568 458 453 +4 439 723 454 443 +4 439 443 593 723 +4 439 447 454 723 +4 440 568 455 461 +4 440 673 620 450 +4 441 457 452 723 +4 441 723 452 435 +4 442 451 462 567 +4 442 567 462 456 +4 443 702 459 446 +4 443 446 593 702 +4 443 454 459 723 +4 444 450 457 723 +4 444 723 457 441 +4 445 568 460 448 +4 445 449 460 567 +4 445 568 567 460 +4 446 702 459 466 +4 446 451 567 702 +4 446 702 567 593 +4 447 452 463 723 +4 447 723 463 454 +4 448 568 464 458 +4 448 460 464 568 +4 449 456 467 567 +4 449 567 467 460 +4 450 440 461 620 +4 450 461 469 620 +4 450 457 620 469 +4 451 446 466 702 +4 451 702 468 462 +4 451 466 468 702 +4 452 457 465 463 +4 453 568 470 455 +4 453 458 472 568 +4 453 568 472 470 +4 454 723 471 459 +4 454 463 471 723 +4 455 568 470 461 +4 456 462 473 567 +4 456 567 473 467 +4 463 478 579 465 +4 458 464 472 568 +4 463 471 723 579 +4 459 702 471 466 +4 461 620 470 474 +4 461 620 568 470 +4 462 477 702 468 +4 463 579 457 465 +4 464 569 483 472 +4 464 472 568 569 +4 464 475 483 569 +4 465 469 479 579 +4 467 473 481 569 +4 467 569 567 473 +4 467 569 481 475 +4 462 702 473 567 +4 523 545 541 543 +4 469 461 474 620 +4 469 474 479 620 +4 469 579 457 620 +4 470 472 480 620 +4 470 620 568 472 +4 470 620 480 474 +4 523 543 541 599 +4 520 543 523 599 +4 472 569 483 490 +4 473 477 488 569 +4 473 569 488 481 +4 474 479 480 484 +4 474 620 480 479 +4 475 481 486 569 +4 475 569 486 483 +4 476 482 485 569 +4 487 639 722 491 +4 479 480 484 639 +4 479 492 487 639 +4 480 472 490 569 +4 480 639 490 484 +4 481 569 488 486 +4 483 486 493 569 +4 483 569 493 490 +4 484 639 492 479 +4 484 490 495 639 +4 486 488 497 569 +4 486 569 497 493 +4 487 491 722 496 +4 487 496 722 492 +4 487 492 722 639 +4 488 569 498 497 +4 490 639 619 495 +4 490 499 495 619 +4 490 499 619 493 +4 490 493 619 569 +4 112 534 522 118 +4 257 547 570 598 +4 121 141 522 122 +4 118 534 522 121 +4 112 534 113 522 +4 495 492 619 708 +4 492 501 496 722 +4 619 708 499 495 +4 257 547 598 279 +4 493 569 497 619 +4 494 504 498 497 +4 494 497 498 569 +4 495 492 708 501 +4 572 552 554 602 +4 552 607 554 602 +4 722 496 500 501 +4 722 500 619 708 +4 503 510 708 499 +4 493 619 497 502 +4 495 499 503 708 +4 552 583 607 602 +4 496 500 501 506 +4 497 505 504 498 +4 552 583 602 572 +4 500 619 504 494 +4 500 708 506 509 +4 500 501 506 708 +4 504 619 497 494 +4 500 504 708 509 +4 500 506 508 509 +4 510 516 511 708 +4 708 503 511 510 +4 708 516 512 509 +4 501 708 511 512 +4 708 506 509 512 +4 708 504 505 509 +4 497 619 505 507 +4 504 505 509 513 +4 505 507 708 515 +4 506 508 509 514 +4 506 509 512 514 +4 507 708 515 510 +4 505 509 513 515 +4 509 516 513 515 +4 509 512 514 516 +4 509 516 514 513 +4 708 511 512 516 +4 505 708 509 515 +4 423 430 590 653 +4 590 567 564 430 +4 546 570 517 598 +4 546 570 541 517 +4 671 570 546 261 +4 671 541 546 570 +4 261 570 546 598 +4 520 597 540 537 +4 544 613 541 548 +4 546 541 613 517 +4 600 587 561 581 +4 638 562 581 587 +4 565 533 534 625 +4 573 565 534 625 +4 581 564 587 561 +4 653 564 587 581 +4 699 561 587 564 +4 699 587 561 600 +4 676 402 699 707 +4 573 604 538 586 +4 526 576 525 522 +4 720 534 522 113 +4 580 602 555 521 +4 580 717 347 521 +4 334 347 580 717 +4 605 551 583 713 +4 584 599 520 582 +4 582 523 541 599 +4 520 523 582 599 +4 119 589 674 615 +4 526 720 576 522 +4 605 551 601 583 +4 460 569 475 464 +4 460 467 475 569 +4 460 569 567 467 +4 460 569 568 567 +4 460 568 569 464 +4 211 599 232 520 +4 520 543 599 232 +4 568 569 723 592 +4 702 592 723 569 +4 530 573 528 604 +4 591 59 525 41 +4 59 73 525 41 +4 540 575 518 523 +4 231 662 247 237 +4 237 662 518 231 +4 237 662 544 518 +4 237 247 544 662 +4 121 534 522 141 +4 141 522 533 534 +4 591 41 525 526 +4 41 73 525 526 +4 224 544 644 563 +4 517 596 519 548 +4 596 519 548 588 +4 571 517 519 548 +4 588 519 548 529 +4 571 519 529 548 +4 568 569 592 567 +4 520 582 540 597 +4 702 567 592 569 +4 532 576 534 565 +4 573 532 534 565 +4 613 517 548 596 +4 613 541 548 517 +4 333 580 713 334 +4 577 580 347 521 +4 598 550 519 601 +4 282 296 598 601 +4 564 592 567 590 +4 593 564 592 567 +4 590 592 567 568 +4 29 37 70 72 +4 37 70 72 76 +4 70 72 92 527 +4 29 72 70 591 +4 591 72 70 527 +4 76 70 72 92 +4 662 235 252 545 +4 662 545 575 235 +4 41 591 45 526 +4 227 518 221 206 +4 231 518 594 575 +4 549 598 596 605 +4 579 569 723 620 +4 579 471 723 569 +4 620 569 723 568 +4 702 569 723 471 +4 530 146 129 674 +4 674 146 124 615 +4 471 478 482 569 +4 478 579 639 569 +4 471 579 478 569 +4 671 543 570 257 +4 362 521 577 347 +4 361 559 556 554 +4 361 559 554 712 +4 554 718 557 559 +4 712 554 557 559 +4 426 560 561 564 +4 560 561 411 426 +4 572 519 552 583 +4 531 565 533 576 +4 576 533 534 565 +4 211 223 599 584 +4 211 584 599 520 +4 560 564 581 561 +4 336 607 356 353 +4 353 595 554 607 +4 549 605 596 641 +4 584 597 537 205 +4 584 520 537 597 +4 287 289 529 267 +4 478 569 491 482 +4 478 639 491 569 +4 639 569 494 491 +4 482 569 491 485 +4 485 491 494 569 +4 36 52 617 603 +4 12 36 617 603 +4 566 592 673 723 +4 603 52 617 606 +4 617 52 670 606 +4 644 541 544 613 +4 607 583 551 580 +4 577 607 580 521 +4 583 713 551 580 +4 108 524 720 109 +4 109 524 720 532 +4 309 323 328 572 +4 662 545 571 517 +4 541 545 662 517 +4 318 330 338 607 +4 662 571 548 517 +4 541 662 548 517 +4 601 607 551 318 +4 231 662 575 235 +4 234 235 575 545 +4 575 662 518 523 +4 662 545 252 571 +4 231 662 518 575 +4 694 666 627 4 +4 269 252 545 571 +4 609 78 71 69 +4 7 16 614 13 +4 13 614 26 48 +4 13 608 614 48 +4 618 561 560 581 +4 563 644 582 544 +4 557 560 581 618 +4 518 563 582 544 +4 13 16 614 608 +4 7 614 26 13 +4 206 563 202 586 +4 12 617 36 623 +4 13 48 53 608 +4 48 61 53 608 +4 349 607 577 358 +4 595 521 554 607 +4 522 720 576 534 +4 101 117 522 525 +4 662 247 548 571 +4 117 522 525 533 +4 544 541 662 548 +4 15 610 49 616 +4 610 35 616 15 +4 544 548 662 247 +4 616 609 49 74 +4 616 74 49 56 +4 39 610 69 609 +4 303 298 643 316 +4 610 39 49 609 +4 316 715 332 329 +4 303 643 322 316 +4 630 54 50 47 +4 50 670 54 630 +4 608 48 61 614 +4 26 616 49 56 +4 152 625 565 536 +4 152 536 565 531 +4 385 402 410 676 +4 720 132 136 534 +4 720 136 532 534 +4 539 542 541 644 +4 539 542 599 541 +4 582 539 599 541 +4 636 622 537 604 +4 636 597 622 655 +4 636 537 622 597 +4 539 644 541 582 +4 296 279 598 550 +4 296 550 598 601 +4 16 614 44 632 +4 715 718 555 602 +4 634 602 715 643 +4 634 718 715 602 +4 9 16 632 614 +4 3 711 693 666 +4 268 547 283 294 +4 636 597 655 628 +4 379 408 398 624 +4 379 390 408 624 +4 191 597 636 628 +4 4 0 694 711 +4 296 550 601 552 +4 604 656 612 537 +4 571 517 550 519 +4 604 537 535 656 +4 638 559 581 562 +4 638 557 581 559 +4 581 557 600 559 +4 465 579 479 478 +4 478 579 479 639 +4 318 551 601 304 +4 301 314 551 641 +4 612 656 187 537 +4 304 601 549 551 +4 301 311 551 314 +4 656 604 536 535 +4 609 49 74 75 +4 609 78 74 71 +4 609 78 75 74 +4 622 586 540 604 +4 573 158 179 625 +4 573 625 534 158 +4 215 640 575 218 +4 557 600 559 664 +4 664 559 714 600 +4 581 559 600 562 +4 210 539 633 225 +4 225 542 539 633 +4 644 633 539 542 +4 210 628 633 539 +4 600 562 559 714 +4 600 562 587 581 +4 572 602 643 583 +4 707 562 587 600 +4 572 519 583 643 +4 14 616 614 9 +4 600 562 714 707 +4 12 33 679 697 +4 16 649 44 614 +4 656 650 536 604 +4 16 608 649 614 +4 466 468 702 477 +4 617 32 50 53 +4 617 58 53 50 +4 13 32 617 53 +4 617 53 608 13 +4 588 596 519 553 +4 596 519 553 605 +4 643 519 583 553 +4 489 569 488 477 +4 643 588 519 553 +4 605 519 553 583 +4 485 569 494 489 +4 489 569 498 488 +4 489 494 498 569 +4 401 407 562 566 +4 707 566 562 407 +4 611 562 587 566 +4 306 324 572 328 +4 569 471 702 466 +4 466 569 477 702 +4 466 476 477 569 +4 707 587 562 566 +4 611 401 562 566 +4 482 471 569 466 +4 485 569 477 476 +4 485 569 489 477 +4 574 636 683 604 +4 636 604 537 683 +4 622 540 537 604 +4 574 635 604 528 +4 28 47 51 688 +4 635 622 604 528 +4 605 598 519 601 +4 605 519 583 601 +4 164 656 535 175 +4 53 608 61 58 +4 28 688 630 47 +4 164 656 536 535 +4 549 598 605 601 +4 580 551 577 340 +4 330 577 607 551 +4 419 564 430 653 +4 551 607 580 577 +4 340 551 577 330 +4 215 585 575 640 +4 28 47 630 32 +4 653 430 590 564 +4 217 218 575 640 +4 217 594 575 231 +4 617 608 53 58 +4 582 539 563 655 +4 274 571 289 267 +4 571 267 529 289 +4 164 175 187 656 +4 539 644 582 563 +4 656 175 187 537 +4 563 633 539 644 +4 704 42 629 669 +4 655 539 563 628 +4 628 563 633 539 +4 205 621 223 584 +4 584 223 599 690 +4 6 16 13 631 +4 199 206 188 594 +4 206 518 586 594 +4 623 608 36 16 +4 631 608 16 13 +4 649 608 55 61 +4 16 649 608 645 +4 585 575 540 523 +4 669 670 42 629 +4 204 520 220 585 +4 616 614 56 26 +4 26 614 56 48 +4 674 129 124 146 +4 2 666 631 627 +4 602 718 555 521 +4 209 597 628 539 +4 608 64 61 58 +4 203 597 209 539 +4 189 586 188 206 +4 199 219 206 594 +4 540 594 538 586 +4 219 518 206 594 +4 608 55 61 64 +4 573 538 626 179 +4 563 582 540 518 +4 582 563 540 655 +4 56 614 68 48 +4 35 652 62 659 +4 610 35 659 616 +4 574 636 604 635 +4 636 622 604 635 +4 622 540 563 655 +4 636 622 635 721 +4 622 586 563 540 +4 563 518 540 586 +4 721 622 655 636 +4 721 622 563 655 +4 721 202 563 586 +4 202 198 721 563 +4 158 159 179 625 +4 158 625 534 159 +4 574 528 604 530 +4 574 604 535 530 +4 574 683 535 604 +4 195 201 217 538 +4 195 538 217 208 +4 208 217 594 538 +4 217 538 640 594 +4 201 538 640 217 +4 357 559 371 664 +4 32 50 630 679 +4 630 670 54 42 +4 591 527 526 522 +4 191 597 628 209 +4 165 683 162 710 +4 285 287 588 266 +4 105 104 589 120 +4 105 589 104 524 +4 120 719 589 133 +4 589 565 532 530 +4 591 527 522 101 +4 306 572 550 309 +4 44 668 709 689 +4 622 597 540 655 +4 44 689 709 65 +4 622 537 540 597 +4 591 522 526 525 +4 7 26 614 14 +4 28 688 660 630 +4 28 630 660 32 +4 298 553 643 316 +4 152 625 533 565 +4 635 622 528 721 +4 152 565 533 531 +4 298 553 588 643 +4 583 715 580 602 +4 287 529 588 266 +4 643 602 715 583 +4 266 529 588 548 +4 656 612 650 604 +4 612 650 604 626 +4 589 531 532 565 +4 531 565 719 536 +4 589 531 565 719 +4 721 586 563 622 +4 204 585 612 520 +4 612 585 540 520 +4 611 587 653 590 +4 611 566 587 590 +4 711 693 681 648 +4 333 580 340 551 +4 410 699 413 600 +4 413 699 561 600 +4 399 413 561 600 +4 397 410 413 600 +4 693 8 681 648 +4 187 612 537 194 +4 194 520 612 537 +4 631 679 12 617 +4 554 556 718 559 +4 662 252 247 571 +4 518 523 662 582 +4 699 707 587 600 +4 542 541 644 613 +4 699 587 707 566 +4 664 718 357 559 +4 357 718 556 559 +4 12 666 679 631 +4 2 13 631 6 +4 6 623 16 631 +4 607 583 580 602 +4 580 607 602 521 +4 583 553 580 715 +4 193 628 210 209 +4 631 608 623 16 +4 431 673 450 723 +4 673 723 620 450 +4 13 32 631 617 +4 673 723 568 620 +4 631 617 608 13 +4 2 631 13 627 +4 631 627 32 13 +4 166 168 650 536 +4 168 187 650 656 +4 187 650 656 612 +4 557 600 664 558 +4 706 600 558 664 +4 557 664 718 558 +4 706 664 558 718 +4 297 641 596 553 +4 596 605 553 641 +4 297 553 596 588 +4 9 632 35 668 +4 313 657 646 663 +4 313 329 646 553 +4 582 662 544 541 +4 329 646 553 715 +4 646 715 580 553 +4 646 580 713 553 +4 320 646 713 657 +4 168 656 650 536 +4 643 715 553 583 +4 164 536 656 168 +4 14 26 614 616 +4 616 614 68 56 +4 616 614 691 68 +4 9 616 614 668 +4 349 330 577 607 +4 634 602 643 572 +4 634 556 602 572 +4 653 564 581 560 +4 585 523 540 520 +4 287 267 529 266 +4 146 528 574 530 +4 571 548 529 267 +4 616 610 49 609 +4 520 523 540 582 +4 616 668 691 614 +4 188 199 594 183 +4 540 518 594 586 +4 594 540 538 640 +4 318 551 330 607 +4 166 536 650 625 +4 203 597 191 209 +4 164 656 187 168 +4 625 650 626 536 +4 617 50 52 58 +4 556 554 718 602 +4 257 543 570 547 +4 521 554 718 557 +4 602 554 718 521 +4 593 723 592 566 +4 595 372 379 696 +4 721 182 202 586 +4 182 198 721 202 +4 617 36 608 52 +4 573 538 604 626 +4 55 61 64 66 +4 612 626 604 538 +4 679 50 630 670 +4 617 679 33 670 +4 617 679 670 50 +4 669 630 42 670 +4 614 68 48 61 +4 310 313 657 553 +4 310 657 641 553 +4 313 553 646 657 +4 657 646 713 553 +4 641 657 713 553 +4 329 651 646 715 +4 651 715 580 646 +4 555 558 521 718 +4 55 64 608 52 +4 36 55 608 52 +4 649 608 61 614 +4 603 606 617 33 +4 590 567 430 445 +4 693 686 8 648 +4 590 568 567 445 +4 691 709 66 614 +4 582 655 540 597 +4 582 539 655 597 +4 628 597 655 539 +4 354 706 350 718 +4 354 706 718 664 +4 528 167 635 721 +4 636 721 635 680 +4 680 721 635 167 +4 254 256 276 545 +4 654 686 10 675 +4 254 545 276 269 +4 269 571 545 276 +4 256 545 547 276 +4 276 571 545 547 +4 605 713 553 641 +4 654 684 28 701 +4 575 545 662 523 +4 662 545 541 523 +4 394 561 618 558 +4 375 391 394 558 +4 391 394 558 561 +4 375 558 394 647 +4 647 394 618 558 +4 196 563 213 628 +4 721 628 563 196 +4 2 637 631 666 +4 2 666 694 695 +4 600 676 699 707 +4 385 676 410 600 +4 35 616 652 659 +4 600 676 410 699 +4 659 616 652 609 +4 683 604 537 535 +4 35 652 616 668 +4 664 559 371 714 +4 160 146 167 574 +4 558 561 618 581 +4 557 618 581 558 +4 146 574 528 167 +4 161 167 146 528 +4 528 167 574 635 +4 680 635 574 167 +4 160 680 574 167 +4 182 167 528 721 +4 310 663 320 657 +4 663 657 646 320 +4 332 350 555 718 +4 332 718 555 715 +4 663 646 334 320 +4 44 645 687 649 +4 16 649 645 44 +4 693 679 654 697 +4 697 654 18 679 +4 589 565 530 719 +4 654 28 692 660 +4 668 652 616 691 +4 710 636 680 174 +4 710 636 574 680 +4 636 635 574 680 +4 636 721 680 180 +4 636 180 680 174 +4 34 28 51 688 +4 616 74 652 609 +4 616 685 652 74 +4 616 652 685 691 +4 587 564 653 590 +4 424 426 561 564 +4 426 561 411 424 +4 62 705 691 65 +4 666 694 695 711 +4 62 652 71 69 +4 354 368 350 706 +4 354 368 706 664 +4 5 11 686 682 +4 198 563 213 196 +4 721 196 563 198 +4 687 645 55 649 +4 180 721 680 167 +4 706 364 555 558 +4 706 555 718 558 +4 648 682 672 5 +4 648 10 686 5 +4 56 68 616 74 +4 616 68 685 74 +4 182 721 528 586 +4 172 586 189 182 +4 182 189 202 586 +4 616 685 68 691 +4 182 586 528 172 +4 9 35 15 616 +4 9 616 668 35 +4 12 658 679 666 +4 463 471 579 478 +4 693 686 10 654 +4 542 541 613 546 +4 620 480 639 569 +4 666 658 637 12 +4 658 679 697 12 +4 686 684 654 701 +4 693 32 654 679 +4 546 598 596 549 +4 278 291 272 596 +4 693 701 654 32 +4 165 636 683 710 +4 658 693 679 666 +4 3 665 693 648 +4 693 679 697 658 +4 693 654 10 697 +4 677 17 18 675 +4 278 272 613 596 +4 278 596 613 548 +4 656 537 535 175 +4 677 703 17 675 +4 62 661 652 691 +4 266 548 247 267 +4 255 544 247 548 +4 652 661 685 691 +4 62 661 691 705 +4 691 661 685 678 +4 634 715 332 643 +4 691 705 661 678 +4 634 718 602 556 +4 634 718 332 715 +4 12 679 33 617 +4 12 603 617 33 +4 181 197 597 203 +4 181 597 191 203 +4 197 205 597 621 +4 520 584 582 597 +4 584 621 597 205 +4 601 607 552 583 +4 3 693 711 648 +4 601 552 607 315 +4 671 546 541 542 +4 539 599 584 582 +4 1 681 672 0 +4 251 547 545 543 +4 543 541 547 545 +4 541 547 545 517 +4 547 545 517 571 +4 600 707 714 676 +4 714 600 676 385 +4 584 539 582 597 +4 386 600 399 561 +4 659 652 62 69 +4 610 659 69 609 +4 386 561 558 600 +4 0 681 672 711 +4 702 723 592 593 +4 681 1 682 8 +4 83 59 525 591 +4 83 591 525 84 +4 661 667 685 678 +4 661 705 667 678 +4 518 662 544 582 +4 1 682 672 681 +4 612 640 585 215 +4 617 608 36 623 +4 617 608 623 631 +4 12 617 623 631 +4 611 587 638 653 +4 638 587 581 653 +4 676 388 402 707 +4 676 707 714 388 +4 676 402 410 699 +4 18 704 679 660 +4 688 42 669 630 +4 660 630 679 32 +4 637 631 12 6 +4 679 654 18 660 +4 666 637 631 12 +4 652 74 71 609 +4 691 668 709 614 +4 69 652 71 609 +4 659 652 69 609 +4 610 659 609 616 +4 689 62 668 691 +4 654 32 660 679 +4 704 42 669 688 +4 220 523 585 520 +4 220 543 523 520 +4 658 3 693 666 +4 666 3 637 658 +4 35 62 652 668 +4 691 709 65 66 +4 689 62 691 65 +4 683 537 181 176 +4 683 176 535 537 +4 683 636 181 537 +4 711 4 693 666 +4 694 711 666 4 +4 193 628 636 721 +4 655 628 563 721 +4 665 693 10 697 +4 50 52 54 670 +4 711 681 693 4 +4 169 170 183 538 +4 169 538 573 170 +4 169 183 188 538 +4 711 648 681 672 +4 169 538 188 586 +4 169 586 573 538 +4 4 681 693 698 +4 76 92 72 63 +4 645 608 55 649 +4 704 669 33 679 +4 333 580 348 340 +4 580 340 577 348 +4 679 630 669 670 +4 679 670 669 33 +4 585 640 540 575 +4 612 640 540 585 +4 660 669 679 630 +4 704 669 679 660 +4 666 627 32 631 +4 677 11 703 675 +4 484 495 492 639 +4 495 639 619 492 +4 652 685 71 74 +4 675 19 21 28 +4 28 675 19 684 +4 654 684 675 28 +4 654 28 675 692 +4 530 146 674 615 +4 679 32 50 617 +4 384 562 559 373 +4 373 562 559 638 +4 212 202 563 198 +4 648 686 8 682 +4 614 61 66 68 +4 32 679 631 617 +4 631 666 679 32 +4 217 640 575 594 +4 617 606 670 33 +4 594 540 640 575 +4 327 335 341 634 +4 223 543 599 244 +4 244 599 671 543 +4 718 341 354 357 +4 673 592 568 723 +4 691 705 678 65 +4 590 673 592 568 +4 632 614 44 668 +4 9 632 668 614 +4 641 551 605 713 +4 549 605 641 551 +4 44 687 65 709 +4 364 706 377 558 +4 706 377 558 600 +4 10 11 675 686 +4 619 502 499 708 +4 507 510 502 708 +4 502 510 499 708 +4 683 165 181 636 +4 153 160 174 710 +4 710 680 160 174 +4 710 683 535 574 +4 710 636 683 574 +4 35 62 668 689 +4 691 668 689 709 +4 704 629 33 669 +4 617 52 608 58 +4 52 64 608 58 +4 636 628 655 721 +4 669 670 629 33 +4 5 11 10 686 +4 558 561 581 600 +4 718 341 357 556 +4 634 556 341 718 +4 320 713 333 314 +4 713 580 333 551 +4 688 30 704 40 +4 688 30 40 34 +4 497 504 505 619 +4 688 51 34 40 +4 507 619 708 502 +4 688 47 51 42 +4 688 42 630 47 +4 62 71 652 661 +4 668 62 652 691 +4 652 71 685 661 +4 549 601 605 551 +4 145 528 146 530 +4 145 146 528 161 +4 681 698 8 693 +4 681 648 8 682 +4 693 8 686 701 +4 698 701 8 693 +4 686 8 684 701 +4 613 272 724 596 +4 319 634 643 572 +4 666 4 698 627 +4 666 693 32 698 +4 679 693 32 666 +4 557 664 559 718 +4 590 566 592 673 +4 660 654 18 692 +4 695 3 637 666 +4 695 3 666 711 +4 654 675 18 692 +4 238 543 523 220 +4 238 523 543 545 +4 181 597 636 191 +4 35 689 668 44 +4 206 563 518 221 +4 206 518 563 586 +4 632 668 44 35 +4 658 693 665 697 +4 573 528 604 586 +4 586 538 540 604 +4 316 553 715 329 +4 675 28 21 692 +4 691 678 68 66 +4 614 68 66 691 +4 666 4 693 698 +4 2 666 627 694 +4 0 681 711 4 +4 666 698 32 627 +4 692 30 704 688 +4 704 688 660 692 +4 649 61 66 614 +4 649 66 61 55 +4 660 688 669 630 +4 704 688 669 660 +4 617 670 52 50 +4 18 30 704 692 +4 336 552 607 554 +4 607 554 602 521 +4 338 349 607 330 +4 324 556 572 328 +4 328 572 554 556 +4 572 602 554 556 +4 654 32 28 660 +4 162 683 535 710 +4 151 710 162 535 +4 675 19 17 21 +4 675 11 703 19 +4 675 11 19 684 +4 675 17 18 692 +4 688 40 704 42 +4 654 684 686 675 +4 605 713 583 553 +4 698 32 701 693 +4 583 553 713 580 +4 693 701 686 654 +4 654 701 28 32 +4 641 320 713 657 +4 648 682 681 672 +4 648 665 693 10 +4 648 693 686 10 +4 615 535 574 710 +4 134 574 153 710 +4 134 615 574 710 +4 697 33 679 18 +4 688 51 40 42 +4 692 688 660 28 +4 10 677 18 675 +4 10 11 677 675 +4 62 71 661 705 +4 186 612 640 538 +4 186 538 640 201 +4 661 71 685 667 +4 17 692 21 30 +4 675 17 692 21 +4 501 500 722 708 +4 503 511 501 708 +4 495 708 503 501 +4 703 17 19 20 +4 675 703 17 19 +4 611 590 418 415 +4 611 590 653 418 +4 612 540 604 537 +4 613 253 542 258 +4 691 678 685 68 +4 595 700 378 365 +4 595 365 554 700 +4 595 624 379 378 +4 595 557 554 521 +4 686 11 675 684 +4 697 10 18 654 +4 134 615 710 151 +4 133 535 589 615 +4 134 574 615 137 +4 144 133 615 535 +4 530 574 615 535 +4 371 387 714 369 +4 3 693 665 658 +4 615 589 530 535 +4 369 383 714 559 +4 654 10 18 675 +4 709 649 66 614 +4 687 66 649 55 +4 709 649 687 66 +4 709 687 65 66 +4 510 708 515 516 +4 5 1 682 672 +4 661 705 71 667 +4 381 618 696 647 +4 619 639 722 492 +4 28 30 688 34 +4 621 214 223 690 +4 621 690 223 584 +4 584 539 597 621 +4 21 30 28 34 +4 28 30 692 688 +4 437 568 590 438 +4 437 568 673 590 +4 316 332 715 643 +4 584 690 599 539 +4 621 539 690 584 +4 692 30 28 21 +4 440 673 568 620 +4 620 440 461 568 +4 429 414 593 432 +4 432 567 564 593 +4 166 650 178 625 +4 625 173 179 626 +4 573 625 179 626 +4 193 628 721 196 +4 188 586 594 206 +4 183 190 594 538 +4 573 625 626 536 +4 613 272 271 724 +4 340 330 577 349 +4 122 522 533 141 +4 715 580 602 555 +4 329 555 715 332 +4 378 642 624 395 +4 267 548 247 571 +4 313 646 334 663 +4 313 329 334 646 +4 329 334 646 651 +4 334 651 580 646 +4 333 347 348 580 +4 334 580 713 646 +4 320 334 713 646 +4 347 580 577 348 +4 204 520 612 194 +4 612 520 540 537 +4 111 127 674 532 +4 716 371 578 714 +4 716 600 385 377 +4 415 437 673 590 +4 716 377 706 600 +4 716 664 371 714 +4 716 600 706 664 +4 278 280 596 548 +4 334 346 717 651 +4 346 555 363 717 +4 363 717 555 521 +4 580 555 717 521 +4 334 717 580 651 +4 387 562 407 707 +4 387 707 714 562 +4 714 676 388 385 +4 716 714 385 600 +4 716 664 714 600 +4 586 721 528 622 +4 582 523 540 518 +4 196 184 198 721 +4 642 560 557 624 +4 413 427 429 593 +4 186 612 626 192 +4 306 519 550 572 +4 192 186 612 200 +4 186 538 626 612 +4 720 116 125 136 +4 215 226 234 575 +4 226 585 523 575 +4 226 234 575 545 +4 226 575 523 545 +4 123 133 615 144 +4 215 226 575 585 +4 624 560 696 390 +4 546 549 596 724 +4 611 673 590 415 +4 628 213 633 563 +4 188 538 594 586 +4 380 642 393 638 +4 380 638 712 642 +4 638 393 404 653 +4 638 557 559 712 +4 479 639 487 478 +4 490 569 619 639 +4 619 569 494 639 +4 591 70 80 527 +4 591 80 526 527 +4 200 612 215 640 +4 612 215 585 207 +4 612 538 540 640 +4 200 612 640 186 +4 291 724 641 305 +4 291 641 724 596 +4 292 549 724 301 +4 361 559 712 373 +4 361 712 376 373 +4 708 507 505 619 +4 642 638 557 560 +4 642 638 712 557 +4 653 590 423 418 +4 281 285 588 548 +4 281 280 588 297 +4 153 574 160 710 +4 710 680 574 160 +4 644 229 633 542 +4 280 596 548 588 +4 281 548 588 280 +4 280 297 596 588 +4 376 389 638 396 +4 396 638 611 562 +4 180 184 196 721 +4 647 558 557 521 +4 699 427 593 566 +4 210 213 229 633 +4 563 213 633 644 +4 315 318 338 607 +4 368 664 371 716 +4 368 716 706 664 +4 393 642 406 653 +4 329 555 346 651 +4 329 651 715 555 +4 638 393 653 642 +4 638 581 560 653 +4 651 555 580 715 +4 136 573 532 534 +4 149 136 534 573 +4 651 346 717 555 +4 651 717 580 555 +4 530 145 129 146 +4 136 532 573 139 +4 139 530 532 573 +4 198 213 563 212 +4 647 558 521 363 +4 647 363 375 558 +4 314 713 333 551 +4 641 314 551 713 +4 696 647 557 521 +4 224 544 563 221 +4 227 221 518 544 +4 221 563 518 544 +4 650 536 604 626 +4 647 618 557 558 +4 479 480 639 620 +4 480 569 490 639 +4 595 696 379 624 +4 595 557 521 696 +4 174 180 193 636 +4 180 721 193 636 +4 27 29 72 23 +4 180 680 160 167 +4 271 724 292 549 +4 271 549 546 724 +4 368 578 385 716 +4 578 714 388 385 +4 521 718 558 557 +4 716 578 385 714 +4 182 167 161 528 +4 450 723 620 457 +4 457 579 723 620 +4 427 439 593 566 +4 439 593 566 723 +4 192 612 207 215 +4 261 277 598 546 +4 277 598 546 549 +4 230 239 243 671 +4 457 579 469 465 +4 417 673 420 440 +4 431 723 566 673 +4 550 572 519 552 +4 105 107 674 524 +4 105 674 589 524 +4 107 111 674 524 +4 111 127 129 674 +4 127 674 532 530 +4 674 589 532 530 +4 433 590 430 445 +4 433 568 590 445 +4 524 589 531 532 +4 524 674 589 532 +4 306 572 309 328 +4 320 333 713 334 +4 618 560 405 390 +4 618 390 696 560 +4 618 411 405 560 +4 354 718 357 664 +4 389 562 373 638 +4 389 562 638 396 +4 173 178 626 625 +4 178 650 192 626 +4 373 559 712 638 +4 214 216 690 621 +4 216 539 230 690 +4 690 542 539 230 +4 690 539 542 599 +4 203 197 597 621 +4 680 180 160 174 +4 620 472 480 569 +4 620 569 568 472 +4 423 430 433 590 +4 613 546 271 258 +4 613 724 546 596 +4 611 415 420 673 +4 469 620 479 579 +4 579 620 639 569 +4 591 527 101 87 +4 591 522 525 101 +4 624 560 557 696 +4 618 696 557 560 +4 224 544 242 644 +4 696 618 557 647 +4 402 566 422 699 +4 402 699 707 566 +4 699 422 427 566 +4 200 186 640 201 +4 700 712 380 367 +4 700 367 554 712 +4 700 378 642 624 +4 595 624 378 700 +4 595 700 554 557 +4 305 641 320 314 +4 641 320 314 713 +4 619 569 497 494 +4 671 259 261 546 +4 671 546 542 259 +4 299 318 315 601 +4 299 601 549 304 +4 601 607 318 315 +4 452 723 457 463 +4 463 579 723 457 +4 285 266 588 548 +4 266 267 529 548 +4 700 378 380 642 +4 595 557 624 700 +4 443 723 459 702 +4 443 702 593 723 +4 702 592 567 593 +4 219 518 227 206 +4 700 642 380 712 +4 700 712 554 557 +4 133 143 719 535 +4 143 147 719 535 +4 147 719 535 536 +4 133 535 719 589 +4 589 719 530 535 +4 517 598 550 519 +4 546 517 596 598 +4 517 598 519 596 +4 519 601 552 583 +4 108 109 720 125 +4 720 532 576 534 +4 702 473 567 569 +4 477 462 702 473 +4 473 569 702 477 +4 612 604 540 538 +4 557 581 600 558 +4 638 560 581 557 +4 118 522 527 121 +4 104 531 589 120 +4 104 589 531 524 +4 120 719 143 531 +4 120 531 589 719 +4 440 568 673 437 +4 591 527 87 72 +4 621 203 216 539 +4 203 621 597 539 +4 638 642 653 560 +4 125 109 720 532 +4 219 518 594 231 +4 219 237 518 231 +4 595 696 624 557 +4 720 125 532 136 +4 700 624 642 557 +4 700 557 642 712 +4 184 182 198 721 +4 642 395 406 653 +4 642 560 624 395 +4 504 619 500 708 +4 619 502 493 499 +4 492 722 619 708 +4 350 555 718 706 +4 337 634 341 718 +4 337 718 332 634 +4 229 644 253 542 +4 644 253 542 613 +4 99 522 113 526 +4 252 571 267 247 +4 303 298 588 643 +4 720 113 132 534 +4 720 522 526 113 +4 309 572 550 552 +4 491 496 500 722 +4 491 722 494 639 +4 722 500 491 494 +4 722 494 619 500 +4 619 639 494 722 +4 426 421 560 564 +4 611 566 417 401 +4 611 566 673 417 +4 621 216 690 539 +4 228 671 244 599 +4 618 394 405 411 +4 618 411 560 561 +4 377 386 558 600 +4 282 290 601 549 +4 282 598 549 601 +4 290 299 601 549 +4 260 278 613 548 +4 451 702 462 567 +4 261 257 598 279 +4 279 547 598 550 +4 615 535 151 144 +4 151 710 165 162 +4 671 542 690 230 +4 671 690 542 599 +4 671 599 541 543 +4 434 430 564 567 +4 288 724 305 301 +4 724 549 641 301 +4 724 641 549 596 +4 269 274 252 571 +4 571 274 252 267 +4 425 428 441 566 +4 425 566 441 435 +4 428 441 566 723 +4 435 723 566 441 +4 395 560 412 653 +4 642 395 653 560 +4 157 166 178 625 +4 152 536 166 625 +4 625 178 626 650 +4 94 103 108 526 +4 94 108 524 526 +4 108 524 526 720 +4 103 526 720 108 +4 358 595 356 607 +4 577 595 370 372 +4 595 696 370 372 +4 370 595 577 521 +4 370 595 521 696 +4 237 247 255 544 +4 611 566 590 673 +4 611 673 420 417 +4 242 249 613 544 +4 249 613 544 548 +4 358 595 577 372 +4 595 521 607 577 +4 653 564 560 419 +4 459 723 471 702 +4 524 532 111 674 + +CELL_TYPES 2395 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 diff --git a/data/boot.vtk b/data/boot.vtk new file mode 100644 index 000000000..8ab2f33eb --- /dev/null +++ b/data/boot.vtk @@ -0,0 +1,5457 @@ +# vtk DataFile Version 2.0 +boot_, Created by Gmsh +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 610 double +-0.360270411 0.795204222 -0.451430261 +-0.35090062 0.802636325 -0.30427748 +-0.333121657 0.795066297 -0.596493959 +-0.326804578 0.616782427 -0.522764742 +-0.3192622489038995 0.5610982661560358 -0.3983194176588474 +-0.313694 0.807003438 -0.153467208 +-0.3109991507325673 0.6179438605822976 -0.2589362807775814 +-0.3009361026603136 0.4557923361658565 -0.4814633596883026 +-0.2881073400578985 0.4510305993512781 -0.3042056014962912 +-0.287240654 0.494966179 -0.598984063 +-0.2810057570491061 0.3611775305994662 -0.3848156639938226 +-0.271672457 0.487286061 -0.195940137 +-0.2683248040445367 0.6230297499045701 -0.1263898592532567 +-0.267865181 0.630878329 -0.651342928 +-0.266073704 0.253227144 -0.464489579 +-0.264445037 0.336961329 -0.551487148 +-0.2525635207889535 0.8031479242005976 -0.04604684492949893 +-0.2539085499626947 0.2464521593803828 -0.322562918823809 +-0.2539774356394759 0.2119355931150132 -0.3870380057072288 +-0.248278663 -0.828537166 0.252431452 +-0.243192628 0.313438714 -0.23788543 +-0.240854114 -0.684005499 0.181022912 +-0.239917219 -0.689890146 0.326839745 +-0.239502236 0.108641423 -0.453061819 +-0.238232717 -0.567889035 0.220296547 +-0.233515427 0.172455743 -0.579681635 +-0.227293938 -0.812826872 0.416949123 +-0.226794809 0.086412482 -0.328618795 +-0.226195991 0.847773433 -0.678713441 +-0.225611299 0.386086732 -0.659065902 +-0.225477859 -0.58953315 0.095998995 +-0.2243747214997257 -0.8017775415522977 0.06869848783015124 +-0.222385094 0.503543377 -0.694270253 +-0.22113052 -0.456504792 -0.47875762 +-0.219988495 -0.815666676 -0.529414058 +-0.218597487 0.5053567289999999 -0.0781684592 +-0.218421196035536 -0.3645416917169683 -0.4657587309361743 +-0.216213673 -0.413850367 -0.571975589 +-0.2138612115967307 -0.572542189358206 -0.5230261195906846 +-0.213513269314495 0.3711608087543036 -0.1286092496997337 +-0.2126410253994236 -0.04663338141126127 -0.4110532588422314 +-0.212684959 -0.816179335 -0.434046447 +-0.2116660591527077 -0.6514877826974862 -0.4022778879219147 +-0.211072087 -0.700573087 -0.5184268950000001 +-0.2103313572618657 0.8497022608361567 -0.5070875719176714 +-0.2082631335133119 -0.5083923472513825 -0.3719489945590048 +-0.2056936011034265 -0.3343135395182205 -0.3502611508252832 +-0.2013797594174525 -0.4946037303867271 -0.2188269064172977 +-0.2014175523129153 -0.6528528747682082 0.02097593397892816 +-0.199406102 -0.354823828 -0.206152648 +-0.197591498 0.106220149 -0.202036709 +-0.195878789 -0.768731654 -0.304807782 +-0.194989562 0.851368785 -0.363065362 +-0.194927499 -0.172689766 -0.499658227 +-0.192750379 -0.203598678 -0.297025174 +-0.192635775 -0.5483711959999999 0.379054397 +-0.192317247 -0.622832835 -0.28765139 +-0.190007016 -0.0140361246 -0.566937208 +-0.187286794 -0.65950799 0.491346359 +-0.186453313 -0.462750196 0.0861877427 +-0.18239224 0.22165291 -0.680217385 +-0.182188004 -0.504183948 -0.059396822 +-0.182040557 -0.0671922266 -0.239866644 +-0.180133611 -0.672270238 -0.6250731349999999 +-0.177630991 -0.763592482 -0.0684797093 +-0.176367879 -0.214848191 -0.150786057 +-0.174225315 0.213643909 -0.123362936 +-0.173403934 0.853422642 -0.210435614 +-0.172644913 0.64208591 -0.0152312536 +-0.17135644 -0.774124563 0.560293138 +-0.171254396 -0.641220987 -0.163076758 +-0.164686173 -0.297911286 -0.6324895619999999 +-0.16230996 0.65603137 -0.742551267 +-0.160372153 0.855195999 -0.0789481848 +-0.156042978 -0.35026145 -0.0547124334 +-0.1555949 -0.488649458 -0.672747672 +-0.152666852 0.80735147 0.0227210987 +-0.151438609 -0.801576972 -0.659423172 +-0.150741518 -0.455034167 0.233876467 +-0.136088952 -0.128574178 -0.6631222960000001 +-0.133355319 0.0374672674 -0.6850082280000001 +-0.132877156 -0.0606197603 -0.104254454 +-0.129955977 -0.754499018 -0.208677426 +-0.125374228 -0.49210608 0.494707584 +-0.124407895 -0.3594504 0.0977452993 +-0.123164743 0.365924895 -0.0408659466 +-0.120472476 -0.815828621 0.0223580226 +-0.119490646 0.801542222 -0.760011792 +-0.1204642911981656 0.08753908942908918 -0.07974698915156458 +-0.112354785 -0.754121304 0.664246142 +-0.110572957 -0.655428886 0.629527152 +-0.10734573 -0.817615986 -0.31063807 +-0.107092172 -0.198603287 -0.034518674 +-0.104832418 0.329099745 -0.754250824 +-0.09730958939999999 0.8523586990000001 -0.575503111 +-0.0968717784 -0.64306885 -0.69981575 +-0.0944191813 -0.859337986 0.175261468 +-0.0859219581 -0.295532137 -0.712087154 +-0.0840959176 -0.458234727 0.372781545 +-0.08200058339999999 0.122889295 -0.729147375 +-0.0746995956 -0.0259259418 -0.0359094664 +-0.0630664006 -0.100402102 -0.699405134 +-0.0611636415 0.677043021 0.0242888536 +-0.0587005839 -0.856396437 0.308962107 +-0.0523521006 0.680982053 -0.7509799 +-0.0507825799 -0.833655119 0.4618662 +-0.0494653806 0.857895374 -0.130961135 +-0.0491750054 0.543070972 0.00799992308 +-0.0442252271 -0.863306701 -0.471515834 +-0.042539753 -0.699804425 -0.703835487 +-0.0369458422 -0.863306701 -0.559197664 +-0.023190733 0.811561942 0.0375166014 +-0.0208377149 0.23298341 -0.0270390324 +-0.0162453726 0.85370636 -0.661460042 +-0.0161909498 -0.558849633 0.701667905 +-0.0110421609 -0.800424814 -0.0361574739 +-0.0106353108 -0.770411849 -0.279982388 +-0.00800043624 -0.374909759 0.253951162 +-0.00704049133 0.526374102 -0.732782543 +-0.00473007141 0.804878592 -0.741170943 +-0.006071748418285471 -0.4374001598887427 0.483672567248209 +0.00111298985 -0.6449080109999999 0.736854315 +0.00382796954 0.0922110453 -0.0202013664 +0.00565531291 0.225629866 -0.703870058 +0.008009323635729995 0.02920241486601841 -0.6860339161146526 +0.005041363717791944 -0.8538649369930001 0.09662055765532793 +0.0087443348 -0.477023065 -0.708875716 +0.0113048637 0.855919838 -0.521724701 +0.01386098 -0.8359375 -0.330868006 +0.0146886576 -0.832981825 -0.691895127 +0.019094184 -0.140593529 -0.662125289 +0.0215367489 -0.06902197 0.00391134433 +0.02335712933447814 0.8575413542084709 -0.3796653233767709 +0.03112988669817807 0.3952045873848547 -0.6920193569388798 +0.0321582407 -0.268341601 0.115929447 +0.0321765058 -0.313978255 -0.699245334 +0.02641786385088513 -0.7758133314672961 -0.1449570528782566 +0.0356189087 -0.423546612 0.385901809 +0.03092948332912753 -0.8613242289809753 0.2098978820084228 +0.0480644479 0.859584987 -0.239979491 +0.0490662642 0.641548634 -0.697127521 +0.0500906445 0.654851556 -0.00140750594 +0.05530050329767385 -0.8510169608487981 0.3494330520957986 +0.06936203689999999 -0.591531277 -0.673164666 +0.0702434778 -0.723134458 -0.67223686 +0.0732250363 0.861617446 -0.116034105 +0.07696615900000001 -0.748185515 0.72878617 +0.08514079450000001 -0.616317451 0.71541959 +0.0864749029 0.214175612 -0.0689473674 +0.08636264958304865 0.3706589181576458 -0.052436708962819 +0.0872103274 0.863045752 -0.0176324751 +0.08727473769999999 -0.826903403 0.484531909 +0.0896900818 -0.430448413 0.5952952500000001 +0.09253987347265116 -0.01569356572490188 -0.5938414489400577 +0.0924979672 0.506654978 -0.6477918030000001 +0.0950254723 0.168759644 -0.610724449 +0.09551249439999999 0.059823975 -0.07711497690000001 +0.0984129757 -0.297491223 -0.62819916 +0.100415587 -0.432542801 0.479959279 +0.101815432 0.344771206 -0.600281775 +0.102240928 -0.157773346 -0.546911001 +0.106392659 0.808690608 -0.660172045 +0.107388578 -0.442210317 -0.643689096 +0.122717857 -0.825311899 -0.618776262 +0.12548019 -0.427441359 0.354081392 +0.127194881 -0.798021495 0.59494704 +0.1298816166013098 0.2738277575236225 -0.5393933197676144 +0.1303318224169449 -0.7760223315569542 -0.1921393710578642 +0.133428946 0.147058129 -0.509829104 +0.135827988 -0.0112522114 -0.464679211 +0.137863562 0.633895278 -0.584724605 +0.140389904 -0.346060604 -0.497623682 +0.141773805 0.529984176 -0.101427004 +0.142967731 0.676713228 -0.0787487254 +0.143094689 -0.0862841755 -0.133967727 +0.1435470853787408 -0.6795128886902857 -0.5914647754299301 +0.144512326 0.176229015 -0.17698203 +0.144691348 -0.829557955 -0.0512732379 +0.147239551 0.463307172 -0.518607199 +0.147734836 0.362128615 -0.164326921 +0.147869036 -0.18887575 -0.397241265 +0.151215598 -0.859129548 0.115865424 +0.151839092 0.00595229492 -0.213026837 +0.1525223473313913 0.3194859273226787 -0.4609007699234466 +0.1530065136290136 -0.02841976117046172 -0.3413931936040054 +0.15741092 -0.140593469 -0.234443828 +0.157445252 0.0988840461 -0.38126117 +0.159321845 -0.541306198 -0.544490695 +0.1600943954178103 0.1109348048361102 -0.2826616495415911 +0.165048867 0.249829784 -0.372602224 +0.166440725 -0.237569124 -0.104909129 +0.167752221 0.321619183 -0.292756259 +0.172875777 -0.395722359 0.196179479 +0.174281627 -0.858028948 0.243443146 +0.174638808 0.460680366 -0.390633613 +0.1734323084465734 0.6200488476265005 -0.4624439492054685 +0.1754207732813418 0.8174582088986908 -0.5165028692028552 +0.175964862 0.814889491 -0.10463772 +0.179673105 -0.273264229 -0.239785567 +0.180331901 -0.348597407 -0.355274171 +0.1859286528579371 -0.8217139413492982 0.4840310768222911 +0.183367819 0.499067158 -0.25679481 +0.184812814 0.638967931 -0.185194403 +0.184976444 -0.824638546 -0.490540892 +0.185503811 -0.843217432 0.373345166 +0.1857739966860616 -0.676906637750519 -0.4736601138516432 +0.1850535823331309 -0.5136508717889362 -0.4348956912302657 +0.1934382662492038 0.6409779414745185 -0.320635339585451 +0.196515024 -0.328473836 0.0366359241 +0.196529299 -0.576009452 0.6809026 +0.201898694 0.811400414 -0.385127723 +0.204532206 -0.457078785 0.436814785 +0.204854414 -0.705364943 0.710002303 +0.206307203 0.813853562 -0.231528997 +0.209077805 -0.6653877499999999 -0.345049381 +0.2105447846641392 -0.79659967997352 -0.3546815705334064 +0.209213629 -0.413922787 -0.208821177 +0.216096535 -0.5198385720000001 -0.285382003 +0.222636908 -0.369766533 -0.0768596232 +0.233453125 -0.47534138 0.312963724 +0.233569518 -0.619843602 -0.208220512 +0.23561959 -0.837968171 -0.0618026778 +0.2529053402806382 -0.46976650455032 -0.07455524994106622 +0.259980291 -0.553368807 -0.124389559 +0.260360152 -0.515967607 0.563154161 +0.263627082 -0.75430429 -0.179129139 +0.2672170122237414 -0.4234431756269894 0.04093246097712905 +0.271830857 -0.800414145 0.573493183 +0.283700079 -0.664684415 -0.0558411255 +0.288171768 -0.625955641 0.571363807 +0.298276544 -0.49471578 0.171411037 +0.311004728 -0.781411946 0.00391090289 +0.313544303 -0.56076169 0.00208512694 +0.321718127 -0.585165083 0.461940259 +0.328786582 -0.667592704 0.106779717 +0.341983974 -0.842508316 0.121303469 +0.345109731 -0.703431964 0.427407026 +0.3481985759569923 -0.8093772090579345 0.4172878712348541 +0.355405271 -0.748922825 0.225999638 +0.356863171 -0.643423021 0.29608044 +0.367213726 -0.833656847 0.270671099 +-0.01516661837330839 -0.6842387991251004 -0.3530995985406293 +-0.1038364182475301 -0.6667806381901306 -0.44018715167843 +-0.04424870132435369 -0.57750794171926 -0.3545663984180183 +0.05519735010112541 0.3827254944303638 -0.3239883533178926 +0.06489617078225209 -0.5889039786745697 -0.4374258844590888 +-0.04916096577006725 -0.3187828775212522 -0.5409876354956336 +-0.06423940671364611 -0.5129590180408742 -0.6093800163708188 +0.06793065862944107 0.06488991876889072 -0.2440615297278582 +0.06104183096447444 0.6986170765774582 -0.5161264805031263 +-0.2039712863711774 0.666299597821516 -0.1266748141429059 +-0.03836604039184401 -0.4895116954989642 0.175051231887421 +0.05038085912435767 -0.524790074771445 -0.1893751323536057 +-0.03841920110974498 0.6342874928842819 -0.5071042864362028 +0.2226484337641577 -0.5345527299636351 0.09577217452595507 +0.04222612385310694 -0.06497113948738668 -0.1418287944454058 +0.06234990193130338 -0.6470112466759443 -0.287044792542319 +-0.1298029740320732 -0.4170221221613959 -0.408483668588785 +-0.1232483389559539 -0.5301522037547401 -0.4473617329996495 +-0.04873499249628267 -0.4036108320337408 -0.6161526651180348 +0.08218438850942922 0.4997529473397724 -0.1888283249670307 +-0.02452568442126781 0.6809296950092939 -0.6129527849051406 +-0.1235268827041862 -0.5135428658940108 0.1395448083466359 +-0.09655556000340661 -0.4728601004667475 -0.1196147908164918 +-0.07449417934999999 -0.1979671195 -0.705746144 +-0.1637873526839208 0.745844611721165 -0.4092679817553788 +0.1444230509120569 -0.5748646508084772 0.3962820247485481 +0.003720295500908532 0.1202901956846461 -0.2999726594264623 +0.101028398885923 -0.4527601193169976 -0.06820678639686192 +0.02194901377527404 -0.5362065291805502 -0.01143240492233416 +0.1115331288542401 -0.5370594071240675 0.08342537301364292 +-0.1172992712794922 -0.468247767944113 -0.1935908456450557 +-0.2219748115652297 0.5828667469975489 -0.5819089546196131 +-0.2457512369335265 0.6441361628509172 -0.417450903251387 +-0.2424690031988042 0.7184589362158688 -0.5263325909530127 +-0.2298714385969167 0.7390582741008711 -0.2786682652793973 +-0.1013902434388698 0.4134355814451671 -0.2528732282403525 +0.0788646739285071 -0.7493553506710302 -0.07120323533877623 +0.06883336180450332 -0.7717162165488283 0.1140092418963619 +-0.01254002365 -0.7905123535 0.5743890254999999 +-0.1406055037288251 -0.7487327235426073 0.2767447154937704 +0.02769223230218885 -0.6908823747743122 0.639774754418195 +-0.147184205406739 -0.6394567401393753 0.1389229964191241 +-0.1425635344870045 -0.6284483417790944 0.2796519038274589 +0.1601772931949255 -0.6760254363303235 0.5934420969980487 +-0.1193161027508175 -0.6726639591945356 -0.3292325605860831 +-0.1678642555 -0.5804598479999999 -0.6489104035 +0.05651262160994593 0.4185025587488633 -0.1550510875741851 +-0.1401451108785856 0.04806685723537291 -0.4409400650159934 +-0.1386800620640785 0.1775772439070139 -0.4257320063046379 +-0.1674452846168165 0.2758068139232797 -0.5242983015108866 +-0.167073130406575 0.2935773872872147 -0.412828095543388 +-0.1408475155358994 0.2982525328649374 -0.2864504104526154 +-0.05286315710495622 -0.7440722380715928 0.3436867203821727 +-0.162447856262259 0.4122768924441493 -0.1693525702832186 +-0.1617080795322758 0.5060167293923151 -0.5338139001146092 +-0.1670707222159307 0.5076727567644962 -0.3013828700893551 +-0.153807137758826 0.5559939566465852 -0.1599403949062413 +-0.1347089891628173 0.6078719275248157 -0.6480128053526252 +-0.1439682718718177 0.6330330580720551 -0.5271416630571911 +-0.167510263575876 0.6395730750391071 -0.3190886003353937 +-0.1411115851560732 0.7431136926000589 -0.6332028875204901 +-0.2101062548944941 0.4569858808001463 -0.4150838203725229 +-0.1852670560327649 0.7541227773810404 -0.1597247399472156 +0.02436971778785706 0.7623946821321861 -0.07322230575735852 +-0.02979750712320895 0.775614033924237 -0.5684670066425611 +-0.1284671686 -0.8394866885 -0.544305861 +-0.0724204064878612 0.8558131964276422 -0.268889861820613 +-0.1095159981387333 -0.7252169621477272 0.002597890173557196 +-0.04261753998376452 -0.7398923249243822 0.1135583929166431 +-0.0410298100676783 -0.6465517332643104 -0.2002528649465011 +-0.07421745003712611 -0.6452932021612899 0.02916709399075243 +0.09929948285000001 -0.2529553625 0.005510159000000001 +-0.0329878111148544 -0.6473620204914337 0.2685500067885168 +-0.04510069492380248 -0.6524998730706871 0.3807018866682773 +-0.05678508878634721 -0.6539015536159194 0.5138588468708973 +-0.1507510570400494 -0.7476049574023709 -0.399877294225076 +-0.03550412919908662 -0.5158613958353444 -0.5167473485757833 +0.09766653784280703 -0.5717114748139084 0.1946473011504498 +-0.05738364990395242 -0.5186038004411195 0.282327411603284 +-0.03764214326197613 -0.5268525726061921 0.4069923760640229 +-0.04637361165914036 -0.4102616363071517 -0.3104952321574284 +-0.03146884446651445 -0.4147871925738892 -0.06437856242436914 +0.0949308794275415 0.5700634736423831 -0.387169761316161 +-0.04046038500293044 -0.2700669687877452 -0.4305803097084324 +-0.04084410309923409 -0.2964501278855499 -0.07530360169032434 +-0.0508834157227975 -0.1924474119759091 -0.5283704206269965 +-0.07768756242500439 -0.1678075558722162 -0.4343624449722856 +-0.05288188573846675 -0.1890768203954488 -0.311810490601195 +-0.04232783113906836 -0.1753357621357035 -0.1717421033155047 +-0.01889040901874376 -0.0813073483721327 -0.5158378527170734 +-0.06613184623250291 -0.06021824847035954 -0.4127687560693022 +-0.06874109809683933 -0.06299454826021536 -0.3070011882969901 +-0.03296424016326154 -0.485891718118505 -0.3975325155222627 +-0.04116453400189356 0.05253844650375191 -0.5315743329679471 +-0.07474468668430467 0.06714006320187579 -0.316104141753111 +-0.05054237187750505 0.07043572655395268 -0.1866276849964905 +-0.06071604585352285 0.1364293001762346 -0.6278481355696105 +-0.06819825386388963 0.1722043449563821 -0.5224190754051936 +-0.03027533818042522 0.1722564671063676 -0.4138946453968565 +-0.01891302763177446 0.3458773150355637 -0.2774941148832079 +-0.07903731050988351 0.2995323546253846 -0.6394689847556206 +-0.04311785717040582 0.295858146419898 -0.1690557620888477 +-0.08160922009870471 0.4189725438976243 -0.6568423111717796 +-0.04116339499009936 0.3919124588177486 -0.4145264402952112 +-0.04895554487591526 0.5507054456859332 -0.6197333067663726 +-0.06020509245021324 0.5167464876727024 -0.5182717965801009 +-0.02962465678954992 0.526026761923899 -0.4132645570027549 +-0.03115405106221494 0.518156949284305 -0.1951014900941493 +-0.05062292950997811 0.5114739793834951 -0.08623419678446125 +-0.03731411005477289 0.372190302764195 -0.5553335910910918 +-0.03151613084170071 0.7501247620910095 -0.44243510668758 +-0.05609570238917142 0.7352688937115154 -0.3138645214320424 +-0.03406772418354841 0.7446010247801856 -0.1870849806067243 +0.04049011188017014 -0.7599293743747169 -0.5238845252527395 +0.05931913785000798 0.4785744006444566 -0.4331380308643591 +0.05412637506981312 -0.7463184285265464 0.2876850548760746 +0.03578235683948933 -0.7318307187334745 0.412677878863006 +0.05018941665033506 -0.6423222955029358 0.0526672828733643 +0.05421920941502577 -0.6504204761244066 0.1604453965324863 +0.06430561861879634 -0.6063848919291535 0.3032558567910273 +0.08160647353457798 -0.6248100491179428 0.5067684417195567 +0.01295619822282088 -0.5968431910700619 0.602771859854844 +0.04561817839406142 -0.5118129350488325 -0.3218060752510774 +0.1882456499402341 -0.7195539659415668 -0.07321644602628058 +0.04140007739063312 -0.3982794137921029 -0.5363777591341139 +0.06806702026728781 -0.4158607941591007 -0.4003090103259003 +0.07649224345722848 -0.3785225486407517 -0.300164374380523 +0.0499140712348471 -0.4262051748474424 0.02163083521550545 +0.04166649498947928 -0.4100927954257022 0.1366509027332524 +0.04445086216931746 -0.2705179068542455 -0.5142764938070129 +0.04738909374074354 -0.268104776416499 -0.3224223075154273 +0.05612968216936808 -0.2841678995237972 -0.1868274891278607 +0.05908257010465473 -0.2573098600249528 -0.08342281063883947 +0.03780490790564472 -0.1671161755534442 -0.4219643825533548 +0.07140202701567989 -0.1642772739352439 -0.1513136141764671 +0.05322433170270254 -0.05241461451376127 -0.4200552864258515 +0.04613157129410252 0.06508828196474195 -0.4157087968597886 +0.04099709310237416 0.1990403231555819 -0.5069782179842941 +0.06794952974196058 0.1644125206846948 -0.4028820103490431 +0.06419590141350388 0.3839619209831191 -0.4759777915854046 +-0.05221991485201905 0.2793445988454365 -0.496505985993958 +0.05898184635459695 0.5487840893721118 -0.5119565307847976 +0.05668873960689468 0.5024533975836316 -0.3126328183770923 +0.05236097841688669 0.6344548212650076 -0.2947610597350573 +0.05018048702787267 0.6268500340426121 -0.1718992311851589 +0.08498120697637543 0.7449374938777404 -0.4109705728200929 +0.05775269996616451 0.7651142060742937 -0.2969897890936795 +-0.04384041312278954 -0.4092159328710809 -0.473257657795793 +-0.0464313648669679 -0.5079460582395391 -0.2453264858807392 +-0.06137571870266476 -0.03247083184336908 -0.2325405717389603 +0.06933166230416661 -0.4831187464988431 0.2210037174026012 +0.1438260142677743 -0.7322351084627358 0.1748489262700822 +0.1828974259649463 -0.7434429188568589 0.2983058511712224 +0.1647046188809715 -0.7320025395093005 0.5083152654006778 +0.1731407276337705 -0.6346780014830802 0.02618034502544842 +0.1576952855029733 -0.5083227927344987 -0.1750426531412364 +0.175475179560819 -0.5257673693353341 -0.02344963462962484 +0.1598141257141633 -0.5582165092849282 0.2765393330527918 +0.1421095177224921 -0.4242458302270916 0.07576177402314868 +-0.04667654657484888 0.6285763641659922 -0.2775959281074729 +-0.03696592632138751 0.6289447111368461 -0.1005000759728445 +0.2492196060714338 -0.7466254808928061 0.1674108005935503 +0.2551728424260196 -0.7541162012909347 0.395776824959804 +-0.1651195416637103 0.3746478124693924 -0.4770617142393561 +0.06749199628192783 -0.4826311241699348 -0.4704202463989485 +0.1622502546146493 -0.4998605830937703 0.1627007848775459 +0.104042837559012 -0.7158239239711286 -0.4214866699075888 +0.08624916745737782 0.1786644482435265 -0.3001161111943936 +0.09614725589169658 -0.6657280485636569 -0.5020547750155907 +0.1036802746347534 -0.4023338232709932 -0.178386719251496 +-0.0835587843634471 0.6514920231051267 -0.4049481388352014 +-0.09766639030879649 0.6554329128278867 -0.2075076787293941 +-0.2230671501115378 0.568103904515911 -0.248666855250193 +-0.09753151495 0.2233136595 -0.0752009842 +-0.04926586772602443 -0.3157238314879232 0.1064725615289508 +0.05058958905476622 -0.7199651716265337 0.5370405943331138 +0.02045876689607906 -0.7747398849476546 0.6367509664030245 +0.03615812380292567 0.2751053608135626 -0.1084467625699371 +0.07219453902369696 -0.7371320846420008 -0.3153063718104406 +-0.03719550001302759 -0.5965653370952981 -0.4529203120975391 +0.183484410662755 -0.6081518521615361 -0.07778034881302988 +-0.0323171703615218 -0.7391565255641513 0.2227391093116915 +-0.1846491095 -0.5318560154999999 -0.5983676615 +-0.05299588495457002 -0.6292703994556509 -0.6193877608626934 +0.09385385326278477 -0.1578683829925953 -0.04736204562743743 +0.07977157865228185 0.2793534293480348 -0.2518071813813316 +-0.04620445003853372 -0.6076245234498828 0.1325268914132696 +-0.148695029 0.289784402 -0.08211444130000001 +-0.07149611829500382 -0.5234079342164223 0.5937993465887432 +0.1447832970356743 -0.5675888392137982 0.5776226950218897 +-0.1482714312889327 0.752521350297968 -0.05657776639008117 +0.2679359215083816 -0.6763568054313676 0.3498894892472389 +-0.3301699911370826 0.656426665857782 -0.3469878330876001 +-0.2698417302213574 0.3407864577065969 -0.3130652875849203 +0.03793835832116829 -0.4956050405117455 0.3184655290799733 +-0.1127682399554304 -0.5829377120002084 0.5761283139794029 +-0.02414734706595418 -0.1876756013753043 -0.6993398350187969 +-0.01317725584390936 -0.4901158553318383 0.576233485032088 +-0.1452704724263506 -0.731481432590412 0.08856335626673266 +0.03193201125769752 -0.846530059343918 -0.5311475603946268 +-0.0576957493073297 -0.769465587712245 -0.4130760840259873 +-0.002501685608795115 0.1726439071898592 -0.1221162399356999 +0.01338701803144447 0.465608414075905 -0.01967664669569302 +0.3354603349868608 -0.7552922062328541 0.1273724632170554 +0.07239449250556726 0.7353530967241665 -0.1501368574954326 +-0.1352703690157785 0.7602117002510013 -0.2657846687954945 +0.09941871199999999 -0.830288023 -0.410704449 +0.0357840460086554 -0.5180462800502067 -0.5844420971962083 +0.07252185960537327 -0.8433272094522797 -0.4850514500451789 +-0.0003952337356163456 -0.2459575549001307 -0.613877269207647 +-0.142471756056716 0.552966890873596 -0.4248831620421548 +0.06893926150527853 -0.3037775100328594 -0.4079725278799413 +-0.05125620399604335 0.5269215237445734 -0.2960895988069934 +0.03541112108736277 -0.611531486922568 0.4210283444998401 +-0.07583109529359106 -0.5268619330344847 0.04305396547452818 +-0.08135139017375627 0.1876900481540029 -0.2226018402675326 +-0.1502082070602808 0.3874268370442077 -0.5745892742878935 +-0.1900484391174759 0.4063725809921304 -0.2895486545485104 +0.02630056931831318 -0.1584183510176315 0.05415232128203682 +0.2316801061171584 -0.55538417211929 0.2169331325039822 +-0.2009295807824788 -0.2636532056731017 -0.4132262770124185 +-0.072533492 0.0112435965 -0.7142762545000001 +-0.08406065744323962 -0.7931502140138431 0.5635660975110519 +0.05154683343742941 -0.5220070396422233 0.5542182062474307 +0.002354124797718812 0.7473596720621315 -0.6623292436356503 +-0.0652666200583802 -0.7699017374084222 -0.1148982240968443 +-0.1361871021833298 -0.7399270942834645 0.4747657668481883 +-0.2532370335987405 0.7340024945801128 -0.6603096486697033 +0.2463164550173692 -0.6597132015441184 0.2491010955407691 +0.08820067638026732 -0.5320536293955843 0.6608846666383021 +-0.134085965262465 0.08927562549967678 -0.5538730511433252 +-0.055936454665 0.4277369235 -0.7435166835 +-0.114712792665 0.5149587394999999 -0.713526398 +-0.1607602212765926 0.4146240036022951 -0.7251867443326804 +-0.1486032136589616 0.004649078090406746 -0.3293885915515453 +0.1304563298769548 0.8341297540050808 -0.3032403969758948 +-0.03746696565 -0.233472444 0.0407053865 +-0.2394352532210237 0.5468631953174872 -0.4765801526994395 +-0.01215063047750734 0.317134150832673 -0.3567106138591475 +0.07202085447224625 -0.351426270623801 -0.09495834337745462 +-0.220392063 0.2098294315 -0.2199610695 +0.06185710467906097 -0.6380766297051272 -0.1856147538988 +0.2322833691676552 -0.4867285151836998 -0.1799991416611027 +-0.3119880555 0.712339222 -0.2037833185 +0.1368893059072595 -0.5814999872484523 -0.3270941698780799 +-0.1223071778862461 -0.5500050771089829 -0.1729712314216239 +0.06673690977023662 0.7693208929709499 -0.00842732778346417 +-0.1904251377391052 0.7558432491878341 -0.7130312581052586 +0.1690808584450985 0.3473269672367376 -0.3830608285420153 +0.288801782 -0.8402382435 0.0297503956 +0.02622232879693486 -0.5302982662437763 0.4757327292407768 +-0.0183449014 0.370518938 -0.0464378372 +-0.1903826693072722 -0.4222361134323813 -0.1354671209421879 +0.2496463254447532 -0.7889088030870256 0.0735407830804036 +-0.1235056335024319 -0.4749265429806165 -0.3308942062412519 +0.2409085293862189 -0.6701442653846353 0.4654051772183429 +0.2945699992893762 -0.5585811554989011 0.304602544507207 +-0.1191296235736261 -0.3875761244942451 -0.6933370865773161 +-0.1157500335 -0.2790268435 0.03161331265 +0.2763587685 -0.8384371395 0.3220081325 +0.2649115024159078 -0.849579838301815 0.1790176788524503 +-0.262152277 0.8280294834999999 -0.257356547 +0.350257501 -0.7261773945 0.326703332 +0.10251700885 -0.33203198 0.156054463 +0.1183149376427278 -0.07838331800977584 -0.5087555364878619 +0.277585626 -0.5302532315 0.3874519915 +-0.1944368152152246 -0.1826192554925006 -0.4138110551348969 +-0.1526688550908809 -0.8345162454849302 0.3489068008396785 +-0.04082009606855339 -0.3769089911320876 -0.7103408443156345 +-0.165234327 0.02280019435 -0.1531455815 +-0.1654898333624731 0.4800790526570085 -0.6282812272500738 +0.1602023126870977 -0.7294838765835799 -0.2747437646392027 +0.1096524882737264 0.835133968076802 -0.4461380289030565 +0.07660774370499999 -0.8420233425 0.02287079955 +0.3275698575 -0.5690694005 0.2337457385 +-0.08467522566500001 0.5912027360000001 -0.737666905 +0.1455054532161788 -0.4514353813380044 -0.5377435286478244 +-0.1411481991846898 0.2968919083048049 -0.1824990965114713 +0.0114079507010491 -0.5950125531386308 -0.1094682470079718 +0.199663073 0.724069089 -0.2763845175 +0.1114886675 -0.8168376685000001 -0.3451368215 +-0.1099503437177288 -0.2412901388203659 -0.2366880763596546 +-0.017694313 -0.7511534095 0.6965161559999999 +0.1431096904 -0.5032289325 0.638098925 +0.3520407975 -0.779178053 0.321155153 +-0.2825469857957459 0.3495969325764126 -0.4680903132032763 +0.1803878695 -0.474255204 0.52155672 +-0.1858486264790977 0.1063104813196252 -0.6289363222483447 +0.1570712724314283 0.731716340776735 -0.5510983970508274 +-0.06659147403420877 -0.01578208631143236 -0.6129054588725832 +0.193417594 -0.8485488594999999 0.0270313731 +0.036749566 -0.494649023 0.6484815775 +-0.115587214355867 0.7439639012432957 -0.5174425558540378 +-0.0440637218 -0.5600459575000001 -0.704345733 +0.1896268749832072 0.7235026308420007 -0.4144016160972038 +0.2707476765 -0.8458428975 0.2570571225 +-0.261118114 0.713357359 -0.08613733364999999 +0.234586273701081 -0.7098037924357111 -0.2677717035528014 +-0.3294648188318147 0.7093617979608021 -0.2751809072022084 +-0.1219437900420682 0.2083239786354575 -0.3329841638425331 +-0.09712485548186824 0.3580326771095317 -0.3442060248304637 +0.005759818725479139 -0.5661672625397649 0.2258401061863436 +-0.0004943746962023828 -0.3442789086332137 -0.2454731391425157 +-0.001778130806560553 0.2422034786432708 -0.5842750424037224 +-0.1257867992287664 -0.5670333836557611 -0.686487540977054 +-0.09680619228880116 -0.5783730251666797 0.348451695446895 +0.2043724157584696 -0.6839367988769828 0.1060939440280873 +0.01448772671178451 -0.1150590299145745 -0.2360321189989673 +0.09363434379463564 -0.5602119622043179 -0.1026846147559647 +0.008510844999139264 0.6967894253685725 -0.3638876387562547 +0.1043664951969917 -0.460479556202861 -0.2454760935195052 +-0.1049117673349831 0.4505900979281928 -0.4685720440215463 +-0.1086961050837022 0.4617753692976997 -0.3596490095161626 +0.1096166037155372 -0.6681979702807177 0.2444326586334644 +0.02776952701932755 0.4351801427532089 -0.2430554130926877 +0.1019682923644694 -0.683478655310825 0.3485334805933175 +0.01636921647873059 0.4567975896164695 -0.5892435977354653 +-0.2757093025755675 0.8239742536588234 -0.4075517157250914 +0.02931901047247204 0.09858173079113175 -0.5684135731428268 +-0.07219052696963615 0.8539461501112448 -0.4737491016274907 +-0.1601405365 -0.393280372 -0.6526186169999999 +-0.3435374945 0.7059933245 -0.4870975015 +0.175769272272458 0.7205167214392192 -0.4842287770124099 +0.1998981055908728 -0.3184811893273326 -0.1565513786861612 +0.004034359909640936 -0.6916111228604457 -0.4551165422028181 +-0.206685655 -0.267484382 -0.48288098 +0.05075907426101605 0.03030921191603789 -0.5016696156051818 +0.180388838 0.726928711 -0.1449160615 +0.1750251169 -0.47320801 0.5792247055 +0.06766988811584136 0.764203621693781 -0.5776983792930263 +-0.202859208 -0.125351509 -0.3529131265 +0.2383061459837614 -0.7744797329829067 -0.2628698983387917 +-0.3299631175 0.705924362 -0.5596293505000001 +0.1221281105 0.721292943 -0.622448325 +0.3428248765 -0.6555078625 0.2014300785 +0.07356931 -0.806006193 -0.2614029945 +-0.1084001177 0.8269504605 -0.6677574515 +0.1645888315 0.225419566 -0.2917363345 +-0.2041942250739363 -0.4136377169403514 -0.2841912992792802 +-0.1835665925 -0.7049763204999999 -0.23394227 +-0.2117612215 0.07920980919999999 -0.5733094215000001 +-0.1377745006200073 -0.8378807378762957 -0.49791136569991 +0.1401251550456934 -0.09770588862763839 -0.4368083750572376 +0.006595256270000001 0.13104741455 -0.6954632995000001 +-0.301568031 0.4664848445 -0.393743485 +0.1383860621519387 0.3663672144931047 -0.5290883327992658 +-0.1259974283546055 -0.2179057713112924 -0.370702729293721 +-0.1218432371183575 -0.3375668519839077 -0.2626387881933172 +0.1977311490457127 0.7275538877656103 -0.3535811160893466 +0.198214218 -0.4342179895 -0.320328087 +0.02501715165 0.8365896939999999 -0.0392587518 +0.2549392361876615 -0.8170230348505372 0.452648407737674 +-0.2169762883101183 0.7249875896495308 -0.03419695654017618 +-0.2038329315 -0.546858549 0.0183010865 +-0.1247507953913713 -0.5935627594762262 -0.03508700435920114 +0.07772946159999999 0.7251196209999999 -0.678649783 +0.2368015520624202 -0.7507025250363716 0.6448887271205004 +-0.12845509305 -0.839743018 -0.4527811405 +-0.07269027868559851 -0.3540139948996949 0.009731121950225024 +-0.2370330765 0.8310997185 -0.1162076964 +-0.01375487075 -0.6173000635 -0.6864902079999999 +0.148296398684003 0.2235200308859782 -0.4584545419363154 +-0.09097361897930679 -0.7427386655039429 -0.5361431510111075 +0.2586347985 -0.6422640085 -0.13203081875 +-0.1255313794153674 -0.2752062265803566 -0.3144704671876326 +0.1598548792069995 0.3964411162221494 -0.4445518925227961 +0.01681363709686317 -0.3214828055764626 0.000560461022505567 +-0.02181580202723144 -0.358556705128774 -0.3878883674691768 +0.003846899016539269 0.002007224688906339 -0.3550223848305504 + +CELLS 2419 12095 +4 0 274 562 2 +4 206 366 551 590 +4 60 341 337 99 +4 1 52 502 275 +4 116 91 285 441 +4 116 419 441 241 +4 37 246 259 71 +4 445 476 213 520 +4 80 471 530 337 +4 478 7 9 295 +4 250 412 297 413 +4 585 478 302 7 +4 4 478 585 7 +4 312 134 607 504 +4 5 67 600 303 +4 5 303 502 67 +4 42 38 242 43 +4 42 242 243 285 +4 43 424 242 603 +4 6 12 11 413 +4 6 484 250 275 +4 7 585 10 302 +4 7 295 15 9 +4 297 349 348 401 +4 303 250 412 353 +4 7 10 526 302 +4 8 458 434 10 +4 8 458 296 11 +4 9 272 32 13 +4 292 540 541 479 +4 9 15 29 295 +4 9 29 32 511 +4 42 242 258 243 +4 344 355 380 346 +4 10 17 291 434 +4 10 541 434 291 +4 10 434 541 458 +4 11 12 35 297 +4 11 35 39 294 +4 11 35 294 297 +4 349 260 172 287 +4 151 394 357 416 +4 256 407 245 214 +4 12 68 250 537 +4 13 32 72 298 +4 256 214 245 485 +4 14 290 25 15 +4 14 526 290 15 +4 14 18 23 289 +4 14 18 289 291 +4 14 23 25 289 +4 14 290 289 25 +4 15 25 60 290 +4 15 457 60 29 +4 15 404 526 290 +4 322 480 268 543 +4 18 27 289 540 +4 17 27 18 540 +4 17 20 481 292 +4 540 291 289 18 +4 18 289 27 23 +4 17 291 540 18 +4 322 269 268 368 +4 543 410 372 480 +4 19 280 103 96 +4 20 292 458 518 +4 21 22 280 283 +4 21 282 30 24 +4 21 283 282 24 +4 21 280 282 283 +4 435 542 360 319 +4 22 283 467 280 +4 23 27 288 289 +4 23 25 471 581 +4 23 471 25 289 +4 26 467 105 508 +4 140 596 261 574 +4 28 87 577 301 +4 29 511 474 32 +4 29 60 93 341 +4 192 406 391 369 +4 30 594 282 48 +4 80 337 530 462 +4 560 127 132 351 +4 188 176 408 248 +4 380 489 183 606 +4 32 298 473 72 +4 32 474 473 511 +4 16 593 600 431 +4 426 555 191 244 +4 420 424 317 245 +4 34 582 43 41 +4 333 420 317 245 +4 33 45 258 257 +4 244 194 191 489 +4 35 294 297 349 +4 116 441 419 128 +4 36 257 246 566 +4 128 521 441 419 +4 521 215 407 214 +4 297 349 401 68 +4 250 68 401 102 +4 38 43 63 424 +4 36 246 37 71 +4 39 518 428 66 +4 40 53 57 327 +4 247 317 448 259 +4 247 424 448 317 +4 247 448 126 259 +4 247 534 126 448 +4 40 331 57 288 +4 40 475 331 288 +4 40 331 571 327 +4 247 424 534 448 +4 41 316 582 43 +4 42 242 316 43 +4 42 45 56 243 +4 42 285 56 51 +4 42 51 316 285 +4 42 285 243 56 +4 42 316 242 285 +4 43 424 603 63 +4 44 52 558 265 +4 44 274 533 265 +4 271 543 263 389 +4 45 47 56 495 +4 45 56 243 495 +4 271 389 263 486 +4 468 2 274 28 +4 46 588 49 579 +4 46 588 257 605 +4 255 248 174 548 +4 47 486 70 56 +4 248 548 182 174 +4 49 74 588 522 +4 50 62 390 510 +4 50 66 88 442 +4 50 456 481 66 +4 50 336 88 510 +4 570 161 196 529 +4 51 56 580 285 +4 249 351 550 386 +4 51 82 91 285 +4 52 446 307 67 +4 52 265 275 558 +4 52 275 265 446 +4 299 451 346 253 +4 53 587 326 327 +4 253 411 347 550 +4 54 65 522 332 +4 54 328 522 605 +4 54 605 587 328 +4 54 522 328 332 +4 55 320 83 58 +4 55 58 283 314 +4 55 320 98 83 +4 55 320 546 98 +4 56 70 580 310 +4 57 79 80 530 +4 581 528 25 471 +4 530 337 334 124 +4 58 315 320 83 +4 437 101 264 79 +4 493 271 263 486 +4 74 263 271 543 +4 59 455 594 61 +4 22 19 280 26 +4 19 508 280 26 +4 59 262 30 594 +4 60 80 99 337 +4 458 294 276 11 +4 47 493 486 271 +4 458 276 296 11 +4 99 341 123 93 +4 22 26 280 467 +4 318 547 270 406 +4 26 508 280 467 +4 61 70 486 595 +4 272 295 299 478 +4 478 9 272 295 +4 62 81 390 510 +4 62 390 332 475 +4 63 424 77 95 +4 63 424 603 77 +4 300 411 400 453 +4 10 404 541 291 +4 65 325 92 74 +4 65 329 325 522 +4 66 428 414 518 +4 291 344 404 541 +4 66 481 518 456 +4 593 76 431 16 +4 530 334 330 153 +4 69 315 90 89 +4 71 561 498 259 +4 71 450 259 97 +4 570 161 529 574 +4 170 195 249 382 +4 195 249 382 550 +4 72 104 298 516 +4 9 511 32 272 +4 272 295 298 299 +4 511 298 32 272 +4 140 261 170 574 +4 73 76 16 431 +4 3 9 272 478 +4 74 599 499 84 +4 37 317 247 259 +4 37 423 247 317 +4 78 319 117 98 +4 78 319 251 117 +4 78 55 24 262 +4 79 530 101 80 +4 61 493 263 486 +4 462 101 124 530 +4 61 263 74 322 +4 80 101 462 530 +4 251 319 542 391 +4 337 99 124 462 +4 427 359 358 251 +4 310 277 482 519 +4 310 482 256 252 +4 363 252 485 551 +4 81 100 255 390 +4 82 285 116 91 +4 82 310 136 116 +4 83 98 120 320 +4 249 253 550 351 +4 38 286 423 424 +4 286 423 545 75 +4 87 465 113 577 +4 87 104 119 465 +4 360 432 556 554 +4 88 255 122 100 +4 121 362 147 281 +4 392 402 469 393 +4 306 582 110 603 +4 306 603 110 77 +4 89 281 315 90 +4 255 548 375 329 +4 90 114 121 362 +4 146 165 281 212 +4 212 165 281 284 +4 212 147 284 281 +4 146 147 212 281 +4 92 477 325 373 +4 93 343 133 472 +4 93 343 341 133 +4 94 113 127 305 +4 94 113 305 465 +4 258 495 257 45 +4 95 109 601 424 +4 95 424 601 534 +4 266 233 496 432 +4 221 225 364 231 +4 96 309 138 125 +4 96 125 86 309 +4 96 138 422 103 +4 96 103 422 280 +4 97 509 135 259 +4 97 450 135 437 +4 390 255 329 548 +4 97 450 259 135 +4 364 225 228 231 +4 98 320 137 120 +4 271 49 493 74 +4 100 255 390 88 +4 101 530 130 124 +4 48 308 466 311 +4 318 398 391 360 +4 318 360 554 398 +4 554 547 318 398 +4 103 356 142 138 +4 434 17 291 292 +4 434 541 292 291 +4 434 292 541 458 +4 57 53 326 327 +4 57 326 330 327 +4 106 139 145 353 +4 491 435 320 137 +4 491 320 360 454 +4 326 57 79 53 +4 108 441 91 128 +4 109 129 144 603 +4 508 293 103 280 +4 467 314 293 283 +4 280 422 293 103 +4 283 293 313 314 +4 398 547 318 406 +4 491 454 360 266 +4 137 435 164 491 +4 112 442 148 122 +4 112 148 442 418 +4 391 398 318 406 +4 112 418 442 342 +4 554 547 469 392 +4 392 402 547 469 +4 114 362 147 121 +4 201 384 383 260 +4 348 260 383 384 +4 115 136 277 177 +4 50 510 390 336 +4 203 407 215 205 +4 116 419 576 128 +4 116 128 91 441 +4 116 256 310 136 +4 116 419 241 256 +4 205 407 215 214 +4 117 435 319 391 +4 118 345 154 140 +4 119 465 161 113 +4 120 491 320 137 +4 120 464 158 152 +4 121 281 147 146 +4 66 442 414 88 +4 88 112 122 442 +4 122 156 442 148 +4 123 155 159 544 +4 123 544 337 155 +4 123 159 341 544 +4 124 153 155 559 +4 124 337 559 584 +4 59 24 262 78 +4 126 143 162 448 +4 129 354 163 144 +4 130 157 160 450 +4 19 439 96 31 +4 130 330 326 160 +4 130 160 326 450 +4 108 603 441 354 +4 131 156 174 255 +4 131 174 425 255 +4 131 425 373 255 +4 603 354 565 441 +4 132 387 476 139 +4 132 513 210 386 +4 132 387 386 210 +4 171 180 370 452 +4 134 415 607 369 +4 135 450 162 157 +4 353 106 303 431 +4 136 310 277 482 +4 136 167 277 177 +4 137 491 164 158 +4 139 353 387 445 +4 140 154 170 261 +4 144 163 175 354 +4 145 445 197 150 +4 147 209 212 284 +4 42 45 243 258 +4 273 274 265 299 +4 273 411 299 265 +4 274 265 299 533 +4 265 533 411 299 +4 229 233 496 266 +4 229 496 361 266 +4 149 172 179 287 +4 53 71 79 450 +4 53 71 450 246 +4 53 71 246 566 +4 151 165 200 394 +4 151 394 416 165 +4 151 200 204 394 +4 152 158 527 464 +4 152 464 569 524 +4 129 603 354 144 +4 110 603 354 129 +4 153 559 168 155 +4 153 505 330 160 +4 153 567 169 168 +4 153 559 567 168 +4 153 567 505 169 +4 171 517 206 405 +4 360 266 556 432 +4 154 382 557 178 +4 154 261 140 345 +4 154 345 557 382 +4 155 378 168 166 +4 104 261 345 140 +4 104 140 345 118 +4 298 261 345 104 +4 516 104 345 118 +4 298 104 345 516 +4 324 328 371 374 +4 324 371 452 374 +4 157 370 365 171 +4 159 380 586 178 +4 160 374 370 180 +4 160 374 330 326 +4 160 330 374 505 +4 339 379 479 267 +4 248 176 408 426 +4 339 267 377 379 +4 133 557 350 159 +4 164 192 219 406 +4 170 178 382 154 +4 165 394 227 200 +4 165 212 597 284 +4 165 227 394 284 +4 166 168 602 378 +4 166 602 183 479 +4 167 572 215 512 +4 167 220 225 512 +4 167 215 576 512 +4 168 379 377 186 +4 168 379 378 377 +4 169 583 184 376 +4 59 61 74 322 +4 59 74 84 599 +4 170 195 529 249 +4 59 322 74 599 +4 171 452 366 199 +4 171 365 366 452 +4 172 173 202 385 +4 173 197 568 445 +4 176 408 578 188 +4 607 599 368 369 +4 338 378 381 339 +4 178 380 606 194 +4 178 606 380 586 +4 178 380 355 382 +4 179 555 201 191 +4 409 424 448 175 +4 187 409 448 175 +4 187 409 175 205 +4 180 548 198 185 +4 180 548 371 198 +4 180 370 452 374 +4 180 548 374 371 +4 11 413 297 296 +4 4 413 296 300 +4 413 11 8 296 +4 4 413 8 296 +4 414 442 112 88 +4 311 358 466 269 +4 414 112 442 342 +4 59 455 262 594 +4 602 183 479 189 +4 181 193 501 402 +4 181 402 392 193 +4 181 547 494 531 +4 181 494 547 402 +4 262 251 455 599 +4 181 125 138 278 +4 181 193 278 138 +4 181 547 392 402 +4 182 184 185 548 +4 182 248 188 184 +4 182 184 548 248 +4 184 248 188 186 +4 61 263 595 486 +4 184 376 548 609 +4 61 595 263 322 +4 415 477 134 607 +4 359 358 270 547 +4 186 188 578 408 +4 186 408 248 188 +4 406 226 230 254 +4 187 205 206 245 +4 31 86 64 308 +4 31 439 86 308 +4 530 153 330 130 +4 530 153 130 124 +4 540 50 335 456 +4 190 372 373 375 +4 191 555 201 194 +4 347 323 382 550 +4 192 208 226 399 +4 192 226 230 406 +4 193 500 393 204 +4 193 402 536 501 +4 193 392 393 402 +4 245 424 448 409 +4 187 245 448 409 +4 194 201 207 383 +4 187 245 409 205 +4 205 245 409 407 +4 245 565 409 407 +4 195 550 382 323 +4 197 445 213 568 +4 198 371 372 548 +4 199 366 367 452 +4 200 403 592 204 +4 200 204 394 403 +4 200 592 394 227 +4 201 202 207 384 +4 202 445 520 207 +4 202 207 384 445 +4 202 384 385 445 +4 286 424 95 545 +4 545 95 534 424 +4 545 424 534 247 +4 204 403 500 393 +4 205 245 214 206 +4 205 245 407 214 +4 206 214 217 485 +4 411 347 550 400 +4 206 485 245 214 +4 71 450 97 79 +4 79 97 264 450 +4 437 264 97 450 +4 209 224 229 430 +4 212 284 229 597 +4 470 362 430 147 +4 292 276 518 342 +4 292 342 340 276 +4 276 342 340 287 +4 216 217 483 396 +4 216 396 590 217 +4 216 396 483 222 +4 217 396 220 223 +4 217 551 485 396 +4 29 341 457 60 +4 290 350 341 457 +4 457 343 350 341 +4 221 547 231 364 +4 222 223 232 397 +4 222 397 396 223 +4 222 226 397 232 +4 359 547 270 318 +4 223 421 396 220 +4 309 278 358 359 +4 224 233 229 266 +4 278 358 359 547 +4 495 47 56 486 +4 495 271 486 389 +4 495 56 243 310 +4 495 310 243 389 +4 226 254 232 230 +4 67 307 106 446 +4 446 353 412 352 +4 228 395 364 547 +4 311 115 466 358 +4 115 277 358 547 +4 229 236 496 233 +4 230 232 234 254 +4 270 399 268 368 +4 279 416 165 151 +4 269 270 268 368 +4 270 399 397 268 +4 269 270 397 268 +4 259 365 388 317 +4 178 355 380 194 +4 236 403 503 237 +4 244 555 191 194 +4 236 239 503 432 +4 74 543 588 522 +4 356 393 556 142 +4 142 394 393 556 +4 271 543 588 74 +4 187 245 206 405 +4 281 165 416 284 +4 417 89 281 315 +4 505 567 376 169 +4 505 376 567 330 +4 243 241 245 256 +4 243 256 245 363 +4 595 269 311 466 +4 595 252 519 310 +4 50 456 540 481 +4 285 310 243 56 +4 491 435 164 266 +4 304 445 141 401 +4 346 350 552 457 +4 149 492 349 287 +4 353 445 304 401 +4 268 222 397 396 +4 410 268 396 222 +4 216 410 396 222 +4 445 387 520 207 +4 445 207 384 387 +4 53 79 326 450 +4 28 533 301 94 +4 450 79 326 130 +4 416 394 357 361 +4 103 356 422 293 +4 293 313 314 556 +4 157 162 171 365 +4 162 365 517 171 +4 4 302 8 585 +4 423 424 247 317 +4 423 424 258 38 +4 423 317 258 424 +4 145 304 150 591 +4 145 150 304 445 +4 106 145 304 353 +4 591 111 106 304 +4 94 305 127 560 +4 32 511 473 298 +4 511 345 473 298 +4 136 466 115 277 +4 226 254 397 232 +4 171 366 405 206 +4 171 366 206 199 +4 43 603 34 63 +4 226 399 397 254 +4 285 243 310 241 +4 34 603 77 63 +4 116 256 241 310 +4 310 241 243 256 +4 116 285 310 241 +4 45 46 579 495 +4 257 495 46 45 +4 167 221 364 177 +4 167 221 225 364 +4 457 350 552 404 +4 142 293 357 356 +4 441 447 521 128 +4 304 111 431 141 +4 111 102 431 141 +4 111 304 487 141 +4 136 466 277 310 +4 31 439 96 86 +4 246 587 326 53 +4 50 66 442 456 +4 50 456 442 336 +4 426 148 176 179 +4 418 148 426 179 +4 131 459 373 425 +4 286 424 545 423 +4 316 285 91 441 +4 211 266 233 224 +4 211 506 233 266 +4 424 247 545 423 +4 22 55 58 283 +4 26 22 58 467 +4 22 283 58 467 +4 227 229 236 496 +4 227 229 496 284 +4 351 132 550 386 +4 132 550 386 387 +4 307 352 353 446 +4 307 446 52 352 +4 195 323 382 355 +4 195 194 323 355 +4 544 155 159 166 +4 110 354 163 129 +4 440 110 354 163 +4 273 451 299 411 +4 23 471 288 57 +4 23 581 471 57 +4 23 40 57 288 +4 190 198 372 375 +4 198 375 548 372 +4 292 342 456 479 +4 292 479 340 342 +4 58 315 90 69 +4 58 69 467 315 +4 478 299 274 273 +4 478 272 274 299 +4 340 344 555 244 +4 340 344 244 479 +4 292 340 541 276 +4 292 479 541 340 +4 198 185 548 375 +4 350 344 381 380 +4 325 480 372 373 +4 308 466 115 64 +4 64 308 86 115 +4 164 406 219 398 +4 406 398 460 219 +4 391 164 398 406 +4 347 382 323 355 +4 338 341 381 544 +4 290 338 341 381 +4 398 547 406 460 +4 398 460 469 547 +4 219 497 398 460 +4 469 460 398 497 +4 325 373 372 329 +4 329 375 373 372 +4 519 277 482 549 +4 519 549 482 252 +4 599 368 369 251 +4 305 570 161 127 +4 113 305 161 127 +4 127 161 196 570 +4 167 220 364 225 +4 225 604 364 228 +4 228 421 604 364 +4 358 547 277 395 +4 54 62 65 332 +4 332 62 65 390 +4 353 307 387 352 +4 307 132 387 352 +4 77 603 129 109 +4 77 110 129 603 +4 46 33 257 45 +4 290 291 381 404 +4 290 404 381 350 +4 350 404 381 344 +4 85 492 342 287 +4 85 492 287 349 +4 85 349 287 294 +4 227 592 496 236 +4 227 592 394 496 +4 227 284 496 394 +4 273 274 275 265 +4 273 300 265 275 +4 273 4 451 300 +4 275 250 300 446 +4 595 322 269 252 +4 89 90 121 281 +4 388 246 324 452 +4 388 608 452 324 +4 89 121 523 281 +4 607 368 480 399 +4 208 480 399 607 +4 208 480 607 312 +4 483 217 223 396 +4 21 439 282 280 +4 508 105 103 293 +4 483 396 223 222 +4 439 308 309 86 +4 283 546 314 313 +4 313 314 360 546 +4 389 321 543 551 +4 332 248 335 390 +4 390 335 336 248 +4 359 251 318 270 +4 270 399 368 369 +4 391 164 406 192 +4 451 553 552 347 +4 288 377 338 289 +4 288 334 331 57 +4 288 377 475 331 +4 288 331 334 377 +4 288 475 377 335 +4 74 493 271 263 +4 25 289 338 290 +4 289 540 335 339 +4 289 377 338 339 +4 540 267 456 335 +4 290 291 289 381 +4 291 381 479 289 +4 292 458 518 276 +4 292 276 541 458 +4 292 479 456 540 +4 295 451 346 299 +4 295 552 346 451 +4 296 451 300 453 +4 296 412 453 300 +4 296 453 276 553 +4 414 85 112 342 +4 428 85 414 342 +4 518 342 85 428 +4 409 424 175 354 +4 85 342 492 112 +4 174 548 182 185 +4 265 300 411 352 +4 265 351 411 533 +4 300 400 412 453 +4 537 303 600 593 +4 528 471 338 25 +4 528 337 338 471 +4 326 330 79 57 +4 57 334 330 530 +4 57 79 530 330 +4 401 445 141 385 +4 445 173 141 385 +4 401 304 431 141 +4 304 173 141 445 +4 86 125 115 309 +4 103 356 138 422 +4 105 293 467 357 +4 409 175 205 407 +4 300 446 412 352 +4 407 565 409 354 +4 115 309 125 278 +4 400 352 353 384 +4 409 175 407 354 +4 309 422 138 278 +4 309 311 282 427 +4 309 278 138 125 +4 313 314 556 360 +4 391 435 542 360 +4 422 278 356 138 +4 313 356 554 360 +4 315 454 314 320 +4 310 256 243 389 +4 310 252 256 389 +4 42 258 242 38 +4 311 427 455 594 +4 311 595 455 269 +4 258 424 242 38 +4 391 435 319 542 +4 451 552 346 347 +4 431 353 401 250 +4 250 401 431 102 +4 367 372 543 410 +4 321 367 608 605 +4 401 431 102 141 +4 322 599 269 368 +4 322 607 480 325 +4 322 268 252 543 +4 322 252 268 269 +4 599 251 455 269 +4 360 266 432 398 +4 324 605 608 371 +4 605 522 543 328 +4 432 233 506 266 +4 605 371 367 608 +4 522 372 329 325 +4 522 372 328 329 +4 522 328 372 543 +4 325 607 480 373 +4 326 327 324 374 +4 327 374 332 328 +4 328 548 332 329 +4 329 548 372 328 +4 329 372 548 375 +4 326 53 450 246 +4 467 357 314 315 +4 315 416 357 361 +4 467 416 357 315 +4 330 331 374 376 +4 332 548 390 329 +4 332 248 609 335 +4 201 260 555 179 +4 10 302 404 526 +4 172 201 179 260 +4 15 457 404 290 +4 10 302 541 404 +4 290 350 457 404 +4 39 518 294 85 +4 39 518 85 428 +4 334 338 378 559 +4 335 336 248 267 +4 558 0 44 274 +4 0 44 274 2 +4 116 136 167 256 +4 116 167 576 419 +4 505 376 583 169 +4 339 377 378 379 +4 116 167 419 256 +4 248 176 426 442 +4 248 156 182 176 +4 380 489 479 183 +4 344 380 479 381 +4 380 479 166 183 +4 344 194 380 355 +4 344 355 346 347 +4 75 259 126 498 +4 75 247 126 259 +4 75 534 126 247 +4 426 555 179 191 +4 61 263 493 74 +4 345 346 557 382 +4 347 382 355 346 +4 547 402 234 469 +4 37 258 33 38 +4 37 423 258 38 +4 405 333 317 245 +4 405 317 333 388 +4 405 388 365 317 +4 192 399 406 369 +4 348 385 401 349 +4 170 178 195 382 +4 348 385 384 400 +4 68 401 102 107 +4 369 399 406 270 +4 351 352 550 132 +4 352 353 384 387 +4 352 384 550 387 +4 342 426 340 287 +4 418 179 426 287 +4 287 555 179 426 +4 6 12 413 250 +4 413 12 297 250 +4 441 407 354 565 +4 441 447 354 407 +4 390 548 248 255 +4 125 115 278 514 +4 138 193 278 356 +4 356 142 556 357 +4 356 556 554 360 +4 315 361 362 416 +4 359 358 251 270 +4 210 387 386 589 +4 210 387 589 476 +4 406 460 254 230 +4 520 589 387 476 +4 207 589 386 387 +4 520 589 207 387 +4 171 452 199 180 +4 180 371 199 198 +4 321 367 543 551 +4 452 371 199 180 +4 277 395 269 358 +4 277 395 549 269 +4 358 270 269 251 +4 358 270 395 269 +4 402 547 234 494 +4 444 494 402 234 +4 444 494 235 402 +4 360 454 556 266 +4 268 226 397 222 +4 243 245 333 363 +4 3 4 7 478 +4 3 7 9 478 +4 530 79 130 330 +4 79 437 130 450 +4 599 477 415 607 +4 317 333 388 258 +4 37 258 317 388 +4 335 267 248 609 +4 144 354 424 603 +4 144 424 354 175 +4 314 454 360 320 +4 357 454 556 314 +4 177 181 531 547 +4 177 547 514 181 +4 299 345 261 253 +4 299 346 345 253 +4 298 299 345 261 +4 295 346 345 299 +4 295 345 298 299 +4 67 303 106 73 +4 277 364 220 421 +4 277 549 421 220 +4 460 254 230 234 +4 230 460 234 515 +4 469 239 497 432 +4 469 393 238 239 +4 460 230 497 515 +4 236 233 239 432 +4 547 234 460 469 +4 460 469 234 515 +4 469 460 497 515 +4 406 547 254 460 +4 547 254 460 234 +4 267 408 379 479 +4 339 378 381 479 +4 62 390 81 65 +4 390 329 81 65 +4 65 81 92 329 +4 595 252 269 519 +4 252 519 549 269 +4 198 367 372 371 +4 198 372 367 410 +4 198 199 367 371 +4 14 10 18 291 +4 10 291 17 18 +4 427 251 358 269 +4 311 358 269 427 +4 159 557 350 380 +4 311 427 269 455 +4 455 269 251 427 +4 105 69 463 467 +4 543 252 410 268 +4 276 294 342 287 +4 85 287 342 294 +4 518 342 294 85 +4 543 551 410 252 +4 518 276 294 342 +4 519 277 549 269 +4 216 551 410 367 +4 216 551 367 590 +4 199 367 590 216 +4 198 410 367 216 +4 198 199 216 367 +4 318 251 391 270 +4 251 542 318 391 +4 542 391 360 318 +4 246 370 324 452 +4 406 460 230 219 +4 315 454 361 357 +4 22 24 55 283 +4 419 214 407 256 +4 419 407 241 256 +4 547 358 270 395 +4 228 231 234 547 +4 299 451 253 411 +4 228 547 234 232 +4 297 412 401 348 +4 195 386 535 563 +4 195 563 249 386 +4 195 386 550 207 +4 195 249 550 386 +4 603 354 424 565 +4 195 207 535 386 +4 276 348 412 297 +4 276 348 453 412 +4 217 396 590 551 +4 206 590 551 217 +4 366 367 363 551 +4 84 78 262 415 +4 59 262 84 78 +4 113 465 161 305 +4 465 570 161 305 +4 564 480 410 218 +4 216 564 410 218 +4 410 268 218 480 +4 410 268 222 218 +4 216 410 222 218 +4 3 478 274 273 +4 127 386 513 132 +4 127 132 351 386 +4 127 351 249 386 +4 258 333 257 495 +4 186 578 189 408 +4 13 301 298 72 +4 13 299 301 274 +4 13 468 301 72 +4 13 299 298 301 +4 13 274 301 468 +4 281 416 315 362 +4 38 258 45 42 +4 33 258 45 38 +4 348 287 555 260 +4 204 393 394 403 +4 469 432 393 239 +4 165 417 281 416 +4 417 416 165 279 +4 165 417 146 281 +4 442 148 176 426 +4 149 179 148 418 +4 353 139 145 445 +4 130 330 160 153 +4 353 145 304 445 +4 299 301 533 261 +4 299 253 261 533 +4 298 261 301 299 +4 419 521 407 214 +4 419 167 576 512 +4 256 167 512 220 +4 303 353 431 250 +4 509 126 135 259 +4 96 439 422 309 +4 439 309 282 422 +4 139 476 213 445 +4 139 445 213 145 +4 44 560 52 265 +4 560 52 265 351 +4 242 420 243 241 +4 243 241 420 245 +4 211 219 506 266 +4 223 228 421 604 +4 432 506 219 266 +4 127 249 351 305 +4 305 249 570 127 +4 143 448 187 162 +4 187 448 143 175 +4 309 427 422 359 +4 313 554 356 422 +4 37 247 75 259 +4 37 423 75 247 +4 226 208 218 480 +4 226 208 480 399 +4 168 169 186 377 +4 158 211 527 266 +4 158 164 211 266 +4 158 527 491 266 +4 567 377 169 168 +4 491 266 164 158 +4 38 424 242 43 +4 258 420 317 333 +4 17 540 481 27 +4 481 540 50 27 +4 415 599 607 369 +4 471 288 57 334 +4 471 334 57 530 +4 425 174 190 375 +4 159 341 350 133 +4 425 190 373 375 +4 159 350 341 544 +4 425 312 373 190 +4 595 466 310 519 +4 20 39 66 518 +4 20 66 481 518 +4 466 358 277 269 +4 466 115 277 358 +4 595 269 466 519 +4 276 297 349 348 +4 294 349 276 297 +4 276 555 453 348 +4 172 385 141 173 +4 342 479 340 426 +4 281 147 284 362 +4 281 416 362 284 +4 147 430 284 362 +4 416 361 362 284 +4 430 362 361 284 +4 98 117 137 435 +4 98 117 435 319 +4 255 156 174 248 +4 156 248 182 174 +4 309 311 427 358 +4 309 359 358 427 +4 172 201 260 384 +4 172 384 202 201 +4 413 296 300 412 +4 127 386 249 513 +4 127 570 513 249 +4 249 570 513 529 +4 563 513 249 386 +4 563 529 249 513 +4 126 448 162 259 +4 259 450 162 135 +4 259 448 162 365 +4 259 365 162 450 +4 126 259 162 135 +4 395 397 549 269 +4 395 397 421 549 +4 107 349 401 385 +4 388 366 452 608 +4 152 470 464 524 +4 209 430 229 284 +4 430 284 361 229 +4 347 253 550 382 +4 346 382 345 253 +4 5 1 502 484 +4 13 274 2 573 +4 36 46 257 461 +4 556 432 393 554 +4 40 53 327 507 +4 356 393 554 556 +4 566 71 246 36 +4 58 26 467 69 +4 69 26 467 105 +4 85 492 349 107 +4 99 123 337 584 +4 108 440 354 449 +4 114 147 362 470 +4 252 396 410 268 +4 154 178 557 159 +4 212 229 284 209 +4 227 237 592 236 +4 467 293 280 283 +4 283 313 293 280 +4 283 280 282 313 +4 80 99 337 462 +4 380 586 183 166 +4 158 527 464 491 +4 258 317 420 424 +4 141 487 173 304 +4 177 221 364 547 +4 68 250 431 102 +4 496 233 236 432 +4 393 394 403 432 +4 242 243 285 241 +4 256 482 310 136 +4 491 360 320 435 +4 491 435 266 360 +4 435 398 164 266 +4 435 360 320 319 +4 391 398 164 435 +4 394 496 432 266 +4 394 403 432 496 +4 37 259 561 71 +4 7 526 15 295 +4 302 552 295 451 +4 526 295 404 15 +4 302 295 552 404 +4 37 259 75 561 +4 106 304 431 353 +4 304 111 106 431 +4 41 598 582 316 +4 582 242 441 603 +4 9 295 511 272 +4 295 298 511 272 +4 602 168 186 379 +4 209 430 284 147 +4 557 346 380 382 +4 557 346 350 380 +4 446 352 300 265 +4 181 125 278 514 +4 181 392 547 278 +4 278 392 547 359 +4 605 54 587 46 +4 108 449 354 447 +4 447 203 407 215 +4 327 53 587 507 +4 188 176 248 182 +4 477 607 325 373 +4 477 312 607 373 +4 177 364 277 547 +4 331 376 609 332 +4 332 548 376 609 +4 491 315 320 454 +4 450 370 326 246 +4 309 282 422 427 +4 282 313 422 427 +4 571 54 587 328 +4 571 54 328 332 +4 571 332 328 327 +4 435 360 398 266 +4 463 69 89 315 +4 391 360 398 435 +4 86 115 308 309 +4 311 309 115 358 +4 120 83 320 491 +4 553 347 555 344 +4 553 453 555 347 +4 302 451 296 553 +4 451 296 553 453 +4 273 300 411 265 +4 273 451 411 300 +4 451 411 300 453 +4 142 151 204 394 +4 180 452 371 374 +4 324 328 374 327 +4 142 394 357 151 +4 347 323 383 355 +4 142 204 393 394 +4 180 548 185 184 +4 180 184 376 548 +4 583 180 184 376 +4 276 340 555 287 +4 553 453 276 555 +4 453 348 383 384 +4 23 27 40 288 +4 537 600 16 593 +4 110 354 603 108 +4 421 549 396 220 +4 149 418 148 112 +4 421 397 396 549 +4 418 112 149 492 +4 295 346 552 457 +4 401 385 412 353 +4 348 385 412 401 +4 357 454 361 394 +4 454 361 394 266 +4 314 454 315 357 +4 228 395 421 364 +4 277 364 421 395 +4 272 299 13 274 +4 3 272 274 478 +4 272 299 298 13 +4 19 21 439 31 +4 31 21 439 48 +4 234 232 547 254 +4 547 254 395 270 +4 98 320 319 435 +4 406 547 270 254 +4 518 428 414 342 +4 518 414 442 342 +4 518 442 456 342 +4 179 287 418 149 +4 291 344 479 381 +4 291 541 540 479 +4 291 292 540 541 +4 169 184 186 377 +4 169 377 376 184 +4 184 377 248 186 +4 184 376 609 377 +4 248 184 609 377 +4 389 252 551 543 +4 59 322 455 61 +4 61 455 595 322 +4 59 599 262 455 +4 455 595 322 269 +4 81 100 390 88 +4 269 270 368 251 +4 599 368 251 269 +4 251 319 391 117 +4 391 251 369 270 +4 270 254 397 399 +4 79 330 326 130 +4 494 547 234 231 +4 402 575 238 234 +4 558 275 1 0 +4 6 12 250 484 +4 250 300 446 412 +4 253 351 411 550 +4 300 352 400 411 +4 172 384 260 385 +4 172 385 202 384 +4 412 385 400 353 +4 412 250 401 353 +4 33 257 37 36 +4 106 307 353 446 +4 106 353 303 446 +4 46 54 587 461 +4 187 245 405 448 +4 448 245 405 317 +4 245 317 448 424 +4 436 491 83 429 +4 89 463 315 279 +4 89 315 417 279 +4 440 108 354 110 +4 438 120 152 464 +4 15 295 457 29 +4 15 295 404 457 +4 457 552 295 404 +4 10 458 541 302 +4 458 302 296 553 +4 458 276 553 296 +4 309 422 278 359 +4 422 554 356 278 +4 278 392 554 356 +4 444 231 494 234 +4 444 231 235 494 +4 444 234 402 238 +4 444 235 238 402 +4 48 282 439 311 +4 282 311 309 439 +4 248 184 548 609 +4 445 353 384 385 +4 208 504 399 192 +4 285 56 580 310 +4 433 1 539 275 +4 186 602 379 189 +4 173 445 202 385 +4 436 58 83 315 +4 115 309 278 358 +4 278 115 358 547 +4 436 315 90 58 +4 60 341 99 93 +4 28 488 87 301 +4 438 491 83 120 +4 438 429 83 491 +4 417 89 523 281 +4 432 506 497 219 +4 432 469 398 497 +4 99 341 337 123 +4 431 102 111 76 +4 19 96 439 280 +4 96 439 280 422 +4 142 103 293 356 +4 438 429 362 114 +4 293 357 556 314 +4 336 248 267 456 +4 122 156 255 442 +4 442 336 456 248 +4 123 584 155 337 +4 36 461 257 566 +4 461 507 587 53 +4 194 383 207 323 +4 355 194 323 383 +4 443 149 349 172 +4 201 260 383 555 +4 82 310 116 285 +4 555 383 201 194 +4 244 383 555 194 +4 345 382 261 253 +4 446 275 265 300 +4 495 46 579 588 +4 257 588 46 495 +4 156 176 442 148 +4 156 176 248 442 +4 479 344 244 380 +4 344 244 380 194 +4 350 344 380 346 +4 462 337 530 124 +4 463 105 467 279 +4 3 13 274 272 +4 13 274 573 3 +4 120 491 158 464 +4 464 362 361 430 +4 438 362 532 114 +4 438 120 464 491 +4 456 426 479 342 +4 486 389 252 310 +4 486 252 595 310 +4 104 465 140 119 +4 119 140 596 465 +4 140 596 465 261 +4 104 261 140 465 +4 574 570 261 249 +4 163 203 354 449 +4 447 203 354 407 +4 449 203 354 447 +4 163 354 203 175 +4 175 203 407 354 +4 594 455 595 61 +4 594 427 455 262 +4 594 427 282 311 +4 106 307 139 353 +4 408 479 426 189 +4 489 479 183 189 +4 353 304 431 401 +4 468 28 301 488 +4 280 313 293 422 +4 422 356 313 293 +4 190 198 375 185 +4 174 185 190 375 +4 393 469 238 402 +4 479 381 339 289 +4 57 471 530 80 +4 289 339 479 540 +4 530 471 334 337 +4 23 288 471 289 +4 472 343 133 118 +4 452 608 366 367 +4 473 298 516 72 +4 473 345 343 118 +4 473 472 118 343 +4 491 362 315 361 +4 21 283 24 22 +4 491 361 464 362 +4 255 174 425 375 +4 255 425 373 375 +4 329 255 373 375 +4 388 333 257 258 +4 37 258 388 257 +4 474 93 472 343 +4 27 288 475 40 +4 419 407 441 241 +4 419 521 441 407 +4 5 484 502 303 +4 132 387 210 476 +4 520 210 589 476 +4 94 305 533 301 +4 478 451 299 273 +4 478 295 302 7 +4 478 302 295 451 +4 155 544 378 166 +4 450 157 160 370 +4 108 447 441 128 +4 108 354 441 447 +4 160 171 370 157 +4 27 288 289 335 +4 268 218 480 226 +4 27 475 288 335 +4 27 390 475 335 +4 73 431 111 76 +4 106 73 303 431 +4 106 431 111 73 +4 27 335 540 50 +4 27 50 390 335 +4 27 335 289 540 +4 86 309 439 96 +4 480 372 190 564 +4 499 477 415 599 +4 105 357 151 142 +4 142 103 105 293 +4 142 293 105 357 +4 19 21 22 280 +4 19 439 21 280 +4 482 277 220 549 +4 136 482 277 167 +4 256 167 482 136 +4 332 548 248 390 +4 332 548 609 248 +4 8 458 302 296 +4 594 455 311 595 +4 484 1 275 539 +4 59 84 262 599 +4 256 485 245 363 +4 84 262 599 415 +4 484 303 250 275 +4 348 555 383 260 +4 160 505 374 583 +4 374 180 376 548 +4 583 374 180 376 +4 172 260 179 287 +4 287 179 555 260 +4 372 480 410 564 +4 190 198 564 372 +4 480 372 373 190 +4 486 310 70 56 +4 495 486 56 310 +4 495 486 310 389 +4 9 295 29 511 +4 295 511 457 29 +4 534 448 143 126 +4 536 238 402 393 +4 536 500 240 238 +4 536 238 393 500 +4 342 418 426 287 +4 591 304 487 111 +4 591 487 150 111 +4 488 72 87 301 +4 468 488 301 72 +4 316 51 91 285 +4 448 405 365 317 +4 120 491 137 158 +4 114 470 362 532 +4 470 147 430 209 +4 470 362 464 430 +4 491 266 361 454 +4 491 527 361 266 +4 491 527 430 361 +4 464 491 430 361 +4 245 424 409 565 +4 565 424 409 354 +4 281 90 121 362 +4 281 362 315 90 +4 206 366 363 551 +4 492 149 349 443 +4 90 362 315 436 +4 494 547 231 221 +4 494 231 490 221 +4 494 231 235 490 +4 179 176 426 578 +4 12 297 68 35 +4 418 112 492 342 +4 418 287 342 492 +4 47 271 486 495 +4 495 389 333 321 +4 229 496 284 361 +4 519 466 310 277 +4 519 269 466 277 +4 71 498 97 259 +4 498 259 509 97 +4 74 325 92 499 +4 499 92 477 325 +4 533 305 253 261 +4 500 237 240 525 +4 301 533 261 305 +4 155 378 337 559 +4 559 337 338 378 +4 155 378 544 337 +4 467 357 293 314 +4 44 558 274 265 +4 558 265 275 274 +4 337 378 544 338 +4 558 274 275 0 +4 266 164 219 398 +4 398 432 219 266 +4 266 164 211 219 +4 50 442 88 336 +4 442 336 255 88 +4 256 241 245 407 +4 501 238 240 235 +4 263 252 543 322 +4 47 61 70 486 +4 263 543 252 389 +4 47 61 486 493 +4 151 416 357 467 +4 279 105 467 151 +4 279 467 416 151 +4 467 357 151 105 +4 283 58 467 314 +4 353 307 139 387 +4 503 403 525 237 +4 503 239 238 393 +4 594 262 282 427 +4 262 251 427 455 +4 117 192 369 504 +4 223 228 232 421 +4 223 397 421 232 +4 228 232 421 395 +4 232 421 395 397 +4 506 432 239 233 +4 117 192 391 369 +4 391 318 270 406 +4 391 406 270 369 +4 40 507 327 571 +4 461 54 587 507 +4 605 587 257 46 +4 605 328 324 587 +4 46 587 257 461 +4 19 508 103 280 +4 498 259 126 509 +4 44 533 560 265 +4 533 560 265 351 +4 261 154 170 382 +4 154 382 261 345 +4 339 379 378 479 +4 253 351 249 305 +4 487 150 173 304 +4 192 399 226 406 +4 406 399 226 254 +4 511 345 343 473 +4 511 295 346 345 +4 474 472 473 343 +4 198 564 410 216 +4 198 564 372 410 +4 287 492 418 149 +4 512 538 215 214 +4 512 215 521 214 +4 419 512 521 214 +4 557 382 380 178 +4 207 387 550 384 +4 557 178 380 159 +4 439 422 282 280 +4 144 424 175 143 +4 448 424 143 175 +4 206 485 551 363 +4 504 399 369 607 +4 469 515 497 239 +4 94 305 560 533 +4 533 305 560 351 +4 473 345 118 516 +4 142 393 204 193 +4 504 134 607 369 +4 607 399 369 368 +4 504 369 399 192 +4 142 193 356 393 +4 283 313 282 262 +4 313 282 262 427 +4 40 327 57 331 +4 57 327 330 331 +4 162 448 187 517 +4 517 187 206 405 +4 20 39 518 294 +4 37 388 317 259 +4 605 328 543 371 +4 520 210 476 213 +4 139 476 445 387 +4 150 445 197 173 +4 150 173 304 445 +4 328 371 372 543 +4 521 447 407 215 +4 450 160 326 370 +4 322 268 480 368 +4 270 399 406 254 +4 582 242 603 43 +4 582 108 603 441 +4 3 4 478 273 +4 305 249 253 261 +4 468 274 301 28 +4 28 274 301 533 +4 274 299 301 533 +4 492 443 349 107 +4 255 174 375 548 +4 523 121 146 281 +4 417 523 146 281 +4 115 177 277 547 +4 115 547 514 177 +4 90 429 362 436 +4 524 430 224 209 +4 524 470 430 209 +4 525 500 238 240 +4 503 393 238 525 +4 459 312 373 425 +4 473 345 516 298 +4 353 445 401 385 +4 505 330 374 376 +4 505 376 374 583 +4 153 567 334 330 +4 153 334 567 559 +4 124 153 559 334 +4 2 44 274 28 +4 152 527 569 464 +4 118 133 154 557 +4 263 389 252 486 +4 118 557 343 133 +4 263 252 595 486 +4 263 595 252 322 +4 118 557 154 345 +4 118 345 343 557 +4 528 337 80 60 +4 57 80 528 471 +4 80 528 471 337 +4 72 301 104 87 +4 72 301 298 104 +4 529 195 563 249 +4 87 465 301 104 +4 298 104 301 261 +4 301 261 104 465 +4 415 251 599 369 +4 338 377 378 339 +4 87 465 119 113 +4 177 531 221 547 +4 531 547 494 221 +4 531 494 490 221 +4 272 298 32 13 +4 536 393 402 193 +4 536 393 193 500 +4 268 226 399 397 +4 532 152 470 464 +4 438 464 152 532 +4 268 480 399 226 +4 368 480 399 268 +4 267 426 408 479 +4 232 254 397 395 +4 228 395 547 232 +4 232 254 395 547 +4 167 220 277 364 +4 167 482 277 220 +4 256 220 482 167 +4 359 360 554 318 +4 360 398 432 554 +4 398 547 469 554 +4 535 513 210 196 +4 199 367 366 590 +4 199 590 366 206 +4 259 365 317 448 +4 511 295 457 346 +4 536 238 240 501 +4 60 25 338 290 +4 60 341 290 338 +4 59 599 455 322 +4 322 455 269 599 +4 512 572 215 538 +4 512 220 225 538 +4 267 248 408 426 +4 74 325 499 599 +4 456 248 267 426 +4 599 499 477 325 +4 599 477 607 325 +4 433 539 6 275 +4 484 539 275 6 +4 255 88 122 442 +4 199 452 367 371 +4 109 424 603 144 +4 109 143 424 144 +4 81 255 329 390 +4 81 329 255 92 +4 290 289 338 381 +4 289 381 339 338 +4 307 352 52 132 +4 540 267 339 479 +4 52 352 351 132 +4 307 132 139 387 +4 598 441 582 316 +4 598 91 441 316 +4 478 451 295 299 +4 3 9 13 272 +4 4 296 451 300 +4 564 190 480 218 +4 57 334 331 330 +4 475 609 332 331 +4 475 332 609 335 +4 404 291 381 344 +4 541 340 344 555 +4 541 479 344 340 +4 291 541 479 344 +4 451 347 346 253 +4 451 347 253 411 +4 553 451 453 347 +4 90 114 362 429 +4 451 411 453 347 +4 491 315 454 361 +4 388 246 452 365 +4 388 366 365 452 +4 246 370 452 365 +4 321 367 366 608 +4 322 368 607 599 +4 322 368 480 607 +4 153 505 567 330 +4 330 334 376 567 +4 330 376 334 331 +4 331 334 377 376 +4 41 316 43 42 +4 41 42 51 316 +4 350 380 381 166 +4 380 166 479 381 +4 347 384 323 550 +4 347 383 323 384 +4 347 384 400 453 +4 347 453 383 384 +4 251 542 359 318 +4 551 252 485 396 +4 78 55 262 319 +4 78 319 262 251 +4 283 313 262 319 +4 313 262 319 542 +4 262 319 542 251 +4 60 528 338 25 +4 60 338 337 341 +4 25 289 471 338 +4 296 276 412 297 +4 296 276 453 412 +4 400 384 348 453 +4 256 485 363 252 +4 256 363 243 389 +4 256 252 363 389 +4 313 360 359 542 +4 542 318 360 359 +4 313 427 542 359 +4 542 359 427 251 +4 605 543 367 371 +4 338 544 381 378 +4 544 381 378 166 +4 348 385 400 412 +4 395 270 397 269 +4 546 314 360 320 +4 405 388 333 366 +4 405 366 365 388 +4 313 360 542 319 +4 543 522 325 372 +4 327 374 331 332 +4 374 331 332 376 +4 332 376 548 374 +4 159 166 350 544 +4 159 350 166 380 +4 349 172 260 385 +4 485 252 220 396 +4 217 485 220 396 +4 482 220 485 252 +4 482 485 220 256 +4 251 117 391 369 +4 389 321 551 363 +4 321 551 363 367 +4 389 252 363 551 +4 324 371 328 605 +4 328 548 374 332 +4 252 549 220 396 +4 549 397 396 268 +4 252 396 268 549 +4 58 315 467 314 +4 52 351 352 265 +4 265 352 411 351 +4 352 351 550 411 +4 288 377 334 338 +4 338 378 377 334 +4 288 471 338 334 +4 288 289 335 377 +4 289 335 377 339 +4 328 548 372 371 +4 400 550 352 384 +4 347 384 550 400 +4 216 396 410 551 +4 252 551 410 396 +4 216 396 551 590 +4 92 325 329 373 +4 50 336 335 456 +4 456 267 336 335 +4 353 385 400 384 +4 552 344 346 347 +4 404 344 552 541 +4 552 344 350 346 +4 350 344 552 404 +4 541 552 553 344 +4 552 553 344 347 +4 541 555 344 553 +4 344 555 244 383 +4 344 244 194 383 +4 344 194 355 383 +4 344 383 355 347 +4 344 383 347 555 +4 347 383 453 555 +4 346 382 355 380 +4 293 313 556 356 +4 313 556 356 360 +4 357 293 556 356 +4 554 469 393 392 +4 356 393 392 554 +4 294 349 287 276 +4 276 287 555 348 +4 555 453 348 383 +4 346 343 350 457 +4 346 350 343 557 +4 346 345 557 343 +4 511 346 343 345 +4 511 346 457 343 +4 556 266 394 432 +4 357 556 454 394 +4 357 394 142 556 +4 556 454 394 266 +4 556 432 394 393 +4 165 416 284 394 +4 416 361 284 394 +4 60 337 338 528 +4 52 275 1 558 +4 559 378 168 155 +4 567 378 377 168 +4 567 334 377 378 +4 40 332 475 62 +4 40 571 331 332 +4 40 332 331 475 +4 78 415 117 251 +4 94 533 560 44 +4 561 75 498 259 +4 562 274 573 2 +4 562 274 273 3 +4 562 3 273 4 +4 24 283 282 262 +4 59 30 262 24 +4 248 442 426 456 +4 141 172 107 385 +4 107 385 172 349 +4 171 517 405 365 +4 171 366 365 405 +4 517 187 405 448 +4 563 513 535 196 +4 563 196 529 513 +4 268 218 226 222 +4 48 439 308 311 +4 308 466 311 115 +4 439 311 309 308 +4 308 115 311 309 +4 441 242 241 565 +4 603 565 242 441 +4 242 420 241 565 +4 603 565 424 242 +4 566 587 246 53 +4 566 461 587 53 +4 567 559 378 168 +4 567 377 376 169 +4 567 334 378 559 +4 567 334 376 377 +4 529 170 249 574 +4 560 305 127 351 +4 130 530 101 79 +4 173 568 202 445 +4 20 518 481 292 +4 518 342 456 292 +4 11 12 297 413 +4 4 6 413 300 +4 514 115 278 547 +4 181 514 278 547 +4 569 430 224 524 +4 569 527 224 430 +4 513 570 196 529 +4 249 570 529 574 +4 127 570 196 513 +4 571 332 62 54 +4 571 507 587 54 +4 167 225 572 512 +4 512 225 572 538 +4 436 362 491 429 +4 438 429 491 362 +4 562 274 3 573 +4 469 575 515 239 +4 469 239 238 575 +4 234 575 515 469 +4 28 577 94 301 +4 577 465 113 94 +4 426 189 191 578 +4 45 579 47 495 +4 579 271 49 47 +4 495 579 47 271 +4 436 362 315 491 +4 123 341 337 544 +4 208 607 399 504 +4 402 575 234 469 +4 402 469 238 575 +4 57 528 581 471 +4 390 335 332 475 +4 181 402 235 494 +4 181 494 235 490 +4 181 501 235 402 +4 30 262 282 594 +4 30 282 262 24 +4 450 365 162 157 +4 450 370 365 157 +4 450 365 246 259 +4 450 365 370 246 +4 417 315 281 416 +4 315 416 417 279 +4 55 314 320 58 +4 58 315 314 320 +4 38 63 286 424 +4 5 12 484 250 +4 5 12 250 537 +4 582 108 110 603 +4 48 595 70 61 +4 48 64 70 466 +4 241 565 245 407 +4 441 407 565 241 +4 241 565 420 245 +4 271 74 588 49 +4 271 389 321 543 +4 495 271 389 321 +4 579 588 49 271 +4 495 588 271 321 +4 4 8 302 296 +4 4 302 451 296 +4 160 374 180 583 +4 71 246 259 450 +4 99 584 337 124 +4 257 388 246 324 +4 608 324 388 257 +4 257 324 246 587 +4 510 81 390 88 +4 510 88 390 336 +4 473 474 343 511 +4 78 251 262 415 +4 415 262 599 251 +4 0 274 273 562 +4 0 275 273 274 +4 0 562 273 4 +4 0 4 273 433 +4 0 433 273 275 +4 571 587 327 328 +4 46 605 54 588 +4 588 522 605 54 +4 207 535 386 589 +4 535 210 386 589 +4 443 172 349 107 +4 208 607 504 312 +4 145 591 106 304 +4 487 591 150 304 +4 594 311 282 48 +4 594 48 595 311 +4 13 2 274 468 +4 258 242 420 243 +4 258 420 242 424 +4 285 242 241 441 +4 316 242 285 441 +4 297 412 250 401 +4 179 426 191 578 +4 500 238 393 525 +4 503 239 393 432 +4 503 403 393 525 +4 413 412 300 250 +4 6 11 8 413 +4 284 496 394 361 +4 496 403 432 236 +4 348 349 260 385 +4 348 349 287 260 +4 160 171 180 370 +4 55 283 24 262 +4 55 283 262 319 +4 92 100 131 255 +4 92 131 459 373 +4 92 131 373 255 +4 276 294 297 11 +4 200 403 394 592 +4 592 403 496 236 +4 592 237 403 236 +4 592 403 394 496 +4 194 323 207 195 +4 175 203 205 407 +4 0 433 275 1 +4 340 426 555 287 +4 31 308 64 48 +4 31 439 308 48 +4 50 390 335 336 +4 271 543 321 588 +4 67 106 303 446 +4 332 65 522 329 +4 332 522 328 329 +4 68 250 593 431 +4 537 68 250 593 +4 36 246 257 37 +4 44 533 28 94 +4 44 274 28 533 +4 243 420 333 245 +4 258 420 333 243 +4 242 424 420 565 +4 420 565 424 245 +4 27 50 62 390 +4 27 62 475 390 +4 107 401 141 385 +4 481 540 292 456 +4 543 410 480 268 +4 252 549 268 269 +4 495 243 333 389 +4 206 485 217 551 +4 206 363 245 485 +4 432 469 393 554 +4 432 398 469 554 +4 145 445 213 197 +4 305 465 570 261 +4 253 382 249 550 +4 261 170 249 382 +4 253 249 382 261 +4 202 445 213 520 +4 568 445 213 202 +4 84 499 415 599 +4 47 49 493 271 +4 540 456 267 479 +4 541 340 555 276 +4 541 276 553 458 +4 541 276 555 553 +4 350 381 544 166 +4 549 397 268 269 +4 255 248 390 336 +4 257 37 246 388 +4 34 582 306 603 +4 34 603 43 582 +4 349 401 68 107 +4 107 401 102 141 +4 8 11 20 458 +4 11 294 39 20 +4 458 11 20 294 +4 437 264 450 79 +4 52 560 132 351 +4 35 107 349 68 +4 48 466 70 595 +4 405 363 333 245 +4 405 333 363 366 +4 206 363 405 245 +4 206 405 363 366 +4 596 161 570 574 +4 119 596 161 465 +4 596 161 465 570 +4 297 401 250 68 +4 96 138 309 422 +4 364 547 231 228 +4 288 471 289 338 +4 190 312 373 480 +4 165 597 227 284 +4 597 284 229 227 +4 5 250 484 303 +4 5 250 303 537 +4 117 504 369 134 +4 415 369 134 117 +4 295 345 511 298 +4 598 108 441 91 +4 598 108 582 441 +4 257 321 608 605 +4 605 587 324 257 +4 49 65 74 522 +4 65 74 522 325 +4 325 480 322 543 +4 74 322 543 325 +4 248 377 267 379 +4 186 379 377 248 +4 207 201 384 383 +4 207 383 384 323 +4 10 14 526 291 +4 10 404 291 526 +4 14 291 290 526 +4 526 404 291 290 +4 423 247 545 75 +4 225 220 364 604 +4 604 421 220 364 +4 223 604 421 220 +4 332 390 65 329 +4 130 135 157 450 +4 437 450 135 130 +4 124 155 584 559 +4 55 78 98 319 +4 36 33 257 46 +4 415 117 251 369 +4 600 67 73 303 +4 255 248 336 442 +4 546 55 98 319 +4 546 320 319 98 +4 546 319 283 55 +4 340 426 244 555 +4 426 479 244 489 +4 426 191 489 244 +4 380 244 489 194 +4 263 322 543 74 +4 29 343 341 93 +4 29 511 457 343 +4 29 457 341 343 +4 29 343 93 474 +4 29 343 474 511 +4 438 491 464 362 +4 46 588 54 49 +4 49 54 65 522 +4 49 522 588 54 +4 4 6 8 413 +4 5 537 600 16 +4 5 537 303 600 +4 537 250 303 593 +4 600 303 73 431 +4 601 109 143 424 +4 601 424 143 534 +4 584 337 559 155 +4 438 362 464 532 +4 532 470 362 464 +4 17 481 540 292 +4 481 518 456 292 +4 81 255 100 92 +4 37 33 258 257 +4 500 237 525 403 +4 500 525 393 403 +4 166 602 479 378 +4 602 479 379 189 +4 408 379 479 189 +4 87 301 465 577 +4 94 465 305 301 +4 301 305 261 465 +4 577 301 465 94 +4 391 435 164 117 +4 117 164 391 192 +4 441 521 447 407 +4 128 576 521 419 +4 576 215 521 512 +4 419 576 521 512 +4 378 168 602 379 +4 378 602 479 379 +4 181 392 278 193 +4 193 392 278 356 +4 554 392 359 547 +4 554 547 359 318 +4 593 250 303 431 +4 588 321 257 605 +4 495 588 579 271 +4 477 459 134 312 +4 477 373 459 312 +4 333 366 608 321 +4 388 257 333 608 +4 388 366 608 333 +4 259 365 246 388 +4 37 246 388 259 +4 207 550 323 384 +4 195 550 323 207 +4 15 457 290 60 +4 60 341 457 290 +4 446 52 352 265 +4 167 364 277 177 +4 35 294 85 39 +4 35 85 294 349 +4 107 35 349 85 +4 40 332 62 571 +4 27 475 62 40 +4 88 255 390 336 +4 116 285 241 441 +4 192 406 230 219 +4 219 497 460 230 +4 130 101 437 79 +4 37 317 258 423 +4 340 479 244 426 +4 489 479 244 380 +4 585 302 478 4 +4 585 8 10 302 +4 204 237 500 403 +4 592 403 237 204 +4 48 64 466 308 +4 48 311 466 595 +4 258 243 333 495 +4 464 527 569 430 +4 315 467 416 279 +4 315 463 467 279 +4 426 189 489 191 +4 426 479 489 189 +4 8 458 20 434 +4 434 292 20 17 +4 434 20 292 458 +4 456 426 267 479 +4 190 312 480 208 +4 208 218 480 190 +4 162 365 448 517 +4 517 448 405 365 +4 258 495 45 243 +4 68 76 102 431 +4 68 76 431 593 +4 133 350 343 341 +4 594 48 61 595 +4 6 273 275 300 +4 433 273 6 4 +4 433 275 6 273 +4 4 300 273 6 +4 92 255 373 329 +4 535 386 210 513 +4 563 386 535 513 +4 34 603 306 77 +4 463 69 315 467 +4 408 248 267 379 +4 186 408 189 379 +4 186 379 248 408 +4 35 349 297 68 +4 98 320 435 137 +4 117 435 164 137 +4 236 432 503 403 +4 503 432 393 403 +4 123 341 159 133 +4 93 133 341 123 +4 149 172 287 349 +4 600 431 73 16 +4 156 248 255 442 +4 217 220 485 214 +4 256 485 220 214 +4 512 220 538 214 +4 256 512 214 220 +4 389 363 333 321 +4 321 366 363 333 +4 243 363 333 389 +4 547 364 277 395 +4 533 253 305 351 +4 346 347 382 253 +4 299 411 253 533 +4 533 351 411 253 +4 300 412 400 352 +4 412 400 352 353 +4 251 270 368 369 +4 55 314 283 546 +4 55 546 320 314 +4 4 451 478 273 +4 4 302 478 451 +4 63 424 95 286 +4 418 148 442 426 +4 467 293 508 280 +4 467 105 508 293 +4 92 459 477 373 +4 530 334 153 124 +4 178 195 382 355 +4 178 194 195 355 +4 501 402 238 235 +4 536 402 238 501 +4 51 580 82 285 +4 580 70 82 310 +4 285 580 82 310 +4 82 310 70 466 +4 136 466 310 82 +4 82 466 70 64 +4 445 387 476 520 +4 464 527 430 491 +4 502 1 275 484 +4 502 484 275 303 +4 419 167 512 256 +4 419 512 214 256 +4 66 414 442 518 +4 66 442 456 518 +4 442 456 342 426 +4 12 68 297 250 +4 600 593 303 431 +4 52 67 275 446 +4 67 275 446 303 +4 502 52 67 275 +4 502 303 275 67 +4 21 282 48 30 +4 48 439 282 21 +4 100 122 131 255 +4 255 122 131 156 +4 479 166 378 381 +4 14 289 290 291 +4 17 540 291 292 +4 289 479 291 540 +4 312 477 607 134 +4 480 373 607 312 +4 324 608 452 371 +4 452 371 608 367 +4 74 325 599 322 +4 322 607 325 599 +4 257 608 324 605 +4 171 365 452 370 +4 335 267 609 377 +4 248 267 377 609 +4 331 376 377 609 +4 475 377 609 331 +4 475 609 377 335 +4 270 395 397 254 +4 381 341 350 544 +4 290 381 341 350 +4 337 544 341 338 +4 367 543 372 371 +4 543 367 410 551 +4 348 260 384 385 +4 20 518 458 294 +4 518 458 294 276 +4 313 262 542 427 +4 262 542 427 251 +4 321 367 605 543 +4 588 605 543 321 +4 588 543 605 522 +4 256 482 485 252 +4 571 331 332 327 +4 326 374 330 327 +4 327 330 331 374 +4 223 397 396 421 +4 277 395 421 549 +4 325 372 480 543 +4 74 543 522 325 +4 310 519 482 252 +4 482 549 220 252 +4 283 319 546 313 +4 313 360 319 546 +4 546 360 319 320 +4 352 550 400 411 +4 321 363 366 367 +4 366 367 551 590 +4 453 411 400 347 +4 174 185 375 548 +4 328 327 324 587 +4 160 326 370 374 +4 326 324 370 374 +4 324 374 452 370 +4 246 326 324 370 +4 587 324 326 327 +4 246 324 326 587 +4 328 371 374 548 +4 302 541 552 553 +4 302 552 541 404 +4 552 451 302 553 +4 458 541 302 553 +4 8 458 10 302 +4 412 400 348 453 +4 394 496 266 361 +4 352 550 132 387 +4 207 387 386 550 +4 540 339 267 335 +4 335 377 339 267 +4 427 313 422 359 +4 280 422 282 313 +4 313 554 359 360 +4 313 359 554 422 +4 422 359 554 278 +4 278 392 359 554 +4 445 353 387 384 +4 275 250 446 303 +4 446 303 412 353 +4 250 446 303 412 +4 556 454 360 314 +4 334 337 338 559 +4 471 334 337 338 +4 124 337 334 559 +4 276 297 296 11 +4 276 349 287 348 +4 7 526 295 302 +4 526 302 404 295 +4 133 154 557 159 +4 133 557 343 350 +4 181 494 490 531 +4 83 315 320 491 +4 436 83 491 315 +4 442 418 426 342 +4 595 70 310 466 +4 486 70 310 595 +4 65 92 325 329 +4 219 398 497 432 +4 224 430 361 229 +4 527 224 430 361 +4 266 224 527 361 +4 224 229 361 266 +4 257 587 246 566 +4 257 461 587 566 +4 424 448 143 534 +4 75 545 534 247 +4 41 91 598 316 +4 41 316 51 91 +4 305 570 249 261 +4 596 570 261 574 +4 596 570 465 261 +4 138 142 193 356 +4 193 393 392 356 +4 506 432 497 239 +4 408 189 426 578 +4 176 408 426 578 +4 333 321 257 495 +4 257 321 588 495 +4 333 257 321 608 +4 163 449 354 440 +4 464 430 569 524 +4 464 470 430 524 +4 77 424 109 95 +4 77 424 603 109 +4 316 242 441 582 +4 43 242 316 582 +4 571 507 327 587 +4 266 211 527 224 +4 6 250 300 275 +4 413 412 297 296 +4 6 413 300 250 +4 159 380 166 586 +4 380 489 606 194 +4 586 606 380 183 +4 574 170 249 261 + +CELL_TYPES 2419 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 diff --git a/data/bread.vtk b/data/bread.vtk new file mode 100644 index 000000000..84445be2d --- /dev/null +++ b/data/bread.vtk @@ -0,0 +1,5459 @@ +# vtk DataFile Version 2.0 +bread_, Created by Gmsh +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 600 double +-0.632750154 -0.169042692 -0.0420185886 +-0.6288443246876976 -0.1705579217513381 -0.3351307801083133 +-0.627599597 -0.109560184 0.193951771 +-0.6272581820000001 -0.114782199 -0.210253716 +-0.625870824 -0.0827441439 -0.427821785 +-0.6231711491346996 -0.06909719498907307 0.002936688823399516 +-0.62187928 -0.141489297 -0.508545637 +-0.619109273 -0.20065099 0.184942082 +-0.617258906 -0.188365549 0.361364186 +-0.6129253917250003 -0.2218187221626448 -0.4644520959176477 +-0.610847414 -0.116566934 0.5788511039999999 +-0.6064457512030659 -0.2352903814435132 -0.230278498718858 +-0.6044247584245859 -0.1573721353194774 -0.6921649477036715 +-0.599655211 -0.0301100835 0.3933267 +-0.599308133 -0.00959637761 -0.174717903 +-0.5946914598433086 -0.05483923448012094 -0.5899801086581294 +-0.5914479019638696 0.03570287255665958 -0.01173501270444369 +-0.589221179 -0.261734068 0.0183134377 +-0.580695808 0.00741301198 -0.342411518 +-0.578120291 -0.0621187836 -0.733076096 +-0.5770764082772468 0.04924874594879038 0.1728624384460362 +-0.573213279 -0.277133137 0.242307156 +-0.572819948 -0.280526549 -0.47517699 +-0.5701879437432005 0.03380056009679081 -0.4826306659682689 +-0.566561699 -0.269750744 -0.65587604 +-0.565325379 -0.198542327 0.753390372 +-0.5602347812989127 -0.03010290306825392 0.7269903863243912 +-0.551763969677439 0.05868815822636407 0.5632105985678141 +-0.544118583 -0.161922947 0.9043152330000001 +-0.5421236913557756 -0.3015934031519119 -0.1749102803550466 +-0.539183497 -0.312826395 -0.32370013 +-0.531418324 -0.265421718 0.571821272 +-0.531964049763488 -0.2823650230284698 0.4176381279843231 +-0.5284860314640324 0.1197725297225716 -0.1107031543127817 +-0.529390991 -0.238249063 -0.8648890259999999 +-0.527566016 -0.13658902 -0.911993921 +-0.5157039705235493 0.1354325357079283 0.06587362794318305 +-0.515270948 0.0243360605 0.849618018 +-0.5106149465438188 0.1241951957329448 0.3857279094163172 +-0.501122871397868 0.08859164469998822 -0.6071032264793886 +-0.496035725 0.053251069 -0.755786538 +-0.4983220164542533 0.1388671870757597 -0.2633632307202013 +-0.493199825 -0.293509364 -0.625630617 +-0.480049849 -0.0182162169 -0.928551733 +-0.4763332328535265 0.09234152159422696 0.7453582794836001 +-0.4691692954495922 -0.3187734399407047 -0.4828477831576954 +-0.466014534 0.158395573 -0.438228101 +-0.455727488 0.19950524 0.228771374 +-0.450623274 0.213120311 -0.0584133416 +-0.450235724 0.173662543 0.5848733780000001 +-0.443132192 -0.327136248 -0.203062564 +-0.436799198 -0.28999579 0.746441722 +-0.436711341 -0.295194775 0.528864026 +-0.434919626 -0.327220947 -0.355632126 +-0.433127433 -0.327016205 0.188225135 +-0.432362795 -0.0260486659 1.02163148 +-0.424319714 -0.299656779 -0.7710540890000001 +-0.418731123 -0.313259393 0.355326653 +-0.413272083 -0.324938089 -0.008454406629999999 +-0.411766768 -0.0759606436 -1.06218159 +-0.41078791 0.0896513909 0.904253781 +-0.405130446 -0.195588112 -1.0563339 +-0.401077837 -0.215362862 1.04552662 +-0.3937088250104729 0.245475505294996 0.06479695352004036 +-0.392320693 0.234469444 -0.17958805 +-0.389818847 -0.271718085 0.898724556 +-0.3795171357699217 0.1809822122349252 -0.6980056575345682 +-0.3780350239703167 -0.305379206730437 -0.6344336427341352 +-0.370097399 0.158385307 -0.781004548 +-0.367291033 0.247168347 0.403802454 +-0.364090204 0.186925083 0.775446653 +-0.3470260280980581 -0.3027576235086966 0.6734690732238851 +-0.355703861 0.253342092 -0.314534515 +-0.350980073 0.101343967 -0.916194201 +-0.347247034 0.0157141015 -1.04280066 +-0.3595367577682014 0.266857520213798 -0.06286025187794499 +-0.337775946 0.221784905 -0.579429924 +-0.328021646 -0.119099461 1.16399503 +-0.318886369 -0.0310313143 1.14137971 +-0.318799227 0.07324688140000001 1.05263996 +-0.2957631714678706 -0.3073946044611651 0.5066511915606143 +-0.3127899016637216 0.2572660637572521 -0.4539712702373595 +-0.289707197271735 -0.3209373398136868 0.338809711576317 +-0.294695824 -0.297897995 0.848340631 +-0.2859863698231691 -0.3168436944107536 -0.4816956185589286 +-0.2050836642212009 -0.3283384680338079 -0.2379208951790336 +-0.272871733 0.168182269 0.940995455 +-0.277079499705114 -0.3000428409279249 -0.9169077167535318 +-0.272068143 -0.0405149758 -1.12342548 +-0.295996154668075 -0.3262434121132616 -0.08421675764658507 +-0.270420015 0.323353469 0.197032914 +-0.268410921 -0.309475809 -0.779071093 +-0.268395036 -0.208364695 1.1530025 +-0.264329612 -0.256120145 1.07805526 +-0.259477824 0.327272594 -0.0111165987 +-0.2592313875191768 -0.3249120960690486 0.1978007259453491 +-0.25307101 0.323009104 -0.184089899 +-0.251887619 -0.234202489 -1.10509062 +-0.248427853 -0.283111513 0.975000679 +-0.246959835 0.264334142 0.636605024 +-0.2181768215788349 0.3148565992168524 -0.354203011750959 +-0.2180756929972778 -0.3075298268879092 -0.6435980304712747 +-0.210101098 0.228287876 0.806589246 +-0.202347532 0.262150735 -0.693429112 +-0.1839312457747164 -0.3120072389676618 0.6302934408698672 +-0.19505471 0.30804196 0.419340342 +-0.192441091 0.297783345 -0.543626845 +-0.184508383 -0.06387588380000001 1.19952679 +-0.181825727 0.0902422145 -1.04319906 +-0.177366897 -0.1370534 1.20709574 +-0.1682010884207567 0.1280394421628014 1.019456040237935 +-0.169369817 0.0490187593 1.13689983 +-0.1765642876422064 -0.3005752621112343 0.7741778632191527 +-0.09659571797728024 -0.3237966410734795 0.2886771364054303 +-0.1336776037396663 -0.3179802104644576 0.4940151754285145 +-0.133609027 0.0104971519 -1.15442598 +-0.131370261 0.200698078 -0.912176609 +-0.1276849418564198 -0.3193038441335848 -0.7420211627663338 +-0.1351091351651363 0.3357484667587539 0.0903005479823103 +-0.116616637 0.202693298 0.923615277 +-0.1229354562983514 -0.3080274488447292 -0.8591248307540573 +-0.112234853 -0.317026734 -0.525991261 +-0.1163232382313243 -0.2967481632539131 0.9047067889050232 +-0.105704643 -0.296082586 -0.99867332 +-0.104093514 -0.201623037 -1.19715738 +-0.1032609614529138 0.3327737476564569 -0.1328512096669709 +-0.09791703783755819 0.3284248194629804 0.2704485780114113 +-0.0983490348 -0.252254248 1.11909378 +-0.1015933632547309 -0.2757315094153424 1.02850602998658 +-0.04103881647229869 -0.3210421079334427 -0.3626250277573286 +-0.08450169120000001 0.251937985 0.789444208 +-0.08598792527834564 0.3232353681098715 -0.2826794810793276 +-0.03374240552202475 -0.3244333671049457 0.1424277709063964 +-0.0811243728 -0.184031144 1.19313872 +-0.07457840440000001 0.25377962 -0.769655883 +-0.0734984875 -0.268205345 -1.11824799 +-0.06817381829999999 0.306654483 0.616369545 +-0.0596126728 0.318042129 -0.47548461 +-0.0405420773 0.292198926 -0.6369735 +-0.01870391618062854 0.1596260767811929 -0.9783108844652629 +-0.0316687301 0.083737433 -1.09117258 +-0.0305270702 -0.0404514931 1.18008959 +-0.01584179292081353 -0.3205144693268325 0.6252624661388994 +-0.0189404469 0.10489472 1.0481838 +-0.006335911393910501 -0.323431466416447 -0.6214821431776921 +-0.01127676548726419 0.3165175322894282 0.4631381901625266 +0.002409144363770846 -0.3208803520384314 0.4320024870467693 +0.000919584951808175 0.3415618767929457 0.1767606700895136 +0.000645813299 -0.09917979690000001 -1.19051278 +0.008616645819999999 -0.222254485 -1.16051412 +0.025074914711979 0.3380979433533188 -0.02320140506932112 +0.02636187673282629 -0.3064423296633813 0.7810130865081631 +0.03056910242726388 -0.3229203979667208 -0.755044213298667 +0.03634912020353433 0.3339697098275954 -0.1988757168514349 +0.0501571037 0.203280225 0.901214659 +0.04937708833617034 -0.3153870584242271 -0.4956943949505555 +0.06068216386457771 -0.3126368916061305 -0.8881250615823352 +0.0760550201 0.331426531 -0.416961432 +0.07770191880000001 -0.194863036 1.14329684 +0.0793634132 0.221359968 -0.886946797 +0.0797847012985648 -0.2720259276082105 -1.111607439943101 +0.07176420901698481 -0.293709923554148 -0.9947101135604581 +0.0852158442 -0.263870746 1.05535865 +0.0901784137195092 0.239410954863809 0.7651561193390096 +0.09257778530000001 -0.300593853 0.92074877 +0.08792032944601967 0.3195215167958628 0.2962139813845267 +0.1342230365776022 -0.3270383612159197 -0.1660587084214412 +0.101610214 0.297426939 -0.581822574 +0.104322709 0.277264059 -0.7141513229999999 +0.116591886 0.285359144 0.585500419 +0.123508625 0.141643688 -1.0245229 +0.1302383234369273 0.3188593423328711 0.09891125126623798 +0.137453675 0.10356693 0.98128587 +0.146170378 -0.193035126 -1.17209935 +0.15372315 0.0248839483 1.09257102 +0.159167114116769 0.3216188743443609 -0.09939655874006298 +0.156300545 0.00622173585 -1.14503849 +0.1575934927965348 0.2944301746273211 0.4224994968600683 +0.1722454811080495 -0.3196874483267366 0.4791635503420602 +0.180058092 0.312006146 -0.29130584 +0.191490456 -0.339167327 -0.628670752 +0.196154401 -0.32713595 0.655051947 +0.2102015058527576 0.3023736253060144 0.2308796626183597 +0.209355786 -0.32167244 0.788386106 +0.209819317 -0.281819344 -1.03263426 +0.2052527717200844 -0.3204325388348114 -0.7606181132933152 +0.22060965 0.149422914 0.8681468369999999 +0.2201567361834727 0.2964075260987493 -0.4932177711543656 +0.2289035564744689 0.2418606446205045 0.5318907552007455 +0.235204756 -0.153555259 1.03785145 +0.239215314 -0.308211148 -0.88586849 +0.2422585768382945 0.3032605503001788 0.02221725245713789 +0.2478584060581097 0.2084897329185708 -0.8191325973240935 +0.2676329525906204 -0.325214048118874 0.1274202087489643 +0.255572438 0.145951435 -0.955286026 +0.257206708 0.0452529229 0.974785566 +0.26167649 0.247318402 -0.655356109 +0.2684987404931198 -0.3213963279202536 0.3151476389232072 +0.26445508 -0.227457494 0.952282429 +0.2556580412300001 -0.3239696394418858 -0.2463806522608801 +0.266461968 -0.324571252 -0.0473213829 +0.2674483364146153 -0.3185688487481381 -0.4400408770713561 +0.268301487 0.192615628 0.669675469 +0.2641387452983279 0.2567713777596122 0.3542781695822994 +0.278398782 0.0301054921 -1.06906998 +0.283945382 -0.0854744092 -1.11898184 +0.285041392 0.295302272 -0.148033321 +0.286989987 -0.281600296 0.853645146 +0.304370552 0.259223163 0.19495742 +0.3004473285101412 -0.3225054582555733 0.52306308186266 +0.3419884622066078 -0.3087892646543236 -0.6985964743235571 +0.347079903 0.24267967 -0.347697914 +0.350178272 0.0544311069 0.787789524 +0.350742877 0.18654497 0.513641119 +0.353308976 -0.0690704286 0.899787664 +0.3619258414908827 0.2015886782682507 0.3453064394214022 +0.3605229425850597 0.2157690326366382 -0.5001157242503148 +0.3582991004894012 0.2390164366865543 0.02033576081052964 +0.364086866 0.115434065 -0.864582241 +0.364299774 -0.30852145 0.633717418 +0.3685576720111329 -0.3250923823875746 0.02062236750528922 +0.383982152 -0.266817331 -0.936348796 +0.3807620323528138 0.1396142657229902 -0.7723730030213513 +0.385951102 -0.278697878 0.734899104 +0.390427053 -0.150731742 0.814497888 +0.394065022 -0.300544053 -0.81161499 +0.396751434 0.0179673433 -0.952465892 +0.399975926 -0.323856771 -0.533718824 +0.401687384 0.08169486369999999 0.575719118 +0.406446248 -0.317711622 -0.117804103 +0.4104364527558984 -0.3271946228711065 -0.3330122440229071 +0.4068240385998976 -0.3341294034073119 0.1797475265112388 +0.409801334 0.163595542 -0.634979606 +0.422241271 -0.0931896195 -0.980081856 +0.431205809 0.10813991 0.364281833 +0.444439799 0.169566467 0.185777366 +0.4435488637323559 -0.03431360961029391 0.679915480732488 +0.451285452 -0.311986566 0.364973009 +0.453583568 0.189398542 -0.169136196 +0.464307785 -0.170633867 0.674857736 +0.465479702 0.110205002 -0.538143754 +0.468048453 -0.294528127 0.482398331 +0.471837521 -0.244346827 0.576957941 +0.475833774 0.00567169301 -0.7929189210000001 +0.48184371 -0.286418259 -0.6896054740000001 +0.484312713 0.115773782 -0.404838234 +0.486227691 -0.131620109 0.55663085 +0.488401592 -0.217733011 -0.840291619 +0.4941459 -0.0306554474 0.432690978 +0.494831145 0.104029663 -0.267513901 +0.494948685 -0.315942019 0.0212940983 +0.4978108709283288 0.09568670499549034 0.009657679408726555 +0.50901866 -0.107348382 -0.818821073 +0.5086943039866562 0.03599045328340306 0.2128394470331411 +0.511425257 0.0332089514 -0.62854135 +0.5173667492978211 -0.1749566938860382 0.4357265819170917 +0.5335243654735508 0.02902684838156043 -0.1361782567465196 +0.542708695 -0.241015062 0.322714776 +0.547406733 -0.304356784 -0.357866287 +0.547821522 -0.300795585 -0.157615721 +0.550165117 -0.111375749 0.25379914 +0.5541378019755472 -0.02028652340202351 -0.2977492982523566 +0.551303625 -0.214603633 -0.6958712339999999 +0.551618099 -0.0174828954 -0.47293824 +0.556722581 -0.297283679 0.200931713 +0.560321867 -0.267647058 -0.542330325 +0.5581963424898763 -0.06275648727955054 0.05894752139948921 +0.569673896 -0.152694196 -0.589271784 +0.5892118698315169 -0.1055063104624098 -0.1447469935280529 +0.5923772054854053 -0.2613427695509241 0.0143138508181237 +0.593496919 -0.185401455 0.144956768 +0.6059530796477788 -0.161368568924735 -0.03354311809085728 +0.613636851 -0.176757962 -0.362412333 +0.62586715348393 -0.2295170435511966 -0.1801972299670868 +0.235056533258229 -0.0120356511347283 -0.02608664511073183 +-0.294837466142725 -0.03638797476500752 -0.1575591852776718 +-0.4077270390546363 -0.1799652379691176 -0.3317597075995502 +-0.1540631655180561 -0.2038524891450093 -0.3817263917585392 +0.1416031981625268 0.002240683846048277 -1.014394157451564 +-0.103537698383817 -0.3268273342685049 -0.0813377785162222 +-0.4640679140581339 -0.1477428474905214 -0.6838486755841178 +-0.2606204736109808 0.05261490134571593 -0.527600749057885 +-0.3293484018372281 -0.1906315378774555 -0.2141347503454874 +-0.4762280916422231 -0.1894610326162511 0.4610472470633845 +-0.04545171053106777 -0.1771820217092792 -0.2890666553863091 +-0.5086006559774328 -0.09347570065477208 -0.4031627010825047 +-0.5252099091705799 -0.1063297774683439 -0.2653560452621012 +-0.5182255592969928 -0.07467930175224791 -0.09639873978456268 +-0.4990348284206155 -0.07333723637071697 0.1671817319073981 +-0.4874159774000664 -0.07395929498092607 0.4356536533530988 +-0.4840434115697701 -0.06900911154308091 0.5636714106123424 +-0.2744316464808581 -0.1728155726636257 -0.3462663900082444 +-0.4486333919915438 -0.2179896326884634 -0.1015692790323588 +-0.3190349171351078 -0.1752523116678865 -0.8006663236468987 +-0.3339329791097286 -0.2107604942982681 0.01245945879615159 +-0.397382041437046 -0.193702879904675 0.1230527802547303 +-0.3505182402262418 -0.2127393607238003 0.2638279264224339 +-0.364467703673791 -0.2132558562973731 0.5997909842199085 +-0.315461814321399 -0.06525993758445217 -0.6457599860709946 +-0.3802273735908921 -0.1480811398494645 -0.5023357127409046 +-0.3371039862734003 -0.09633460769517657 0.02303006092720512 +-0.3678024819481842 -0.06708716154360625 0.2427170297282195 +-0.3434572671872417 -0.03662126550015469 0.4583066149416989 +-0.3571087600210078 -0.06966885744593609 0.6358080579877416 +0.04088871114230961 -0.1801305040576834 -0.415941678185882 +-0.1821073822497183 -0.1708440038367704 -0.1626138630477305 +0.1251431083274118 -0.3231820646153859 0.2484680462342079 +-0.3293537527084144 0.1123185284122672 0.4545425345514276 +-0.3964424874301052 0.04451125471078127 0.5653461862260807 +-0.3910793026258311 0.0732527270123043 0.6791232115754769 +-0.323124307656664 0.01391441538058619 0.7951579473597056 +-0.4188068405503143 0.01124187407462989 -0.04058920990722771 +-0.4108465207710866 -0.1603108437088947 0.721602695087369 +-0.2798010624843861 0.1795963452745023 -0.08820691364909607 +-0.2674359940828882 -0.1603483987622125 0.4998342086306083 +0.4362274561791842 -0.1565888255695466 0.003046470896816286 +-0.2023211596558263 -0.1668524677960372 -0.9701159941374512 +-0.09430736060068808 -0.1540895577035938 -0.6716882750363021 +-0.01634963770961941 0.02361106310577533 -0.6815216554830621 +-0.1975571742039778 -0.1897356529565794 -0.003704158227059853 +-0.2772842362020859 -0.1467873008933963 0.8911547352962133 +-0.2190807291690174 -0.07602105564343237 -0.8029554230489824 +-0.1820088890314257 -0.07473486326346283 -0.5580969610671465 +-0.2028931306742471 -0.05625917326189141 -0.2654505604075257 +-0.2711069871343141 -0.1007728686248378 0.126818929223232 +-0.2042234998754151 -0.03485483521017257 0.648230760260361 +-0.2146837176920142 0.07210030448505052 -0.8018824599611524 +-0.1888655482129395 0.09946542732243503 0.2158991967171965 +-0.2217533690946829 0.0669400926606392 0.5415169057398446 +-0.2008405596135326 0.1089125380694557 0.6984915446620906 +-0.1812723069824003 0.09626722815505365 0.8649139598319849 +-0.1741933050728894 0.1883253629705375 -0.4861885486915489 +-0.2136936554740226 0.1362984341269404 -0.2249699767215333 +-0.2247425224769834 0.1864985984123723 0.04419086624164103 +-0.1505517774679761 0.2257680457962071 0.1740876371886896 +-0.2405863675392797 0.225567688394666 0.247824040398845 +-0.2008958051173673 0.1960798813720792 0.5720565950681551 +-0.3410293891099315 0.1180835756256851 0.2875225205596443 +0.1355557822699097 -0.1865160657156918 0.858084945357638 +-0.2402093954365108 0.1366753877374269 -0.6701862347515433 +0.02765682361795284 0.1673481203571626 -0.6345605270536934 +0.1635397305327533 -0.1788350204456515 -0.3140973573673874 +0.02290180934580428 -0.3259610945501263 -0.008147942702972297 +-0.04994368532957806 -0.1789629107321086 -0.8865135666541073 +-0.06372505314255114 -0.2009038370106466 -0.5216430951773022 +0.2589125619334321 -0.1052343321848907 0.7902362679580435 +-0.08137804576245052 -0.1398816150763008 0.2650187680871962 +-0.05255937605920671 -0.2084228962455832 0.388053919530626 +-0.0610940838956746 -0.1975352147734389 0.7191347590781653 +-0.02847429436829107 -0.1406878058463639 0.893596232175088 +-0.1161188650118093 -0.06760460796812834 -1.062478704219613 +-0.1216921516225895 0.01398881421035822 -0.9256830187896803 +-0.08546618531509211 -0.06192371548063535 0.005984666809820121 +-0.01968852203231181 -0.11911499116442 0.1361690537875068 +-0.1958853519145896 -0.32031563505488 -0.4046062305228226 +-0.06951424555604294 -0.07408436337083289 0.5368976904433417 +-0.06937842019870852 -0.06351528753420298 0.6953983431335627 +-0.06229146951174672 -0.09719158560166377 1.065737198726496 +-0.5147158313474506 -0.2089155410864463 -0.5110700502445542 +-0.08861511993859365 0.1215479949177415 -0.7685569266328846 +-0.08389577614511963 0.04228804443112102 -0.5669519396633091 +0.4380391163415359 -0.03491995602894394 -0.5280265522193031 +-0.08462227499375073 -0.008904462569615051 -0.2742840363613134 +-0.1044520681224678 0.01656372440278623 -0.1429028474240853 +-0.02466110233721708 0.09374971270005773 -0.03936718029783625 +-0.05888953161716449 0.08014452321463582 0.10702676215484 +-0.05320405123703709 0.0586033518085889 0.5469622336213691 +-0.01937047747235692 0.07310218754394707 0.83971301012445 +-0.4548321782725977 0.02627391906326635 0.2359240497845566 +-0.04000102427907472 0.1531867725223221 -0.4215310730939596 +-0.05754073468145875 0.2161322759378342 -0.1234455779275133 +-0.04998324663715139 0.2124067637398978 0.05094964350134245 +-0.07646501424798517 0.2153647228102641 0.4130038965399286 +-0.05183705450183342 0.1987804807436486 0.5630901631521744 +-0.1445865666964886 -0.1829147355980108 0.1479555519857285 +0.461913431126831 -0.0593477527720814 -0.1686939157144107 +-0.005406511867050523 -0.1589736675504839 -0.155145569863764 +-0.1789523235885893 0.1654610118724154 0.4703999382505659 +-0.2223379017 0.2060824635 -0.7753302154999999 +0.4287557609846052 0.002708814233482092 -0.04287708402035991 +0.09956474897435749 -0.148673600644969 -1.051920063964533 +0.1595454868586938 -0.1969733108195983 -0.841767050051904 +0.02398302327684333 -0.17507107587311 -0.001445270984510269 +0.04779000039155958 -0.2048007888224781 0.2753993082842633 +0.1580781354298379 -0.1943158902350526 0.438399295862469 +0.1388033392256428 -0.1882642768861524 0.5832003436050862 +-0.002580680163575191 -0.08260145803669838 -1.047197529931853 +0.03818802883834366 0.008810062832806657 -0.8100703791789798 +0.03980184608632317 -0.04492818113483068 0.2235393852527257 +0.08750675549065637 -0.05209371266632507 0.3749509297594523 +0.1104697950194658 -0.03985694374379745 0.525472877272581 +-0.363077231207092 -0.06391063164594608 -0.317411464483348 +0.06873671008851648 0.05260587685125048 -0.5463687978068482 +0.08235295281629421 0.004272800083929775 -0.3194414808765957 +0.07309832721055952 0.02691544864827158 -0.09375366858492233 +0.08464806773647369 0.1068442688058315 0.0605820431469033 +0.0681374271173923 0.09821735035696989 0.2136529506662567 +0.03960135048145286 0.07523190332511616 0.4100211068187878 +0.08507880035202696 0.1955605616078763 -0.2178618699605751 +0.0763980844607446 0.2085363723074083 -0.004479686054216185 +0.05684241773679882 0.2083925746993921 0.1868755381087397 +0.0712041934434073 0.1912883781680433 0.4151518852439607 +-0.1523969671244068 -0.3249023475752869 0.06372989597784171 +0.2336894992960057 -0.2138649746542237 -0.7090457662352703 +0.2327186890989112 -0.2174448452592526 -0.582909304799258 +0.2372196379057117 -0.1934531697338017 0.02924747311216706 +0.2606068820761314 -0.2024174698668231 0.2948425479362535 +0.20321125098658 -0.01842555715088153 -0.8826267283723467 +0.2344702354975904 -0.0792743211672727 -0.7276257517916612 +0.1938709785579744 -0.05667199115835578 -0.5214227835426123 +0.2385240019563775 -0.03003420036447207 -0.2741118320881786 +0.1834890018302141 -0.1535999063224062 -0.1449033165088677 +0.2272423394204236 -0.03060345851799344 0.6693209420043651 +0.2233918188349693 0.0756072793947988 -0.8015470916224887 +0.2165110309376049 0.07897917054867198 -0.6782180285452418 +0.1898562519114729 0.1190605770020391 0.2801216771433201 +0.2378303921805618 0.1114009517200644 0.4331542042796968 +0.2091323471439511 0.1856214553227049 -0.3579824672646562 +0.2122958639273076 0.140803392367491 -0.1211039192733228 +0.20807053504025 0.1751934077113878 0.1370720756667596 +-0.04555776237212009 0.1113474649060658 0.2810704580139992 +0.2048647078236662 0.1547394608133656 0.009815714090144104 +0.4476410434751801 -0.04175951301503236 -0.8939341228152804 +0.3248088308625864 -0.1979350059279816 -0.7960067127925106 +0.3365625313150374 -0.1802309994941698 -0.6348724153530155 +0.3321482276768279 -0.2153674639921609 -0.1192716927954634 +0.357412297832675 -0.1897598909200615 0.5418833857700533 +0.3251436358049948 -0.1247317109182759 -0.8904534752998884 +0.3770314201131766 -0.07018756616503079 -0.786425185000634 +0.3234814219377659 -0.1588077614855086 -0.4703160075146873 +0.3406612313337812 -0.07687084694686072 -0.124647485936511 +0.3152191216016219 -0.08589296349059491 0.1713990616027491 +0.3736407779465723 -0.1144413203171895 0.3736274477605788 +0.3567789524607734 -0.1119515227155971 0.6405989933246231 +0.3581038772958468 0.01820268238358316 -0.6449684875003947 +0.3418761192436113 0.03867582857997607 -0.2348142600215415 +0.3376642367757754 0.05718337133284317 0.2778554431006919 +0.3492166144286751 0.02540001426496525 0.4423807621009067 +-0.07831049395564289 -0.04371349925479548 -0.7850430574333236 +0.4553437340043157 -0.201743433072669 -0.5497374620178135 +0.4785641480859852 -0.2076772957704019 -0.4195606712197842 +0.5006930469817525 -0.1956301451215143 -0.2692865826460606 +0.4760928898560638 -0.1992446614914462 -0.1325182552084059 +0.07615399105350647 -0.2065004500282057 -0.5618858366640651 +0.4523273960516714 -0.06552298101443942 -0.4014122075044529 +0.08398489118701867 -0.06843717793454046 0.7804830039538839 +-0.07602895499104406 -0.04341842540995552 -0.4243885096915852 +0.28682778 -0.315096945 0.7110517620000001 +-0.2378263296935333 -0.1672979090337034 0.7086062966783493 +0.006730808756646762 -0.08309310246044305 -0.5433698527959587 +-0.1777035661914723 0.00194813914845731 -0.6786508060462324 +0.01447374917851763 -0.1763353666422657 0.5303931590623508 +-0.03052128387500846 -0.3283332118221204 -0.189928597566322 +-0.4951963350305815 -0.1476782677716813 0.2824725083691091 +-0.2317531682351111 0.009941844803824672 -0.01965919390189422 +0.06216159381612416 0.06699849521021922 -0.9278584494186015 +-0.5885202585 0.009023461500000001 0.291354485 +0.2661253839173343 -0.05852871439471465 0.5259123303887956 +-0.6310842201582583 -0.1691839234822397 -0.2112359161539457 +-0.6232426092128992 -0.084263552388107 -0.1076983632614595 +-0.1198414424706636 0.1507588778841537 -0.6387557230928487 +-0.5975463957571627 -0.2484486063747277 -0.1146035920376723 +-0.6265432670674598 -0.0982727731700877 -0.3223680090462325 +-0.2713136193139823 -0.1819414318253814 -0.673020031010089 +-0.6090876317520353 -0.2303036070461051 -0.3331446744490243 +0.1385772635675258 -0.3256153467446084 -0.01207575304424752 +0.5812650844651608 -0.2727100302728923 -0.2796390631923442 +-0.5950264687083633 -0.2506565735010583 -0.313101091331551 +0.310894165025311 0.09763852315371323 -0.4428517848466869 +0.2244497608806354 -0.1233470985068375 0.908739965360969 +0.09622349285239674 -0.02582787905315692 0.9573939019787829 +-0.523355171 0.08290429249 -0.3903198095 +-0.01877090560516489 0.2338260817449825 0.3008051052450599 +-0.5347287074440473 -0.1647410894194042 -0.1716557766323908 +-0.3424842245684931 0.08504259494012185 0.1136526482627993 +0.1599418136574531 -0.2014975979586135 0.714873287189321 +-0.1916194260632076 -0.2125659395719756 -0.7949962125505342 +0.333963767 -0.1761458701 -1.027665318 +0.2663831686838643 0.155491831033473 -0.2554595260926634 +-0.3214428646626149 -0.3271523453927522 -0.3192400998199176 +0.4265664891366099 0.07291539273621651 0.4801633942068546 +0.3277208381063536 -0.07788921306052055 -0.5647856367516129 +0.5162284386563655 -0.05257796046467225 -0.6953879593271081 +-0.4340237149896715 0.001510963716717071 0.353889518201792 +-0.4712297308903751 -0.2288671707098198 -0.2409264933689148 +-0.403457995197371 -0.265484383936735 -0.8993778093632829 +-0.4952290851908102 -0.236134214244517 -0.3838523597084021 +-0.3617453136255294 0.1060675432929375 -0.1030690049542968 +-0.213228497706704 -0.003408668663054269 -0.3884025928211242 +0.3458855178266971 0.08838916931392254 0.08421472029112591 +0.1242796502207231 0.01985956433312843 -0.7038805934344395 +-0.4087633785 0.210415445 0.494337916 +-0.2588966759586523 -0.2199332636151662 0.1258385737822901 +-0.09788241951439466 -0.2156437843658519 0.5686483102817524 +0.1121596408235937 -0.179806163981583 0.1315584605521503 +0.1889195203455339 0.05788660066238087 0.099807449573649 +-0.2177238144183367 -0.1913336457883025 -0.5153733919024074 +-0.3235224072087456 0.2498090466095282 0.5084344850396774 +-0.3611709685158725 -0.1103314113987186 -0.9142126366847918 +-0.3084772809420559 0.1803435945436039 0.1747509192630983 +-0.1433811910341334 -0.02171840804217669 0.376981254347245 +-0.4173686836156164 -0.08738360651122987 0.8682108826777892 +-0.3486962007490331 0.02906621681679501 -0.718891302157178 +-0.4548768914195485 0.04187881494911656 0.4700359848148038 +0.444136183293568 -0.1290545266626573 -0.623421395092925 +0.1402682500874713 0.0978339686987359 0.6052091739610184 +0.2445723112086994 -0.0490470059591255 1.007116877254474 +-0.589534521 -0.2467996775 -0.5610865350000001 +0.4695574045000001 -0.032211056 0.554573238 +0.1087261274705382 0.1344580501047321 -0.782381358519131 +-0.2295936488867352 -0.1679362370516203 0.2988370603449237 +-0.2108651278256038 -0.135216536859703 1.043962651661762 +0.3274410665 -0.189094618 0.8833901585 +-0.6295814785862741 -0.1332185798243695 0.0747486115500349 +0.4257452107132649 -0.1497807504747948 -0.7247829353724851 +-0.4065788543392076 0.05641794349363485 -0.2023940581892574 +-0.4741952581146936 0.005567467827913972 -0.2896368447685682 +0.537822015986264 -0.1247336251456899 -0.7026911632659789 +0.04691878121100163 -0.3253583793446858 -0.2438536447787282 +-0.3265080875888459 0.2795614212058176 0.3114509736717221 +-0.340804238035824 -0.1325442633794833 -0.08457635333686102 +-0.608271837 -0.190787099 -0.581274092 +0.4342257262379472 -0.04067893294669516 0.09281223529302308 +0.1101293171872833 -0.09314342498009091 1.121054020095585 +-0.4778838755 -0.312555179 -0.08227032131499999 +-0.5164019481386234 0.1243769929743952 0.2008169062230181 +-0.4282021375 -0.3260371685 -0.105758485315 +-0.4252241373367756 -0.09247602905317821 -0.1931424815446258 +-0.6034349072244448 -0.06765509035174504 0.4846041290632107 +-0.3905038412015657 -0.1287959856176534 0.3798498501512843 +0.4456397576215616 -0.2131574080402554 0.2509255350650204 +0.06405319440287052 -0.09438844282826886 0.6391120059462931 +0.194463953 -0.06433565534999999 1.065211235 +-0.149802249858435 -0.1558969139329281 0.8381148001156568 +-0.1675730032687616 -0.02901624078251305 0.7999767064659036 +0.08261363219099564 -0.1473192553925075 -0.6972028901368317 +-0.1441330307870139 0.1468866921058483 -0.0500613193155267 +0.1263125915806811 0.1740851728217416 -0.4559514659170312 +-0.3493140812357224 0.09467407130730869 -0.3504597611615711 +-0.4022298241254121 -0.02250306300117746 0.09885513548347585 +0.1517818098649741 0.04452164200874875 -0.194721200975942 +-0.1134407254762351 -0.15216846751374 0.4638633640341714 +-0.1557319845522709 -0.1274157200462065 0.6216502484948287 +-0.149041180888718 -0.01605216246602444 0.9549317524469565 +0.09040654379374929 -0.1568678067119083 0.996347333895657 +0.08067303214587271 -0.3200617991586214 0.5304156856447007 +-0.2327373625 0.3156977145 0.308186628 +-0.5406248937081048 -0.1555610374474114 0.1006509803063154 +-0.1259252380638327 0.3077710313436116 0.5156707982575212 +0.3372507556580723 0.1243928887401214 -0.07902207205907434 +0.264821429112476 -0.06589660515412041 -0.9914717394813669 +-0.4762331924014874 -0.2199990042924753 -0.9467878141858205 +-0.1774517559731612 0.2443815165722797 -0.1092042417848363 +-0.6259297134999999 -0.184846841 0.07146174670000001 +-0.3494537544742879 0.2152722202677307 0.6329361195629418 +-0.4372909499137471 -0.001028484248193989 -0.5597600633195453 +-0.2126431186987784 -0.3192296626479658 0.4251503397668951 +-0.292517672900954 -0.3255300192793423 0.05418119085547689 +0.382043645 -0.3170942815 0.434096098 +0.484649935405379 -0.3128916810391669 -0.2320088920400883 +0.3268450657457643 0.03222040583409845 -0.7885801031715454 +-0.006836105344560687 -0.2879631480921122 0.9755035462735366 +0.4317963324332161 -0.1653558320557807 0.4775831713651762 +0.3160606475 0.268990971 -0.2478656175 +-0.460863978 0.177050777 -0.141708184 +-0.0260034239 0.211029023 -0.899561703 +0.16400032695 -0.316489041 -0.4615788755 +0.5548961049636433 -0.03625854681237809 -0.0550648167397855 +0.4767830965 0.14109694955 -0.07861112364999999 +0.3967671898040719 -0.3231961606528706 -0.2294773873221734 +-0.0362816679786072 0.3226495652511001 0.3598074719832498 +-0.5422572596636415 -0.1903879113726161 -0.2969539253393564 +-0.5692358523353277 -0.2743552515677863 -0.5786632337904605 +-0.6253618023438487 -0.1560236093756691 -0.4218382085541567 +-0.5148286783814756 -0.01835906229564318 0.06966704474899003 +-0.6245011517224567 -0.08576961643896416 0.1003515002554732 +-0.5857579999080184 -0.2630417316459531 -0.3877238770333834 +-0.5334992755996751 -0.2229378214462615 -0.6025014447352878 +-0.5611497437803065 -0.2005087752013338 -0.3907976492188439 +-0.6208195960519357 -0.1978003331983729 -0.3916264101709223 +-0.6078842772695214 -0.231298754899959 -0.3950660527155458 +-0.3308457279587632 0.2851445140609312 0.1335716590224278 +0.4210661228722955 0.05458855427132342 -0.1462639131937262 +0.02065451607110848 0.248029396399095 -0.7973502586324333 +0.06844542813564602 -0.09344185930672386 -0.8955850263911164 +0.08204261636616872 -0.02694818161862675 0.09086463469911082 +0.3898127342952864 0.1504831755055776 0.4287978315658085 +-0.4621967718854053 -0.1343656082484689 0.01354397389617127 +-0.4093212893931232 -0.1274506582714651 0.5365320823636459 +-0.2557746905748986 -0.009461920643268997 0.281213658930842 +-0.2953433418119981 0.02373277616460369 0.6179896757025107 +-0.04293405725493453 0.1135279419722774 -0.2601518412193714 +-0.1535957869986199 -0.01683298933800276 0.1545624430330931 +0.3249614107997155 -0.03433777060896533 -0.4366513011764698 +0.3626904847866749 -0.1556978137631675 -0.2846123329071047 +-0.1849447280773641 0.168784960700547 0.3450033506239037 +0.5103811030112638 -0.3037458571790111 0.2730307560973112 +-0.09113302725397168 0.3360428159740929 -0.01380509259030093 +0.2609707547491137 -0.207552677521198 0.6178846905139959 +0.3207713658215219 0.1914018645525489 -0.7248264376644808 + +CELLS 2425 12125 +4 48 313 474 487 +4 410 435 418 274 +4 299 391 281 285 +4 500 366 397 595 +4 193 220 431 231 +4 209 384 426 406 +4 122 112 320 533 +4 462 4 18 285 +4 339 106 76 331 +4 249 594 261 375 +4 27 290 289 503 +4 286 3 18 462 +4 6 299 280 15 +4 356 451 348 493 +4 198 469 512 207 +4 2 453 8 7 +4 279 376 382 342 +4 142 451 348 531 +4 415 431 419 436 +4 71 104 80 297 +4 356 445 531 505 +4 205 477 233 550 +4 3 286 18 14 +4 3 287 286 14 +4 105 126 570 372 +4 465 306 494 342 +4 4 6 15 285 +4 340 196 392 414 +4 146 545 384 451 +4 124 135 149 386 +4 4 15 23 285 +4 4 285 23 18 +4 5 459 16 287 +4 5 16 575 574 +4 143 141 357 470 +4 407 408 427 560 +4 399 418 421 394 +4 295 492 294 324 +4 6 9 521 358 +4 6 12 15 280 +4 6 285 358 299 +4 7 8 21 453 +4 8 289 453 13 +4 8 453 32 21 +4 8 32 453 283 +4 82 556 510 314 +4 8 283 453 289 +4 548 136 336 373 +4 10 312 26 25 +4 10 25 31 312 +4 586 215 234 416 +4 134 340 359 583 +4 10 31 8 283 +4 217 421 191 549 +4 10 283 8 528 +4 12 280 19 15 +4 430 315 379 274 +4 13 503 38 27 +4 150 147 399 171 +4 13 503 483 38 +4 315 271 567 266 +4 14 287 33 16 +4 534 356 533 448 +4 69 307 595 497 +4 470 195 469 345 +4 15 555 39 23 +4 592 388 346 353 +4 346 383 353 388 +4 16 33 36 311 +4 583 509 565 159 +4 16 311 287 33 +4 454 474 324 592 +4 16 574 311 36 +4 3 473 286 287 +4 360 446 449 392 +4 18 516 471 41 +4 19 35 43 280 +4 19 280 43 40 +4 19 40 555 280 +4 305 279 319 89 +4 0 461 292 17 +4 20 574 36 525 +4 21 32 57 453 +4 515 275 332 487 +4 464 571 578 1 +4 24 42 56 280 +4 186 505 445 367 +4 386 278 455 584 +4 176 278 386 380 +4 380 386 584 278 +4 482 254 434 361 +4 29 484 50 30 +4 30 486 53 45 +4 30 50 53 484 +4 31 283 52 32 +4 31 297 51 52 +4 32 52 57 283 +4 32 57 453 283 +4 278 407 455 584 +4 33 515 14 41 +4 34 498 551 35 +4 36 539 574 311 +4 37 44 60 310 +4 39 40 66 502 +4 380 278 407 550 +4 380 407 278 584 +4 40 502 68 66 +4 41 515 14 516 +4 42 280 67 56 +4 43 59 74 498 +4 400 399 419 395 +4 43 498 74 73 +4 44 310 70 60 +4 44 310 309 70 +4 44 309 26 27 +4 44 26 309 310 +4 226 427 560 407 +4 45 42 358 67 +4 47 63 581 499 +4 47 499 474 63 +4 208 489 235 436 +4 47 519 499 581 +4 47 499 337 474 +4 47 337 499 519 +4 48 64 75 313 +4 49 309 554 70 +4 51 65 83 312 +4 51 312 83 71 +4 52 314 80 57 +4 52 57 283 314 +4 297 104 314 448 +4 386 140 278 176 +4 54 57 82 296 +4 170 278 140 176 +4 386 455 278 140 +4 170 278 455 140 +4 54 82 95 296 +4 54 95 295 296 +4 55 511 79 78 +4 56 67 91 463 +4 56 91 293 463 +4 57 80 82 314 +4 57 82 296 314 +4 57 54 453 296 +4 58 294 557 89 +4 63 75 94 333 +4 63 333 48 75 +4 64 313 96 75 +4 38 483 337 307 +4 65 320 98 83 +4 65 83 312 320 +4 66 339 502 68 +4 67 463 101 91 +4 68 326 502 73 +4 159 509 194 192 +4 455 407 194 509 +4 509 413 194 192 +4 509 407 194 413 +4 68 502 326 339 +4 38 483 368 337 +4 69 595 307 337 +4 307 500 595 377 +4 81 538 281 331 +4 71 297 312 448 +4 72 81 100 538 +4 72 332 538 100 +4 290 26 308 27 +4 484 292 50 282 +4 292 282 89 50 +4 75 313 96 94 +4 75 333 313 94 +4 75 48 313 333 +4 81 331 281 76 +4 77 78 107 511 +4 77 92 62 511 +4 77 511 109 92 +4 77 107 109 511 +4 78 79 111 511 +4 78 511 111 107 +4 502 555 281 76 +4 79 86 110 330 +4 80 82 314 556 +4 80 104 114 314 +4 80 114 556 314 +4 81 331 106 100 +4 81 331 76 106 +4 82 95 296 510 +4 82 113 510 556 +4 314 556 510 500 +4 83 98 122 320 +4 348 533 448 112 +4 348 533 112 122 +4 83 320 448 312 +4 84 101 67 496 +4 85 282 50 89 +4 86 330 119 110 +4 86 330 102 119 +4 64 332 538 72 +4 87 91 120 476 +4 87 120 123 316 +4 87 120 316 476 +4 179 417 398 537 +4 157 398 537 179 +4 89 319 520 294 +4 90 94 118 334 +4 90 335 126 546 +4 91 101 117 476 +4 186 412 212 345 +4 92 511 127 93 +4 93 511 128 98 +4 93 127 128 511 +4 94 96 125 552 +4 94 597 552 125 +4 395 421 495 274 +4 399 421 419 395 +4 274 489 421 495 +4 95 557 295 492 +4 96 100 131 332 +4 96 552 131 125 +4 2 453 456 13 +4 470 195 345 186 +4 470 345 445 186 +4 25 26 501 312 +4 97 124 88 316 +4 186 345 212 195 +4 2 453 13 8 +4 98 511 128 122 +4 99 102 329 130 +4 99 554 329 70 +4 99 329 336 130 +4 100 106 137 331 +4 101 496 317 463 +4 2 288 456 453 +4 103 460 138 106 +4 103 106 339 460 +4 453 456 368 288 +4 103 134 138 460 +4 13 456 483 453 +4 104 112 151 348 +4 86 310 70 102 +4 102 310 70 329 +4 104 314 448 493 +4 106 331 138 137 +4 59 88 498 61 +4 107 357 141 109 +4 107 109 511 357 +4 61 88 316 97 +4 279 376 305 319 +4 53 484 276 486 +4 108 115 140 350 +4 61 498 316 88 +4 108 351 139 116 +4 89 279 319 402 +4 108 351 140 139 +4 108 351 350 140 +4 109 357 141 133 +4 211 478 249 238 +4 110 543 143 111 +4 452 279 305 85 +4 110 143 367 119 +4 110 143 543 367 +4 111 357 143 141 +4 40 555 280 502 +4 502 326 321 73 +4 502 321 298 293 +4 563 211 238 478 +4 112 122 151 348 +4 83 448 320 112 +4 113 114 146 347 +4 113 347 556 114 +4 113 510 556 347 +4 114 556 314 541 +4 114 493 541 314 +4 115 124 148 350 +4 41 538 516 471 +4 294 319 520 300 +4 117 144 152 317 +4 218 560 413 407 +4 117 152 343 317 +4 218 226 560 407 +4 118 147 371 597 +4 118 371 334 333 +4 411 405 425 430 +4 120 123 316 343 +4 120 343 476 117 +4 121 344 155 144 +4 121 144 101 344 +4 121 155 344 129 +4 121 496 277 344 +4 122 128 561 349 +4 122 349 511 128 +4 83 320 122 112 +4 389 397 366 390 +4 181 447 219 598 +4 598 447 219 223 +4 124 350 386 148 +4 597 370 150 371 +4 391 323 538 515 +4 391 323 488 538 +4 597 125 150 370 +4 323 538 332 488 +4 64 538 515 41 +4 64 538 41 72 +4 323 515 332 538 +4 128 127 162 544 +4 128 561 544 162 +4 129 304 566 155 +4 129 518 566 304 +4 323 305 277 284 +4 323 277 446 284 +4 217 489 549 251 +4 163 373 366 130 +4 103 106 76 339 +4 356 505 531 366 +4 280 463 293 298 +4 15 39 555 19 +4 19 555 40 39 +4 134 359 565 583 +4 135 380 160 149 +4 339 331 281 460 +4 460 331 281 360 +4 138 340 168 167 +4 113 346 374 510 +4 139 140 170 455 +4 139 455 351 140 +4 139 455 170 159 +4 95 374 492 510 +4 140 386 351 350 +4 140 351 386 455 +4 545 178 384 385 +4 142 475 531 348 +4 163 186 367 505 +4 144 152 317 535 +4 144 317 344 443 +4 144 155 443 344 +4 154 163 186 367 +4 25 26 28 501 +4 85 291 282 305 +4 145 401 373 372 +4 291 305 85 277 +4 146 178 306 384 +4 146 178 384 545 +4 349 470 338 445 +4 146 383 347 384 +4 147 472 400 165 +4 148 149 173 380 +4 124 350 135 386 +4 148 176 380 173 +4 148 380 386 149 +4 135 350 343 386 +4 149 160 173 380 +4 150 399 175 171 +4 150 399 398 175 +4 150 399 147 371 +4 150 371 370 399 +4 152 381 185 156 +4 152 156 343 381 +4 152 180 185 535 +4 152 185 381 535 +4 152 343 317 535 +4 153 175 398 179 +4 153 398 370 131 +4 55 60 79 501 +4 79 310 543 320 +4 55 320 79 511 +4 154 367 186 172 +4 60 79 501 310 +4 456 20 38 368 +4 468 410 593 435 +4 156 185 190 381 +4 308 26 309 27 +4 308 303 309 26 +4 157 537 167 187 +4 159 509 192 168 +4 160 161 184 380 +4 160 380 184 173 +4 161 584 380 343 +4 161 380 584 184 +4 323 284 446 362 +4 323 488 362 446 +4 221 427 247 233 +4 221 427 423 247 +4 165 177 401 415 +4 165 415 401 400 +4 166 411 200 199 +4 323 446 277 488 +4 168 192 196 509 +4 170 194 278 204 +4 171 182 400 419 +4 171 400 399 419 +4 172 470 195 174 +4 189 506 469 544 +4 544 470 506 469 +4 173 184 205 380 +4 140 176 386 148 +4 175 418 399 398 +4 510 346 374 589 +4 177 416 203 188 +4 177 203 416 415 +4 178 598 385 181 +4 178 209 384 598 +4 178 384 385 598 +4 179 175 398 206 +4 86 79 310 330 +4 179 478 206 398 +4 180 403 210 185 +4 180 185 535 403 +4 180 404 227 210 +4 180 210 403 404 +4 348 531 445 475 +4 182 415 208 203 +4 17 54 295 547 +4 182 165 400 415 +4 17 295 587 547 +4 172 195 470 186 +4 485 498 87 61 +4 185 190 381 423 +4 185 423 403 210 +4 185 403 381 535 +4 187 468 196 216 +4 188 505 213 202 +4 188 202 169 505 +4 188 203 213 416 +4 188 505 416 213 +4 188 401 169 177 +4 188 169 401 505 +4 189 469 214 198 +4 191 419 217 208 +4 192 194 218 413 +4 193 200 405 220 +4 193 306 406 405 +4 220 405 431 315 +4 195 469 345 214 +4 195 214 345 212 +4 197 237 406 558 +4 197 384 406 306 +4 406 558 432 426 +4 33 515 311 287 +4 33 311 515 487 +4 311 275 487 454 +4 199 200 229 425 +4 199 425 411 200 +4 145 401 472 165 +4 199 229 569 425 +4 199 425 594 411 +4 200 229 425 220 +4 201 404 566 429 +4 305 282 275 323 +4 202 213 228 505 +4 104 348 142 493 +4 203 208 215 415 +4 203 213 416 215 +4 203 415 215 416 +4 300 454 319 520 +4 206 563 238 478 +4 398 394 540 418 +4 206 549 478 238 +4 206 418 478 549 +4 207 345 224 223 +4 208 215 415 436 +4 372 401 472 145 +4 209 219 241 426 +4 209 241 558 426 +4 277 304 344 446 +4 209 384 598 426 +4 210 227 244 424 +4 221 184 190 427 +4 477 427 184 221 +4 277 446 344 496 +4 212 214 345 236 +4 212 228 236 412 +4 236 433 412 228 +4 236 345 412 433 +4 56 280 293 485 +4 280 293 485 498 +4 531 475 385 412 +4 531 445 475 412 +4 421 495 489 419 +4 480 234 248 437 +4 214 224 345 236 +4 213 437 586 480 +4 416 437 436 234 +4 216 232 240 468 +4 359 318 387 509 +4 318 490 535 387 +4 227 424 429 439 +4 424 504 429 439 +4 218 560 243 222 +4 218 226 243 560 +4 218 407 413 194 +4 219 242 426 223 +4 247 427 423 252 +4 219 223 426 598 +4 390 385 384 457 +4 220 315 250 229 +4 252 423 514 428 +4 252 428 427 423 +4 384 385 598 457 +4 247 423 514 252 +4 222 434 243 232 +4 483 456 368 453 +4 222 434 599 560 +4 483 456 38 368 +4 226 233 422 427 +4 227 439 265 244 +4 229 442 559 569 +4 229 250 259 442 +4 229 250 442 315 +4 229 569 425 442 +4 229 425 220 315 +4 230 441 559 258 +4 230 258 440 441 +4 141 174 523 470 +4 231 270 264 250 +4 231 530 264 270 +4 232 240 434 254 +4 207 338 183 164 +4 198 338 207 164 +4 179 417 537 187 +4 157 537 187 179 +4 163 169 202 505 +4 163 505 202 186 +4 71 104 297 448 +4 52 80 314 297 +4 237 257 255 241 +4 237 241 255 558 +4 237 255 257 432 +4 237 257 530 432 +4 238 582 249 568 +4 239 426 246 242 +4 239 223 426 242 +4 239 426 223 433 +4 240 361 263 245 +4 39 555 502 76 +4 39 66 76 502 +4 241 242 255 562 +4 241 255 558 562 +4 242 246 255 562 +4 243 514 428 252 +4 244 514 262 247 +4 244 439 265 262 +4 244 262 514 504 +4 244 262 504 439 +4 246 248 255 562 +4 246 248 562 508 +4 246 508 562 426 +4 247 514 262 252 +4 249 375 261 256 +4 249 256 582 375 +4 402 342 382 132 +4 261 594 444 441 +4 250 442 269 259 +4 250 264 269 270 +4 402 382 374 132 +4 250 269 442 315 +4 251 253 522 266 +4 251 567 379 256 +4 71 83 112 448 +4 71 448 312 83 +4 251 266 522 379 +4 58 294 292 587 +4 17 58 292 587 +4 460 360 281 450 +4 281 360 322 450 +4 256 261 268 375 +4 298 321 450 463 +4 256 567 375 268 +4 463 321 450 317 +4 256 379 375 567 +4 258 272 440 441 +4 259 269 273 442 +4 259 273 441 442 +4 530 431 432 260 +4 261 263 272 444 +4 261 441 444 272 +4 262 265 267 439 +4 262 517 504 267 +4 262 267 504 439 +4 180 201 227 404 +4 566 404 201 180 +4 265 440 272 267 +4 360 340 392 318 +4 267 439 361 504 +4 84 277 496 291 +4 40 43 502 280 +4 498 293 316 321 +4 84 291 479 277 +4 502 321 293 498 +4 84 277 479 354 +4 84 121 496 277 +4 84 121 277 354 +4 497 491 69 307 +4 76 281 502 339 +4 287 520 292 527 +4 287 520 527 311 +4 402 113 132 374 +4 354 277 85 129 +4 393 411 341 410 +4 527 282 520 292 +4 277 85 129 284 +4 468 444 245 249 +4 468 444 249 435 +4 398 393 537 417 +4 458 11 571 473 +4 384 406 432 426 +4 550 226 407 427 +4 550 427 233 226 +4 500 397 389 420 +4 327 420 595 500 +4 358 9 507 22 +4 521 9 507 358 +4 151 475 183 181 +4 142 151 181 475 +4 115 350 148 140 +4 140 386 350 148 +4 354 121 277 129 +4 163 373 505 366 +4 6 285 573 358 +4 245 444 263 261 +4 45 358 22 486 +4 361 444 263 245 +4 254 240 361 263 +4 181 598 475 447 +4 598 223 475 447 +4 64 487 515 332 +4 373 169 163 505 +4 13 289 453 483 +4 537 468 393 409 +4 537 393 468 417 +4 492 374 319 324 +4 137 131 369 157 +4 14 41 516 18 +4 157 131 369 398 +4 341 201 566 429 +4 566 429 409 341 +4 341 409 410 429 +4 341 594 429 410 +4 47 337 519 69 +4 120 343 156 123 +4 123 156 161 343 +4 46 538 281 81 +4 506 470 195 469 +4 506 174 195 470 +4 506 195 214 469 +4 454 333 592 365 +4 454 592 352 365 +4 161 135 343 380 +4 135 380 161 160 +4 123 161 135 343 +4 595 472 372 420 +4 223 433 598 345 +4 223 475 345 598 +4 305 352 363 454 +4 116 378 359 134 +4 378 359 134 103 +4 194 278 455 170 +4 17 54 58 295 +4 430 379 582 549 +4 64 332 515 538 +4 595 334 420 327 +4 474 327 589 592 +4 474 333 327 592 +4 180 404 443 566 +4 291 323 488 391 +4 204 278 550 194 +4 502 326 450 321 +4 339 502 326 450 +4 147 400 399 171 +4 61 87 97 316 +4 31 283 290 588 +4 312 31 290 588 +4 10 31 283 290 +4 10 312 31 290 +4 391 275 282 323 +4 97 123 316 87 +4 23 39 46 555 +4 23 471 555 46 +4 53 50 479 484 +4 496 446 344 322 +4 488 446 496 322 +4 53 484 479 276 +4 276 484 479 282 +4 484 50 479 282 +4 543 367 143 470 +4 172 367 470 143 +4 180 144 155 443 +4 154 172 143 367 +4 180 535 144 443 +4 500 366 355 389 +4 358 507 572 22 +4 521 507 24 577 +4 42 280 358 67 +4 547 295 587 288 +4 283 453 289 529 +4 283 289 290 588 +4 345 445 475 338 +4 288 539 295 587 +4 289 529 483 302 +4 290 289 503 302 +4 85 452 284 305 +4 422 560 427 428 +4 560 226 422 427 +4 300 454 324 319 +4 362 363 376 393 +4 284 393 362 376 +4 434 468 409 593 +4 410 435 594 593 +4 512 345 224 207 +4 512 214 224 345 +4 58 294 587 295 +4 286 527 276 391 +4 429 481 361 504 +4 148 386 380 176 +4 294 300 324 319 +4 295 300 539 324 +4 296 510 529 314 +4 296 295 301 324 +4 314 529 302 510 +4 297 448 303 312 +4 293 321 476 316 +4 55 511 77 62 +4 298 299 463 322 +4 500 389 355 541 +4 84 67 299 496 +4 84 291 496 299 +4 55 511 78 77 +4 301 302 510 589 +4 303 590 309 310 +4 303 308 309 590 +4 303 310 448 325 +4 438 351 584 343 +4 285 516 391 538 +4 202 186 412 212 +4 202 412 228 212 +4 337 307 589 595 +4 337 474 499 327 +4 337 327 499 335 +4 307 589 595 500 +4 308 309 590 554 +4 308 302 307 328 +4 339 76 281 331 +4 308 328 307 554 +4 66 502 339 76 +4 309 554 329 590 +4 208 217 235 489 +4 217 489 251 235 +4 179 211 417 187 +4 345 183 475 223 +4 447 223 475 183 +4 525 368 47 38 +4 275 332 363 323 +4 254 361 267 263 +4 267 361 254 482 +4 39 46 555 76 +4 46 76 281 555 +4 438 359 318 387 +4 389 388 406 383 +4 351 321 343 438 +4 538 488 281 331 +4 599 434 414 560 +4 323 488 332 362 +4 323 363 362 332 +4 277 129 304 284 +4 319 352 305 454 +4 324 510 492 374 +4 589 500 592 327 +4 500 389 347 346 +4 326 438 351 359 +4 488 331 538 332 +4 327 334 335 595 +4 327 388 500 592 +4 327 500 388 420 +4 328 373 336 329 +4 328 373 377 336 +4 328 314 500 366 +4 329 130 373 336 +4 329 330 534 367 +4 333 536 597 371 +4 105 336 377 548 +4 508 480 248 437 +4 336 548 373 377 +4 90 118 126 334 +4 90 335 334 126 +4 335 595 334 126 +4 13 528 289 27 +4 283 290 289 528 +4 13 27 289 503 +4 390 412 505 531 +4 531 385 390 412 +4 151 338 475 445 +4 151 338 183 475 +4 17 58 524 292 +4 524 526 50 292 +4 79 320 543 511 +4 343 535 438 317 +4 343 535 584 438 +4 523 532 189 544 +4 189 532 506 544 +4 374 352 353 382 +4 544 532 506 470 +4 129 518 304 284 +4 356 505 367 445 +4 347 451 541 493 +4 595 307 377 497 +4 497 307 377 336 +4 348 356 445 531 +4 349 164 338 544 +4 351 438 584 387 +4 438 387 535 584 +4 432 437 248 436 +4 342 166 452 376 +4 344 449 322 446 +4 344 304 155 443 +4 505 445 531 412 +4 407 194 278 455 +4 376 382 166 411 +4 166 411 382 465 +4 342 166 376 382 +4 166 465 382 342 +4 352 585 365 353 +4 389 390 366 355 +4 355 531 451 390 +4 356 531 355 366 +4 525 474 36 47 +4 525 474 539 36 +4 360 449 318 392 +4 281 360 369 446 +4 362 393 446 591 +4 362 591 332 363 +4 363 591 370 364 +4 363 364 352 394 +4 363 376 393 394 +4 364 365 585 395 +4 364 585 394 395 +4 365 400 334 420 +4 365 420 388 396 +4 365 371 334 400 +4 365 585 395 396 +4 595 334 126 472 +4 420 389 388 396 +4 500 366 389 397 +4 595 397 420 372 +4 366 390 531 355 +4 98 320 511 122 +4 340 168 196 509 +4 340 196 168 167 +4 369 131 591 398 +4 371 334 400 147 +4 371 364 370 399 +4 372 373 366 401 +4 524 58 526 292 +4 58 89 526 292 +4 353 383 494 388 +4 313 332 96 552 +4 67 101 463 496 +4 26 312 303 310 +4 199 341 594 201 +4 155 443 304 566 +4 383 494 388 406 +4 461 484 473 292 +4 29 484 461 292 +4 584 381 407 408 +4 535 409 392 449 +4 488 281 369 446 +4 376 393 394 411 +4 488 281 446 322 +4 382 585 494 274 +4 382 405 411 274 +4 388 415 396 389 +4 388 406 431 389 +4 389 390 384 457 +4 389 396 397 415 +4 369 537 167 157 +4 340 537 196 167 +4 369 340 167 537 +4 393 394 411 540 +4 396 397 415 401 +4 401 505 169 373 +4 390 385 457 412 +4 120 316 476 343 +4 398 399 394 418 +4 398 540 478 418 +4 400 419 396 395 +4 411 430 274 405 +4 229 425 315 442 +4 404 409 443 566 +4 199 594 341 411 +4 406 432 389 384 +4 384 389 457 432 +4 598 426 384 457 +4 344 449 443 317 +4 344 317 322 449 +4 408 427 560 428 +4 408 434 560 414 +4 66 339 103 76 +4 457 389 416 437 +4 457 412 598 433 +4 171 175 191 421 +4 171 399 175 421 +4 331 137 100 369 +4 137 100 369 131 +4 393 410 468 478 +4 398 478 393 417 +4 103 460 359 134 +4 116 359 565 134 +4 424 504 481 429 +4 389 432 406 431 +4 220 431 231 315 +4 389 436 432 431 +4 594 375 435 430 +4 261 375 594 441 +4 315 266 379 522 +4 430 435 549 582 +4 567 379 375 315 +4 592 353 352 365 +4 522 266 270 315 +4 367 470 445 186 +4 64 72 96 332 +4 64 332 96 313 +4 463 321 317 476 +4 132 306 494 383 +4 132 383 494 353 +4 132 383 346 113 +4 132 383 353 346 +4 306 132 113 383 +4 146 347 451 384 +4 142 385 545 451 +4 87 476 293 91 +4 87 476 316 293 +4 498 316 293 87 +4 485 293 87 498 +4 56 293 91 87 +4 56 485 293 87 +4 37 44 310 26 +4 37 501 26 310 +4 79 110 111 543 +4 79 110 543 330 +4 79 543 111 511 +4 142 475 348 151 +4 28 55 62 501 +4 373 372 366 377 +4 213 228 416 437 +4 62 501 55 320 +4 213 228 505 416 +4 281 488 538 391 +4 299 488 281 391 +4 376 411 166 341 +4 211 468 245 249 +4 542 356 355 325 +4 542 314 325 355 +4 211 216 245 468 +4 97 124 316 135 +4 124 316 135 350 +4 317 449 318 360 +4 317 449 360 322 +4 450 317 318 360 +4 450 322 317 360 +4 9 22 358 578 +4 6 9 358 573 +4 1 578 579 573 +4 53 84 276 479 +4 276 84 291 479 +4 46 538 41 471 +4 46 471 555 538 +4 281 322 299 298 +4 498 316 88 351 +4 88 351 316 350 +4 108 350 351 88 +4 296 324 301 510 +4 488 362 591 332 +4 488 591 369 332 +4 166 411 465 200 +4 332 591 369 131 +4 488 299 281 322 +4 281 538 555 285 +4 281 285 555 299 +4 275 363 305 323 +4 275 363 454 305 +4 534 448 325 356 +4 35 498 59 43 +4 35 498 61 59 +4 52 71 80 297 +4 466 441 273 272 +4 297 104 80 314 +4 268 272 273 441 +4 364 394 399 395 +4 364 394 398 399 +4 178 197 306 384 +4 178 384 209 197 +4 149 380 386 135 +4 137 167 340 138 +4 137 167 157 369 +4 153 157 179 398 +4 131 398 157 153 +4 471 538 516 285 +4 483 337 589 301 +4 483 589 337 307 +4 588 303 312 297 +4 290 303 312 588 +4 151 348 445 475 +4 151 349 338 445 +4 551 498 61 35 +4 151 348 349 445 +4 547 295 288 453 +4 316 343 351 321 +4 66 68 103 339 +4 303 314 448 297 +4 585 394 382 352 +4 130 367 163 154 +4 469 214 512 345 +4 430 315 375 379 +4 430 379 549 274 +4 274 549 489 379 +4 520 454 319 305 +4 275 454 520 305 +4 319 382 352 374 +4 411 200 425 405 +4 29 524 50 292 +4 526 89 50 292 +4 415 389 431 436 +4 248 432 260 255 +4 255 432 260 257 +4 303 448 314 325 +4 448 314 325 542 +4 20 574 525 368 +4 368 474 525 47 +4 368 474 539 525 +4 525 574 539 368 +4 280 463 298 299 +4 13 289 483 503 +4 44 70 309 49 +4 56 34 280 485 +4 70 60 310 86 +4 96 100 332 72 +4 187 196 537 167 +4 187 537 196 468 +4 228 508 457 437 +4 248 432 508 437 +4 28 37 55 501 +4 228 437 457 416 +4 26 501 37 28 +4 206 563 478 179 +4 460 360 318 340 +4 460 450 359 318 +4 366 397 595 372 +4 259 466 441 273 +4 0 513 553 547 +4 1 458 286 462 +4 462 286 285 18 +4 6 299 358 280 +4 15 555 280 19 +4 116 68 326 378 +4 280 298 293 502 +4 280 293 498 502 +4 35 280 498 43 +4 416 437 389 436 +4 465 193 200 405 +4 465 405 306 193 +4 344 446 304 449 +4 107 111 141 357 +4 107 357 511 111 +4 543 111 511 357 +4 146 113 347 383 +4 306 113 146 383 +4 392 537 369 393 +4 393 369 398 537 +4 188 416 401 177 +4 188 401 416 505 +4 21 453 57 54 +4 315 269 442 271 +4 341 393 376 411 +4 137 340 331 138 +4 137 340 369 331 +4 211 478 417 468 +4 468 361 245 444 +4 469 470 345 338 +4 114 146 347 493 +4 142 451 545 146 +4 146 347 493 451 +4 220 425 405 315 +4 48 64 313 487 +4 460 331 138 106 +4 460 106 339 331 +4 45 84 67 299 +4 45 67 358 299 +4 67 280 358 299 +4 2 453 547 288 +4 391 282 291 323 +4 539 36 474 311 +4 305 85 279 89 +4 2 288 20 456 +4 456 20 368 288 +4 476 91 120 117 +4 476 463 293 91 +4 284 393 304 446 +4 304 341 409 393 +4 304 341 393 284 +4 85 479 50 282 +4 341 429 594 201 +4 405 274 315 430 +4 286 287 473 527 +4 225 423 221 190 +4 549 421 191 418 +4 389 416 397 390 +4 267 482 504 361 +4 390 397 505 416 +4 276 282 479 291 +4 85 479 282 291 +4 309 310 329 70 +4 29 484 292 50 +4 225 423 247 221 +4 55 320 511 62 +4 291 299 276 391 +4 225 244 247 514 +4 11 467 571 30 +4 225 244 514 210 +4 523 532 544 470 +4 544 470 469 338 +4 30 22 486 45 +4 45 299 358 486 +4 486 285 276 299 +4 137 167 369 340 +4 458 1 571 464 +4 198 544 469 338 +4 162 198 164 544 +4 277 304 446 284 +4 348 445 356 349 +4 356 445 367 349 +4 73 116 68 326 +4 465 405 382 494 +4 132 494 382 353 +4 132 382 374 353 +4 465 405 494 306 +4 61 316 498 87 +4 315 266 270 271 +4 250 269 315 270 +4 315 269 271 270 +4 487 64 313 332 +4 224 239 223 433 +4 224 433 223 345 +4 236 224 345 433 +4 224 236 239 433 +4 363 352 376 394 +4 352 394 382 376 +4 210 423 190 185 +4 453 289 529 483 +4 210 190 423 225 +4 245 361 468 240 +4 216 245 468 240 +4 539 324 474 301 +4 301 589 324 474 +4 313 536 552 333 +4 454 536 313 333 +4 252 514 262 517 +4 252 482 243 514 +4 293 321 463 476 +4 104 448 112 348 +4 497 49 491 307 +4 125 370 597 552 +4 34 498 485 551 +4 313 332 552 536 +4 552 333 536 597 +4 422 233 252 427 +4 210 244 514 424 +4 210 514 423 424 +4 362 488 591 446 +4 233 247 252 427 +4 351 455 387 584 +4 584 407 455 387 +4 584 387 408 407 +4 422 428 427 252 +4 165 415 182 177 +4 177 182 203 415 +4 419 421 217 489 +4 171 421 191 419 +4 466 441 272 258 +4 405 406 193 431 +4 405 274 431 315 +4 274 431 315 522 +4 468 435 593 444 +4 486 22 30 576 +4 379 522 251 489 +4 467 578 576 464 +4 287 587 292 520 +4 287 587 520 311 +4 587 311 300 520 +4 587 520 294 292 +4 587 294 520 300 +4 331 100 332 369 +4 100 332 369 131 +4 331 332 488 369 +4 197 406 237 231 +4 231 237 596 530 +4 541 451 355 493 +4 541 451 389 355 +4 460 450 318 360 +4 329 130 367 366 +4 449 409 392 393 +4 449 393 392 446 +4 535 490 392 409 +4 318 340 392 490 +4 318 535 490 392 +4 340 509 414 490 +4 163 130 366 367 +4 122 533 511 349 +4 284 376 341 393 +4 408 560 413 414 +4 490 413 414 408 +4 366 505 531 390 +4 564 41 64 515 +4 564 487 64 48 +4 564 515 64 487 +4 95 296 492 295 +4 324 352 374 319 +4 324 592 374 352 +4 319 352 454 324 +4 324 454 592 352 +4 114 142 146 493 +4 353 382 585 494 +4 306 406 494 383 +4 143 172 174 470 +4 496 463 299 322 +4 143 174 141 470 +4 143 470 357 543 +4 345 445 412 475 +4 238 582 435 249 +4 478 549 435 238 +4 402 382 319 374 +4 238 549 435 582 +4 478 435 249 238 +4 187 537 468 417 +4 468 444 593 361 +4 429 361 593 444 +4 341 594 410 411 +4 446 304 449 393 +4 304 449 409 443 +4 305 291 282 323 +4 291 323 305 277 +4 306 383 146 384 +4 492 402 319 374 +4 6 12 280 521 +4 6 358 521 280 +4 554 49 497 307 +4 34 280 485 498 +4 599 560 414 413 +4 280 67 463 299 +4 279 342 382 402 +4 499 581 333 63 +4 581 335 334 90 +4 344 449 304 443 +4 292 520 294 89 +4 58 294 89 292 +4 460 340 138 331 +4 104 493 448 348 +4 448 493 542 348 +4 501 310 312 26 +4 275 454 311 520 +4 216 468 211 187 +4 211 468 417 187 +4 443 404 180 535 +4 392 409 196 537 +4 33 515 287 14 +4 14 527 287 286 +4 2 547 453 7 +4 7 453 21 547 +4 339 281 502 450 +4 331 340 369 360 +4 252 482 514 517 +4 54 547 453 295 +4 21 453 54 547 +4 176 205 204 278 +4 278 204 550 205 +4 479 291 85 277 +4 479 277 85 354 +4 198 214 512 469 +4 470 445 345 338 +4 504 482 434 361 +4 514 434 424 504 +4 39 40 502 555 +4 207 469 345 338 +4 260 270 522 266 +4 460 360 340 331 +4 98 511 320 62 +4 132 342 382 494 +4 132 306 342 494 +4 519 335 581 90 +4 519 337 499 335 +4 119 367 130 154 +4 119 330 130 367 +4 113 346 132 374 +4 374 346 132 353 +4 95 402 492 374 +4 555 299 285 15 +4 555 299 15 280 +4 345 433 598 412 +4 345 475 412 598 +4 476 91 101 463 +4 366 373 505 401 +4 366 505 397 401 +4 8 31 32 283 +4 497 99 554 336 +4 391 282 276 291 +4 18 286 285 516 +4 139 565 455 159 +4 159 194 509 455 +4 517 267 482 504 +4 517 514 262 504 +4 62 92 93 511 +4 518 166 376 452 +4 518 166 341 376 +4 95 113 374 510 +4 82 510 113 95 +4 95 113 402 374 +4 49 309 308 554 +4 49 554 308 307 +4 347 383 389 384 +4 347 389 451 384 +4 90 519 335 546 +4 368 337 474 47 +4 36 48 474 311 +4 36 48 63 474 +4 474 454 313 333 +4 17 54 547 21 +4 305 282 520 275 +4 275 282 520 527 +4 292 282 520 89 +4 46 538 81 72 +4 46 41 538 72 +4 496 299 488 322 +4 286 473 484 527 +4 473 527 292 484 +4 432 530 260 257 +4 118 147 126 334 +4 334 472 420 400 +4 472 420 400 401 +4 71 104 448 112 +4 597 147 371 150 +4 463 299 67 496 +4 436 432 253 248 +4 218 226 407 194 +4 550 226 194 407 +4 509 599 196 414 +4 192 509 599 196 +4 192 509 413 599 +4 509 414 413 599 +4 156 190 161 381 +4 161 190 184 381 +4 55 501 79 320 +4 501 79 320 310 +4 448 493 314 542 +4 511 357 133 127 +4 109 133 511 357 +4 59 74 498 88 +4 74 498 88 351 +4 56 67 463 280 +4 56 463 293 280 +4 333 327 592 365 +4 327 365 388 592 +4 327 388 365 420 +4 476 101 117 317 +4 476 463 101 317 +4 494 431 405 274 +4 519 595 335 546 +4 335 546 595 126 +4 594 430 442 375 +4 119 143 367 154 +4 346 383 388 389 +4 389 406 384 383 +4 349 470 445 367 +4 513 575 547 5 +4 312 31 588 297 +4 31 283 588 297 +4 326 359 351 116 +4 116 378 326 359 +4 351 116 359 565 +4 317 438 343 321 +4 317 321 450 438 +4 411 430 410 274 +4 382 274 411 394 +4 389 397 416 415 +4 397 416 415 401 +4 38 307 337 69 +4 178 181 209 598 +4 38 307 69 491 +4 38 337 47 69 +4 46 76 81 281 +4 92 109 133 511 +4 92 133 127 511 +4 142 475 385 531 +4 142 385 451 531 +4 478 211 417 179 +4 563 211 478 179 +4 102 330 130 119 +4 102 330 329 130 +4 283 453 529 57 +4 283 314 57 529 +4 453 295 301 296 +4 483 589 302 301 +4 483 302 589 307 +4 368 483 301 337 +4 274 585 494 431 +4 207 345 183 338 +4 151 164 183 338 +4 345 338 475 183 +4 296 82 510 314 +4 301 510 324 589 +4 500 347 556 510 +4 337 589 474 327 +4 309 310 590 329 +4 310 329 534 325 +4 310 543 534 330 +4 370 364 591 398 +4 222 560 243 434 +4 420 401 397 396 +4 79 330 543 310 +4 186 412 445 505 +4 301 337 589 474 +4 186 345 445 412 +4 593 435 594 444 +4 416 215 436 415 +4 176 205 278 380 +4 380 278 550 205 +4 314 510 302 500 +4 510 302 500 589 +4 105 548 372 145 +4 372 595 126 472 +4 340 509 196 414 +4 490 414 392 409 +4 592 365 388 353 +4 305 452 376 279 +4 198 469 207 338 +4 469 345 512 207 +4 23 285 555 471 +4 281 391 538 285 +4 471 285 555 538 +4 490 413 408 407 +4 408 413 560 407 +4 48 474 313 333 +4 435 549 478 418 +4 410 435 478 418 +4 274 430 435 549 +4 410 430 435 274 +4 435 549 418 274 +4 287 574 311 16 +4 287 574 587 311 +4 539 311 474 454 +4 127 133 158 357 +4 133 141 158 357 +4 141 357 523 158 +4 127 158 544 357 +4 158 544 357 523 +4 337 595 327 335 +4 319 376 352 382 +4 305 352 376 363 +4 320 533 543 511 +4 533 543 511 349 +4 533 356 349 348 +4 500 388 389 346 +4 534 329 367 356 +4 533 349 534 543 +4 534 330 543 367 +4 533 349 356 534 +4 534 367 349 356 +4 535 438 318 387 +4 0 5 547 587 +4 0 547 17 587 +4 0 587 287 5 +4 139 565 351 455 +4 30 484 53 486 +4 99 548 136 336 +4 584 381 184 407 +4 170 204 278 176 +4 304 449 393 409 +4 304 341 566 409 +4 387 408 407 490 +4 455 407 509 387 +4 159 194 455 170 +4 181 209 598 219 +4 219 426 209 598 +4 197 558 406 209 +4 136 169 373 145 +4 415 416 389 436 +4 515 527 311 287 +4 515 527 287 14 +4 390 366 505 397 +4 105 595 126 372 +4 540 394 274 418 +4 540 394 411 274 +4 570 472 145 372 +4 105 377 595 372 +4 105 548 377 372 +4 33 311 48 36 +4 33 311 487 48 +4 41 538 515 516 +4 516 515 391 538 +4 117 343 152 120 +4 120 152 156 343 +4 89 557 402 319 +4 89 319 294 557 +4 557 492 402 319 +4 557 319 294 492 +4 498 316 351 321 +4 536 370 364 363 +4 332 536 363 370 +4 60 79 310 86 +4 446 360 369 392 +4 446 393 392 369 +4 360 369 392 340 +4 323 305 284 376 +4 323 376 363 305 +4 323 376 362 363 +4 323 376 284 362 +4 384 426 432 457 +4 361 434 240 254 +4 361 434 468 240 +4 361 481 593 434 +4 408 409 424 481 +4 352 364 585 394 +4 404 408 409 424 +4 147 472 126 334 +4 102 310 329 330 +4 147 334 400 472 +4 145 165 177 401 +4 207 223 183 345 +4 316 343 135 350 +4 326 438 359 450 +4 450 438 359 318 +4 317 449 443 535 +4 496 101 317 344 +4 451 385 384 390 +4 317 535 318 449 +4 449 535 318 392 +4 365 388 585 396 +4 356 505 366 367 +4 180 404 403 535 +4 535 443 404 409 +4 535 408 404 403 +4 535 404 408 409 +4 465 494 382 342 +4 382 494 405 274 +4 388 431 406 494 +4 585 388 494 431 +4 409 408 434 481 +4 352 592 374 353 +4 592 353 346 374 +4 388 396 415 585 +4 388 389 431 415 +4 184 190 427 381 +4 381 427 408 423 +4 408 514 424 423 +4 593 361 429 481 +4 408 423 427 428 +4 410 594 429 593 +4 593 444 594 429 +4 192 218 222 560 +4 192 599 560 222 +4 192 218 560 413 +4 192 599 413 560 +4 142 493 348 451 +4 356 451 355 531 +4 542 493 355 356 +4 204 226 194 550 +4 429 439 361 444 +4 429 440 439 444 +4 234 235 253 436 +4 204 550 205 226 +4 234 436 253 248 +4 594 249 444 435 +4 147 126 472 165 +4 570 472 126 165 +4 295 300 324 294 +4 286 527 391 516 +4 14 516 527 286 +4 587 300 295 294 +4 587 539 300 311 +4 368 301 474 337 +4 283 289 588 529 +4 289 588 529 302 +4 588 303 297 314 +4 289 503 302 483 +4 503 302 307 308 +4 539 454 324 300 +4 410 430 411 594 +4 539 324 454 474 +4 474 592 589 324 +4 307 302 589 500 +4 303 308 590 302 +4 303 325 314 590 +4 308 590 302 328 +4 590 328 325 314 +4 500 541 314 556 +4 331 281 360 369 +4 295 296 492 324 +4 363 332 370 591 +4 363 394 393 591 +4 332 131 370 591 +4 365 371 395 364 +4 365 396 395 400 +4 371 395 364 399 +4 372 366 397 401 +4 127 128 511 357 +4 128 127 544 357 +4 540 274 410 418 +4 495 419 431 489 +4 398 540 393 478 +4 540 410 478 418 +4 395 396 585 495 +4 313 552 96 94 +4 395 419 495 421 +4 313 333 552 94 +4 396 401 415 400 +4 396 415 495 419 +4 128 357 349 511 +4 128 544 349 357 +4 253 260 522 266 +4 468 478 410 435 +4 191 206 549 418 +4 191 206 217 549 +4 175 191 418 206 +4 134 168 340 583 +4 509 490 407 413 +4 134 138 340 168 +4 509 407 490 387 +4 399 421 395 394 +4 395 421 274 394 +4 17 58 587 295 +4 487 454 275 332 +4 487 454 332 313 +4 499 334 327 333 +4 499 327 334 335 +4 307 377 328 500 +4 307 328 377 336 +4 99 336 329 554 +4 554 336 329 328 +4 542 325 448 356 +4 493 451 355 356 +4 454 365 352 364 +4 353 585 365 388 +4 328 325 314 366 +4 325 366 356 355 +4 101 144 317 344 +4 416 505 457 228 +4 404 429 424 409 +4 409 481 429 424 +4 245 249 444 261 +4 457 598 426 433 +4 598 433 223 426 +4 495 431 274 489 +4 495 415 431 419 +4 436 419 208 489 +4 415 419 208 436 +4 429 504 361 439 +4 538 81 100 331 +4 530 270 431 260 +4 538 332 331 100 +4 430 435 582 375 +4 508 432 457 437 +4 578 22 486 576 +4 576 22 9 578 +4 327 334 420 365 +4 268 442 441 273 +4 268 441 442 375 +4 540 274 411 410 +4 393 540 411 410 +4 263 272 444 267 +4 263 361 267 444 +4 272 440 444 267 +4 267 361 439 444 +4 14 516 286 18 +4 232 468 434 240 +4 291 488 299 391 +4 17 524 29 292 +4 0 287 292 473 +4 0 473 292 461 +4 461 292 17 29 +4 0 292 287 587 +4 0 17 292 587 +4 286 391 285 516 +4 276 391 299 285 +4 5 574 287 16 +4 5 574 587 287 +4 515 323 332 275 +4 24 572 42 577 +4 577 507 24 572 +4 15 285 555 23 +4 343 351 584 386 +4 307 497 554 336 +4 496 121 101 344 +4 10 290 27 26 +4 0 3 287 473 +4 0 3 459 287 +4 396 415 585 495 +4 585 415 431 495 +4 573 578 9 358 +4 4 285 573 6 +4 144 317 443 535 +4 104 151 142 348 +4 45 299 486 53 +4 53 486 276 299 +4 45 84 299 53 +4 53 299 276 84 +4 51 71 297 312 +4 312 297 51 31 +4 545 385 384 451 +4 545 385 181 178 +4 236 433 246 239 +4 239 246 426 433 +4 246 433 508 426 +4 426 508 457 433 +4 508 433 246 236 +4 544 470 338 349 +4 286 527 484 276 +4 276 527 484 282 +4 314 500 355 541 +4 193 406 231 431 +4 571 285 286 276 +4 571 484 276 286 +4 286 285 391 276 +4 22 45 42 358 +4 572 22 42 358 +4 0 473 11 458 +4 392 340 369 537 +4 235 436 489 253 +4 253 431 489 522 +4 253 431 436 489 +4 496 322 344 317 +4 548 373 145 136 +4 573 285 578 358 +4 324 589 374 592 +4 3 458 286 473 +4 589 592 346 374 +4 0 3 473 458 +4 391 275 527 282 +4 340 509 318 359 +4 340 318 509 490 +4 486 576 30 467 +4 578 576 486 467 +4 164 198 338 544 +4 162 189 198 544 +4 459 14 16 287 +4 315 270 231 250 +4 501 312 310 320 +4 205 550 233 226 +4 550 427 407 184 +4 380 205 550 184 +4 550 184 407 380 +4 380 584 184 407 +4 486 285 571 276 +4 171 399 421 419 +4 399 421 418 175 +4 145 401 177 169 +4 145 373 401 169 +4 486 484 276 571 +4 551 498 485 61 +4 74 498 351 73 +4 74 73 351 108 +4 308 590 328 554 +4 590 554 329 328 +4 378 339 359 103 +4 305 89 520 282 +4 85 282 89 305 +4 571 286 473 484 +4 196 468 232 216 +4 196 468 434 232 +4 409 468 434 196 +4 458 571 286 473 +4 1 458 571 286 +4 356 531 348 451 +4 134 359 340 460 +4 116 139 565 351 +4 340 509 359 583 +4 0 473 461 11 +4 521 12 280 24 +4 521 577 24 280 +4 18 23 471 285 +4 18 285 471 516 +4 451 390 389 355 +4 227 230 258 440 +4 451 384 389 390 +4 454 352 363 364 +4 332 454 363 536 +4 454 364 363 536 +4 521 507 577 358 +4 96 332 131 552 +4 577 572 42 358 +4 358 507 577 572 +4 521 358 577 280 +4 358 577 280 42 +4 287 527 292 473 +4 484 527 292 282 +4 391 527 276 282 +4 25 312 65 51 +4 460 138 340 134 +4 0 513 547 5 +4 30 571 486 467 +4 576 578 580 464 +4 304 518 566 341 +4 595 334 472 420 +4 578 1 579 464 +4 467 571 578 464 +4 486 358 578 285 +4 358 299 285 486 +4 249 582 435 375 +4 36 574 539 525 +4 368 539 288 574 +4 27 309 49 44 +4 27 309 308 49 +4 118 334 371 147 +4 248 253 260 432 +4 595 377 105 497 +4 69 595 105 497 +4 69 595 519 105 +4 467 571 486 578 +4 519 595 546 105 +4 513 2 7 547 +4 553 547 7 17 +4 553 513 7 547 +4 578 486 285 571 +4 1 4 462 285 +4 1 286 285 462 +4 268 271 567 442 +4 315 442 567 271 +4 1 571 285 286 +4 256 582 375 379 +4 430 379 375 582 +4 1 285 578 573 +4 99 105 548 336 +4 1 578 285 571 +4 4 285 1 573 +4 497 99 336 105 +4 340 168 509 583 +4 555 299 298 281 +4 579 578 9 573 +4 578 579 9 580 +4 576 578 9 580 +4 30 484 486 571 +4 404 201 227 429 +4 404 424 227 210 +4 186 505 202 412 +4 514 504 482 434 +4 438 387 351 359 +4 458 3 286 462 +4 11 571 473 484 +4 11 484 473 461 +4 29 11 484 30 +4 29 484 11 461 +4 11 571 484 30 +4 12 280 34 35 +4 34 280 498 35 +4 578 579 580 464 +4 11 464 571 467 +4 571 458 464 11 +4 581 519 499 335 +4 489 274 522 431 +4 274 489 522 379 +4 21 547 17 7 +4 530 406 432 431 +4 70 554 329 309 +4 182 415 419 208 +4 419 431 489 436 +4 2 575 20 288 +4 182 400 419 415 +4 472 372 420 401 +4 372 401 397 420 +4 546 105 595 126 +4 105 570 145 372 +4 555 502 281 298 +4 212 236 345 412 +4 503 308 307 49 +4 349 164 151 338 +4 122 349 164 151 +4 353 585 388 494 +4 348 122 151 349 +4 181 598 385 475 +4 206 398 478 418 +4 274 315 379 522 +4 414 434 196 409 +4 110 367 330 119 +4 110 367 543 330 +4 108 350 88 115 +4 115 350 88 124 +4 124 88 316 350 +4 54 295 95 557 +4 460 340 318 359 +4 129 155 344 304 +4 129 304 344 277 +4 163 169 373 136 +4 163 373 130 136 +4 112 448 320 533 +4 565 509 455 159 +4 565 509 359 387 +4 565 509 387 455 +4 103 460 339 359 +4 570 145 472 165 +4 40 502 73 68 +4 43 498 73 502 +4 229 442 259 559 +4 127 158 162 544 +4 284 305 277 85 +4 231 596 264 530 +4 200 220 425 405 +4 129 452 284 85 +4 20 368 288 574 +4 574 539 288 587 +4 258 440 272 265 +4 227 258 265 440 +4 74 351 88 108 +4 519 595 69 337 +4 519 335 595 337 +4 142 385 181 545 +4 142 181 385 475 +4 234 437 436 248 +4 68 326 378 339 +4 339 450 326 359 +4 378 326 359 339 +4 406 306 494 405 +4 228 457 433 412 +4 202 505 228 412 +4 13 456 38 483 +4 596 237 257 530 +4 104 493 142 114 +4 104 114 314 493 +4 146 493 142 451 +4 535 438 317 318 +4 411 465 200 405 +4 419 421 191 217 +4 261 441 272 268 +4 501 312 65 25 +4 501 65 312 320 +4 122 561 164 349 +4 561 164 544 162 +4 562 255 558 432 +4 562 558 426 432 +4 237 255 432 558 +4 237 432 406 558 +4 452 376 284 305 +4 518 376 341 284 +4 319 279 376 382 +4 279 452 376 342 +4 518 452 376 284 +4 411 405 382 465 +4 543 357 143 111 +4 63 333 474 48 +4 311 487 474 454 +4 311 48 474 487 +4 129 121 277 344 +4 206 549 238 217 +4 217 568 549 238 +4 68 339 378 103 +4 319 305 352 376 +4 70 99 102 329 +4 253 431 432 436 +4 253 260 431 522 +4 253 432 431 260 +4 26 309 310 303 +4 304 518 341 284 +4 228 480 508 437 +4 12 24 34 280 +4 24 280 56 34 +4 562 248 255 432 +4 562 248 432 508 +4 562 508 432 426 +4 426 508 432 457 +4 141 523 357 470 +4 265 267 439 440 +4 8 283 289 528 +4 62 320 98 65 +4 62 93 98 511 +4 488 446 277 496 +4 296 510 301 529 +4 529 301 302 510 +4 320 543 534 310 +4 27 38 49 503 +4 84 496 121 101 +4 329 367 356 366 +4 312 310 320 448 +4 310 320 448 534 +4 586 437 234 480 +4 215 416 436 234 +4 585 274 395 495 +4 274 549 418 421 +4 217 489 421 549 +4 421 418 274 394 +4 175 421 418 191 +4 181 447 475 183 +4 557 294 295 492 +4 251 266 379 567 +4 567 379 315 266 +4 315 442 375 567 +4 267 439 440 444 +4 454 364 536 365 +4 536 365 364 371 +4 392 414 196 409 +4 189 544 469 198 +4 523 174 532 470 +4 497 377 105 336 +4 568 379 256 251 +4 459 3 14 287 +4 251 489 549 379 +4 568 582 256 379 +4 243 434 254 232 +4 532 174 506 470 +4 189 506 214 469 +4 311 539 574 587 +4 477 427 550 184 +4 37 501 60 55 +4 199 569 230 594 +4 569 441 559 230 +4 569 230 594 441 +4 404 210 403 424 +4 63 581 333 94 +4 291 277 496 488 +4 291 488 496 299 +4 543 470 357 349 +4 349 367 543 470 +4 369 157 398 537 +4 38 307 491 49 +4 38 503 307 49 +4 279 382 319 402 +4 196 468 537 409 +4 555 298 280 502 +4 201 594 230 227 +4 227 440 594 230 +4 244 504 514 424 +4 51 297 71 52 +4 199 201 566 341 +4 150 153 175 398 +4 370 398 153 150 +4 171 419 191 182 +4 182 191 208 419 +4 340 414 392 490 +4 499 333 474 63 +4 208 489 419 217 +4 237 530 406 432 +4 231 237 530 406 +4 502 43 40 73 +4 502 43 498 280 +4 243 428 422 252 +4 12 19 280 35 +4 5 574 575 547 +4 5 547 587 574 +4 575 574 20 288 +4 557 95 402 492 +4 425 442 430 315 +4 425 315 430 405 +4 316 476 343 321 +4 228 505 457 412 +4 347 451 389 541 +4 38 368 47 337 +4 581 334 94 90 +4 499 581 335 334 +4 499 334 333 581 +4 94 333 597 118 +4 94 333 552 597 +4 118 371 333 597 +4 101 317 144 117 +4 477 221 233 427 +4 125 370 131 153 +4 125 552 131 370 +4 241 242 562 426 +4 241 562 558 426 +4 242 246 562 426 +4 339 460 450 359 +4 211 468 249 478 +4 89 319 305 520 +4 144 535 180 152 +4 128 561 349 544 +4 561 164 349 544 +4 567 442 375 268 +4 10 290 26 312 +4 147 400 171 165 +4 165 171 182 400 +4 404 429 227 424 +4 351 565 359 387 +4 460 450 281 339 +4 197 406 193 306 +4 193 197 231 406 +4 518 284 129 452 +4 173 380 205 176 +4 275 332 454 363 +4 442 441 559 569 +4 442 569 594 441 +4 442 441 259 559 +4 113 346 347 383 +4 235 251 253 489 +4 251 253 489 522 +4 568 217 549 251 +4 439 440 429 227 +4 439 227 265 440 +4 258 466 441 259 +4 559 441 259 258 +4 379 568 549 251 +4 25 312 51 31 +4 586 213 416 437 +4 336 373 136 130 +4 548 373 372 145 +4 54 295 557 58 +4 58 557 294 295 +4 0 547 553 17 +4 86 330 310 102 +4 130 367 330 329 +4 172 470 367 186 +4 238 549 582 568 +4 568 549 582 379 +4 27 503 49 308 +4 393 341 409 410 +4 20 368 525 38 +4 513 2 547 575 +4 482 504 514 517 +4 94 334 333 118 +4 581 334 333 94 +4 165 401 472 400 +4 16 574 36 20 +4 575 16 20 574 +4 163 366 505 367 +4 599 222 232 434 +4 599 196 434 232 +4 414 434 599 196 +4 243 560 422 428 +4 583 168 509 159 +4 583 359 565 509 +4 205 477 550 184 +4 382 585 274 394 +4 395 274 585 394 +4 535 449 443 409 +4 124 386 149 148 +4 135 343 380 386 +4 343 584 380 386 +4 343 381 584 535 +4 535 387 408 584 +4 531 385 451 390 +4 352 382 585 353 +4 304 566 443 409 +4 494 406 405 431 +4 387 408 490 535 +4 376 411 394 382 +4 585 431 274 495 +4 388 585 415 431 +4 389 457 416 390 +4 390 416 505 457 +4 390 457 505 412 +4 535 490 409 408 +4 490 409 408 414 +4 283 529 588 314 +4 529 588 314 302 +4 298 293 321 463 +4 324 510 374 589 +4 516 527 391 515 +4 14 515 527 516 +4 311 539 300 454 +4 588 314 302 303 +4 503 307 483 38 +4 483 503 302 307 +4 453 483 301 368 +4 453 529 296 301 +4 290 302 503 308 +4 290 308 303 302 +4 290 303 308 26 +4 27 290 503 308 +4 302 314 500 328 +4 303 302 590 314 +4 302 590 314 328 +4 303 325 590 310 +4 590 325 328 329 +4 590 310 325 329 +4 6 285 299 15 +4 446 393 369 591 +4 591 393 369 398 +4 362 393 591 363 +4 394 540 393 398 +4 363 394 591 364 +4 591 394 393 398 +4 591 364 394 398 +4 365 371 400 395 +4 371 400 395 399 +4 365 396 400 420 +4 396 419 495 395 +4 393 478 468 417 +4 393 540 410 478 +4 587 295 300 539 +4 533 356 348 448 +4 430 435 594 410 +4 454 332 313 536 +4 554 328 307 336 +4 510 347 346 500 +4 556 347 500 541 +4 541 389 347 500 +4 542 348 493 356 +4 542 448 348 356 +4 314 355 500 366 +4 314 325 355 366 +4 325 329 356 366 +4 534 543 349 367 +4 429 440 444 594 +4 589 346 592 500 +4 500 388 346 592 +4 314 493 355 542 +4 314 355 493 541 +4 438 317 318 450 +4 403 424 408 404 +4 408 424 514 434 +4 408 481 424 434 +4 404 429 409 566 +4 434 593 409 481 +4 411 425 594 430 +4 193 220 405 431 +4 550 194 278 407 +4 409 429 593 410 +4 457 389 437 432 +4 389 437 432 436 +4 534 329 356 325 +4 425 594 430 442 +4 594 442 441 375 +4 430 442 375 315 +4 231 270 315 431 +4 231 530 431 406 +4 431 522 270 315 +4 260 270 431 522 +4 552 536 332 370 +4 536 364 370 371 +4 454 365 536 333 +4 536 333 365 371 +4 333 365 371 334 +4 333 327 365 334 +4 500 366 595 377 +4 377 366 595 372 +4 328 366 377 373 +4 331 488 281 369 +4 274 489 549 421 +4 393 409 468 410 +4 550 477 233 427 +4 36 474 63 47 +4 257 260 270 530 +4 596 257 264 530 +4 243 428 434 560 +4 482 243 434 254 +4 243 434 428 514 +4 514 482 243 434 +4 201 429 594 227 +4 227 440 429 594 +4 594 375 249 435 +4 261 375 441 268 +4 273 269 271 442 +4 175 418 398 206 +4 455 565 351 387 +4 372 126 570 472 +4 560 226 243 422 +4 199 594 230 201 +4 294 492 319 324 +4 33 41 564 515 +4 33 487 564 48 +4 33 515 564 487 +4 158 523 189 544 +4 158 189 162 544 +4 199 569 594 425 +4 569 594 425 442 +4 73 116 351 108 +4 420 396 397 389 +4 347 346 389 383 +4 150 370 398 399 +4 370 364 398 399 +4 306 383 384 406 +4 177 416 401 415 +4 337 595 589 327 +4 595 589 327 500 +4 483 529 301 302 +4 453 483 529 301 +4 57 453 529 296 +4 57 314 296 529 +4 392 537 393 409 +4 392 537 196 340 +4 215 213 416 586 +4 152 343 535 381 +4 113 510 347 346 +4 122 533 320 511 +4 348 349 533 122 +4 597 536 370 371 +4 552 597 536 370 +4 156 381 161 343 +4 350 351 343 386 +4 351 455 584 386 +4 343 584 381 161 +4 535 403 381 408 +4 490 414 413 509 +4 298 502 450 321 +4 527 520 275 311 +4 520 311 300 454 +4 593 481 429 409 +4 97 135 316 123 +4 123 343 135 316 +4 117 343 476 317 +4 317 343 476 321 +4 316 351 343 350 +4 371 147 400 399 +4 396 400 415 419 +4 190 423 427 381 +4 221 190 423 427 +4 210 424 423 403 +4 403 424 423 408 +4 408 434 428 560 +4 230 441 440 594 +4 31 52 283 297 +4 52 297 314 283 +4 283 297 314 588 +4 290 588 302 303 +4 290 312 303 26 +4 54 295 453 296 +4 289 290 588 302 +4 288 453 295 301 +4 288 453 301 368 +4 288 295 539 301 +4 288 368 301 539 +4 539 301 474 368 +4 499 474 333 327 +4 307 302 500 328 +4 281 450 322 298 +4 298 322 463 450 +4 555 298 299 280 +4 95 510 492 296 +4 296 510 492 324 +4 328 329 325 366 +4 328 366 373 329 +4 329 130 366 373 +4 349 357 544 470 +4 544 470 357 523 +4 548 372 373 377 +4 114 556 541 347 +4 114 493 347 541 +4 500 377 328 366 +4 552 332 131 370 +4 197 209 406 384 +4 227 244 424 439 +4 244 504 424 439 +4 231 270 431 530 +4 511 357 349 543 +4 0 287 459 5 +4 502 321 498 73 +4 73 498 351 321 +4 257 270 264 530 +4 225 514 247 423 +4 225 514 423 210 +4 208 436 235 215 +4 215 234 436 235 +4 276 299 291 84 +4 185 423 381 403 +4 220 231 250 315 +4 478 468 249 435 +4 320 534 533 448 +4 320 533 534 543 +4 310 448 325 534 +4 500 589 346 510 +4 310 534 329 330 +4 500 389 388 420 +4 500 397 420 595 +4 312 448 303 310 +4 535 584 408 381 +4 409 593 468 410 +4 593 468 361 434 +4 318 509 490 387 +4 391 275 323 515 +4 311 515 487 275 +4 527 275 391 515 +4 527 311 275 515 +4 321 438 326 450 +4 281 298 502 450 +4 351 438 326 321 +4 73 321 351 326 +4 73 326 351 116 +4 272 440 441 444 +4 594 444 441 440 +4 249 444 261 594 +4 381 423 408 403 +4 381 407 427 184 +4 381 427 407 408 +4 446 393 362 284 +4 408 428 514 423 +4 408 514 428 434 +4 322 449 360 446 +4 281 360 446 322 +4 591 488 369 446 +4 463 317 450 322 +4 496 463 322 317 +4 454 474 592 333 +4 352 585 364 365 +4 481 434 361 504 +4 424 504 434 481 +4 409 414 434 408 +4 385 457 412 598 +4 385 598 412 475 +4 295 539 301 324 +4 131 370 591 398 +4 420 400 401 396 +4 397 416 401 505 +4 37 501 310 60 +4 426 219 241 242 +4 209 406 426 558 +4 99 136 130 336 +4 249 582 256 568 +4 46 538 555 281 +4 547 574 575 288 +4 547 288 587 574 +4 2 547 575 288 +4 161 584 381 184 +4 28 501 65 25 +4 28 62 65 501 +4 62 65 501 320 +4 577 24 280 42 +4 486 358 22 578 +4 273 442 271 268 +4 291 277 488 323 +4 228 433 508 236 +4 228 508 433 457 +4 155 180 443 566 +4 179 417 478 398 +4 474 313 454 487 +4 125 370 153 150 +4 586 416 234 437 +4 213 437 480 228 +4 8 528 289 13 +4 528 290 289 27 +4 10 290 283 528 +4 528 10 290 27 +4 166 341 411 199 +4 566 166 199 341 +4 518 166 566 341 + +CELL_TYPES 2425 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 diff --git a/data/ditto.vtk b/data/ditto.vtk new file mode 100644 index 000000000..73657259c --- /dev/null +++ b/data/ditto.vtk @@ -0,0 +1,23419 @@ +# vtk DataFile Version 2.0 +ditto_small_, Created by Gmsh +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 2580 double +-2.266613721628773 0.6468019269309846 0.1247034841114323 +-2.25759912 0.654327273 0.359414369 +-2.25357819 0.449681759 0.106850438 +-2.25147796 0.447774142 0.353660494 +-2.22007942 0.8728742 0.126479611 +-2.206287741462754 0.8695781508151502 0.3642948160480015 +-2.205806632533764 0.6524415301541702 -0.1299830036893869 +-2.20054793 0.295265973 0.100473419 +-2.191903962610785 0.4564544556203757 -0.143275524151874 +-2.184153681220465 0.2785948333761406 0.3352892499389331 +-2.17916894 0.656039953 0.585083663 +-2.17502832 0.446752936 0.584108651 +-2.160581404275744 0.8599889844672665 -0.1128477530260419 +-2.137243092023698 0.2931572077149552 -0.1362033976770088 +-2.13017869 0.872863948 0.572633207 +-2.122668339444397 1.093233040375276 0.1352116498534346 +-2.11620879 1.08634329 0.358220011 +-2.110147301027515 0.2765715787298201 0.5570941807384018 +-2.08788753 0.168897197 0.0931103975 +-2.07868886 0.6553376910000001 -0.362433404 +-2.07862926 1.07377219 -0.0951772183 +-2.069584329581335 0.4547195080478004 -0.3707488151630964 +-2.065531644069279 0.157776692124946 0.3068038896446674 +-2.04639935 1.08045375 0.555087507 +-2.04434943 0.651496172 0.767780185 +-2.0373888 0.4461371 0.768527806 +-2.03530955 0.866828144 -0.345532745 +-2.010614290045211 1.29115804941337 0.1513001985193747 +-2.02128768 0.164846942 -0.130709842 +-2.006402784585344 3.05722839068507 0.2003012789064664 +-2.001808838384276 0.2899673906674147 -0.3686237218621271 +-2.008795311042196 0.8502759308000356 0.7445676126078551 +-2.00006938 2.91327477 0.198504776 +-1.99393868 1.24578226 -0.0724132881 +-1.99243891 3.07048488 0.277205735 +-1.99226892 3.05958509 0.112976901 +-1.99014783 0.156854942 0.5056590439999999 +-1.988819 3.1718154 0.190909848 +-1.984904567955338 2.942549864234536 0.2953764130208684 +-1.978784123486364 2.906613334919355 0.09372216732223128 +-1.97333508931913 3.183835849278675 0.2626315988541904 +-1.97805757450754 3.162245804514373 0.1222370568601326 +-1.974942339374683 1.050035702489964 -0.3284162951432916 +-1.96871889 0.273991317 0.738351405 +-1.957276835495525 3.065478019832113 0.3591386171712304 +-1.96148074 2.70626521 0.199547723 +-1.962051059038659 3.049210966844202 0.04606540081687916 +-1.95434856 3.17558455 0.326840729 +-1.954181425873289 3.152668099729248 0.06023880832823854 +-1.965647735365329 1.224876736620887 0.5371447772984353 +-1.945469577934344 3.260025755548534 0.1831023998684968 +-1.944067352044318 2.716117143303869 0.08141489293638965 +-1.94560945 2.9501245 0.387835622 +-1.94429076 2.72237563 0.325443715 +-1.94354951 2.93160462 0.0104048112 +-1.940502001489294 3.256225712033761 0.2549893381654016 +-1.940854869734202 3.233041404412455 0.1108766416754069 +-1.941139893162799 1.056659970336959 0.7141875712040888 +-1.931936054879243 3.124345637912981 0.01644135311035805 +-1.925259112722381 3.168691560138117 0.3748456843339861 +-1.913899328994043 3.223698483901244 0.05226137089816724 +-1.92069852 3.24881434 0.318068713 +-1.91550174468922 3.091303317632242 0.4120823871922004 +-1.910588178171088 3.050518083618543 -0.02638520787749419 +-1.9155575 1.39072251 -0.0474857837 +-1.933739590358977 0.6520173015197507 -0.5372973463814723 +-1.90727079 2.49315524 0.201954558 +-1.90481877 1.23609197 -0.301197976 +-1.90472031 2.75297499 -0.0215055272 +-1.894550572352014 2.743168063811586 0.4359322522867925 +-1.898314440769919 3.178625689681764 0.00109402381413039 +-1.901679698841787 3.312210149562231 0.1748035398221995 +-1.89471841 3.22593474 0.378048629 +-1.890148233798027 0.6578905438294081 0.9217154557462625 +-1.88739656538277 2.972461597387532 0.4611633942792212 +-1.88097938319913 2.923269251266182 -0.06900255257592307 +-1.89101090605074 3.29822576464499 0.1071717367067093 +-1.8877069155562 2.497422495358433 0.0751394124263194 +-1.911395573100969 0.4627512554182864 -0.5456084745437103 +-1.889809452030174 3.316298682900225 0.2481049155242671 +-1.785147097716635 0.4628483474828613 1.016876984039725 +-1.88522112 2.49162507 0.338759422 +-1.876337078014645 0.8471975245094866 -0.5671948563173632 +-1.877027074467494 0.150706354752067 -0.3395110018990512 +-1.87757994997391 3.271169856822717 0.05243097370828886 +-1.87729764 0.0470308587 0.0762234777 +-1.87671745 1.51391315 0.163586631 +-1.886203148495081 1.369329792047533 0.5181991838851264 +-1.873976453165775 3.109260530863247 -0.04730819451128677 +-1.870583137847212 0.0508787200670487 0.2682162708090151 +-1.867916935209288 3.30480470837873 0.3166948536794367 +-1.8665489 3.15891433 0.435112536 +-1.871406241413895 1.499331761941155 0.3280917430829068 +-1.838259662983978 0.8648812856210736 0.9084499932910433 +-1.85560623215528 3.222949844158181 -0.007314977027813897 +-1.856148296154742 1.238034419175343 0.6906819605874797 +-1.852225077247213 1.510282133804937 -0.01841924745140758 +-1.84603083 2.55417514 -0.0489670932 +-1.84576857 0.147387117 0.680282772 +-1.845047451828216 2.812469584485 -0.1039711343369072 +-1.84103036 2.8143146 0.511936545 +-1.841164834270186 3.27546251111833 0.3800471957720271 +-1.844158722602283 1.366873759578924 -0.2788859036653375 +-1.845031052049093 1.048275268943997 -0.5294251964678067 +-1.833160867068715 3.335957574394235 0.09200846505600857 +-1.834221283966579 2.530086497895272 0.4634655834689121 +-1.826206224436753 2.99076775001226 -0.1080180705244138 +-1.837313356761486 3.357126768603893 0.1588776415823838 +-1.834055017446344 3.293771915103449 0.03544437137387087 +-1.82544219 2.29608512 0.0586929023 +-1.819228761439372 1.624880422650313 0.1624144290903624 +-1.824734352626982 3.047695676322533 0.4959191290437782 +-1.818997610181814 3.36760263545235 0.2282163562906041 +-1.820243327041335 0.3069350932536375 -0.5605598932360311 +-1.818120238398937 3.144265019581665 -0.06967498964670767 +-1.81498666238651 3.24624272723007 -0.01834221507146603 +-1.811615997413409 3.351566355815723 0.2937986472479314 +-1.808860529810749 1.621153778194391 0.3309206902219742 +-1.8087814288467 1.509667461696333 0.5120526118918142 +-1.80167639 1.61359346 0.00082018174 +-1.79992831 0.0502542965 0.432747275 +-1.80393488828106 1.073082384624997 0.8469933453213593 +-1.798774666689105 0.04914253859244882 -0.1310039501771638 +-1.803346611349153 3.217344032604907 0.438353136488906 +-1.786813375548881 1.705189489161071 0.17412076971131 +-1.7844733 2.06246471 0.204768136 +-1.781789832747276 1.4031427600928 0.662355156488462 +-1.78119838 3.32387471 0.361968726 +-1.784272296331781 1.235676503249804 -0.5037242733579105 +-1.785179544654562 1.507949705173573 -0.2361641659967343 +-1.77695084 2.61466479 -0.143498167 +-1.77232206 2.34004521 -0.0699586943 +-1.77175999 2.86287475 -0.157028079 +-1.765823786150624 2.605616185118678 0.5585075898082267 +-1.765516972564937 3.255977676160992 -0.03226579757611892 +-1.77186949643874 1.698410061798002 0.04111295293366696 +-1.770919988500568 1.714309888674948 0.3373884474588345 +-1.760048142865088 3.02314933792759 -0.1297958108794711 +-1.768209201975451 3.176408346479713 -0.07505057421500884 +-1.762317648850245 3.306459646174559 0.01269057659431311 +-1.76416492 1.79423428 0.198919013 +-1.76202226 2.30726433 0.478061199 +-1.768139307754138 2.098673462339955 0.3548977797119753 +-1.76033294 2.07557464 0.0530244969 +-1.763165977892388 2.912728805695026 0.5504678264526834 +-1.75830841 3.34952426 0.06592115010000001 +-1.75401366 1.90261447 0.205965027 +-1.754053123867293 1.616968047333637 0.5147435099790864 +-1.666943423069785 0.6641844079916097 1.126113125256682 +-1.74812829 3.38075423 0.135979906 +-1.74418509 1.79247415 0.040505778 +-1.744304892725039 1.809753914100463 0.3441388667436914 +-1.743630466571437 3.390004435345114 0.2115538513994096 +-1.732284486325839 3.120468210723044 0.4995649863915522 +-1.735079186833828 3.376660363952987 0.2871957297574133 +-1.73403955 0.658417344 -0.756616533 +-1.729021594277746 3.34695159489717 0.3427345021939539 +-1.73339403 1.91695464 0.359492004 +-1.73304403 1.9118042 0.0521779731 +-1.724223901728245 1.63296171887378 -0.2139801564041342 +-1.72365733561198 1.276406189912128 0.817462484979501 +-1.734198783144669 3.271837079102594 0.4163857082875478 +-1.709885480835182 3.212928717275562 -0.06135337990856081 +-1.71944702 1.52546275 0.6603656409999999 +-1.71906948 0.846693516 -0.755853534 +-1.705511019179138 1.397596961438224 -0.499686821287218 +1.30507021353091 1.337103843097178 -0.2983441031568932 +-1.71287942 0.477492869 -0.750767112 +-1.713240377510141 1.732526463281372 0.5044959670983655 +-1.712912590364138 3.081346912630091 -0.1224483807123782 +-1.708272286402024 0.1740660258747694 -0.5264848771886097 +-1.7017628 2.11483431 0.49474287 +-1.69998538 1.73760402 -0.155116796 +-1.698480417365708 2.116689256266395 -0.08729465007485385 +-1.701030575065008 2.925801811018702 -0.1707104900971897 +-1.691248748138998 2.407928029304216 0.5858104562425203 +-1.693767158674113 2.689388980458457 -0.2023979366144235 +-1.690984425091191 3.271178958531965 -0.01694438193677933 +-1.628158925 0.1475151925000001 0.8782138525000001 +-1.67723716167248 2.735757344777535 0.6010789633767163 +-1.680536196185042 1.844307047865313 0.5091097373197223 +-1.625944375 0.2909855395 1.07507014 +-1.686326872938787 1.847273297510883 -0.1027934812764387 +-1.67799842 0.0538077466 -0.314404786 +-1.682800845115221 1.051672161922178 -0.7328839176523742 +-1.67342646965447 3.309103351575612 0.3749847559895783 +-1.67337382 1.95517385 0.504033744 +-1.67305374 1.95331419 -0.097137481 +-1.66823983 2.99615407 0.5493204 +-1.66767597 1.65407336 0.64819324 +-1.660714744201698 3.310809756777418 0.03259851918995012 +-1.643131495 1.607942995 -0.4111744465 +-1.637716719535825 1.475400699220012 0.7964898024670592 +-1.66116905 3.18704391 0.466493458 +-1.636876099152775 0.06223508226842737 0.6288733501458892 +-1.579519706769095 1.175068569929105 1.004448775717558 +-1.659858232678829 3.128965767212253 -0.1024475383670137 +-1.651211053023216 3.357242386262917 0.1167910069833802 +-1.644406808819699 3.35079376164955 0.2970206374228531 +-1.650288555663856 0.3102802203945798 -0.7264531555533797 +-1.64577806 3.3742733 0.206657752 +-1.632046277769037 2.965645207079032 -0.1649613291101235 +-1.63179647849582 1.772664234423045 0.6341015416612047 +-1.62101269 2.20792389 0.612263858 +-1.622816716714053 1.234332819922014 -0.714434069273612 +-1.612124536988655 3.195187726299232 -0.05083309289145554 +-1.61076248 2.20759439 -0.207131669 +-1.60921025 2.77210402 -0.219497234 +-1.60480154 2.5589745 0.638945997 +-1.60132122 2.51073432 -0.242855355 +-1.596848222584662 3.251112478638896 0.3928279755422456 +-1.585978206486537 1.905981253471383 0.6469126545199175 +-1.58915496 1.79006374 -0.331787765 +-1.592094024130082 3.028290952609655 -0.136124966499528 +-1.58238828 -0.0099619329 0.0593561493 +-1.58203948 3.08071399 0.503109455 +-1.57931828 -0.00763000129 0.231948256 +-1.57692373 2.04176378 0.635295749 +-1.572272575981628 3.241882380805644 0.01277613032177418 +-1.4994843 0.6431613265 -1.020037054 +-1.57255411 1.90740383 -0.282563865 +-1.56909347 2.03609443 -0.237249896 +-1.56265771 1.40110195 -0.685541093 +-1.557561370622483 3.291351535084812 0.3063463503164157 +-1.564193377307171 1.654488027919327 0.7835843774894733 +-1.565547321331103 0.4855324676207664 -0.9162320137313099 +-1.571379892050445 0.8502688807450959 -0.9165674323965465 +-1.55414891 3.29368329 0.101004802 +-1.549856273595204 2.823067245065426 -0.2060220961385998 +-1.54590869 3.31452346 0.204805717 +-1.518608327826977 0.07371393245341125 -0.5006292052154719 +-1.54362917 0.180623174 -0.693501472 +-1.544321016933915 -0.003246246181542406 -0.1123381251011178 +-1.54801415383617 0.006109246995360819 0.4037453205074611 +-1.5423662978035 3.089416750645754 -0.08599742603407014 +-1.52607238 2.39874339 0.673690677 +-1.49341823957168 1.461713773379962 0.942531756315956 +-1.523918962131337 2.631100783981757 -0.2542976747845137 +-1.500000216779262 1.828800409128798 0.7746871779015772 +-1.522553110651217 3.150743978550315 0.4273934405797573 +-1.506070428186638 1.597404098684609 -0.6072233085328919 +-1.495595012479056 2.897435231581141 -0.1672222076296674 +-1.50403082 2.72541332 0.625254035 +-1.518678974839092 1.026600069609263 -0.9208551695325807 +-1.49383211 2.32927418 -0.294769734 +-1.49185944 0.31279543 -0.904084682 +-1.490418692927594 3.148989375569639 -0.005876699105869299 +-1.500657578407424 0.4838895301316072 1.282147984943028 +-1.48744905 0.658343911 1.29245031 +-1.491109218098998 2.001504763641082 0.7324165195927566 +-1.46826923 3.19808364 0.321379572 +-1.46137917 3.20091367 0.0912077129 +-1.45323300735212 0.00661778991328003 -0.2872394220287642 +-1.45598948 0.161308214 1.05937994 +-1.45551896 0.0167591888 0.5502617359999999 +-1.45391071 2.72141409 -0.231335595 +-1.440854106496422 3.2071311663992 0.2050121406228347 +-1.44875002 2.96631384 -0.111533381 +-1.44751346 2.22581339 0.727129579 +-1.468296715576146 0.8760004692166604 1.236865803299178 +-1.44035947 0.312933534 1.26092005 +-1.433733321701126 1.818264243438944 -0.5151577809230887 +-1.394559779204603 1.124488161530005 1.180974234864695 +-1.43054938 0.0799903199 0.871994436 +-1.42321861 1.21191156 -0.931680858 +-1.414093456613295 1.650650757279012 0.9240202049241552 +-1.433048853713222 2.606494241291861 0.656007795153173 +-1.410656456044996 1.972642718897385 -0.4428454134296245 +-1.41596174 2.48934412 -0.298299879 +-1.4138391 0.0894744173 -0.640032589 +-1.42255961600027 0.4751572074950235 -1.087121672298261 +-1.41322064 2.85978389 0.555750132 +-1.397436427646135 2.79378666197873 -0.1881655426267442 +-1.40431285 2.16192365 -0.36757797 +-1.410208657270986 3.026077489035393 -0.0305299323719795 +-1.39882851516097 0.7907724139336746 -1.112832156024104 +-1.384537910377088 0.1799667413073275 -0.8728237508094404 +-1.374978093181644 1.86938517070085 0.8715129086133004 +-1.359348337044509 1.40654599995331 -0.8833438051148232 +-1.355914340699849 3.075019554538851 0.08148862404444229 +-1.331949178019405 1.457825491351839 1.068316949435224 +-1.35933765597259 2.873136543877648 -0.1152279279676847 +-1.352170297193929 0.3015492639140291 -1.079795289969547 +-1.35214102 2.62173343 -0.268032819 +-1.34858036 2.95464325 0.452612221 +-1.344489564909594 2.050588734350683 0.8365621260325596 +-1.33858943 0.173720464 1.18691993 +-1.344595374389738 0.08560268752398613 0.9781397417122858 +-1.308906381125115 -0.01871486182325695 0.0473517207080054 +-1.382668327391865 -0.01443127416800116 0.2223069586184865 +-1.3294127 2.51709342 0.695966542 +-1.32306671 1.57942212 -0.802220166 +-1.32259119 2.77346301 0.581974745 +-1.342731632329448 0.9991555933158773 -1.099612977411685 +-1.318258094307533 2.939213129361366 -0.02337387302498587 +-1.30480087 2.72584319 -0.211926863 +-1.30333173 2.39012337 -0.361452103 +-1.30270898 -0.0167307165 -0.11723917 +-1.31130038799554 3.016252225343074 0.3296358568669963 +-1.335855914672608 -0.007407972368658962 0.3729625412491209 +-1.287298158073426 2.259586178816179 0.8073049258987044 +-1.29155898 0.6244558690000001 -1.25128961 +-1.321022169812577 0.03531882391605615 0.7704567348779019 +-1.290990241156922 0.4775706333730488 -1.245740427770223 +-1.28525031 2.9859333 0.0794323087 +-1.301123917171267 0.08959229352266782 -0.7683928533771209 +-1.27718008 3.01623321 0.203042299 +-1.27299905 0.0393452607 -0.590324581 +-1.26946068 2.80418301 -0.139239952 +-1.274396037735775 2.886143402240672 0.4693773586366284 +-1.26424909 0.471406758 1.47221005 +-1.2642467 1.70007217 1.01329935 +-1.2638588 0.653560936 1.47825027 +-1.242051235880319 1.27001944049639 1.219083169694746 +-1.276899907144595 0.7734394924961502 -1.240725476982132 +-1.247130782345241 0.003488925059369174 0.5564662143096195 +-1.238146139197122 -0.00545865871689638 -0.3056704176610541 +-1.244090359335393 1.843285812316653 -0.6680489433863872 +-1.2428993 0.320489198 -1.24877954 +-1.2375319 2.73007298 0.609852552 +-1.236490428252575 2.887319659219384 -0.03143445903005128 +-1.226916751224924 2.559674923433871 -0.3227009954128133 +-1.220285887446604 0.2974774466462472 1.422345489118336 +-1.22981036 2.95292258 0.336857945 +-1.211864841585776 2.031955615903058 -0.5764109079860017 +-1.22317874 0.855413139 1.44996035 +-1.22135961 0.144402444 -1.0485698 +-1.21846032 2.94963288 0.08020802589999999 +-1.21757972 0.0847620964 1.1007899 +-1.219555729593213 0.038716382110354 0.9103104772499108 +-1.190821951443828 2.493795546714003 0.7646274289537314 +-1.21232021 2.97361255 0.207220986 +-1.21194244978609 1.8798793595441 0.978973622102886 +-1.19377279 2.18822265 -0.511542976 +-1.19098091 2.69265318 -0.253039122 +-1.137277679996833 1.406936551358065 1.219676846052795 +-1.164463503097459 0.8984291473616439 -1.298853138980011 +-1.18412125 2.86729312 0.481214613 +-1.171436734001807 0.04004641854096344 -0.7179744881644978 +-1.174019586294788 2.788044445103287 -0.1670780654458874 +-1.193499279231821 0.6154437493224676 -1.347651524729488 +-1.176561011751726 1.180408593031335 -1.145052437982808 +-1.169796177688595 2.069307482092395 0.9365912819226809 +-1.169469337757809 0.478058252795652 -1.371028423926329 +-1.16481066 2.94168258 0.346227765 +-1.156103113854668 2.887543020616604 -0.05301945254144426 +-1.154280924621699 2.948922747109485 0.0810074013620031 +-1.15667045 2.96661258 0.21006985 +-1.15494955 0.159982637 1.31791985 +-1.14994979 0.184796274 -1.24824953 +-1.122170424155855 0.01194040765076296 0.7710691447768321 +-1.145816505691313 0.06709719528288852 -0.9289070254825418 +-1.146502218182772 0.7364541519853615 -1.370959928905579 +-1.149484010989767 1.065626142821847 1.402088100472691 +-1.13415921 0.349362671 -1.38073945 +-1.13321769 1.41172171 -1.04825008 +-1.129395095458531 1.544292075852572 1.162416331112299 +-1.144683944353593 0.01266484445570551 -0.4911568536190626 +-1.09893360779736 2.386247132721553 -0.4753162976078755 +-1.130589405923619 0.04616867950139832 1.048365920476592 +-1.108747754585184 2.251160701620916 0.9040888293660909 +-1.1149019 2.74045253 0.653337419 +-1.122802615564413 -0.01059653384936441 0.2708934738608922 +-1.073939068716256 -0.01140066928081754 -0.06570703826681382 +-1.100440002988899 2.885734030294349 0.5074201153047185 +-1.10086095 2.96010256 0.351141721 +-1.09786057 2.98308277 0.207699776 +-1.09717691 1.59391201 -0.951360166 +-1.088867683480813 2.973411818692583 0.06785674043899174 +-1.07196336081414 2.92499589678807 -0.07105682992036935 +-1.061422025696957 1.721380551765487 1.127370882934372 +-1.050528775451596 2.552381912436374 -0.4139585156728054 +-1.003129829674966 2.460417039354714 0.8720057891241464 +-1.077304859759328 0.2317827304817424 -1.379680434211044 +-1.07079959 0.0733452216 1.19654977 +-1.0415245819312 0.0231256177607903 -0.6701662320289591 +-1.080514064566867 2.815968902062205 -0.2020323298545754 +-1.06642973 0.0168430004 0.964655876 +-1.025091849228415 0.0008375389677219194 0.6470571522942342 +-1.025408143789468 -0.002672592995674874 -0.289931583143976 +-1.05103827 0.617602587 -1.46802938 +-1.05076075 2.71829224 -0.306444049 +-1.04895878 1.03371131 -1.31436968 +-1.033990408609718 0.5001739108201391 -1.484012363459036 +-1.030776369207832 0.7168687377637135 -1.465478683359765 +-1.04061806 1.29777133 1.33757055 +-1.03491473 1.89887238 -0.764123559 +-1.021434297664781 3.039823845073437 0.2061894768137548 +-1.03335083 3.01254249 0.33885482 +-1.031546236639663 0.6546947581996297 1.626877040479172 +-1.01994169435833 1.899373674469719 1.080227796594735 +-1.030741308722487 0.4589150490167011 1.612603025420166 +-1.038861779547535 0.05935823369813985 -1.104611193387706 +-1.02501845 0.8044949769999999 -1.44619966 +-1.0189778735321 3.028406835789299 0.07803431537357206 +-1.003539836106329 2.988066343455718 0.4720221806325947 +-1.012537944704828 0.3696578328975185 -1.485561143039685 +-0.9712670341986653 0.01191166382491893 -0.4916738485209645 +-1.013625250241578 0.09427586190940655 -1.274021798852737 +-1.01208389 2.05054235 -0.69027257 +-1.001459213730735 0.02942137645861031 1.095916478994419 +-1.00594926 0.286482632 1.54491985 +-1.00220859 0.850132763 1.59910047 +-0.9710531654565172 2.684399685327808 0.7793622209733442 +-0.9855297659112408 2.999786661355802 -0.06783493077831661 +-0.9765333695399752 2.925952464069667 0.5925181054311187 +-0.992979825 0.0251170602 -0.984170854 +-0.986358166 0.270792812 -1.47844911 +-0.9855164946562119 2.117287257742532 1.014147417737886 +-0.9562182395438436 1.414239410515651 1.320612408324445 +-0.9814369231176803 0.1474746502577709 -1.394912191937877 +-0.9682942335691008 2.244040107961442 -0.6151642993994697 +-0.9987459465232185 0.9273705060714873 -1.401276955781161 +-1.773703589355068 0.4208412796433448 0.3919616641356512 +-0.9399953826074033 3.125139784058756 0.1739610711636863 +-0.935074061 3.122747185 0.315755159 +-0.956593335 0.145349577 1.4228195 +-0.8792876746744986 3.17606616377768 0.08200129252678884 +-0.9444870660983373 2.905226655069355 -0.2228874501333187 +-0.95903507884858 0.0147178177931614 -0.8510292407616784 +-0.8628987654945299 3.153937394705728 0.4279761524865341 +-0.9274599850102867 0.01862017448669039 -0.6498723846218917 +-0.945810497 0.19967173 -1.4706893 +-0.8867928798983475 2.301890972329184 0.9862586769826484 +-0.9263157842231851 0.8509287167799269 -1.479837605742934 +-0.891978659321303 2.40955288986976 -0.5678631593333323 +-0.9197242656476323 0.7497723164947987 -1.519930847795556 +-0.930365503 1.05049109 1.54772079 +-0.9367150989717036 0.6497252707941716 -1.534347346511259 +-0.882299525554581 3.10762435229324 -0.04859441181386814 +-0.9128333065957035 0.5220346240993884 -1.558955766353187 +-0.9219447931578018 1.567920982667045 1.264182191762136 +-0.8722093152491978 3.070889547688522 0.5375900603449622 +-0.9066141178345511 2.840772207987582 0.7214273480612525 +-0.8852588035977894 0.3971816051014201 -1.565301648535923 +-0.9216650628492654 0.06516170835755247 1.27491893182547 +-0.8983750345 -0.00150969316 0.257842235 +-0.8156748642052015 0.008515212585703662 -0.2368493747216862 +-0.8729825198765213 2.641252046068044 -0.4534077996609349 +-0.8683753105917159 0.2885824510930012 -1.548348012958587 +-0.878416538 1.25341117 -1.27542984 +-0.8360331066784591 0.001109372960415929 0.5493116373260202 +-0.8502148461386284 1.440983861033653 -1.176364545823967 +-0.8606833154970766 2.800754778698003 -0.3636766977506623 +-0.864717424 3.01956201 -0.181108817 +-0.8624567990000001 0.0547911227 -1.31548929 +-0.8417002216606868 0.01660048399282481 1.133988157980736 +-0.858710706 0.115865342 -1.43240917 +-0.8572841879999999 1.71291184 1.23294985 +-0.8503849210880631 0.1948060648964529 -1.511719834794914 +-0.8583715581293634 0.02588400386649059 -1.185587406251225 +-0.840907292192129 2.572655652493423 0.8961230470004644 +-0.844365716 1.6099714 -1.06693006 +-0.842991948 3.24028206 0.194903523 +-0.839326203 3.23413205 0.299182504 +-0.7900780409345842 0.8535064267522156 -1.103976092744313 +-0.8277483107790413 0.009969681572115925 -1.047756581469145 +-0.834030926 -0.000384011335 1.01072001 +-0.8218981499450717 2.994761033700036 0.6580541272264688 +-0.6971537245694722 0.02400306109539873 -0.4984590068422667 +-0.8233335726416591 0.6515282502418935 1.702645283847713 +-0.8191770704565192 1.775743573750869 -0.9516896215645674 +-0.8326403329613012 1.038045322915299 -1.4223750454599 +-0.816230476 0.847396493 1.67306077 +-0.8161915339653415 0.4719235415844916 1.693623825625801 +-0.7975587819224703 1.984868070798095 1.148342575645473 +-0.8199949591265975 0.01076845096449563 -0.9110182661227146 +-0.7504822870512161 0.02057557394012499 -0.7130395594482928 +-0.804146409 0.859132707 -1.52965975 +-0.7927781201472954 0.9922917879262515 1.63156707161528 +-0.800410569 1.91576159 -0.861163318 +-0.8107740022454891 0.7450564550716299 -1.569637624804653 +-0.796695754843172 0.6485896037421541 -1.601081515378817 +-0.7928905912762083 0.2927245527426148 1.624152625420792 +-0.7642430510136458 3.169914751944902 -0.09587305755689521 +-0.7831556650777141 3.232897172718116 0.01062608997955881 +-0.7885462640000001 0.526927352 -1.61777914 +-0.7634219382789841 3.315997948569359 0.1937960509515584 +-0.777601242 2.80911136 0.812410057 +-0.7742675330675814 3.193601379974021 0.4901801413805401 +-0.7719188699990559 2.109119236353469 -0.7676601523254909 +-0.7735998584962693 3.298020782051533 0.2867087100706293 +-0.7563783484708013 0.4157044076881147 -1.62019135550046 +-0.7692248820000001 3.09204125 0.6072942019999999 +-0.782184732473781 3.280026447042465 0.1000232117240032 +-0.7591307798796333 2.954126346069147 -0.3064495132458349 +-0.761308432 0.148206338 1.49535966 +-0.7723540859792967 3.262276054255743 0.3837463504708248 +-0.7359509750811966 0.3015810737992323 -1.596940531299953 +-0.730935395 2.3343066 -0.6724250615 +-0.7553637615271204 1.219427956439693 1.51405430886019 +-0.6826785109114673 2.339794490540382 1.045936310310233 +-0.731064498 0.199053109 -1.54863906 +-0.725936532 0.060172148 1.33959961 +-0.7213165221093887 2.958818772658528 0.7408804752483434 +-0.7282355263993736 0.1128109287833653 -1.468244743723303 +-0.7125296 3.35660172 0.197345927 +-0.6018283507480241 0.0211853243197318 -0.02789056285223238 +-0.707419753 3.34827161 0.289285898 +-0.7026281478198145 3.088060955158881 -0.2213356548600441 +-0.705758989 0.0455939174 -1.35304928 +-0.704628587 3.34696174 0.108581953 +-0.51236704444088 0.01769281130021485 0.4019585046136593 +-0.6955956667706076 1.4132600170658 1.429445770791707 +-0.6945839611251359 0.0191405553952526 1.19859861020742 +-0.6963394897129666 3.328403238652882 0.3648854469853154 +-0.690784991 0.0177393164 -1.21616948 +-0.6976717477670935 3.320607631897948 0.03839509414463792 +-0.6891388400446615 2.567999662125273 -0.5704180145971052 +-1.775159697541515 0.7066231797739592 0.2656185511497698 +-0.664062267387743 -0.000727956153279679 1.052709073735046 +-0.6781082065752694 3.07214879676656 0.6731848128332151 +-0.67306298 0.0120076397 -1.07630956 +-0.6907104891773926 3.28877335271729 0.442492337092867 +-0.671609879 -0.0057731336 0.89543885 +-0.670009553 3.30321121 -0.0167051814 +-0.6488495287591718 3.232761090613994 -0.1060178852657331 +-0.6446468980789892 2.572232525744486 0.9636723772992168 +-0.6564580800000001 0.761751533 -1.6129595 +-0.6710361266719476 0.6496496394323461 -1.639561618665011 +-0.655924737 2.77879119 -0.467441618 +-0.6684742329402791 3.256488731888304 0.5041906564051009 +-0.6580696545700704 0.8668432419692744 -1.56844032208801 +-0.6539776888642512 0.539991530432153 -1.656458497634924 +-0.645871878 1.56801105 1.37231016 +-0.6338918930725783 1.062792175276405 1.625188194181682 +-0.630287558 3.196631435 0.5821006 +-0.63226825 1.049514355 -1.4782297 +-0.638112485 3.39789081 0.195633128 +-0.6500046552629344 0.4263265850317864 -1.648409825844637 +-0.631435849014415 3.386415561324001 0.1071777440382922 +-0.6242157692270198 3.389471151622342 0.2938903808136082 +-0.626750162569196 3.359438761040337 0.03732550622166694 +-0.6149434874408823 3.36983703202742 0.3632298129245772 +-0.6143851695487973 0.8772805407870762 1.692890439514242 +-0.6101536994139242 3.323150974508707 -0.0246648639062426 +-0.619102359 2.94740081 -0.365367442 +-0.617810607 2.78963065 0.878071308 +-0.617411554 0.67673403 1.73248994 +-0.614502072 0.319487691 -1.62568915 +-0.612244844 3.32773137 0.444132864 +-0.607694924 0.487682015 1.72587001 +-0.5874499026639131 3.288397019776746 0.505108565882839 +-0.5840426769678755 1.797115913425782 1.294659241013348 +-0.5900963612339732 0.3135890062424248 1.662121006363248 +-0.5903042781829725 1.429508369869896 -1.270776026705913 +-0.601251338598267 0.223007479974319 -1.576838533925503 +-0.5810384733227865 3.090168302249435 -0.2604685097088932 +-0.589297771 2.94118094 0.79613626 +-0.575610697 1.61983097 -1.15110993 +-0.568775415 0.165506095 1.53749967 +-0.5723735754576318 3.203728883064474 -0.1621199237534089 +-0.5681937929999999 0.128562361 -1.49809921 +-0.5620788893154031 3.100535326161321 0.6807048012645783 +-0.5382949308255796 1.772147268135616 -1.043395179769082 +-0.5617252160766151 3.4239716704869 0.1930856367055509 +-0.5555634964165267 3.411127621282915 0.1026673101586806 +-0.5628813677045152 3.414149711871096 0.2847486451721825 +-0.5603651163105571 3.372970840925654 0.02032483734622711 +-0.5498182387160467 3.312625786706662 -0.05980011109328159 +-0.5502693684716137 3.388361229234516 0.3708813161761724 +-0.531390814441783 0.0653753358750678 -1.386875798341644 +-0.5622704893220053 1.933471496392636 -0.9246147889400644 +-0.544034719 0.0714215711 1.38042998 +-0.5454178494472717 3.351644084944222 0.4344907757965774 +-0.5452347132543405 3.236335316677637 0.5685905950251456 +-0.5171543824965912 3.307015429576025 0.4980652179586048 +-0.532947898 2.04016066 1.20845926 +-0.529287755 2.08482122 -0.8506891130000001 +-0.525068998 0.0349467359 -1.24743938 +-0.4556068861468039 0.02644384432323012 1.222768863359796 +-0.5190949849187081 0.6591972155594311 -1.658948677293353 +-0.510981441 0.7589301470000001 -1.63516939 +-0.4388869758697624 0.004928943771699879 1.053809577443986 +-0.510476768 2.24854112 -0.7745172380000001 +-0.4997241701672357 0.02963591800176675 -1.071681341962662 +-0.498384108905133 0.558877591488031 -1.670360747746314 +-0.2787042804114854 0.01020849951129713 0.8506898324883587 +-0.4168363676946967 0.04289859317436743 -0.5595014223463041 +-0.5212722383884256 0.03296526217298548 -0.8161214578771577 +-0.496780694 0.441658169 -1.66194916 +-0.494233608 0.859948933 -1.59806967 +-0.48664093 2.42828131 -0.6935161949999999 +-0.4356858755189051 0.3458542209876446 -1.630973478424717 +-0.4532209373783225 2.391304663672172 1.078579729662452 +-0.4780957220311734 3.437885385993471 0.1861871016108979 +-0.470864505 3.42610049 0.10058029 +-0.4762299969000942 3.430031798404683 0.2796483968657199 +-0.4783842957606375 3.389027188145936 0.0212352077918903 +-0.463232958382125 3.404866830829009 0.3561549909655329 +-0.4777093505232273 2.632088051639763 -0.5892222367571159 +-0.4728954574397664 3.322056404583175 -0.06224453808473335 +-0.463080853 3.216125605 -0.1661930384999999 +-0.462087721 3.35365033 0.445881933 +-0.4604602876429321 3.079759312660331 -0.285458159857982 +-0.4517468596802677 3.286190899977762 0.5243723729106643 +-0.4721183473158756 2.942061913333154 -0.3946403800367536 +-0.4213094458351025 1.072654986290156 -1.498596492275525 +-0.4530502531450844 2.806198325520383 -0.491833197066863 +-0.454816669 2.57065082 1.00340939 +-0.45448938 0.248137027 -1.5836494 +-0.4588510126667201 3.203279831045701 0.603631344273551 +-0.462436534315636 3.064760222083546 0.7169255529586005 +-0.439011902 2.92966056 0.818266511 +-0.437149763 2.77412057 0.9148386120000001 +-0.420084685 0.166240856 -1.51193929 +-0.404452533 0.887038887 1.68898034 +-0.40332976 0.699346781 1.72788012 +-0.3676408914556693 1.074633075189534 1.626799095925787 +-0.412462652616163 0.5138329614184349 1.724650690526615 +-0.4034539491514622 0.3394215966397723 1.671738919518801 +-0.387783535741685 3.426732414899199 0.2754185724963616 +-0.3903936673384833 3.435439168151018 0.1887888331721844 +-0.3832291418429451 3.389229860292403 0.3731649097432532 +-0.3829394938513346 3.423421535919934 0.1136760241601025 +-0.384541601 3.38690996 0.0222895537 +-0.3829741348632593 3.33511593066041 0.4565737478360131 +-0.367164054648602 0.1056486722466721 -1.408499200656528 +-0.381282747 3.32819033 -0.0495190136 +-0.3573042704043703 0.646411940708116 -1.664391390875676 +-0.3918222375105761 1.269528729122854 1.545324914004164 +-0.3693721720531793 3.255740083805164 0.5443202690129312 +-0.3887707631668255 0.7252940663572819 -1.649883014496235 +-0.376450688 0.550690711 -1.66958928 +-0.376006573 0.188488826 1.55614972 +-0.3563037664994292 3.166280420391223 -0.2042053839334275 +-0.3778073715544713 3.163293451804058 0.6306217174715356 +-0.1885050533550884 1.631724392166647 -0.5903622449682243 +-0.3450974804170627 1.528279306660758 1.445779506787437 +-0.357673973 0.06721077860000001 -1.27053964 +-0.355894953 0.83568877 -1.61773968 +-0.342530996 0.0525741875 -1.12924981 +-0.3136500150808339 0.03588849486382273 0.1276677636779671 +-0.2630701382925798 0.02019015365919745 0.6005713729468841 +-0.3076001743099364 0.2928486566539452 -1.589168548265425 +-0.3323173345863297 0.04905824011082281 -0.9013337237362203 +-0.2708551887269964 0.04569896112272148 -0.2595261857998235 +-0.3340407236519966 3.069579690207576 0.7051457683710809 +-0.2948806240945234 3.33880427330004 0.4138388560666508 +-0.3163935351717519 3.375852783104939 0.3644807032231522 +-0.31115669 3.40797997 0.277542233 +-0.3042353181936869 3.413485465713243 0.1973214896425761 +-0.309396625 3.40324974 0.109449305 +-0.309356689 3.37029958 0.0368492566 +-0.3159962773204115 3.293502418415743 0.4874643247490594 +-0.3020929247519231 3.273472327848173 -0.07974851133633878 +-0.300576717 1.44354057 -1.31308973 +-0.2790391231843946 1.915245278781876 1.299005569204936 +-0.2936120911783247 3.193228317542703 0.584472031480232 +-0.2990514345799548 2.970804690643198 -0.3728657498341653 +-0.282563774356829 1.638526119505314 -1.191679934522094 +-0.2933239231889735 2.925462400638839 0.8160710700750277 +-0.3134969837819377 0.1980582983374801 -1.514743440763849 +-0.271776646 1.93635046 -0.97848767 +-0.2456563472289366 2.119194207360651 -0.8766135612558754 +-0.248892540735439 3.148909247742674 -0.1928464352785741 +-0.217821792 0.8263130784999999 -1.621659695 +-0.1574274205142014 0.7326559612978993 -1.64541409457883 +-0.235213546659367 2.263728581480906 -0.8028293325203032 +-0.2171192080915498 0.6337096094670627 -1.660824481348868 +-0.255183429 2.21155047 1.17617977 +-0.1434767982957592 0.542851403543393 -1.657137432878701 +-0.240837902 3.258269785 0.4921684414999999 +-0.204657916985472 3.314806066808542 0.04662344325664115 +-0.2503061143437195 3.345655779192885 0.3689278091758298 +-0.2180368016179506 3.288202363543237 -0.006736897785741192 +-0.2645916388932106 2.450208494635906 -0.7069161842051126 +-0.2350600937791054 3.364098420516763 0.1080441012333951 +-0.2404103917625286 3.377416102194096 0.2729267156298724 +-0.24176462 2.39681005 1.09690976 +-0.2315507119288268 3.378510133016695 0.199395433887935 +-0.239887699 2.79748988 -0.504088998 +-0.236798361 2.61354041 -0.6189659239999999 +-0.2418740905066701 2.772712549753665 0.9142643220801363 +-0.234780863 2.55743027 1.02308977 +-0.2037975938336357 3.223501176382865 -0.07930372276430871 +-0.2203786199713134 3.082778708016162 0.6676065612680548 +-0.1950035950179218 3.068806271077898 -0.2594805605204024 +-0.210908875 0.151823357 -1.43026948 +-0.203558192 3.29956937 0.408082068 +-0.2209855040289609 0.5377623517876878 1.710938757092763 +-0.1897640854403546 0.7185544517410591 1.708232385610135 +-0.2085108437402861 0.3713125150998035 1.67174059858619 +-0.1671851933345029 0.9184375920313544 1.67389710245354 +-0.192573056 3.32473993 0.344477177 +-0.1664509325000001 3.316709995 0.109489191 +-0.1730033325831476 0.2093535050578705 1.558506906363339 +-0.1829224568921412 3.341770165776733 0.2688231511089319 +-0.1449248598720939 0.1038898112593492 -1.284395951939968 +-0.178388044956802 3.343325881775576 0.1942161380200302 +-0.177087769 0.104521714 1.41022992 +-0.1469796855959169 0.07599443761578818 -1.140109028071973 +-0.2078305637693906 1.042790559912065 -1.527187852266725 +-0.168631896 0.0453216471 1.24489009 +-0.165206626 0.269040287 -1.55159938 +-0.1652692962434453 0.06236218033180128 -0.9388343908023528 +-0.09759078498666644 0.02276038642329558 1.083431045990104 +-0.03428974856690598 0.04186831655965115 0.2045330981422342 +-0.179583556128298 0.0554657077454776 -0.6356370652398089 +-0.1698627887547323 1.091344818454528 1.624539567278248 +-0.04164113402487554 0.04780394602841958 -0.06298774129132605 +-0.1444573850946767 3.097265211030793 0.6221597722660769 +-0.08695704941249921 3.227241907322346 0.3533068375779365 +-0.1363319270373618 3.131703164227427 -0.1535908778753631 +-0.140380904 2.95092988 0.773866892 +-0.1245879315674483 2.960319580435983 -0.3529260427135146 +-0.134417579 0.353928328 -1.60081983 +-0.1172784579198565 3.284000708681373 0.2662722532222657 +-0.1097347250999999 3.28142953 0.1807546835 +-0.127649546 0.448479384 -1.63837993 +-0.1006522924227635 3.215126678222535 0.02014812276028818 +-0.1244588410795249 3.163064382758837 0.5255029074430171 +-0.112793780851828 3.175641085772314 -0.06876907162150339 +-0.08634076037193848 3.019472962229294 0.6884201530269831 +-0.09490713478966785 3.198223586221441 0.4305710557901121 +-0.08488888104978203 3.041060385661621 -0.2525686786133879 +-0.05095205648528202 3.212761800735774 0.1639000890354681 +-0.0431018211 3.08463955 -0.164509758 +-0.04126104422202899 3.072956440223628 0.5936039874016744 +-0.0221675392 3.12301898 -0.058249224 +-0.03112793677566321 3.1337527473604 0.4689486566665326 +0.01012210147977251 0.8896846186007132 1.676525317530182 +-0.0005105873188484822 1.027497597851474 1.643074127346378 +-0.0165020376 0.730005383 1.70239007 +0.01075024019503023 1.533081828246119 1.461641650658166 +-0.007715638427488959 0.5559870526935065 1.706685270949426 +-0.02893440222475864 1.266401851236782 1.562745866261126 +-0.0122832237 0.38269043 1.67153001 +-0.02161387658956779 3.157298409602657 0.3771664655151809 +-0.02029332629198233 3.157284330117807 0.05355575929236308 +-0.005480414019999991 1.93182981 1.302580235 +-0.00673314324 3.160779 0.271875232 +-0.01117789472182495 3.16221982401044 0.1504962218050341 +-0.00458316272 0.222694471 1.56517005 +0.01896304278594574 0.5415336243744179 -1.657707313041806 +0.0002262184946531351 0.6415032092821321 -1.658004471101264 +-0.00160579477 0.440592378 -1.63296986 +-0.000954393938 0.760503531 -1.63847947 +-0.000902170897 0.335926354 -1.58204985 +0.000586501497 0.212468222 -1.47913969 +0.002783505783322615 2.122905358975108 1.219826583549319 +-0.02276455543459647 2.441733768967978 -0.7116689092442503 +0.02093919920177751 2.253137999010498 -0.8136083859962628 +0.00139732403 0.900872409 -1.59262943 +0.006943125027724137 2.331438803628783 1.125674964238458 +0.00333804986 0.124413267 -1.30553997 +0.00371576892 0.113689557 1.4146899 +0.05111047140618147 2.549964307568521 1.011352779015582 +-0.001775108165369195 2.638066966455867 -0.587935646803322 +-0.004769759092047136 2.090204496792727 -0.9032424493902851 +0.005455532761220599 2.77456833977383 0.8821785015480397 +0.00599939702 0.08649378269999999 -1.1532501 +0.00879917666 0.07078367469999999 -1.00698996 +0.008918494920000001 1.19929028 -1.45189977 +0.00913687702 0.0526380353 1.24898994 +0.0229601638861513 1.897902613659798 -1.022428877560797 +0.009263705383111127 0.06082347668679034 -0.7536324131413905 +0.02519637905095226 2.819934467562037 -0.4493178831229433 +0.01006221319149384 1.411569687763033 -1.339442417707398 +0.02515367970488692 0.02051453191042089 0.9248966846763502 +0.0161342410477297 2.922654685087569 0.7425123897891169 +0.03036160471119346 1.617732811346904 -1.214927675143557 +0.0168651957 0.0224814545 0.768691957 +0.02972395505012977 0.03429385033392825 0.4704195769948908 +-0.01947501072095634 0.05387657105642654 -0.3999778449095833 +0.01896519699450179 2.961588945845371 -0.2972683923898842 +0.03257050619779026 3.016403359701038 0.6308889305640125 +0.0268209968 3.03067923 -0.186478674 +0.03210785540676261 3.07830221588758 -0.07903505170276059 +0.03377025221195253 3.078838405221759 0.5142044088375848 +0.03552548147726792 3.10571867282397 0.0291801409873791 +0.03802151910408948 3.124924251995159 0.1508957431562975 +0.03223663679997998 3.119791306526693 0.3941979666466082 +0.0397423323440906 3.129543960549908 0.2941882817692636 +0.09219643412135478 3.129800589714875 0.1876763648758289 +0.09749857566411396 3.131216796518888 0.2900282044267307 +0.08502246192030913 3.11767924925371 0.09303868865346349 +0.09421985354393696 3.118608883211947 0.3815226874806637 +0.09960749000000001 3.09025908 0.479836315 +0.09929582667649497 3.095145810871746 -0.0127813249477203 +0.1069091614256727 3.046135079537474 0.5780704190950523 +0.1246394263754075 3.049035619763404 -0.1437312319885909 +0.1622868079203803 1.105162136915812 1.619277842683308 +0.3257659425170876 0.5332826609042546 -1.679776449475898 +0.1852100495 0.4378137885 -1.648614705 +0.1390855379743174 2.980337153864312 0.6832241683999009 +0.190549798 0.6364078225000001 -1.671774625 +0.1563569148053456 0.3561208973816103 -1.609610162725833 +0.1514116040247449 2.994321621724737 -0.2409511038965949 +0.1188840914072754 0.7174763640918462 -1.653732679438067 +0.1632284211928835 3.15343314026375 0.1809805390269838 +0.2074782026678794 3.170199684876693 0.2624162174788262 +0.1823670669171928 3.147141620066103 0.3465920434090002 +0.164469428194797 3.142844758347071 0.1064744164815527 +0.1739897834225042 0.9315358355543889 1.670464140388736 +0.165011302 0.261784196 -1.54990995 +0.2013280933321976 3.12491778481509 0.433794680078979 +0.1623361759461782 0.7487196995166031 1.708716283634035 +0.1906276233239931 3.13032860726634 0.01655843517949057 +0.170455039 0.557827115 1.71772027 +0.171917602 0.380176216 1.67780995 +0.175131798 2.89711928 0.7786154749999999 +1.370252432991122 1.195317034272076 -0.0615987667937886 +0.179731295 0.219680294 1.56867003 +0.180787966 0.0641053692 -1.00778008 +0.2086263860686823 0.05278483524995991 -0.6379624111350906 +0.182831988 0.0762045309 -1.15018022 +0.2130069432352049 3.084203045375654 0.5248481620219881 +0.185786113 0.111141421 1.41339993 +0.186593994 0.0269693024 1.0837301 +0.1829224029094169 0.05422625018907478 1.253930593232206 +0.187503323 3.08699918 -0.0891926438 +0.3022302707837621 0.02012608984066509 0.8615842540611701 +0.1818489527390529 2.913317389487456 -0.3425391585693121 +0.1575808247971305 0.102632717423193 -1.275306868703483 +0.2901235014028515 0.03466863615011999 0.3290980554362712 +0.204849917683827 0.04763617440096948 -0.2612840707854921 +0.2480455078087717 3.187762450817428 0.1742091779710387 +0.2457458648455352 0.04157765261149234 0.04708772141905978 +0.213494092 0.152355134 -1.42881 +0.2230981820388774 3.033970789500655 0.6084806316895456 +0.2635379785061679 3.077094354925812 -0.1396010109613841 +0.2171180073415157 2.566809059742721 -0.6197342533256451 +0.3695762252105548 0.3410156311875635 -1.631603397316511 +0.246390477 2.43349862 1.062805475 +0.3179989033494179 0.2693740515947253 -1.583658076995321 +0.247992709 2.39256907 -0.7218902109999999 +0.248561725 2.70632863 0.921154797 +0.256342798 2.73039842 -0.507407308 +0.2753903480801965 0.7065342315912507 -1.666070141570509 +0.2454126585864811 2.206347773381907 1.166834483288735 +0.2226660887720655 0.7940045726544728 -1.638716333760651 +0.2894739279035968 3.186850910857246 0.3334583839305656 +0.2809072119359611 1.947917398377274 1.275415894334075 +0.2880728080648096 2.97533520184776 0.6910009135002735 +0.2553175474186931 2.113572413594216 -0.8730386639414034 +0.3164170577391018 1.666217388754994 1.390109441659376 +0.2887219333503253 0.2008928026695898 -1.516252471857153 +0.2971867602464819 3.012750148909796 -0.2342924242662668 +0.2303575231141839 2.799440261877785 0.02726287109316283 +0.2783705300538197 1.887932631035918 -1.006922318753081 +0.3088013806276859 2.848708693834479 0.8190205892925609 +0.3074767836304351 3.207485565873614 0.2548453477724062 +0.3227173714801132 3.214641049980205 0.17925093488981 +0.3060104851962857 1.624039613896341 -1.18094915482823 +0.301676676592492 3.202160623580355 0.1181443150667335 +0.3459780111949196 3.183886360518723 0.3865381045876732 +0.324631721 3.18745816 0.03395833355000007 +0.3413268925 3.1548332 0.447417945 +0.3341804093908431 1.386949019473146 -1.322379853665627 +0.3095304348707613 2.868457209629056 -0.37689495593106 +0.3971215143316656 1.104464070175035 -1.471883426558144 +0.3575384332550738 1.305515594802257 1.537994506289271 +0.3828935662378225 0.04330594481298139 -0.9429666163071816 +0.3687407208764118 3.110612326865896 -0.1079921443010054 +0.353748888 0.0540738888 -1.14153993 +0.47899724983312 0.0343463382310114 -0.677782569350593 +0.357970327 0.819277883 -1.62804925 +0.362652212 3.17762828 -0.0038773499 +0.3430617135534115 0.07066104834303689 -1.261168800373806 +0.364254951 0.0437433682 1.23775995 +0.3668461287286542 1.06733661557586 1.637046494008839 +0.3881853001652723 0.9018687600322838 1.691810144363051 +0.3670212897869751 0.3567494166252954 1.684731107853582 +0.371161683406683 2.954088717949726 0.718239221126177 +0.373481601 0.714093626 1.73736989 +0.3663195192373955 3.205596989807045 0.06984407630873385 +0.374265254 0.204507992 1.57147002 +0.375041217 0.534209669 1.7385 +0.4968484426951197 0.03107588455658134 -0.4159840600342604 +0.3753323658450698 3.21202151595054 0.3174517994059277 +0.3936792914601431 0.7224250791916612 -1.661560992226843 +0.3807285033762426 3.222573922578637 0.1398350168708671 +0.3803191375582509 3.224453969032496 0.2513269226193026 +0.3862892528452047 3.227889368874079 0.1893949779082519 +0.3642689301723092 0.6155850329466291 -1.680940170793392 +0.3588759089069329 0.1081777783811833 -1.401713753993522 +0.3882200359832648 2.950679595141815 -0.2910827969014071 +0.411617815 3.14688826 0.476002455 +0.418520063 3.16932797 -0.0201035459 +0.419569254 0.15983364 -1.50879979 +0.419855356 3.0297277 0.633609474 +0.4168705350350654 3.187976283823048 0.3987706618314357 +0.4204240311542253 3.030476833977046 -0.2034785295469849 +0.4206627145679022 3.202477272572594 0.05302233289256966 +0.4412459220430627 3.214007107816844 0.3300940136310313 +0.4413859206846449 3.221783590735951 0.1164986078059882 +0.4439372009152617 3.227780284243811 0.26533900006852 +0.4422116979172052 3.231183669003629 0.1912463025783451 +0.4419167457335998 0.2286995132671788 -1.574417496291793 +0.4477418938644168 2.686919043995106 0.9089201939510699 +0.459280401 2.81306815 0.83450681 +0.4623101859771544 3.106827595130246 -0.103259045703661 +0.4515267322457293 2.686863577844006 -0.5063177104977404 +0.4832695899211946 2.508744458917766 -0.6096913179327984 +0.4775858879843333 2.502801335816802 0.9966635349342466 +0.4804884126566961 3.122738128290318 0.508442176688799 +0.4804552952987558 3.161210811437222 -0.01693212373775499 +0.4791900042821036 2.84046583737243 -0.3747657768812611 +0.487194061 2.32728815 1.07411087 +0.5087776515573892 2.278215278753644 -0.7337207390373658 +0.5071469088146233 2.920432186871675 0.7325509962452098 +0.4973116985581871 3.177269473256854 0.4162293261124611 +0.4506057090338613 0.4177436761386218 -1.668085613041129 +0.498683602 0.837227762 -1.60549951 +0.5014083137812158 3.188897823245401 0.04191106587269646 +0.5010071708159471 3.20230544743112 0.3550619211566354 +0.4876133188174221 0.5147025773164765 -1.683980482968623 +0.5026758284316913 2.942465866905952 -0.2749784697346629 +0.5102407286121438 3.215155245844908 0.1323678739862678 +0.5196883449659233 3.218785822264989 0.2672559146277736 +0.5241948504619141 2.13181135473027 1.146708300482179 +0.56746490425416 0.02357322084312246 -0.887878300616843 +0.5177593740077412 3.222422851560248 0.198433193902769 +0.5320288021881137 0.7162370707312095 -1.652118269240134 +0.514586329 3.01081729 0.643753588 +0.4926979153849958 0.6259963838281516 -1.67826435286462 +0.1906339934303044 0.7335388759191322 0.6296608932097297 +0.601948917 0.008712550624999999 1.060409965 +0.5394144153869571 3.029089215360032 -0.1696439030564204 +0.5116043124184092 0.03997249485108191 -1.268560629582826 +-0.4145402380002112 1.741401077484777 0.3739287842553796 +0.53816402 0.0288846791 1.21952999 +0.5732746495900731 1.840817658930812 1.259797581636939 +0.544930875 0.0646151155 -1.39506984 +0.6003765179912445 0.01639743265599293 0.556842717326131 +0.549208641 3.12040758 0.497551531 +0.5422200379480361 2.066065445349888 -0.8386305900833854 +0.5462635711077394 3.115913622914305 -0.0562953176355919 +0.560400009 0.0768937245 1.37998998 +0.5756402144812047 3.16033285253563 0.4138488760690094 +0.565305173 0.122869134 -1.50296974 +0.5759715449858833 3.163249410256793 0.03845396745747841 +0.5750491328376577 3.183362408560333 0.3617535600393662 +0.575376272 0.184618577 1.55989003 +0.5814405295018078 3.192296320810318 0.1203746719539058 +0.578288972 1.88231874 -0.9363722209999999 +0.5773230151856665 3.200635397506765 0.2904642657936426 +0.5877055180121085 3.20242780685851 0.2088166708437451 +0.5770061957646223 0.3334111480298526 1.679569147291789 +0.588143349 0.203070909 -1.57882929 +0.6345323448475904 1.496542859403344 1.403281955817541 +0.5938173265410802 0.5076753017298958 1.737718483474867 +0.5935343541367717 0.6882604918767428 1.740400834419929 +0.5827374417861955 0.8810453736638093 1.693928584624177 +0.593274280386009 0.2901373831297253 -1.629160975841998 +0.6205352222695363 2.994159875674673 0.6201348479021056 +0.613828972649944 3.060340617678624 0.5452446490074557 +0.6258411158071896 2.910178472321963 0.702959050761552 +0.616602004 1.05653858 1.6272608 +0.6126194757419237 1.57070627626601 -1.136894512142131 +0.620723248 2.79724765 0.804437101 +0.6441332110940502 3.021889337100669 -0.1176504417611862 +0.623522955488089 3.106001803517655 -0.02193686739871656 +0.621997994175276 3.124289502156624 0.4469740858447057 +0.6258958854305721 2.925885450471268 -0.2446837117491901 +-1.475338201953686 0.7189706652535566 0.2821865305723581 +0.6417157903351975 0.3920237388531869 -1.665190159339468 +0.6471719566163394 3.140337655876299 0.06185593865648745 +0.6341077407815268 1.268495252784027 -1.319416044611872 +0.6364923148879249 3.163046209564795 0.3537322442130968 +0.6410280609734011 2.81925411879585 -0.3403825679426006 +0.6499425332840173 2.645341888202833 0.882526294211176 +0.6349234404568175 3.172009855292414 0.1362968555832511 +0.6569412850511673 1.075488743886341 -1.431680962590309 +0.6385758652777404 3.176611417693067 0.288235621240981 +0.6504775512617528 3.175260391715272 0.2174427323492374 +0.6512441673018863 0.49708883650574 -1.676212915075203 +0.658867478 2.67067766 -0.454165787 +0.659292658945936 0.8681271049136877 -1.557756109712492 +0.6712471740127842 0.6169032055702248 -1.662186169264496 +0.6761010779433118 0.7292463722431544 -1.625802879723938 +0.7457187581981727 0.01226963123537284 -0.6454999528470127 +0.6756656909471557 2.453823457337652 0.9641532270619684 +0.7006524205 3.066626785 0.4761345835 +0.68231684 0.00812766142 -1.11278999 +0.7049230929999999 3.074201825 0.004056622484999972 +0.7066460608269577 2.997599146357298 0.5609834113033232 +0.686084986 2.50240731 -0.548596561 +0.7082322133429289 3.093675360919158 0.4182266753304439 +0.7422131465832937 3.078134542254241 0.05693558455084609 +0.707397001694447 0.01209729698157786 -1.252632943115391 +0.6990931276612814 0.02065570626125951 1.196957093851513 +0.690461221726446 3.133438221617006 0.3560796610503132 +0.7053338078443906 3.130697041144899 0.1248372842058151 +0.7013988910157324 0.03772577724928355 -1.384145582110423 +0.7099406798797094 3.139779671349708 0.2680334971786964 +0.710596391840789 3.140944411565025 0.2002270286551716 +0.711497009 1.25530827 1.50255048 +0.714564025 0.0998443291 -1.49389958 +0.7322475892719092 2.275677201008806 1.018325817744453 +-0.7924179846493172 1.338235745911962 0.3400279971053602 +0.7274141263796438 0.1877774598524459 -1.571567908290663 +0.7240196949921256 2.898908107794302 0.6588467936018794 +0.7223307436049778 0.008934421461844071 -0.2417831261597987 +0.737757981 0.0614127479 1.33730006 +0.7716984078225162 3.041584146957224 0.4314002576553282 +0.7459829920905136 2.923000604744625 -0.1655029911566748 +0.7636386881192019 2.993998169772196 0.5161939852884182 +0.80454068129289 2.951707830243691 -0.06642350919204454 +0.7376584786481405 0.2875091999526011 -1.624170498735331 +0.75567925 2.10707784 1.07633126 +0.7715079145606726 3.075890822026793 0.3563644469349572 +0.792090003383522 3.063432586744469 0.13159884864202 +0.762164295 2.78521705 0.743218124 +0.7729888738188051 3.092495922582671 0.2843614518692322 +0.9563571041025383 -0.01530574603451098 0.04513984191304438 +0.7798861600776751 3.086602949881387 0.1930480193178467 +0.7557195304615792 2.23262000787733 -0.6692274563108698 +0.771530211 0.161687106 1.51063001 +0.773500025 0.382454246 -1.64866948 +0.7770227365736209 1.005255045138892 1.611246668731651 +0.782184422 2.79908681 -0.281829774 +1.319896583289526 0.8042056946850199 1.073851773999195 +0.793966353 0.498043299 -1.65306938 +0.8223075498810931 1.934080686063992 1.1195330660827 +0.8024425873047274 0.3087503224425135 1.631858544046112 +0.7251869492880013 0.007602808819500826 -0.934853968030094 +0.803513944 0.851627648 1.66514015 +0.804166794 0.00459253136 1.03806007 +0.8163380315617292 0.6074198428362046 -1.631766145848693 +0.8529850839376842 2.994240811838745 0.3795147231036553 +0.8174232984761823 0.7258509944638756 -1.592293021785343 +0.81380558 2.62659717 0.820684254 +0.7977564577826435 2.906016227107255 0.5899438101280978 +0.8244886784146063 1.974111893694162 -0.7750214426598546 +0.7978973517790436 0.007025662297422295 0.7962601225097459 +0.820681691 0.671039224 1.70072019 +0.818234519625896 0.8284815459144269 -1.53628430970413 +0.821050584 0.483801186 1.69460011 +0.8372019976427869 3.033627423172082 0.2868273278549779 +0.8298180587294048 3.041525045928711 0.1909390972450157 +0.8446419778278643 2.949326146384647 0.4820331721363267 +0.8537593348431736 1.720634816588125 1.206817317178217 +0.8362485788633736 2.634264943866914 -0.3878391607928003 +0.8279188358832171 0.9400925623337738 -1.45876831515849 +0.8479087747856368 0.02121812278757972 1.156059115516211 +0.84459585 -0.00120223186 -1.08585978 +0.855138302 0.174131066 -1.5485394 +0.8735034981768578 1.796210523294564 -0.85730039793313 +0.860900223 0.0962357074 -1.47771966 +0.8932259993985462 2.954670360349822 0.08927016925565245 +0.869993687 0.00441416353 -1.22657979 +0.8729615991435133 0.03534143211845581 -1.372450756270484 +0.882862260075796 2.755678233919015 0.6672354572189103 +0.8802494111639043 2.448792567023908 0.8783972624215548 +0.8616445668440775 0.2632991479221279 -1.591982039364801 +0.880283058 1.05544913 -1.35892928 +0.8896622712958951 2.472144914946955 -0.4652071785817929 +0.9186630229619032 2.824805378503062 0.5515909606190709 +0.8086155208608209 1.338569794266548 0.6802988747060177 +0.8867698543574251 2.907379694652892 -0.02765079035073555 +0.8559741000312499 0.004276912386237277 0.6050610924256234 +0.8891060696680456 2.806317012806944 -0.1847931471446999 +0.9005065369324449 -0.001682697235363238 -0.853710916831492 +0.9206098102430178 1.049219745685232 1.524789146037716 +0.8943504135350917 1.471119647747099 1.315021580836921 +0.9086268964847526 0.05796276402398901 1.267530100830525 +0.905639044273726 1.587769198987596 -0.9889153628943476 +0.9220596822282779 0.3572139612255315 -1.600207228203389 +0.9151760934570716 1.380951463655435 -1.124015748326038 +0.924165368 1.20020938 -1.23552954 +0.9512709694001639 2.873185961599877 0.4251222877953992 +0.9095335153917984 2.255816425528203 0.9439348861789454 +0.93684113 0.483930916 -1.60556924 +0.9399771689999999 2.28534675 -0.5441723469999999 +0.9159811549749738 2.955194764446893 0.2006522379175978 +0.9428560827862313 2.922792172330091 0.3042892741946255 +0.949059904 2.63943624 0.715356529 +0.95026046 0.602141798 -1.58425891 +0.951453388 0.173890784 -1.52434921 +0.8040559266815273 0.7863589489851123 0.570471946076458 +0.9503537727022109 0.7206976401407278 -1.543329219022909 +0.931167818247936 0.81899268409863 -1.497012291596231 +0.9680196639999999 0.0216022711 1.06583011 +0.8986772937105192 -0.005011200903334461 0.3506701901901551 +0.968764305 0.151016891 1.42526984 +0.9388858223058362 -0.009718261984346999 -0.3302378095363828 +0.99016732 2.06541705 0.976934552 +0.9924870730000001 0.120728962 -1.46217966 +1.008055642827967 0.2400778972306767 -1.530722104285333 +0.999080956 0.843752205 1.58100045 +1.00521791 2.6338861 -0.259511352 +1.00937974 0.009768261570000001 0.799697876 +1.03766477 0.003462938765 -0.94024536 +1.01023614 2.08202672 -0.611962497 +0.9942919502063612 0.9150421349373088 -1.399333863434388 +1.005491664924664 1.262517956423384 1.367901633767799 +1.01853061 0.295481205 1.54135025 +1.02116978 -0.0013877399 -0.658229053 +1.036006736657497 2.670397027935329 0.5867158061382797 +1.038838479582087 0.05877912330180024 -1.347334106210611 +1.054873826226535 2.416103855406915 0.7832155146509963 +1.04111159 0.652791679 1.61436045 +1.04537046 0.346120805 -1.54337895 +1.04640102 0.46327877 1.60304987 +1.046042945242931 1.894868941383154 1.017630420053004 +1.05899711424839 2.444644110990569 -0.3680497589413019 +1.045659688724424 2.724843561445939 -0.101611196189444 +1.06006134 0.775828302 -1.46025932 +1.06128967 0.0241686739 -1.19080985 +1.079497607918587 2.70899096364078 0.4678931083938254 +1.085425735403674 -0.005748576306182059 0.5593804858060747 +1.120599985 0.02557221985000002 0.9010151625 +1.07257009 0.06460323179999999 1.17519987 +1.089317863051725 0.460774957120327 -1.525730428226894 +1.07789123 0.699826121 -1.48545921 +1.052638760529164 2.785143983096882 0.05263680414030438 +1.076955929919424 2.76760686712966 0.3219673232171454 +1.123847857470351 1.73402989237692 1.043354736173375 +1.072062319485778 0.5929499956925489 -1.520932826925004 +1.067945681070558 2.791585107241624 0.1943064163231358 +1.089195591504479 1.904138252341143 -0.6504140926468829 +1.142961209069443 -0.01848475591030282 -0.4278171151967238 +1.093208602666502 1.020627853424412 -1.259850863554742 +1.09841037 0.195944861 -1.45775938 +1.11734235 1.57386744 1.1301111 +1.12378156 1.05095768 1.41043019 +1.109098205969851 1.740767711387327 -0.732059397777878 +1.10827416807806 2.238790440672771 -0.4586116386638416 +1.1304611 0.8147215840000001 -1.3870796 +1.096665453911042 2.213020813602765 0.8576451452991234 +1.15199637 2.49787593 0.644438565 +1.146670425495902 2.721554384553137 0.2074511730018394 +1.153455331174395 2.693476673688673 0.348712494006656 +1.15004251796431 2.697904866565588 0.05320404527979422 +1.148526861642604 2.633541718048845 0.4886585318992234 +1.153333401881615 2.645920964393911 -0.07136865667235778 +1.16627272351116 0.007848778067606909 -0.7366697603527883 +1.17596042 0.31300801 -1.45500934 +1.17921007 0.163806945 1.31529987 +1.164692776422301 -0.02354455435894568 0.3615844770300919 +1.18169999 0.0247527938 -0.948991895 +1.18345726 2.39210606 -0.309264302 +1.180577890241009 1.496377602203667 -0.8643863667492293 +1.217321887056035 0.7014128862414387 -1.381424362352601 +1.19816005 0.136309192 -1.32922947 +1.193470831431706 -0.03674810697183716 -0.1660920410118872 +1.211348854700681 0.8653193817396725 1.439144198669955 +1.233755627226544 -0.03754932852548897 0.1213616615682875 +1.209437563934824 0.4495311301524033 -1.446487701608612 +1.224836668451661 1.979275078636333 0.8773925851678608 +1.222700854071084 0.07575743453599948 1.060955656019076 +1.22329748 2.6772356 0.209540471 +1.233029222678831 0.5787747710121709 -1.411958678404613 +1.22609746 2.6592257 0.0777299628 +1.205146965188837 1.986300780329858 -0.5201750365413322 +1.22766733 2.65514565 0.34381339 +1.23220026 0.293874323 1.41564989 +1.2340374 2.59924579 -0.0507394038 +1.222293958678425 1.155236420638433 -1.066616093928727 +1.2377156 2.27479601 0.743511617 +1.23943746 2.49863601 -0.169814497 +1.235573862820467 2.588610888532338 0.4750557431668212 +1.238012367276228 0.8820928807470553 -1.257195862926976 +1.237050527600388 2.203629402064836 -0.3842265499571066 +1.25875910248238 0.6475363107905838 1.476762805879078 +1.250572906148261 0.02261423035191272 0.7536658926316057 +1.26258075 0.459926844 1.47484004 +1.222171564108988 1.241300915676484 1.239045067703646 +1.258242882967903 2.470109244325905 0.600221196376405 +1.27142715 2.3616662 -0.268828511 +1.291945872783122 0.002911589807510056 -0.57113906665989 +1.285454801646799 2.658032568789102 0.1968763001331611 +1.29393756 2.64094567 0.0826911256 +1.29422987 0.088635534 -1.11753976 +1.302888914360119 2.637633206489204 0.3309378820738776 +1.306560686671442 0.2675565477388291 -1.330739933841621 +1.31359744 2.57813573 -0.0397226401 +1.31689382 1.7976464 0.88528043 +1.34658805429319 1.655309880468699 0.9198076928093257 +1.322417477509423 2.571507031223246 0.4533110265235542 +1.32753527 2.07401586 0.785520554 +1.33097064 0.736909807 -1.27004945 +1.344813913397275 0.0389851599100814 -0.7662774290829129 +1.331432026235022 2.302155635526586 0.6849941119986513 +1.33600104 1.02064788 1.2761904 +1.311581720659672 -0.0007161110210106795 0.5748003546651508 +1.333067045668226 2.473971083241755 -0.1574197171170631 +1.33969247 1.51356697 0.9932471510000001 +1.363274380922488 0.06843789713625069 0.9063299717122401 +1.350347018405315 1.955478536726801 -0.4173110624781883 +1.354304051570721 2.458824603910557 0.5729110230279283 +1.36028016 0.165941998 1.16833985 +1.36100662 2.17160583 -0.324377477 +1.36496747 2.65497541 0.201291963 +1.36791015 0.432905436 -1.31749952 +1.37009013 -0.0261877012 -0.374754041 +1.371567173532946 0.5990464703906878 -1.289546642283209 +1.37302756 2.63721609 0.0811310038 +1.37676477 1.75782609 -0.485287428 +1.37798727 2.63611531 0.321772963 +1.399805337122612 1.625375189284805 -0.5334176288066681 +1.376329546760081 2.326665311034253 -0.2511416915366722 +1.39943016 0.9261536 -1.08396959 +1.402284048944228 0.849199697766036 1.304730997070426 +1.40202749 2.5774858 -0.0337690786 +1.402409647706454 1.529529225734301 -0.6107204332850171 +1.40837705 2.57502532 0.437782019 +1.41106987 -0.0225830041 0.394653976 +1.407970907707308 1.253261328426001 1.079347975912478 +1.41658533 2.11011577 0.733831346 +1.417552455238934 2.311554463764747 0.6564422366576405 +1.42600024 0.293805689 1.26635003 +1.43354249 1.41767752 -0.676947057 +1.40773899162989 1.880340155376795 0.7984674000536048 +1.43875694 2.47482562 -0.143659934 +1.44360006 -0.0435331054 -0.183108047 +1.455809253779325 0.6546427795304109 1.321168848981308 +1.50690160705404 0.05316290174258922 0.7198891127620589 +1.44959676 2.47216582 0.5465319749999999 +1.4561801 0.246422395 -1.15495968 +1.465272393291876 0.4635682275805503 1.315312304317715 +1.46279001 -0.0396163277 0.207522973 +1.469712285837915 0.04211707203052102 -0.618366339051259 +0.8735611023942785 0.7664900341277544 0.8740317380309961 +1.47229576 1.9708252 -0.329758406 +1.47753 -0.0479642451 0.0143693704 +1.47898638 2.16995597 -0.283785701 +1.4866699 0.115354352 -0.880354047 +1.49147022 0.762163997 -1.10201967 +1.4976263 2.33913493 -0.225199923 +1.587312534697337 2.608632136021019 -0.02264587278064137 +1.566714765 0.1468448045 0.9488024724999999 +1.51152647 2.33752537 0.626635909 +1.503315717278847 1.909790313684328 0.7362364257451052 +1.523802462703848 1.784903134900141 -0.3415500216565625 +1.50118162518294 1.137064602680133 -0.8141239977946686 +1.528096103727252 1.559355552167721 0.7964177951167706 +1.5232130199447 0.4228755670769617 -1.159874680597248 +1.53238237 1.44693661 0.839723051 +1.53315377 1.6634959 0.7604726550000001 +1.514990551226963 1.020327399398023 1.121818699319965 +1.529405448174977 0.5967150322919162 -1.135847864819742 +1.343181213762913 0.7502640963039406 -0.3331096989509716 +1.552509867692958 1.330989360824435 0.8805904757744694 +1.566552791140541 1.731527703178401 0.7183561964194175 +1.58119559 1.99911523 -0.276910603 +1.088304306445091 1.685773723907835 -0.03635846428431216 +1.552624197085852 2.171474008858735 0.6761068342299575 +1.591560768914826 0.8182257466205796 1.155494560907837 +1.59237504 1.98106503 0.6875919700000001 +1.62211603 1.171972695 0.905278653 +1.604576756629275 2.696518966814657 0.1979507618125264 +1.60342014 0.0094777206 -0.40605998 +1.60579991 0.288741708 1.10493994 +1.570141956136082 2.66899529401289 0.08464378623713652 +1.60624027 0.9425888059999999 -0.854402661 +1.610263952181285 2.674170993445557 0.3125303759119974 +1.60689342 1.52751577 -0.331741542 +1.608145 1.81408525 -0.270033449 +1.556913287521057 2.327302584433925 0.003270914931706178 +1.6134131 1.44796658 -0.377294749 +1.62427425 1.59602582 -0.280511439 +1.615126785699422 1.783973862152598 0.6768595177547049 +1.62824976 0.253559142 -0.939639866 +1.658192246138643 2.619891342595855 0.4135247581097616 +1.609563781482012 0.6345227263717942 1.190026748594005 +1.63986003 0.453460664 1.15779006 +1.64725006 0.116636887 -0.6495360140000001 +1.652272391063539 0.01719333348579434 0.4636852172062301 +1.664707163692641 2.550758051077614 -0.09253497889888655 +1.663470768105635 2.544074186700104 0.4991512915134769 +1.689160780938372 1.220395548911455 -0.4678210089035836 +1.6763705 0.773670852 -0.892074049 +1.680543488280547 1.477208682858485 0.6295543236228821 +1.68070412 1.64181519 -0.208741426 +1.68258512 2.03508472 -0.243149951 +1.678750660604882 1.557209762639525 0.6160082947175092 +1.68711515078011 1.391828998247323 0.6556714068922871 +1.6915859 2.24753499 -0.224935099 +1.700202304501082 2.238800369909262 0.6264532327685932 +1.70331809757748 1.849421608011969 0.6297685952976779 +1.694314641226546 1.878190465061714 -0.2162772677329975 +1.694822907601715 0.4247057576793555 -0.9607232393780293 +1.711849792885741 1.619696739397626 0.5745467597388558 +1.707420334298152 0.9752196485939086 0.9465459352420171 +1.71249032 0.60027653 -0.928403854 +1.71503186 1.30152667 0.667605937 +1.731206298820723 2.443204877279689 -0.1546054370704618 +1.72718608 2.45187449 0.557345569 +1.72992027 -0.0163663775 -0.184511006 +1.747336818452778 1.075439203404111 -0.5245802227468178 +1.73531473 1.69890487 -0.148180485 +1.756299754335294 2.707069853087904 0.2009753237527106 +1.750905656621477 1.699607895168868 0.5511631610557879 +1.74385011 0.274405569 0.95588398 +1.738318644094829 2.692678489824359 0.2904496287214426 +1.74848711 2.69308376 0.101812713 +1.75104034 0.132173091 0.738656938 +1.74567923618444 1.192329776145562 0.7043651617945506 +1.7522701 -0.00955242012 0.233971983 +1.76329267 1.41837585 -0.091881834 +1.76402688 2.65193367 0.381288528 +1.76760697 2.65209365 0.0149033358 +1.763995205754064 1.361090846788906 -0.1238095957269075 +1.77328874489715 1.486885424910943 -0.04324866006639701 +1.77199018 0.792396963 0.987866342 +1.789466209253287 1.943336903073651 0.5927880484799457 +1.784867513901909 1.924697215141943 -0.1717318078864879 +1.78056037 -0.0210998058 0.0324307941 +1.78154528 2.11700439 0.61262852 +1.78251553 2.11517477 -0.207602128 +1.78433192 1.28450692 -0.138849005 +1.789560808697031 1.484294778373979 0.4117987229491226 +1.787170645532214 1.419380645507608 0.4275916285977496 +1.79113388 1.54950511 -0.016276421 +1.816768220729843 1.78198275553542 0.5164514205685168 +1.79560459 1.75687492 -0.10122072 +1.79838586 2.32769418 -0.182446107 +1.79899049 0.436353654 0.995225072 +1.806942007340083 2.330351490708698 0.5808068905618369 +1.80042362 1.54848504 0.408490509 +1.802010798858812 1.346371079704753 0.4237982964567336 +1.8014065 2.59147382 0.451685518 +1.803060194996722 1.065273807513924 0.7347262900212232 +1.80237985 0.246963695 -0.67614001 +1.817545083274193 0.9236472349739538 -0.5779360644930746 +1.814815568985231 2.5939104502323 -0.04643683115990314 +1.801739844390055 0.6225519208967918 1.00617922497864 +1.82095397 1.61247444 0.0173823778 +1.832622517045567 1.179875942921169 -0.1417920116968577 +1.833237239814918 1.251591351787632 0.429494272482134 +1.82596385 1.61375487 0.394084364 +1.82732296 1.46413529 0.190701559 +1.828032782945135 1.408953817490135 0.1787295918527609 +1.83612347 1.5236448 0.200010538 +1.83812273 1.34294617 0.160374284 +1.8392601 0.09410435709999999 -0.446277052 +1.855911175443312 2.699190460355815 0.2002848465330801 +1.851131271959441 2.689081480480378 0.2791034793857941 +1.847560109002902 2.510194888719715 0.5028919021523772 +0.6833690648604471 1.377091805026932 0.4229499768773658 +1.851383328451149 2.512935200292307 -0.1002973100515337 +1.85554409 1.58410478 0.206840441 +1.868269965666045 1.837582535729819 -0.06081514672179584 +1.865590606778512 2.686521442987136 0.1204074881530367 +1.86128199 1.26657677 0.152210057 +1.86191642 2.66157317 0.348514497 +1.86433399 1.68200457 0.0443326384 +1.86579502 2.02018428 0.5576266050000001 +1.88125465053627 0.761915795986144 -0.6230935981507679 +1.910310785859642 1.759354399609888 0.3710339265722136 +1.86767066 0.932922781 0.771079302 +1.860895544893104 2.020591134246533 -0.148211587421111 +1.875253731692655 1.152372572230137 0.4559078354706739 +1.87773633 2.66221309 0.0541080013 +1.873476292017365 2.1947551328092 -0.1670574204465841 +1.8788954 2.21080422 0.566436529 +1.87999046 0.257337034 0.789088011 +1.87761112889145 0.4161499682003539 -0.7028337319278167 +1.899157053234144 1.045976129348001 -0.210416480046718 +1.92219586772755 1.709167960628431 0.2082554271986617 +1.89850532756125 2.615170033789439 0.3980773731170968 +1.896930655019738 0.6008146327815103 -0.6811351643068405 +1.90488017 0.10897851 0.508007944 +1.915699032638035 2.614129337296233 0.008833514913161719 +1.91405129 1.15979695 0.151586756 +1.915237106529109 2.4263644665919 -0.1152294132681138 +1.9148159 2.41719389 0.519455433 +1.924901889613951 2.654484695866812 0.3189516167729604 +1.92222655 2.67134309 0.269838572 +1.917685713035248 2.679874479626519 0.2046611176092025 +1.930574981927815 2.670465719320653 0.1439178555605604 +1.93167102 1.05205727 0.473629534 +1.932942118013759 2.651169771169556 0.07922248317349434 +1.93463027 0.763688862 0.808352113 +1.93802476 1.9499644 0.468881607 +1.94218481 1.94505441 -0.0460039079 +1.943550259712977 2.555886606293196 0.4308111576137527 +1.964818578602755 0.4136884931390911 0.7968130564393006 +0.3210263485484439 2.075452620953837 0.03317038766356409 +1.95972288403789 2.620797357554516 0.3456849260073604 +1.95463657 2.55745387 -0.0312092602 +1.956109470599096 2.13473619170521 0.510007622897919 +1.955458379482713 2.121135739064607 -0.1057768695343567 +1.96660638 2.62390327 0.06542105970000001 +1.96797025 0.586072385 0.8263332249999999 +1.971059042651208 0.9128074362326133 -0.2911682048813535 +1.968858725297472 2.642782196516968 0.2706616830408672 +1.97698557 2.32266378 -0.107312225 +1.9775753 2.32259345 0.504215419 +1.98230672 2.63542318 0.131858572 +1.97300116230733 2.648182676124024 0.199332673790797 +1.992276742363222 2.483631976954739 0.4443811378431938 +1.99649465 1.89930403 0.344701678 +1.995092393589355 2.573721074631175 0.3674581902155302 +1.994064670782505 1.889668886415215 0.07305372355823206 +1.998321996628085 2.480578017669573 -0.04338812162339626 +2.010546886749167 1.013875260852116 0.1691060805671666 +2.00776649 2.57981348 0.04672864450000001 +2.00996995 0.0806083009 -0.182985947 +2.01113009 0.906437218 0.5364403129999999 +2.01174045 0.233615384 -0.461767018 +2.01689005 0.0889971852 0.272497028 +2.02040458 2.07502389 0.423107475 +2.028501383766037 2.090142213192551 -0.01638460680168109 +2.02084446 1.87924409 0.204542637 +2.013857300014974 2.601820941333024 0.2801849747757945 +2.028843545912096 2.590037080501144 0.1242028450165585 +2.024942246617333 2.602865006703494 0.2057445664141386 +2.035083883825087 2.246522077532326 -0.05424340465488618 +2.04277522689903 2.252889171850049 0.4435434171862092 +2.04208589 2.52025342 0.365142494 +2.03634931080552 0.2400071576812113 0.5691157126853824 +2.04460573 2.41201353 0.429422438 +2.043069395669163 2.518071658238288 0.031921355309525 +2.036309312405443 0.7592049055906648 -0.3793774942089411 +2.04769588 2.4191637 -0.0306829847 +2.06096053 0.0791791603 0.0525033176 +2.06475616 2.53921294 0.282779455 +2.063814116663287 2.535575328072111 0.1075667734344249 +2.06646442 2.03386378 0.320108533 +2.06741452 2.03234363 0.08248452840000001 +2.079412978632908 2.530780569065878 0.1960990110229685 +2.082627967286768 2.44920632613928 0.35571303271128 +2.08211589 2.46736336 0.0478287414 +2.082923996119247 2.208313281544093 0.37937144096417 +2.083937184418246 2.346358803111125 0.389439731337678 +2.086424587072623 2.227988935552997 0.01937176618775672 +2.089186410745571 2.361871598015997 0.01520746690512044 +2.08607078 0.742592216 0.585566163 +2.08695436 2.01534367 0.201428577 +2.096073520687734 0.3950937383884278 -0.4413337375394793 +2.0954504 0.569869697 -0.423392922 +2.099870866432961 2.48096599963315 0.1337322018636557 +2.105601443261881 2.464793607486833 0.2739748962352643 +2.092544443949575 0.8838251953169363 -0.01463825371480913 +2.115758823577712 2.459726982279206 0.2021202242303497 +2.108679615119384 2.413146886775935 0.3238690810234154 +2.105426171469343 2.424319180897632 0.07195786150331203 +2.11309075 0.868563652 0.296070307 +2.11334038 0.395939678 0.595789015 +2.1155355 2.31564379 0.339281529 +2.117223499133478 2.310266589413232 0.06254054165760944 +2.11816502 2.18167353 0.294346511 +2.11838508 2.18140364 0.102851622 +2.123972200346712 2.4252065483855 0.1518696501842523 +2.125992684433349 2.415264032222344 0.2504357740409539 +2.124634174314348 2.374913971711783 0.3030173942843294 +2.126160137643843 2.37867617844421 0.1006570455313993 +2.131858051686973 2.412381858338255 0.199819187413589 +2.12833071 0.560205877 0.609364212 +2.13242507 2.16814351 0.198810562 +2.137564571052935 2.36457714664173 0.2464371545451619 +2.137010974305766 2.369723248112855 0.1489990463835633 +2.13496581718953 2.303951200953713 0.2764752117969811 +2.13643527 2.30157375 0.125407606 +2.141490415998158 2.368407060078326 0.1938377502024031 +2.145570927227891 2.282969489219755 0.1987687555805885 +2.15518069 0.840071321 0.15292123 +2.1736505 0.229061648 0.306871086 +2.173431491299849 0.2265107341592828 -0.1803572984988935 +2.2048502 0.719687283 -0.0847265348 +2.2088902 0.715746343 0.346748143 +2.224276520131327 0.2237517528523519 0.06433830293338991 +2.24755129608071 0.7270014652945946 0.1390662726531696 +2.25277996 0.391612709 -0.157727972 +2.254329730863191 0.3903765015171566 0.3267163054441465 +2.25917077 0.555304945 -0.130154938 +2.26082063 0.552633047 0.349984139 +2.30507064 0.390150517 0.09281414 +2.30751014 0.557481766 0.115873098 +0.04046821005875216 1.605391844093196 1.111678894579011 +0.9480952195404683 1.319366232791094 -0.271556710280334 +-0.4870713023956779 1.180878104846571 0.7211933010896007 +0.9244542084161976 1.93292246243883 0.5197052035369637 +-0.3905392184942202 1.731296008198054 0.6641008772235746 +-0.9404906262089577 1.708532530868413 0.3902220841140559 +0.3929816316335779 0.7308735515640027 1.037183389844176 +0.9532352767583977 0.9894649077027552 0.6515600853949561 +0.6695828302246488 0.6271736367272178 0.3719862691126666 +0.8560605677689611 0.947101009545974 0.3558772866650493 +1.03857050299964 0.4387451011205862 0.3671229257503028 +0.6851217210298463 0.663374572563359 0.07999588095833329 +-1.228801284828893 1.64763911182729 -0.1040822720229643 +-0.80436401670721 1.726049839257721 -0.6616000145399746 +-0.7958374250416013 0.2827706950745666 0.3627612157296127 +-1.658953038077672 0.9832485653271659 0.3630633664864795 +0.3144023109064955 0.2755632101876745 0.5266471438905176 +-0.4388478930717039 1.063535881177849 -1.263794118052971 +0.3164410875637469 1.5273691629629 1.03713020506666 +0.496451806331365 1.485657949414426 0.4697405046451256 +-1.022332575694248 0.8381102779646504 0.795953917481706 +-0.4948171859005412 0.4263852679593141 -0.349968829708236 +1.050416032808323 0.2629292014246017 0.6030662405158642 +-0.1555871738330126 0.3147094621980449 -0.3353919670552275 +1.150933400358489 0.8018733181086932 -1.014052411661971 +-0.9606309078374478 0.7409625099950944 1.130585553447965 +-1.71718886676055 0.2053137365472326 0.381084477421779 +0.07413271073236627 1.495438773916767 0.2789310677696362 +-0.3281880854679922 2.025862298630824 0.7725443606517119 +0.6132907629878573 0.9618398262835913 0.3095811986180665 +0.5567486499201499 2.843031402473833 0.2904075140236186 +-0.8932728123095441 0.4703523260248901 1.081319330125101 +0.3447076874537267 2.295120463166387 -0.4922437918547429 +0.5548781725612831 0.3396228489088287 0.6456160185931828 +0.1765222957775257 1.84245033048878 1.112622426324867 +1.776255167998763 0.9338750827168288 0.04368562247535764 +-1.586382587471445 0.7352123360132218 0.5512186745345854 +-0.2528786225169525 0.4704303787549673 1.331729780134318 +0.8269805501706304 2.643977665786776 0.4819482043417048 +-1.564468182325693 0.2560887967220173 0.1974557628513794 +0.6341906404285579 2.420654932608642 0.6587273431766394 +0.1293605654666894 2.727958034939034 0.6262347829367756 +0.8266434293264672 2.71497981952872 -0.0114267678262056 +0.5266701245450869 1.813251272906872 0.7336487281995403 +-1.276128997918007 0.4957882594796392 -0.8177066293211113 +-1.816990892181086 0.6030629955354876 0.6119312445051152 +-0.8901059569710614 0.4275836838569863 -0.2567804630835223 +-0.2104541947891278 0.5732423942888095 -0.05500640269734203 +-1.663657024662448 0.2333952411445461 -0.1477238539133406 +0.9144403115558479 1.628436115811175 -0.3093058459460407 +0.7985201091820406 0.4549838465469871 -0.02993714283173187 +-0.3736082451758626 0.2711924567638435 1.214122026674032 +-1.653558821620099 0.6064259906169881 -0.4966313101407029 +-1.662120896188279 0.9394828830658725 -0.01314723809536775 +0.4879724199629542 1.1861029938261 1.34357638499669 +-1.651917430254519 0.9358364167912719 0.7907431958566234 +0.9557639063233291 1.564003779151976 -0.7290292857311403 +-1.728135338373568 1.272101405199122 0.1427252527507836 +-1.657620598970937 1.362197756005864 0.4861315976173309 +-1.16767631733049 1.623375774117651 -0.3192670782653662 +-1.652617153643251 1.595947110931299 0.1733434222778008 +-1.16194350844031 0.5828117528649107 -1.096204973216577 +-1.576464308770624 2.115699619803229 0.2116077066647163 +-0.1325554230250854 1.87755946789804 1.050422758425813 +-0.05349627209971197 1.614156418952096 0.03931249615004898 +-1.704020014669134 2.553377175758802 0.2541560140990645 +-1.683201932692459 2.900467024706368 0.001032341585262332 +-1.838993779286754 3.204036490839693 0.1086696748975496 +-0.7761353655701311 1.651174402000292 1.015235606884447 +-0.1704316317919567 1.109963385884956 -1.217206531456281 +-0.5061190814910812 0.5009288362335566 -0.936519116086718 +0.9154303550568171 0.7422339787196318 -1.348515966348464 +-0.02605993470924189 0.5019029141779821 0.2361101532758704 +1.372274600849187 1.890938506681032 0.08733820972991206 +1.134015791218783 0.9566204804192233 0.3348110987167621 +-1.398695316792674 0.2098660141972179 0.4445388037299548 +-1.340564887144079 0.2445961320348318 0.8140268375315975 +-1.326916152371152 0.5600643452568002 -0.4648277732215508 +-1.239261617443228 0.4886362817829735 -0.1176822130598555 +-1.569370981731752 3.117010105268437 0.1613083333528974 +0.1983265653124296 0.7504191984220809 0.3345252249850172 +-1.311506618547492 0.6223352899753041 0.7745765099469368 +-1.244238170510271 0.9167220708719945 -0.8553704623305783 +-1.347302202723897 0.9446210392590049 -0.4280654790395799 +-1.368602026840172 0.9234679788896348 -0.1057092980545234 +-1.335994677193215 0.885676294100552 0.4258524727865623 +-1.321870877984668 0.9428390841266446 0.809153831332254 +0.81822556120207 1.440320463862168 -0.03016487395874226 +-1.308163381191319 1.320548431631528 -0.4785350950621177 +-0.6761747117550779 0.8977486899770449 -1.316284482554951 +-1.255832675888094 1.077099198419137 0.1880876574882456 +-1.307486669934308 1.200125448387884 0.4749512342783149 +-1.323361374005264 1.24426055747674 0.8190103323433414 +-0.8687033665486412 0.967891831293325 1.27936131550297 +-1.488411642657817 1.496589425534611 -0.09199156124515268 +-1.380550817277374 1.635024096943188 0.1650129760123815 +-1.313089626351285 1.573203198028332 0.4621588104566243 +-1.279248749017855 1.594442425027582 0.7866223023094961 +-0.7368479046190332 0.8074548944610953 0.9366620340627532 +-1.380165801466441 1.858955244661179 -0.1656013987416321 +-1.284674519096348 1.840563396430093 0.3405855433035692 +1.509281553081594 0.9333187898062915 0.03349061730915938 +0.8462413313710428 0.5633083744632229 1.143445986474162 +-1.425952981864431 2.112501376941679 0.5158654914959078 +-1.396070808869926 2.5986914885685 0.1715935507427507 +-1.385442968733009 2.574144279210486 0.4716579252399352 +0.5993192825796356 2.495838937879818 0.3197139370810463 +-1.263512246413834 2.854183144653559 0.1772208044615728 +-0.9272942687353287 2.19389685597922 -0.3383360966973306 +-0.2193116085670049 0.2212512723668972 0.9894467164417574 +-0.9298169922098769 0.2467366588802867 -1.154221974330109 +-1.036723774522164 0.1960673642809447 -0.7436225541771717 +-0.9567706742183248 0.2844468491657458 0.07556572832962166 +-1.080599105031485 0.2734361844589244 0.5051979481393147 +-1.000508756305494 0.2045894892056681 0.8473838430597621 +-0.9608923767038612 0.2115573640241691 1.142996367050938 +-0.7370898536174663 1.248415624088162 0.5708970976472697 +-1.000566131381061 0.5622240954874301 -0.5580856006878266 +-0.9776228983073633 0.6661275266837496 -0.04478501181309712 +-1.41255178305885 2.173114409888083 -0.05411710921888129 +-1.043702539187732 0.6555771935227614 0.467997653600958 +-1.471639083108967 1.18859166693217 0.0489056259648006 +-0.9126964839969193 0.5717143018636007 1.433460782932617 +-0.9798326835202652 0.9504335184338619 -0.4381297713005414 +-0.9717736584012852 0.909992788628994 0.2128564707429051 +-1.072950214172158 0.9762583855960461 0.5419573965470459 +-1.024909359164706 1.217070422205907 -0.7912352166544248 +-0.9982342183358488 1.288543364897661 -0.4377708927173754 +-1.003855754942162 1.218642977932232 0.2639418807995987 +-0.9846497659649374 1.227751406916388 0.5565128390724137 +-0.9211822613170263 1.322996549236532 1.111977532451721 +-0.9931364695236183 1.489182184061137 -0.0757103794469777 +-1.047662057280629 1.566204916676621 0.2435535713032344 +-0.9913343952697919 1.513097172813504 0.8144005576461697 +-0.9736112475240948 1.926378544195744 -0.5014581848877608 +-0.9796905769662204 1.899288251274421 -0.1248253195381817 +-0.8772390187562592 1.950222870699108 0.4722526345007671 +-1.041809501204185 1.886241128694954 0.782528596440996 +-0.9856136636542855 2.271323997465649 0.4560138434334047 +-1.029374041650566 2.500982706465745 -0.1818648636757182 +-0.9513048492818185 2.604453797756269 0.5570148479516259 +-1.029905294345338 2.859946662912745 0.1049118913224877 +-1.723940225807136 1.079330909769086 0.6134583647975106 +0.5555771207466078 0.4757293506045509 -1.237698388569461 +-0.67525538662614 0.1944983043334874 -1.233132285221614 +-0.6167521991777208 0.2316927701540307 -0.7755586291806054 +-0.6181038750804184 0.2577670921052854 -0.4428909503360501 +-0.5838059034321466 0.24149190881946 0.1891920665910786 +-0.5371538352954548 0.2737767826038207 0.5540766810844657 +-0.6539857441992611 0.2352619157153792 1.153569153429398 +-1.104513627899726 1.718514811502841 0.5669824110233698 +-0.6791099247175003 0.5468064054872543 -0.4549212426412575 +-0.6036579153607021 0.617241224161331 -0.1579484431001876 +-0.5920519531839764 0.5037721730457253 0.1064851597027782 +-0.5953130012075161 0.5211968963038929 0.8457562468107805 +-0.6062876416168316 0.4937000921436695 1.503489881365481 +-0.638031626847085 0.8441179470869526 -0.7751668430953583 +-0.6843395533648624 0.9438008773283593 -0.503598519143255 +-0.664713935144989 0.9394794234806705 -0.1757885284398167 +-0.6014429636212932 0.9087666231457993 0.1134110151519533 +-0.5699611470195173 0.9220448490758738 0.4830332459958753 +-0.6568805359148054 0.8426431091271579 1.482451793944282 +-0.6937923599242681 1.185097742075244 -1.079308101262804 +-0.6163464467776318 1.218741863140159 -0.6990818886106385 +-0.7046403532170499 1.261476244009909 -0.3360692631112026 +-0.5828945145051688 1.160497608984935 -0.07962223857491642 +-0.626507073279241 1.320404961417122 1.120118119499781 +-0.08678479673052325 1.668220958122568 0.8297249285505722 +-0.6765740712315882 1.531858130736219 -0.5385291691109463 +-0.6247362020630233 1.496336298747878 -0.1327448639711067 +-0.7018177450055779 1.548173170504558 0.2194173763142092 +-0.5864988040629862 1.520771291683188 0.5273196213452843 +-0.6685190547156132 1.905436937438086 -0.4173729780336816 +-0.6386280044098264 1.89838817062479 0.2019762401119486 +-0.5744907736728391 0.5959150537912352 -1.250479582702978 +-0.608718096711194 1.917686219203103 0.8289073713144391 +-0.6698935031352532 2.206647555613617 -0.5191034893634927 +-0.5166565934528978 2.248042110780339 0.1884697552320762 +-0.5812710804636851 2.240882909750958 0.8155950083379763 +-0.6637557649629229 2.59460769767123 -0.2343935550128889 +-0.636944539463103 2.566143483177021 0.1269104182668609 +-0.671035940617099 2.931703032434802 -0.1309812989965405 +-0.6101446633364513 2.877291458852679 0.2041323125133989 +-0.6120732215194863 2.917001408540232 0.5787211445774628 +-0.9286061109877235 0.417709453585509 -0.8810482184984796 +-0.6131969451533263 3.277113365123626 0.2222920238935685 +1.913398537879117 0.734496834446266 0.109530689795462 +1.823924135054865 0.3676812379432686 0.1771270266844259 +1.155137378653418 0.8862818346123492 0.8175833455792946 +0.9480514087063592 2.185391647213167 0.06149301364435809 +-0.3430049922684801 0.2390977362820514 -1.101842421726295 +-0.3741009133721984 0.2920618563328553 -0.1333889770059292 +-1.216434534135623 2.368630417705611 0.1929266853383314 +-1.179170613946675 2.105168209006003 0.2575877767070786 +-0.3124371015997795 0.547929576712666 -1.47663823663028 +-0.211990754385998 0.5790477736208868 -0.7581193623555458 +-0.299356209287965 0.583364041537191 -0.4117384147074876 +-0.3516298453780388 0.5835389381425864 0.5678574064160458 +-0.2700955910816628 0.5264288929326597 0.9641399999638253 +1.636100046420008 1.0487939795107 -0.2136370134636657 +-0.3966229449656172 0.8104708466970005 -1.072900037958412 +-0.3462762416468116 0.9011652412254607 -0.6911408785149075 +-0.3873481748376361 0.8508123016286073 -0.09421036524528088 +-0.3180513872729515 0.95858026686847 0.2386101703492325 +-0.3476684670394016 0.8671142418559941 0.8358990829213857 +-0.3111162322424378 0.8494837986146322 1.471429096256826 +-0.3697491926418519 1.227862253271048 -1.056167309111353 +-0.2881876168410137 1.174781844191123 -0.7599352586151851 +-0.4023007751407594 1.106701306263537 -0.4082478153475195 +-0.2471136238296337 1.101104212140229 -0.07074668153830967 +-0.2344394853963903 1.303257151118672 0.1934775173330555 +-0.2871588513144163 1.197548696397976 1.040350392491254 +0.1345261134114134 1.394164287849529 0.8112137288761218 +-0.3184476414853488 1.436489450565929 -0.7266109767533305 +0.2927087357369667 1.113423562476363 0.8211658065649071 +-0.3142618362347395 1.615083602243 -0.09875598164176995 +-0.2678934703459398 1.491317837278602 0.503356975682711 +-0.3268347890313563 1.563853893535005 1.126281060367709 +0.4265142588404533 2.086100525894804 0.2883060711697131 +-0.5848205281744049 0.649053491391316 1.226596296497459 +-0.2793702756353696 1.910006542170699 0.1750533858694318 +1.548334942611838 0.4122974755886392 0.1824639671227309 +-0.3482978677290495 2.170512372815679 -0.5094127351042852 +-0.2665206060585267 2.158955925091341 -0.09682577696383309 +-0.286315010753014 2.320740774306741 0.5907072331399305 +-0.4114725755917369 2.006996442013014 0.499135462539938 +-0.4962659581986834 1.497850540323479 0.8259302861439226 +-0.8126698049160058 1.040924786094956 0.717995178457565 +-0.3277104865458256 2.530695865030684 -0.4118063900915998 +-0.2902871796357635 2.611353657038473 0.237126244101264 +-0.3008700278680727 2.959336535412031 -0.1507192749479473 +-0.2992131671634924 2.927485352716665 0.1174472915405229 +-0.2928172634048873 3.288962167767268 0.2739425118865894 +0.8573693256810822 2.391671765925753 0.559547044576763 +-0.1665209720874895 2.661476734964096 0.6603761492336377 +0.4303391430453493 2.031490380032223 -0.5502480401326094 +0.04469473644769041 0.338664069893875 -0.5460766995417422 +0.02074339776929455 0.2845771460905148 -0.1701834203006783 +0.09283361439860609 0.2746461720296276 0.1741377712841578 +-0.003747097440393838 0.2496981388625198 0.7976575425509638 +0.02663865782966532 0.5495114401249745 -1.479399709499978 +0.02896684603717301 0.5411457864555357 -1.105474295439028 +0.06134048068738533 0.5296548889884071 -0.8230390999112898 +0.06420782630031811 0.5749095849661291 -0.2778500456984974 +0.03735965062013596 0.4996461914477852 0.5360249482055179 +-0.8333696829425198 1.336773459975183 -0.6217027611104022 +-0.07349296690716588 0.8016147738052245 -1.020301812896748 +-0.01832918033750468 0.8880101409763158 -0.7394291530136952 +-0.1221327759166725 0.8750830078027697 -0.4143891644770512 +-0.002246034742651308 0.8994420997269539 -0.1372304656935907 +-0.01105683715241946 0.9972502813794372 0.2156451815543048 +-1.340043696413558 1.974861705587344 0.1023233665937351 +0.05105532797499401 0.9143410648947032 1.07823275803574 +-0.003975025622508271 0.8959424243403111 1.482339200955367 +-1.925091965482699 1.004874986369309 0.1613092067256059 +-1.595476229990629 1.249211508406592 -0.2410929805614097 +0.462669324300013 0.03020925153659663 -0.09072422496563184 +0.04947592201888631 1.256857127746131 -0.7557368767980317 +-0.07211662013890488 1.268793096328791 -0.4346176006598484 +0.001989235715007995 1.295453507100252 -0.07649942824443806 +0.03917864465214921 1.216717427204864 0.5106325637923226 +0.07999009854826167 1.229598640876473 1.05820338720012 +-1.321521499938403 0.5710269626554517 0.4406175589849449 +-1.6822622976481 0.4061461771570511 0.7178173462694067 +-0.02964921535152456 1.597160687812728 -0.33454985486175 +-0.3184119992721434 0.3482946398560813 0.2458187379222207 +-0.347019803426711 2.238869940157744 0.9203345206565382 +-0.5586248417674147 1.368197490162578 -0.9246692326216386 +-0.01834675661231367 1.881762716373948 -0.6988389069328874 +-0.03136844308554677 2.027824127681256 -0.358720772186771 +0.01467053591538327 1.880184130580326 -0.08040827104491416 +-1.928155147381925 0.3060568194183324 0.1385012675595937 +0.07153569452774737 1.840017984908602 0.5640257657211819 +0.006746594319375831 2.316295383093429 -0.495046678638163 +0.04777402348514013 2.189950115558509 -0.1307261501272023 +0.05263773887081899 2.074093777623088 0.2049871579768948 +-0.03207834537119997 2.16326750258284 0.8572836582562842 +-0.759862233307547 0.3451947927319728 -1.434855843687284 +0.005461979104527209 2.568929158889814 -0.4130435000431956 +0.1931320162963289 2.675792390602854 -0.2113207072968089 +0.06488652329362675 2.614456438966482 0.1241350325272321 +0.001076218664149429 2.519827096152263 0.4206656994730011 +0.03074419645971876 2.464936642370836 0.8053870011882871 +0.07754826250151131 2.884864731280128 -0.1504561780905264 +0.129790229411909 3.020896988474417 0.1581677524716777 +0.08368810996735629 2.942838047927661 0.5270234217340922 +0.1894552634367696 1.403779752459817 -0.5620121576017459 +-1.86744888142506 0.8706903298336904 0.5023212839998453 +0.3510573571739873 0.2354249168885804 -1.13099532957493 +0.3253291569095334 0.2578935464219167 -0.3811505880632099 +0.2885532547704684 0.3166804229111518 -0.08894633191076927 +0.1373509044804751 1.636948384867215 -0.9885574692210235 +-0.1372593093158668 1.36491319205519 -1.02739218797735 +0.3905919659544401 0.2426706274551281 1.097739858831605 +-0.6203562328210901 1.629679580388871 -0.8377756849049588 +0.3372651711172071 0.598385458533488 -1.523000448237104 +0.3344746503318723 0.5134842986257432 -0.9836540397867083 +0.3506420129554383 0.5127329425066304 -0.6608572971219285 +0.3678278673332764 0.5413092493713864 -0.3276089589703767 +0.438666259441287 0.5232343375994351 0.09989311879801005 +0.2961004781171265 0.5003607373104412 0.8411391776322286 +0.3591423215801782 0.5230408620675012 1.509349672919036 +0.4303729490298538 0.8979373984046538 -1.055359079971626 +0.3367615015617929 0.8711996416503162 -0.744841909187559 +0.2603011863396986 0.8513038377369015 -0.4509985069010669 +0.3575595912506322 0.8381461556960185 -0.171708999856023 +0.4913877649135022 0.8667639048346313 0.5551141274628468 +-0.8645768642740541 0.001256992388770448 0.007899034531521812 +0.358636306824303 0.8960800311313389 1.486456655100361 +-2.044010726360471 0.7876937784514542 0.310201867958087 +0.3641628418764382 1.252792814308097 -0.7180911759997881 +0.335665870305008 1.195859002436575 -0.4899768390337028 +0.357385644867693 1.25162926257262 -0.080525038576322 +0.3700265884650766 1.160129511315885 0.3064013195706403 +-1.688582833340796 0.9427122213211817 -0.3825278670889357 +0.3937710011141067 1.253600415953076 -1.130071426842909 +0.3679156397232906 1.505257737880857 -0.8686090857036706 +0.4449220631824067 1.517155952353588 -0.5383568040782976 +0.4962188849342199 1.513390895315953 0.1567381383770449 +0.2641977584829853 1.500909435148582 0.5072848483985493 +-0.1872095291555183 0.2897384685991788 0.482201458417683 +0.7275876785616152 0.3744619131502945 0.2122290311081551 +-0.0995655308864173 1.414713652686132 0.9989734609595632 +0.3690982581562126 1.817901178243881 -0.6976108585412895 +0.4449132483585747 1.807943757396138 -0.09671340007594602 +0.4411344217633779 1.757112441023042 0.4728477084793643 +0.2703826939647872 1.714145475303499 0.8118758692683633 +-0.5812864278277875 2.357286783395969 -0.10055465655138 +0.2763504487613417 2.0516876875165 0.5276482674800271 +1.362232829032129 1.652712237514338 0.1847179530791693 +0.4631853906287482 2.496606720253056 -0.3362447736036254 +0.3586479450153787 2.605621096554823 0.1168660025012623 +0.4189908079152163 2.976932882467465 -0.07431645117580363 +0.4013968443601408 3.144163645667901 0.2095422844345277 +0.3652186678410936 2.893786195902571 0.5499675374113114 +0.9402509813778371 0.6164380064579028 -0.9198194730262685 +-0.3704318114346608 3.163115600454467 0.4401880933412143 +0.6757404739030557 0.8027145496843868 0.7289333957581421 +-1.989624060902496 1.295761977126755 0.355538785204603 +0.7861867427599722 0.2738048530665445 -1.442125406502184 +0.6098664346251753 0.2687854925531307 -0.8679937695359262 +0.5971469926110815 0.2772550720681043 -0.5175838050238016 +0.4161524090505143 2.58354463910824 0.7403698455395206 +1.325488193811636 1.449172836141311 0.07272327397842503 +0.7164827822908351 0.2349831662683821 1.230861804768987 +0.8276742060201067 0.5864562025302041 -1.449791030389685 +0.8222221245258843 0.4657008264074307 -1.127403972139011 +0.6287350342580291 0.5848047622652316 -0.8050101697765004 +0.6665688282105722 0.5205640203230699 -0.4745829055828216 +1.753812374001381 0.8515276456463837 -0.3773942520037859 +0.6430807350529746 0.5935183124472931 0.7836633597751045 +0.7055551902085083 0.5454552803550267 1.475011922453579 +0.4467920139369533 1.237593390660354 1.028306814726636 +0.7186813061730332 0.8847505741483411 -0.8448783881336349 +0.6850124602104105 0.88183200283575 -0.1680392354964467 +0.6778870348633165 0.889670599163516 1.070553339737458 +0.6776965107768523 1.094425365455439 -1.078579216210372 +0.6580984421127877 1.26146963157418 -0.7404099476112628 +0.6934604550479661 1.269506381862807 -0.4762207761682272 +0.6616175116711578 1.195163415697454 0.1723249656116252 +0.6903525903494147 1.182343973737663 0.8531021505256111 +0.6949071785272741 1.560091971704328 -0.7653820738835992 +0.6058508796041463 1.492403922545427 1.123239564997391 +0.6947869278409938 1.864790512860464 -0.5739466197443344 +0.7511732531502122 1.804221491615342 -0.1711550516639345 +0.6560730403797232 1.874219445600844 0.2259044664780499 +0.7818790722284331 1.901961265231109 0.8577342266877489 +-0.127690832010638 0.3070083412562071 0.04066203159213142 +0.6439639506567073 2.210505980088967 -0.4425446347949308 +0.6896424348280473 2.119700062675398 -0.04133433476437843 +0.650686472563095 2.256282537526491 0.3063544270002015 +1.029506500679346 0.6344601633856741 0.6657959939958963 +-1.121837282535066 0.4188753632174732 -0.3754501628037301 +0.7513591176048929 2.591423221511831 -0.2155801696394469 +0.8171333562596108 0.1977741289031782 0.02951257155802671 +0.6906884567692273 3.025233675426026 0.2034160067841761 +0.8087612388525821 0.2767044445639676 0.5909111729298984 +1.816545989338289 0.7556580233384064 -0.1845796976536854 +1.206315411009722 1.891779498740185 0.5795741975505493 +1.16227057404895 1.48778962967351 0.2639240425063969 +0.2434173297285543 1.791725845963156 0.2138811720920303 +1.003001086119293 0.2473693179430348 -0.81769567824492 +0.9428958669858509 0.2346341922266077 -0.4937545275816277 +1.00544431504455 0.2159086433877723 -0.1833980400035597 +0.2247624786904607 1.588752636747747 -0.1009339765282965 +1.035375173758314 0.2336373551693787 0.8498208876308956 +1.033536798389843 0.2826003386237668 1.133139688113901 +-0.265957512894008 1.838440311801709 -0.3761164355420376 +1.052004683195506 0.6526413305612775 -1.272815078508958 +1.203868866969406 0.6306628144087048 -0.1555686331062389 +0.9626660635860519 0.5358015507712682 -0.5244235616968632 +0.9912741418829242 0.5541687713580573 -0.1826708753650927 +0.9781200571559401 0.6780488642226017 0.1844056882657367 +0.9443887232144801 0.8890584947397079 -1.15115564100354 +0.9915029718522681 0.8419436507020948 -0.2054443180859373 +1.048040636359465 0.9277800402066162 1.203832654397905 +0.9701229960096215 1.303835007874552 -0.7639738329551611 +0.959331471968504 1.230043188301046 0.2443446906478539 +1.061201881617244 1.219016611128062 0.7704156222923885 +-0.5629152263423076 0.3880597190923438 -1.182654378783017 +1.104277947848479 1.527232572753267 0.8224278922409956 +0.2553515479205669 2.353380009301638 0.6179909240705851 +1.049838371768297 1.811614830738835 0.2555847100115786 +1.033738582162187 1.841343019216113 0.7712792374767783 +1.056205766366988 2.267563867954272 -0.1699734464448784 +1.1072821233812 2.140066705505253 0.6060855907214625 +-0.8310274289328631 0.4785785957753099 -1.13958017811145 +1.057540479049863 2.600650427153876 0.1426084026844386 +1.064842257783098 2.55041141051988 0.3896692671088142 +0.8675301792898621 1.538765798573882 0.2449675076250292 +1.549518504545073 0.8586505755781016 -0.5387270800348765 +-0.9854470764177578 2.823745618209854 0.3389024942088864 +1.331716149047278 0.2642439276488406 -0.8269701699159689 +1.288824590561676 0.2536489623953377 -0.494804209247882 +1.378682604341337 0.2569055285179165 -0.114199203679947 +1.348646919140076 0.2160090828224741 0.2433748067893634 +1.381874260881701 0.2828940148027079 0.8442860519531006 +-1.110967393000208 0.8819450495829644 -1.100798061471183 +1.257333899747496 0.558047775720646 -1.137960155671828 +1.342893472992735 0.5880194450896442 -0.5163486010877593 +0.7883504108092351 0.9070608523567367 0.09800380648979753 +1.317960734725192 0.7086268692565768 0.4917071118677391 +1.329703899022667 0.5101590144478486 1.14492153876554 +-0.5442883348195682 2.564596096720519 0.4948603624089572 +1.35021769395836 0.8318862675184417 -0.7941801292176375 +1.376464844583883 0.9359419773392674 -0.1983250432922842 +1.424504704057973 0.9181114749596223 0.8562925270793446 +1.401130000377695 1.143832493973586 -0.5164950685614136 +1.292842534338954 1.197731181652211 0.2499472864172588 +1.32550844911339 1.256273304257678 0.8294760058412318 +1.484048439693014 1.565397722553781 -0.1897518170214574 +1.484898234845625 1.611902992935149 0.5577263359853841 +0.587173086148201 0.2981883186716713 -0.1412977168332989 +1.301862913854212 2.193503400768526 -0.1147259158316329 +1.399669520828846 2.160572072490877 0.239051978728745 +1.371299785775346 2.142558982591522 0.5315710901887153 +-1.585930504484143 2.770001567550453 0.4221215168769627 +0.7961012781969314 0.3733488584292957 -0.7121991755697248 +-0.3454552144483192 3.14069905555632 -0.01380695792377713 +0.997775173382617 1.995971978051808 -0.3234590590987495 +1.410188353537714 1.889849256154554 0.3854829279249505 +1.637844324851649 0.3218186248632349 -0.4741861692228677 +1.681798095746942 0.2219225606377501 -0.1325376456156798 +1.630731256899215 0.2902457500753061 0.5386921727082433 +1.687257913042015 0.6195153316856872 -0.4546622245239602 +1.687249071335571 0.5593612246695995 -0.0592626933700915 +1.625327437488276 0.6035312232695664 0.8361505458726735 +-1.022700252198404 1.571947025983273 -0.639326947958884 +1.676606522587034 0.8871115158437135 0.5479909413851523 +-0.7990947606674345 0.3224953169872853 0.6292905020439327 +1.083705400257178 0.633594297379788 1.069463118813309 +1.660899280011838 1.464291920305637 0.1998334724453655 +1.396927624835636 0.9239034897016823 0.2919079900699297 +1.808501626854739 2.124685652120196 0.07076428754986563 +0.5745109209259047 0.1942975853231858 0.3894190516102606 +1.90792164017464 2.574541824599571 0.2219394865305693 +-0.5982991694517995 1.852182394131193 1.061765399601115 +-0.6890429980616057 0.4929547259190431 -0.7410961807308803 +-1.730894934879416 2.312984232409073 0.2510462192403978 +-0.4348078160533226 3.12728213483921 0.1997497013600867 +2.025917763361611 0.5727255721513678 -0.09831091635396999 +2.086515906687564 0.5785312414467189 0.1700510851738107 +-1.05853831689416 0.8703073489265175 -0.650773477980415 +0.3408172984311742 1.159949634995069 -0.9014376185803161 +-0.4576623994849154 2.99400721339919 0.3416365538074414 +-0.1655339475907758 0.4584906962621157 0.7151568644381011 +0.2498184552736826 2.343854954464173 0.2701685716757616 +-0.5113445486720017 1.318224451228965 0.3978321506153358 +-0.8348007829744664 1.053033168444685 -0.3416398158035314 +-1.170622369373739 1.783298537700564 0.08133870236940617 +-1.499476968188606 2.943913209219828 0.3327358163966095 +-1.204718181681785 2.023773225699734 -0.04207210714130401 +1.118702254879015 0.7542100989153463 -0.4720766929594427 +1.169326568270379 0.576085773285282 -0.7676425372041715 +-0.2537362400018206 3.070679581699323 0.2615328040134959 +0.5990224782869706 0.6165539670892505 -0.1772665294095349 +0.2393692446846251 0.4182837722206925 0.3240021628419669 +0.6398767958223029 1.615950738017069 0.3498567239654791 +-1.093725816728272 0.5502855105540779 1.266889318007829 +-0.4351204284479802 1.09397916697541 0.08275074834518337 +-0.4338555960812371 1.917390237316648 -0.1107255664203197 +0.7531073298637689 1.680841234415057 0.05338669400453137 +-1.156557781577349 2.669836339687698 0.1374744432980683 +-1.13144936497324 1.948449606413725 0.4860128939419389 +1.869965700221947 0.5305340162247537 0.6094698498593616 +-1.00663916607405 2.073944442523056 0.6276019426177473 +0.5189428579480696 1.479166081607979 0.7681872434709762 +0.52611340740107 0.9245655448498034 0.847932997923092 +0.5658655807271374 0.5150472883118938 1.138242518506843 +0.2505317801826111 0.8443503186157159 0.8408499971679919 +-0.174370908829437 1.248889834554078 0.7531227034581859 +0.8637888192292474 0.878250181567237 -0.4353469181750546 +-0.8188010058105413 1.504952787956837 0.5038486138080364 +-0.4830834407528754 1.551489106466742 0.298244573870645 +-1.487201629085238 0.9279037913973371 0.1600130709583334 +1.579880933221818 0.7010033159771526 0.2300508949458947 +0.8749630775859579 0.5506920815518372 0.5456638055816437 +-0.8487998290563958 0.3416064140929874 1.349610011848369 +-1.063459248395181 0.1975676301174598 -0.2791312070700099 +-1.60103498716044 2.395682303888731 -0.01311462795473034 +0.5466045125049067 1.738945942522033 -0.3863717117769926 +-0.6535965463946189 1.769164580211628 -0.0936663725577095 +-0.3346838597675038 1.342104423227047 -0.1829970446767618 +-0.9722938717846422 0.7437973411434602 -0.8935911641521505 +-0.3884857420795013 1.545933088295459 -0.9475067224421931 +0.5717098436787158 1.977795386210908 -0.3093307033269787 +1.140361419996338 1.665096383697943 0.486007842608075 +-0.4346239310982252 1.322609941336544 1.294235410775635 +-1.164868948433758 1.093853649876909 -0.3126118881687076 +0.1515784511849466 0.528837812642896 -1.665156308850179 +1.097332252447448 1.361079677436418 -0.04118507018780499 +1.043663076522509 1.125704899361923 -0.4960682877820446 +0.1318352962239816 1.078381707669042 -1.221076266400846 +-0.900164539249783 0.4539781931783064 0.4836893979881864 +1.489914872427523 1.678132279989314 -0.3948813433914457 +-0.1733984612690031 0.8210971958504805 0.07593410220567372 +1.27181619875154 0.7489869439080259 0.1233411813201363 +-0.004060972142172527 0.6624281381947039 0.855873998388341 +-0.2331922871850379 0.8104305282992831 1.187491661965958 +-1.302163729263353 0.4327648043664713 0.2078769601024124 +-0.9534513789894199 1.119221335092099 -1.063272040717561 +1.306306204466096 0.4990218538291004 0.2408749943326439 +0.4134816714165035 0.7068618010763692 0.7555492753104769 +1.253543960832881 1.391926664930192 0.526753331825371 +1.333928272044814 1.061007830943606 0.5557462250976565 +0.9647019538515984 1.4142877194993 0.4947321347466294 +-1.488760084721713 0.7212269606500481 -0.2554535046726577 +0.001017404992235238 0.9935294927366481 0.7826487276346665 +-0.2780996632448048 1.135529652899365 0.4412119423027092 +-0.7354302493164854 1.380892192944971 0.8139720240540576 +-0.6205050400295141 1.146269735451031 0.2408863331840071 +-0.9431475069287125 2.551728633314379 0.1693429254679182 +0.1778965756968277 1.083922777432375 -0.2863911208155801 +-1.564910993017174 1.013077282033336 -0.5586442439151094 +-0.4199390669492674 2.542252489540606 0.8057151914171075 +-1.626329291681431 0.6842379993764839 0.8480303709895852 +-0.3964932213375157 0.2535629275022951 0.8184174087892957 +1.676467555942214 1.060541359106655 0.288276481747609 +-1.369408110872311 1.827123080090961 0.6171411841240345 +0.8750246095590031 2.172809552528826 0.7246890901648919 +1.033469795254548 0.9215768013149417 -0.7583913421759837 +-2.03024617471362 0.5664093245695102 0.04518008574656829 +0.7601092149706949 1.166309758978527 1.213322104283732 +0.3580098198113281 2.25703292322981 0.8500599018274172 +-0.7264590066420178 0.6596420500557848 -0.9503631830229919 +-1.238938616844695 1.372539250768677 -0.7137861311569877 +0.1408933220176492 1.029519413053162 -0.9547899941476178 +-1.423249631626781 0.2124828464366977 -0.02538115085521927 +-1.249668029386631 1.634391945076443 -0.549478687723266 +-1.210401876065114 1.876760858784843 -0.4001359426026953 +0.5148286335805011 0.253732881689303 0.8770294900220924 +-1.279115693951148 0.6453389656052517 1.196493101539952 +-1.212352942650966 0.4155056915797739 1.161433947341399 +-0.9860112846836302 0.515946068996599 -1.322989125647339 +0.6079155356643836 0.2073989820962922 -1.133487941010996 +-0.3912124838758893 1.484863797025941 -0.4177782900348227 +1.091354150411028 0.3669930308568407 0.05740489281149774 +0.1419529299165501 1.39218266690279 -1.041235099227418 +1.619457571589048 1.149596912007456 0.5608474608582578 +0.2449256057800967 1.395854443805981 -0.3052185678308644 +-0.9347683697983695 0.5429509183614636 0.7644128359739372 +0.3710050868440893 0.9936664840335734 1.154960399383355 +0.07554521000842707 0.2740565324942708 -1.06066465569356 +-1.888122479133545 0.7634899761983375 0.06120243299654925 +0.8645064947899349 0.1767124350180705 -1.181736292183966 +-0.2361570689360061 2.415466173976408 0.8545571063582428 +-0.5073770115751913 2.753741205801993 -0.01526591345887662 +0.4004744970724116 1.751247158431298 1.123957058616448 +-1.177777998627151 2.127778059160803 -0.2798740358897156 +1.48970109633841 1.859038262009463 -0.1486901153547162 +-0.7653072741717948 0.6568024592547373 -1.432420212006041 +-1.206954861946786 0.8800007839177663 1.186308403599244 +0.9065705777670484 0.181273087063667 0.3468299704456472 +1.629500066632783 1.689578557685875 0.2036931336584935 +1.298351759189843 1.788546262530444 -0.2266678991747732 +0.01314658553299922 1.50509767760639 0.6203888967256146 +0.08465224040484522 1.596327834022195 -0.7151805315217907 +0.7777085702413437 1.673107676854569 0.5529471869214649 +1.678051707061058 0.5732406156655334 0.4518214484718149 +0.1194547783920281 0.6250372938886425 0.03788320620330032 +-0.2543643067639549 0.492234809505065 -1.149950953836083 +-0.9603412020369381 0.5268238909147616 0.2203395190403565 +1.284066485380752 0.9265813928241946 -0.5194292714274135 +0.4739344251610734 0.8288900928962731 0.1444789898742851 +-0.05263118374214099 0.8537073910692449 0.498904346196349 +-0.9997588030522528 1.077283186064461 -0.1026936993559558 +-1.334231163937955 1.213953516847634 -0.1568936002446693 +0.3813997995654177 1.621187839120116 -0.2987160416664508 +0.3066677912574705 2.598203107887789 0.4069658986390837 +0.3198435132625724 2.158476743411006 -0.2574650487905072 +0.4459012302144965 1.226373980293313 0.6040196081241154 +-1.05133798841643 2.226764798686896 -0.03565845540948968 +-0.01794591954957404 0.3048741726025904 -1.302684987765479 +-0.8644195827327105 0.1628871208132442 -0.103173757836617 +-0.5433323171378358 3.138711500324411 0.4391295202545898 +-0.7594236533934792 0.1597747388487109 0.05585587296961814 +0.2931976854191713 0.2386025983537525 0.8119496422189907 +-1.774253284245955 2.832147110429001 0.2505864815208165 +-0.7577253119725135 1.117991119755621 0.9598637834763883 +1.520806488094198 0.5044359497726572 -0.7810503088931897 +0.8134862174777755 1.502711722811229 -0.5060083197503983 +0.6554093564129941 1.234598565859308 -0.1556905615557691 +-0.3827879292340209 2.478115524185941 -0.06297261697966181 +-0.6723459401337782 2.122488126710722 -0.1547660204914583 +-1.226024354614547 0.7514863488904304 0.1315008376935047 +1.491849888267447 1.318065414900273 0.6521711423784402 +1.03436337325917 1.163055084470525 0.4947785139000273 +0.7116312222093788 1.120199410688737 0.5158670315059177 +0.3120186559501432 0.5005464728595468 1.180779297308526 +0.3901404751276557 0.5772471078656483 0.5030240046771952 +0.2116462059295279 1.588358393720541 -0.4125690315631907 +0.02317020356342777 2.231165260196425 0.5075202790228286 +0.1031903674763624 1.229791352326129 0.1843566560410413 +-0.1935413160538022 2.257405751798889 0.2686087055867898 +-0.2336437440934503 1.488209821491882 0.8256447079785746 +-0.2679186452799089 1.593824371377888 0.2029384403164597 +-0.3215576733597474 0.870411188550642 0.5145083614307577 +-0.6702889243192695 2.182953304945543 0.5081452080975927 +-0.6242938722668947 1.865757785675949 0.5294237102878745 +0.5178832501900515 0.4011338061167996 0.3724365160203338 +-0.6701105796793808 0.556762284384465 0.4571150655725021 +-0.9746213103845174 1.874995721182226 0.2304548047140335 +-1.042667067504626 1.497532030309007 0.4998309278568959 +-1.002759034196278 1.206570481508624 0.8130897734090303 +-0.1386100564237307 1.063023367544802 -0.5906029781442748 +1.582206785 1.25578779 -0.605260253 +0.748231552991164 0.2874089503702815 0.9549503334127378 +-1.197743645589105 0.1854124432804273 -0.04438964648796561 +1.390147469828157 1.881763844756077 0.633829086461784 +1.740141831796007 1.874275654343516 0.3820565152752495 +-1.086879631741835 2.720880634843033 -0.05982685835222367 +-1.985100111389339 0.4179505053794394 0.4801646248400787 +-2.027137795414092 0.6817796306185376 0.5252094821872505 +-1.363834711112718 0.2449353371077602 -0.3453803133181704 +1.218744982166624 1.112919553439154 -0.7251325200782395 +1.779596619426369 1.813813555721533 0.1583111200539533 +-1.508481588445161 1.932952277871218 0.4670414673302559 +0.2236184459915749 0.9988889738304321 0.04071640455331429 +-0.01718740907527356 0.53339959605994 1.486910548238354 +1.680573174752959 1.173981623672257 0.03138353767428005 +-0.5470650579139841 0.005894326206917678 0.6685090726103196 +-1.211183222263569 1.530411265368523 0.03903817091069171 +1.598577535016651 0.1699645642650775 0.2122324644444411 +-0.35769344374167 0.2823442727128802 -0.7973866189829645 +-0.4407792642969799 1.823936905091627 -0.6896050709532845 +0.9619780685781804 0.3346026234190217 -1.349955798361205 +-1.230319933864302 0.4381122044455886 0.6324981712408626 +1.180702257757297 2.033220037962816 0.3346659739305552 +0.7517494629666732 0.9605690369500869 0.7533199729095625 +0.7694060912114338 1.610884399761109 0.8183655830195712 +-1.030741668320727 0.3714908824768525 1.289774999127845 +0.330587832034846 0.2422114672380256 -0.8716807744561501 +2.053577006621567 0.3167788592429344 0.154361982406005 +1.611824464265656 2.034255636190176 0.2139799383961785 +0.5845609144777439 0.7672251348275763 -1.41101721643732 +-1.201636706254884 0.2505890502295006 -0.566639738195347 +-0.1557568430102464 1.664867051143754 -0.9164107390132114 +-0.7116561511744209 0.2305779614994988 0.887231734308398 +0.5924103121596649 2.946040590075155 0.5064041277720265 +0.1606497443363594 0.2955084765771582 1.330436171026726 +-0.0500085660422932 0.6148909182814404 1.14211208330819 +-0.5452752238692842 0.02168437647504463 0.1830735816519817 +-0.5684315067520076 0.7400072018870641 0.6900850455962942 +-1.796355474491586 1.121876890776482 -0.1832028864245441 +0.924716981534232 1.759405318631102 -0.5836404651607571 +0.4249699471532929 0.247060340710524 0.1718187727379068 +1.258729055382993 0.2977349961367237 0.5254942904089502 +0.2410369264388437 0.8251500039602263 -1.410668616371572 +-1.395917163204462 1.130454558772627 -0.7482611510604212 +-0.3293279990626609 0.2868285160995946 -0.5088897387129754 +1.17213788420676 1.457175973543346 -0.548843594140473 +-0.07821854447199926 0.2592132613984747 1.309246510156054 +1.423620541090387 0.6197997233740198 -0.03770411705371766 +-1.255355122430718 0.1767181629348099 0.2465855508069066 +-0.2296689292548069 0.03176929266922295 0.3623753394214769 +0.6445360471448591 2.224411544549365 0.8690362704534559 +-1.682533809459513 0.9757327151263435 1.00385694302142 +0.6457955177882517 0.9277921407871512 1.435450731777952 +-1.535133732657752 1.779223561170031 0.4227785506905599 +0.2568525736182292 1.363599984635285 1.269455016497646 +1.005593387180474 2.496488604439598 -0.07880998972826386 +1.618586087162607 2.041300298369343 0.4809688557585209 +-0.7582036893248242 2.432946853769618 0.7001935685392255 +-0.6666601043718359 0.3079313918773222 -0.13482812203208 +1.074320291596436 1.267006205360624 1.055913691492542 +0.1465674212275975 0.2949935595374414 -0.7903533863203884 +0.80762520456932 0.8049299729853243 1.331769080898416 +-1.517360022301957 0.402794370884528 0.5096855495713527 +-1.269717340708439 2.471907277094879 -0.1210030458905083 +0.350159644201048 0.2611158411441761 -0.6438586305977925 +0.4865813421523277 1.308577871720399 -0.3268462921698829 +-1.155145516835868 2.552542236926636 0.3356171602529887 +1.534344338226407 2.524168809908835 0.2167984348043583 +0.6285267826747575 2.75517423604014 0.6099884213050165 +-1.745416948685058 3.027864661693006 0.3580645607383028 +-1.415068826962383 1.532863025471356 -0.3524420745894213 +-1.138475694676911 0.7461529253230497 -0.2983609430195047 +1.226615735732566 0.7277306133388741 1.256360692997387 +-1.213574393149319 0.7194988313188113 -0.6372040296226705 +-1.45306450848428 2.407996591632484 0.1210715053937398 +0.5979857341422058 1.744806716523918 0.9894385184900926 +0.4761497650019799 1.0238629221928 -1.267224583688969 +0.7064024889512447 0.8975810391174943 -1.270496657125837 +0.1381567963670689 1.0533899484098 -0.6160780914322496 +-0.8467093612372092 1.641152159281086 -0.3183163996913282 +-0.6084850645733642 1.224612638246974 -1.384428076728673 +-1.194193410181121 1.382230873217286 -0.1850177466943469 +-1.130335900983484 0.4070354756608965 0.8934216136803137 +1.836794859059497 0.4126770630439904 -0.3206070466093373 +1.146578605696809 0.4263324824149989 -0.312911251049215 +-0.1255213069514113 0.2928308102821041 -0.8454734206675646 +-0.5258608347823176 1.695257981958904 -0.321918012074396 +1.882644260376181 0.7553136886883495 0.3673852348264601 +0.5868608378944152 1.340118933827976 -0.9796725460032754 +0.5385213782379382 1.045415250396744 -0.344939170661392 +0.4876382320120546 0.7279053689342035 1.312382017620927 +-0.1537642903170046 0.6831544546427349 0.3040273378832241 +-0.7205670628505862 1.730509112409967 0.3798225106107522 +-1.181728117198957 2.770715674614153 0.3890453408398614 +-1.059583095613623 1.047543487174819 1.042984026336344 +-0.807787829366196 2.770163133858237 0.1300609419546207 +1.187471180998949 1.07456117401988 -0.27797788616724 +0.1520526713721897 2.402599740197313 -0.2575776009896055 +0.1628506783530231 0.6449042105006771 1.032491082969383 +0.1737208585003364 0.7081355571541008 1.300248768115258 +0.2399604932107474 0.6946281589214233 -1.204450130209876 +-0.1557403905186532 2.388331168067966 -0.2471221671571128 +-0.1695619462795319 1.051882551778687 -0.9487898242482761 +-0.1789648005644776 0.7355939484450079 0.692857449743386 +-0.6114855012182971 0.9514744750145067 0.7778499880217841 +-0.4775538014832664 1.682859244867902 0.09549541171776268 +-0.7970546044211603 1.706555753240309 0.6566762169419393 +-0.8598773729167342 1.68229386151609 0.0753575617833044 +-0.8301282406573963 0.7731505501112736 -0.2653933414967486 +-1.192663455473334 2.122969688573583 0.6702189328530881 +-1.142147103838935 1.362486683200072 0.9667067252620382 +-1.170109451327634 1.111771497996927 -0.5836008533639688 +0.4341571886231753 0.2984264216145441 1.355158380340737 +0.2658373242437216 0.3209674816838752 -1.323676495786076 +-1.661950889324452 1.604144712713339 -0.03727359299107019 +1.773648616050521 2.35416240088268 0.01967828945004598 +-1.650795287638364 1.728634896999732 0.04918819620760715 +-1.580000432665396 2.933708259676071 0.1830390740358982 +-1.829482763768822 0.7818002671327566 0.7140784117617773 +-0.3737219457699514 1.988650424910997 1.026287960215122 +0.9369081937161491 2.671154858542942 0.3212581355930022 +0.4567781706375204 3.000227310880391 0.2338930536643502 +1.86621425597791 2.384187039862069 0.1905512898897961 +0.9941874335675357 2.513418265927607 0.5783887574343237 +0.3138834485390221 3.053358811886485 0.4769705858366363 +0.3880124646103417 3.13835579491329 0.3401391158573297 +-1.176826865654989 0.2442052149387322 0.9985524856081262 +0.2863102530825014 3.078080201339139 0.3920776702557349 +-0.4663349669310398 0.7355235281624136 1.014046833945786 +-0.6976453663159033 0.258590787771749 -1.008483774355754 +-1.425927848267202 2.876891622832074 0.211955099988686 +0.2404216464011315 3.086805762701338 0.1016203154427902 +0.4761558888156633 3.124067471765739 0.2819394985337164 +-1.534866284382436 1.705653317293659 -0.05954153883971205 +-0.4257895444242869 0.7018270639794927 0.2530276065995316 +1.570541572645813 0.7663726316647117 -0.2365757918480699 +1.58839142 2.462020155 0.551938772 +1.88064187671889 2.610572218330349 0.1310608870241709 +1.241197526251401 2.463901194515311 0.3684173068122469 +1.23038085496378 2.469202628480124 0.01598183423713972 +-1.403124867228579 2.971223503292745 0.188274447566036 +1.136584504771697 2.033233883680555 0.05038290231801233 +0.5632331409010799 2.745134636442817 -0.2019282007964925 +0.2698366379825111 2.015636581774095 0.8006533318961532 +1.122516807337468 1.01139917838508 0.0221572551841631 +1.186220826990897 2.228092294073127 0.3893923584282857 +-1.426739214163088 3.0459706602491 0.4362150287777669 +1.09440654891357 2.367749811014836 0.5008117508457858 +0.5046183506230741 0.284262620943962 -1.401355867926627 +0.5562580314861343 2.414375020611173 -0.01378536279897775 +0.5951171481264289 2.085130049556096 0.5959856021063086 +0.5311250825843756 1.040245767241972 -0.01776341781403003 +0.2547842034197721 3.015138049999085 -0.004400061870085969 +1.516055782798913 1.4941271043253 0.04401098326500884 +-0.8402966228556971 0.7999437532633589 0.4219919954166409 +-1.368941397066847 2.773365261867961 0.3499598766757604 +0.2138998648285394 2.388843231454896 -0.01064190775330319 +0.1535683089696262 1.100518345141077 1.344339950195146 +1.301488191081025 2.350070631234856 0.1406361583424523 +-1.066081985040658 1.743795408352074 0.925585117100775 +1.732898283119201 2.566738385681757 0.2394488065900696 +-0.08003577180281628 2.879499684387938 0.3351328000015894 +1.559596715 2.51059508 0.521251753 +1.326659890404787 2.32979645725114 0.3170206062342936 +-0.08905916401665157 2.932875083796204 -0.1533920361932216 +-0.1937606528177681 1.099546542801345 1.34245634747633 +-0.196098415698191 1.012080210660566 0.6397184179690709 +-1.78998542793593 3.057808169875699 0.07438636512625084 +1.27583878472055 2.315110179514956 0.5206815101744714 +1.475354593138549 2.358962452199713 0.2389898286324662 +0.006205649537549189 2.554936149274686 -0.1377056534592087 +-0.8008033653050328 2.40176218987407 -0.3355659568135639 +1.205143958400106 2.50186089217462 0.1864669565766546 +-0.8028149082507715 0.7901067615691432 0.6461121650971939 +0.2775743594592424 3.089531073881977 0.1871838076336614 +-1.445391235648691 3.06896081695949 0.2411515612059094 +1.971089566395017 2.462531552940052 0.3188252208135227 +0.394805028598409 2.542832525685642 -0.1265663844925241 +-0.0621208775714143 3.008614832485826 0.4898508677801575 +1.633658020614638 2.439971050378513 0.3319047837994235 +1.544006591655271 2.480089666559329 0.4218701127316766 +-1.543313150313667 0.4544937542184272 -0.2839364768003364 +1.483726562485757 0.4900577992522491 -0.2796204178961382 +-1.733694582796039 3.099051157807747 0.1745388020009002 +-2.090392427740284 0.3963170705288593 0.2134198621813408 +0.1511878602291384 2.107957265444032 -0.6080411130508915 +0.1307267762201888 2.9812372452386 -0.005969854063714938 +-1.773296468367228 0.4936108175403511 0.08583409199981484 +-0.1603582086954405 2.030369192164751 -0.5699841019005478 +-1.329612133849925 2.901368747168357 0.3076465010232739 +-0.4527674900273553 2.738987690515326 -0.295149489803993 +-0.5028088705858731 2.355201243636139 -0.3357178697888536 +-0.5266572828397976 1.039353452541296 -0.945531059097764 +0.3184860250677594 3.067706976115149 0.5746812755893104 +-0.1823366138598464 3.20917388060488 0.2571238440909127 +-0.8222277361573417 0.6943632539127736 -0.686904693720698 +-0.7813496820004856 2.766878526595742 0.4158633065632406 +-0.7597050469117238 2.422822106288528 0.3414073188376104 +-0.7989340630658063 0.5087740123881376 -0.01389214938759384 +1.132604842376792 1.763954387234468 -0.4462126063955829 +-1.909619330229119 0.6236877427685039 0.4181555874116781 +-1.465849010166366 0.7959549092156898 -0.7091146087564149 +0.7900258078482458 0.6756919173151287 -0.3405397464278418 +1.690156519301053 2.324887681786254 0.2132113931595247 +-0.337835086146246 2.848536776680937 0.4159711758837822 +1.482705301086084 2.087926207832746 -0.005741613541909295 +-0.4737370912083304 0.4404350632658549 -0.6271753332615913 +1.965843420399996 2.510603272276095 0.09986240523765053 +0.7460739153246766 2.936663247035803 0.3385399248628246 +-0.8693786443502532 2.705217128668795 -0.103026881761056 +0.698647003807051 0.4318822360530091 -1.50442002930263 +-1.955459060927141 0.5002982784065371 0.2650218230507397 +-0.8003767460071491 2.384200047672121 -0.02495344926773552 +-0.8239711117377867 2.065512628232133 0.7331959966739164 +-0.7967671987406528 1.343804423800348 0.05655069427009621 +0.888075887765712 2.443637055163688 0.3055995037681176 +-1.130996422855954 2.852420052539316 0.2576591454581184 +-0.7897381022437544 1.079259381038498 0.06539796621744773 +-0.8131460977484795 1.111765404115756 -0.5863619448179365 +0.385219914961819 2.731829628422897 -0.09672684661176777 +-0.8638322676395689 0.2630007119455198 -0.5500472209072181 +-0.8473649943733436 0.8955944062006886 -0.0011477740569024 +0.1771388500279988 2.825380086505342 0.3134089180057883 +-1.81887520511417 2.274263713722099 0.3476721908774474 +-1.035354932949562 2.104643237360982 0.8006679184458998 +1.280354278881496 1.497074261347046 -0.1262169965352874 +-1.197326507960221 2.83798226814815 0.0661402440238921 +-0.5189494538853638 3.050969743694641 -0.02184273737267809 +-1.676792850043046 3.216149992739546 0.08330693011690063 +-1.845872045 2.277809975 0.203361347 +-0.4987254563221143 1.378737844801214 0.09059101326130166 +-0.5328659535555132 0.9885284615404913 1.056028329208654 +-0.4943725459801921 1.048569590662632 1.329762556124923 +-1.503975887693287 2.34794253752604 0.4079496509301841 +-1.489955793704974 1.135210736844036 0.3225308981950958 +-0.4625015617179831 1.434367827112082 -1.105572696555841 +-0.1316979591234131 3.062726555716673 0.4212790638364856 +1.392295407632677 2.502669442500041 0.3272960853300025 +-1.22662212408403 0.2356800174557382 -1.164239034201272 +-1.509366890815462 1.098267365967991 0.6283374402550567 +-1.867779686760026 3.144959616379931 0.2639450922722724 +0.4443106678617818 2.3592992221385 0.4686121011176493 +0.8578403152859112 1.084935521044619 -0.2926991710558834 +0.8939804181684321 1.110911224928505 -0.9315465462613279 +-2.142385690596923 0.5242268634731843 0.2005685427137374 +0.006046707899367345 2.742751155982775 -0.07976431639864184 +-1.183900008250963 0.3080778812275736 -0.9149740785734719 +0.8410989203237985 0.7431193882824975 -0.6401345626713115 +1.975673103815903 2.354334441391013 0.05573563218467954 +0.6413067469765122 0.1601358910282666 -1.338368589609144 +0.7539056299772307 2.878749495556877 0.4502065655429573 +1.387830566972568 1.465722418576842 0.7293926698908851 +0.9065738132394274 1.947776942462929 0.01869895460855813 +0.8608064183012171 1.380854562955311 0.9666595019711658 +0.9262841014312927 1.050836607992385 0.9497702484015053 +0.8386801924537217 1.123036512981791 -0.03219605034361965 +1.435276764112341 1.374967936633841 -0.1078003106629848 +0.7845796956553209 1.038129192881471 -0.6109149171787911 +-1.681714716623598 0.8319068659574417 1.062483861604881 +0.0186675231147997 3.050811756578527 0.2453525866234674 +1.559164038866791 1.306692328294971 0.4274510189812736 +1.521542727373499 2.598658601112731 0.4230970499311686 +-1.359017093248211 3.1116821881996 0.2040272198114173 +-1.442726428868932 0.8105756387312243 1.011889367108308 +-1.83975386908693 0.7746222918308034 -0.2083412054617344 +-1.264203531863839 2.335290246709829 0.5451212602978218 +0.5243540530575461 3.029298504510775 0.07801209134064239 +-0.3996066314706928 3.356401858144328 0.228837317542697 +-0.5222517695156282 0.03202838102501564 -0.2998776534304415 +-1.293109398324332 2.876413978721306 0.05626540838309409 +0.1696144634390263 1.02143805383223 -1.536254348597615 +1.106797666676866 0.2857856413814158 -1.153076703294672 +0.832886358623729 2.838854173664899 0.28869274381099 +0.5234430581764421 2.61878313130027 0.4975677920299552 +-1.856629094442721 1.125352289898826 0.4437590031008895 +-1.388884352192851 1.084389077121495 -0.5796595289340049 +0.3671017187882459 2.840410070793028 -0.2087069977589277 +-0.8302296607625097 1.449166184846042 -0.8809111983408676 +-0.8796235798631215 2.993083113891098 0.1176135276586326 +-1.54941981444165 0.6040132656589206 0.01351272546539318 +1.164183665868629 2.598657741856442 0.2679580129069825 +-0.1492272243008799 1.72945441902413 1.378388778814448 +-1.518472178611528 2.76408696713224 0.1733668819738643 +-0.1241160634174265 1.374120146989027 1.277098365653516 +1.413881238872381 1.43196717925496 0.3188390755194898 +0.2548491292260952 0.02856908617775549 0.591777647581252 +-0.3707381895990153 2.821711077386537 0.6734816397374677 +-0.5945862507613595 0.5092824692361955 -1.511280084698569 +-1.859642533483686 0.4397892594049663 -0.2463927400564648 +-0.8471078154630705 2.916234847399487 -0.0005570222175525324 +-0.1038053437358488 2.18746886466068 -0.6754313789968166 +2.002292466287275 0.3278286243396851 -0.0775015332759081 +-0.1139782752688211 3.141771343626598 0.2064272057294951 +-0.09706476268132314 2.759008109018742 -0.2722567502659319 +-0.3017602075023693 3.333580705455546 0.1650390676816886 +1.537565934569902 1.707621991162579 -0.01234807056044128 +1.189574810977037 2.602845059189402 0.1745147175320508 +0.7250291026921271 3.026245644215963 0.3462507828757707 +-1.851212330243607 3.112462029417894 0.03425200747336645 +0.3851883954852807 2.702931806976332 -0.2928357533120892 +-1.848435400202302 3.232609958060443 0.2456181990048688 +-0.09337212939599121 3.236997162558903 0.08152247514618155 +-1.907750175949961 3.114040338497704 0.09513567762333187 +0.00627305477426116 2.983706300381393 -0.07166485569860964 +0.5451815317634842 2.7799240329318 0.01808682514597143 +-1.447418994423216 2.532823485478766 -0.1125172387056694 +-1.467645273461385 0.394571109020712 -0.6384547953933449 +-1.771061289259795 3.182227035297289 0.02211051428875252 +-1.509917663145444 2.720193708230199 -0.07823323317812386 +-1.024348880490183 0.2236832440222667 -0.9461287130764595 +-1.329071463352441 0.9740232794539077 1.306122144303408 +-1.157290507335658 0.2770595338569992 -1.305916236583235 +-2.167280291769907 0.9796808767960103 0.2552921706541723 +1.912818934904968 2.570866768849995 0.3164894436285017 +-1.907236126644542 3.208932948864175 0.1926396013105794 +-0.7288151732379264 3.122938501569798 0.1169898922406462 +-0.2196159572493549 3.171252489217693 0.3898538132900252 +1.590445675238601 1.81015719733253 0.4949713767298695 +-1.812290294509738 3.296097633287725 0.1910023437403044 +-1.75048443894859 3.289782230504799 0.1107405306901181 +-0.06813973661732049 3.044424607952785 0.1541077503711084 +1.53220729941693 1.233550880680786 -0.2737246900771192 +-2.192233851722258 0.7622597302640749 0.4764408686960045 +-1.569789347432795 0.5260693582907728 0.2967776897331011 +-1.446847197376339 1.402452632718449 0.6153861820728633 +1.6906314272561 1.385137142465171 0.02457086009188659 +-0.03308908383004404 2.878712555696832 0.05485225873294224 +-1.608818791079811 2.351786876753677 0.2140881740910356 +-1.084106793056837 0.3479570808150597 -1.230826460398701 +2.050602628109194 2.375466786124102 0.2067223587047636 +-0.8405681432832518 0.2114447873512528 -0.8287626488015575 +1.230546451349885 1.059393749952099 1.024933055487939 +0.6057397010781959 0.01785855358940717 0.1701667207328308 +1.598992679867345 1.344492723572374 -0.09702918405023375 +0.757579687652941 2.641759973732514 0.1908346483430432 +1.056067522875706 0.7854932223556497 0.4910112670654319 +1.493804371181023 1.297648221238593 -0.447375799999602 +1.797148317561399 2.50640363108106 0.05684362081186753 +1.593371321413195 1.013229056310631 0.747455573048334 +-2.074027538761914 0.6103640748158645 0.3215279650884643 +1.642181084421165 2.297557738158806 0.4378399257293261 +-1.437440119153147 0.4548350787207055 1.021343289295029 +-2.020071347650893 0.9538118248193972 0.3884182846375959 +1.67359756928652 1.976007072766208 -0.04211861959320946 +1.987172490964357 0.4504594939972375 0.3906042089284002 +1.811909586585541 2.465688166857235 0.3733269386179495 +1.396672985804482 1.407408538576475 -0.4762882653622065 +-0.8863806150176461 0.1575746589113867 -1.035664706182791 +1.414435546711266 1.49436080193448 -0.3733248408788739 +0.2647366701510291 2.490366399908819 -0.4640040770943414 +0.0856445098370955 1.906799928272733 0.9160959392844545 +0.3259919979097791 2.950039713396322 0.09711674958958742 +-1.127830642208472 0.3483711963377016 -1.073721644689198 +1.823275281294653 2.075229709545475 0.3739450921206062 +1.930713388487324 2.279094694563206 0.3547581285244466 +-1.137973263345858 0.6796376554534005 0.9888833917249834 +1.259455125627047 1.595490849084478 -0.344348763578161 +-0.09187578289629357 2.894685563810062 0.5890327192985721 +-1.650602286703159 2.632959138717152 0.04053997938824536 +1.663445245223567 1.696431975585676 0.4126656186829347 +1.789357290294743 2.251518390579871 -0.06206698540701932 +1.591365575133403 1.557825170220098 0.3854081362672724 +-1.436799426953421 2.89218668530716 0.04986895062575443 +1.499979904699288 1.292639724849006 0.1420686991022845 +1.351511835 1.29532838 -0.8451032935 +0.4253070181732402 3.050453168153052 0.3783447345241047 +0.554604722810881 0.5234430015829278 -1.524322299138049 +1.267918321592114 1.408575616816102 1.103156215176484 +1.754162008522783 1.207386836460585 -0.3111606598484288 +-1.162440317533654 2.535507556038127 0.5480435823984771 +-0.423071253159845 2.999697260770442 0.531067382789123 +-0.2320318302692008 1.827007606593055 0.4794434365142946 +0.34136065750404 3.093306388939328 0.03498681393471036 +1.360076658887462 1.668724851082138 -0.03434640651939744 +-0.9743983203084265 2.845618150665184 -0.07384456030291749 +1.089591208428935 0.4605169459838854 1.327585722398095 +1.223247707812238 1.819594932007741 -0.5830865758196923 +0.8156876807025013 2.362654384332267 -0.2563909031331266 +-0.8854304685169293 2.954085761058685 0.2549686170217814 +1.094684858699567 0.4606918879575946 -1.361171997946035 +-0.4708902918163268 0.3104611770027264 -1.422729957541789 +-0.7730609335367867 2.683300495261894 0.6564475777991604 +-1.537601730947319 1.295038045896891 -0.4744039120309449 +1.422803248424171 1.652720311650633 0.3798657175388526 +1.036051574739043 0.6596538865154236 1.357167291025465 +-0.5037369550784456 3.093704902047307 0.5689212964490036 +-0.9787897708323646 2.299861705376072 0.7215621041924193 +-1.294406549237574 2.745102473634883 -0.02201747353919393 +1.662413358771222 1.311676187448664 0.1120191091720217 +1.491641319945521 1.510818901601823 0.1947217596706605 +-0.6020154504665692 3.075681185170257 0.2552914824929541 +0.761129608093344 2.83926196602499 0.1170478817463247 +1.922330571039305 2.222756362548697 -0.02066819472247312 +0.3109067242232126 2.973560314440711 0.2834771163543107 +1.69322556327321 1.290356693711007 0.2691099933197209 +0.3169208621785189 0.3407079517479417 -1.48748030286503 +0.6505594293812281 2.945098169053622 0.03521825045873492 +1.520737999099575 1.417822537275525 -0.5433887984633482 +1.339035023521802 2.521203987885521 0.1692646484755724 +-0.1116460214382103 3.059755293733788 -0.01820929230443789 +-0.4975006310626811 0.7643855569621802 -1.454542043635721 +-0.07866204983440518 3.094953953868924 0.3314192032121273 +0.2297652157258286 2.922851999027457 -0.1313359494104697 +-0.4281898515351245 3.292832073197644 0.1151501571226426 +0.6663902068957203 2.984626528784073 0.4099425039437441 +0.2282881148846952 2.980271580883399 0.4544766322492501 +1.119085519398095 0.1783763926600044 0.2552642986103283 +1.438860962342459 2.375454784716942 0.4321696700907702 +-1.874292269866467 3.017320272662716 0.163990212836311 +0.04039529148355008 3.019166411393775 0.3779098889367619 +-0.1705847435330903 3.167507330668113 0.09158656175262113 +0.8165528618891443 0.4134647135108211 -0.2930339182215796 +-0.5544471453267227 3.242143240077366 0.03841500212682155 +1.69887251 1.36623675 -0.258071877 +0.2793842270216402 3.096576204449784 0.3050614813696473 +1.512425778072352 1.400156050847114 -0.2706783068964229 +0.7543377281265249 2.959430507006779 0.07081012121896883 +0.4467596686139064 3.094637700820238 0.0493238736129465 +-1.067423842706351 0.1864329295705503 -1.084212837312977 +1.49705750608735 1.586853327995271 -0.4338946171052173 +1.500660989594738 1.505283894340537 -0.4920691126371847 +-1.715658470796458 3.077705176659538 -0.01531532237650063 +0.1731523372693452 3.042633386848202 0.3389047514476154 +-0.402709988091379 3.286117440308159 0.3993373365393859 +1.263332512143482 1.674128344174959 -0.6361537642092783 +1.628318822711927 1.449991538619126 0.4825910548140701 +0.5440424808396408 3.114739823360668 0.1662121776649288 +1.687513115 1.443410995 -0.224064127 +-0.3044431229471048 3.265728320718919 0.08436267480099606 +-0.9324114082256771 0.2728006028299402 -1.325668104014563 +-1.721262597189583 3.271028074652847 0.2568558957883803 +1.698781497448575 1.541455622455472 -0.1618800495331985 +-0.454753110879269 3.275075959819377 0.2800594062154256 +-1.810599457027451 3.17670998211538 0.3424261027793968 +1.80312777 1.351126195 0.021993786 +-0.5246884232025745 3.262309549571336 0.4151494425791476 +-0.5236630915211022 3.330717861414991 0.3365119563163286 +-0.6719937359052478 3.188792045466881 0.3783706247692844 +0.8947902162205064 1.645769947879702 0.9938181764229221 +-0.3393494665551468 0.591034148034732 1.534625913143627 +-1.068462688420114 0.7440946055131471 1.356518902867134 +1.980353501006344 2.161702915082858 0.1403017446631853 +1.108882821170866 2.316319324086324 0.1823212020437456 +-1.575114837139135 1.599290366165716 0.4794514623554497 +-0.768430908572353 3.020487494769837 0.4219605794590067 +0.7920162753136856 1.329863110317829 -0.910452240788891 +0.4485812111438929 1.968505322180905 0.9751136533295023 +1.334444720894885 1.655659266846987 0.7091831309100002 +-0.6167292571799808 2.632770506626887 0.7365503190525436 +-0.9697297353096679 0.7474100587695444 -1.302622949580899 +-0.3793413653795101 0.3595638347784222 1.491537615878768 +0.248807688677936 1.829293591937311 -0.3964102831199579 +-0.1128133903210552 1.681746069107655 0.5622176567520126 +0.5730645477372849 0.7832701929540072 -0.4952657106242083 +0.6687475448110177 0.7155264675184523 -1.116540465874051 +0.08657534854824678 0.6493984882946885 -0.5783895516403879 +0.1768962490370116 0.7312607753067273 -0.8999849386099213 +-0.1120179650546415 0.8206046493914462 -1.367736281176297 +-0.08199570998499961 1.763593328784365 0.2989251149678222 +-1.226390923545624 1.35685287547833 0.1651192631504017 +-1.182351510699546 1.382953536015887 0.6206653845295208 +1.221881525133501 0.544446938436469 0.826525185347903 +0.04607916112503271 0.350584313959409 1.099552257337541 +0.5818844639430051 1.509204089623594 -0.2135711162488347 +0.5282147901029605 1.048619360387732 -0.7050115974114194 +0.2086711455815342 0.9851463790263688 0.5441039521501976 +-0.2075840579705437 2.680847185714078 -0.06399887348694715 +-0.06573364212791342 2.390447408289156 0.0376149635593901 +-0.1438186878530379 2.046888716556675 0.4871382033572507 +-0.7558506189627503 0.7216146636599501 0.1611306865665708 +-0.8216146583141321 0.7606456983275468 -0.4916464365881291 +-0.5248413541524377 0.788659334992835 -0.4236897059020337 +-0.4705582483023025 0.6536024581276545 -0.6731298586058354 +-0.8659256196285009 2.172632780800838 0.1944110890385059 +-0.812889819170928 1.02816466209015 0.4198493543764589 +-0.8595488851462175 1.011638441668027 -0.8369006473290929 +1.454335922823551 0.4694426329616132 0.488128107016165 +-1.461465752648496 1.382952157581641 0.2764282481155656 +0.8189581626022919 0.6756021761103747 -0.1038191280969629 +-1.559672278453779 1.852573865362416 0.140143360668665 +0.9258987323819284 0.4631607598609489 0.8430536677654842 +0.9137209362692599 2.14434277086151 0.3206639490588392 +0.8317666240072863 2.395603831908021 0.06830473198394335 +0.5755308720177239 3.092532600967764 0.3243025714837448 +-0.1680189856007794 1.8780760548878 0.7183995762294854 +-0.857299789819255 0.9057910647993745 -0.6486624620116627 +0.8847583632742176 0.4183907727896373 1.42175334513435 +1.630686711187349 1.545477580386198 -0.03319432540654383 +-0.3828080628074074 1.753171432124959 0.9515516497412975 +-0.655954911596943 0.7087396796850985 -0.593916013287443 +-0.2420734399341969 3.015513634035925 0.5424492648603049 +-0.9766982180333665 1.063285038664783 -0.6165383293281937 + +CELLS 10415 52075 +4 0 1 3 2427 +4 1997 673 1697 2374 +4 1482 1781 1332 1776 +4 0 2332 3 2 +4 0 2 6 2004 +4 166 1973 2184 802 +4 1150 1194 1487 1154 +4 549 442 2323 1730 +4 2 2004 8 6 +4 2 7 8 2004 +4 2297 2300 1642 1643 +4 1427 1840 1649 1498 +4 2288 1750 1772 2095 +4 2077 1630 1675 2038 +4 1944 1238 2340 1865 +4 2526 2112 1825 2163 +4 4 5 1 1772 +4 4 20 15 1717 +4 964 969 1035 2117 +4 1809 2542 1798 1856 +4 1035 1047 2165 1856 +4 2237 1371 1832 1681 +4 98 1726 178 194 +4 1698 1963 1968 2539 +4 7 2004 13 8 +4 1501 1569 1493 2422 +4 7 9 22 1734 +4 2280 1480 1663 1552 +4 7 1734 22 18 +4 8 13 21 2376 +4 8 2376 21 19 +4 9 17 22 2094 +4 1565 1849 1913 2463 +4 1072 1808 1534 1073 +4 1734 1502 1511 2275 +4 1986 1842 1969 2471 +4 12 1717 20 4 +4 2160 1208 1013 1195 +4 13 18 28 1734 +4 13 2376 30 21 +4 13 28 30 2376 +4 2439 1493 2392 2354 +4 1913 2549 1651 1013 +4 1138 2160 1195 1156 +4 15 1717 27 16 +4 15 20 33 1717 +4 15 1717 33 27 +4 1910 2365 1708 1589 +4 1283 2036 2575 1320 +4 18 28 1734 85 +4 19 21 65 2376 +4 19 2352 65 26 +4 19 2352 2376 65 +4 646 650 2323 1755 +4 1557 2169 1475 2104 +4 1974 1890 2045 2097 +4 21 30 78 2376 +4 51 2446 97 68 +4 1721 1995 2022 1722 +4 89 1489 1734 22 +4 64 1520 129 96 +4 325 2528 402 389 +4 2488 630 692 2545 +4 1266 2575 1306 1283 +4 2414 2310 1743 839 +4 2147 2342 2341 1861 +4 2185 2265 2052 1793 +4 32 38 2060 2496 +4 26 2352 82 42 +4 26 65 82 2352 +4 598 2278 596 536 +4 1801 16 1717 2362 +4 1712 2100 1722 1713 +4 28 30 2376 83 +4 28 1511 122 83 +4 28 85 122 1511 +4 2151 1655 1567 2162 +4 348 401 416 1960 +4 1975 2130 851 2164 +4 36 22 413 1489 +4 2457 2474 1601 1603 +4 1743 2310 1794 839 +4 29 2496 34 38 +4 855 2017 975 920 +4 29 32 35 2496 +4 2017 975 981 2027 +4 29 2328 37 34 +4 29 35 41 2328 +4 29 2328 41 37 +4 30 2376 113 78 +4 30 83 113 2376 +4 1013 1889 1232 1240 +4 274 279 1542 2450 +4 31 2206 93 73 +4 370 390 1531 2247 +4 801 1504 841 827 +4 462 424 1552 2537 +4 2017 975 1017 912 +4 32 29 38 2496 +4 32 2496 39 35 +4 2060 2271 1529 2496 +4 38 2157 2060 2496 +4 32 2060 45 51 +4 32 2496 2060 39 +4 32 2060 53 45 +4 33 42 67 2126 +4 33 2126 67 102 +4 1041 1107 1111 1505 +4 34 37 40 2328 +4 34 2496 44 38 +4 34 40 47 2328 +4 35 2496 46 2390 +4 35 2390 48 41 +4 35 46 48 2390 +4 36 1489 120 89 +4 275 314 1880 1524 +4 36 98 120 1489 +4 2461 1536 2032 2037 +4 37 2402 50 55 +4 166 2424 2503 2409 +4 1013 1889 2549 1651 +4 37 56 50 2402 +4 286 2214 2429 2015 +4 38 44 52 2157 +4 38 52 69 2060 +4 38 2060 69 53 +4 39 32 51 2060 +4 35 39 46 2496 +4 166 2503 2344 2409 +4 39 68 54 1529 +4 1179 2339 1892 1863 +4 1556 385 2182 353 +4 40 2328 61 47 +4 40 37 55 2402 +4 40 55 61 2388 +4 1073 1086 1534 1099 +4 41 48 60 1530 +4 41 1530 60 56 +4 2183 1644 1645 2029 +4 1711 1767 1710 2166 +4 42 2126 103 67 +4 42 2126 1777 103 +4 42 82 103 1777 +4 1626 1730 1670 2280 +4 916 970 914 2454 +4 1616 1510 2222 1728 +4 1726 1508 25 73 +4 914 2117 971 904 +4 2531 2141 1558 1523 +4 44 2157 74 52 +4 44 59 62 2521 +4 44 62 74 2157 +4 45 1528 77 51 +4 2413 2241 2476 1914 +4 45 53 66 1528 +4 45 53 1528 2060 +4 45 66 77 1528 +4 46 2390 58 48 +4 46 2386 63 58 +4 376 381 418 2297 +4 47 2328 61 59 +4 48 58 70 2390 +4 48 1530 70 60 +4 1066 1041 1111 2479 +4 914 970 971 2454 +4 2079 2254 1465 1667 +4 71 56 76 1530 +4 711 2404 662 679 +4 2402 1530 56 71 +4 322 2113 348 2015 +4 27 64 96 1520 +4 27 86 92 1520 +4 27 1520 96 86 +4 51 1529 68 39 +4 850 2387 898 2364 +4 358 2259 425 371 +4 52 2060 100 69 +4 53 1528 81 66 +4 27 1801 1717 1520 +4 53 69 105 1528 +4 53 1528 105 81 +4 598 2278 671 649 +4 838 850 877 2364 +4 54 68 99 1529 +4 54 1529 99 75 +4 54 63 1529 75 +4 55 2388 90 61 +4 55 50 79 2402 +4 55 79 90 2388 +4 1505 2143 2570 1836 +4 56 60 84 1530 +4 671 2381 649 2278 +4 56 1530 84 76 +4 362 299 315 2136 +4 57 1518 121 93 +4 57 95 121 1605 +4 508 2278 590 520 +4 23 57 2362 49 +4 58 63 88 2386 +4 58 2386 88 70 +4 59 2521 91 62 +4 2521 72 91 123 +4 2369 1463 724 2371 +4 60 70 94 1530 +4 60 1530 94 84 +4 61 101 72 2521 +4 61 90 101 2521 +4 62 2157 111 74 +4 62 91 111 2157 +4 903 823 945 2454 +4 63 2509 106 88 +4 64 33 102 2126 +4 1221 1218 1270 1251 +4 64 102 129 1718 +4 65 78 155 1515 +4 2194 1634 2081 1467 +4 65 1515 155 82 +4 39 2496 54 46 +4 1010 2298 1059 1014 +4 561 2468 617 605 +4 66 1528 109 77 +4 66 81 2317 1921 +4 67 2126 128 102 +4 67 103 128 2126 +4 1501 1503 2361 1569 +4 2219 817 2262 845 +4 545 1669 1480 646 +4 68 1529 130 99 +4 1243 1288 2248 1246 +4 945 2298 1802 957 +4 69 1528 133 105 +4 796 2212 807 2493 +4 908 2230 961 955 +4 70 88 114 2386 +4 70 2395 114 94 +4 71 76 107 2406 +4 71 2406 107 112 +4 59 61 72 2521 +4 73 1998 148 80 +4 73 93 148 1998 +4 1072 1534 1106 1099 +4 74 2157 144 100 +4 137 2509 201 169 +4 144 188 2157 111 +4 74 2157 111 144 +4 75 99 132 1529 +4 2337 2027 981 985 +4 75 1529 132 106 +4 75 63 1529 106 +4 76 84 104 1530 +4 76 104 107 2406 +4 77 1528 131 97 +4 77 51 1528 97 +4 77 109 131 1528 +4 78 113 167 1515 +4 78 1515 167 155 +4 79 2406 116 90 +4 79 71 112 2406 +4 79 112 116 2406 +4 2336 1419 1434 2529 +4 547 2315 594 592 +4 2515 1252 2501 2503 +4 1800 1950 1813 1215 +4 957 2298 1010 967 +4 1156 2160 1208 1885 +4 81 1921 2311 2317 +4 81 105 141 1528 +4 510 573 514 2120 +4 81 1921 141 2311 +4 210 223 250 1542 +4 82 1777 164 103 +4 830 1497 2438 2534 +4 608 1668 525 2320 +4 83 2376 170 113 +4 2113 1578 1960 348 +4 83 122 183 1511 +4 947 2121 954 974 +4 83 1511 183 170 +4 84 94 108 1530 +4 84 1530 108 104 +4 637 2374 603 602 +4 85 214 1511 1502 +4 85 1502 216 214 +4 621 616 644 2511 +4 86 1523 110 92 +4 280 2198 335 313 +4 86 92 1520 1523 +4 86 96 119 1523 +4 1744 1504 2051 2310 +4 86 1523 1520 96 +4 86 1523 119 110 +4 87 92 118 1521 +4 87 1521 126 95 +4 87 118 126 1521 +4 2296 2385 1021 1030 +4 114 106 137 2509 +4 88 2509 106 114 +4 89 120 216 1489 +4 90 2518 127 101 +4 90 116 127 2518 +4 91 2157 153 111 +4 91 123 153 2521 +4 92 110 117 1523 +4 92 117 118 1521 +4 1309 1279 1251 2203 +4 93 121 2139 1518 +4 93 1998 2346 148 +4 94 1530 115 108 +4 509 1478 956 1957 +4 115 114 138 2395 +4 94 2395 114 115 +4 95 1605 160 121 +4 95 126 160 1521 +4 96 2202 159 119 +4 96 129 159 1557 +4 364 395 405 1874 +4 876 2236 2201 859 +4 130 1529 2446 2396 +4 1726 194 1489 2150 +4 1290 2426 1242 2021 +4 125 1525 143 109 +4 933 2571 965 960 +4 99 130 176 1529 +4 99 1529 176 132 +4 100 144 179 1899 +4 1108 1123 1124 2368 +4 101 2521 161 123 +4 101 127 161 2518 +4 102 128 165 1718 +4 103 1777 184 128 +4 103 164 184 1777 +4 424 2033 468 1552 +4 1913 1885 2549 1013 +4 104 108 145 2407 +4 104 145 149 2407 +4 105 1528 175 141 +4 798 2460 811 847 +4 105 1528 133 175 +4 106 132 174 1529 +4 106 1529 174 137 +4 106 2509 1529 137 +4 685 2282 708 689 +4 616 2511 639 638 +4 108 115 139 1530 +4 108 139 145 2407 +4 109 1525 173 131 +4 109 2415 1525 131 +4 109 143 173 1525 +4 110 1523 124 117 +4 110 119 135 1523 +4 110 1523 135 124 +4 1285 1307 2447 2405 +4 111 153 188 2157 +4 728 2489 773 772 +4 2406 2407 149 2518 +4 2486 2251 2246 2257 +4 113 1515 199 167 +4 113 170 199 1515 +4 113 1515 2376 170 +4 142 141 171 1525 +4 2524 2523 1648 2520 +4 2228 1933 2205 2218 +4 114 137 169 2509 +4 114 2509 169 138 +4 634 600 652 2468 +4 557 587 589 2524 +4 178 194 1726 1539 +4 115 134 139 2395 +4 115 2395 138 134 +4 134 138 162 2395 +4 116 2518 156 127 +4 154 2518 198 156 +4 117 1521 147 118 +4 117 124 136 1523 +4 118 1521 163 126 +4 118 147 163 1521 +4 119 2202 159 172 +4 1265 2068 2513 1269 +4 120 194 233 1489 +4 120 1489 233 216 +4 2486 2325 2251 2257 +4 121 160 195 1518 +4 779 811 2274 781 +4 121 1518 195 2139 +4 821 2460 854 858 +4 122 1511 232 183 +4 122 214 232 1511 +4 122 214 1511 85 +4 123 2521 193 153 +4 123 161 193 2521 +4 2492 954 974 979 +4 879 892 897 1795 +4 140 2567 1523 2204 +4 124 1523 140 136 +4 140 2567 2204 150 +4 125 142 157 1525 +4 1551 2199 2008 1590 +4 125 1525 158 143 +4 125 1525 157 146 +4 125 146 158 1525 +4 1467 2459 1679 921 +4 126 1521 192 160 +4 126 163 192 1521 +4 483 521 526 2532 +4 127 156 185 2518 +4 127 2518 185 161 +4 128 2470 204 165 +4 2131 2363 1545 2199 +4 128 165 1718 2470 +4 128 184 204 1996 +4 2540 2572 2459 1467 +4 993 1024 2156 2121 +4 124 2204 150 140 +4 969 1022 1028 2117 +4 820 807 2281 2493 +4 1293 1338 2401 2248 +4 1004 1044 1023 2156 +4 130 2396 209 176 +4 130 1529 2396 176 +4 130 206 209 1962 +4 131 173 206 1962 +4 131 1962 1525 173 +4 132 1529 207 174 +4 132 176 207 1529 +4 174 207 228 1529 +4 134 2395 177 139 +4 134 162 177 2395 +4 135 2204 172 150 +4 135 119 172 2202 +4 136 140 151 1523 +4 151 2531 1523 2141 +4 151 168 2531 2141 +4 2344 2241 1806 2451 +4 2378 2273 749 742 +4 924 2337 989 931 +4 137 174 201 1529 +4 201 2509 1529 213 +4 138 2509 196 162 +4 107 149 152 2406 +4 138 169 196 2509 +4 41 37 2402 56 +4 140 146 151 2567 +4 140 2567 158 146 +4 140 150 158 2567 +4 135 1523 2204 124 +4 453 477 481 1648 +4 141 175 203 2321 +4 1893 1977 2507 2444 +4 1066 2479 2360 1838 +4 141 2321 1528 175 +4 388 2532 420 395 +4 141 203 171 2321 +4 420 479 432 2532 +4 141 1525 2415 2321 +4 142 1525 186 157 +4 142 171 186 1525 +4 143 158 187 1525 +4 143 1525 187 173 +4 144 1899 188 179 +4 2355 589 2520 613 +4 145 2407 197 149 +4 145 190 197 2407 +4 146 2567 157 151 +4 146 2567 1525 157 +4 146 158 1525 2567 +4 147 2531 189 163 +4 147 163 1521 2531 +4 147 168 189 2531 +4 147 2531 117 136 +4 148 259 248 2351 +4 2420 2035 1917 925 +4 601 2057 595 1799 +4 564 533 2524 2523 +4 909 2514 935 913 +4 107 104 149 2406 +4 152 2406 2518 112 +4 150 2567 182 158 +4 150 172 182 2204 +4 150 2567 2204 182 +4 151 157 180 2141 +4 151 2141 180 168 +4 147 2531 136 168 +4 154 116 2518 156 +4 112 2518 152 154 +4 153 2157 215 188 +4 153 193 215 2157 +4 1524 340 343 303 +4 2354 932 905 2514 +4 1239 2144 2428 1271 +4 136 151 168 2531 +4 292 2181 337 319 +4 337 2181 364 361 +4 272 2396 2475 281 +4 228 2396 272 241 +4 155 167 225 2394 +4 155 2394 1515 167 +4 1021 1030 1067 2360 +4 156 2518 198 185 +4 157 2099 186 180 +4 157 2099 1525 186 +4 667 685 689 2382 +4 158 182 187 2567 +4 158 187 1525 2567 +4 159 2221 212 172 +4 159 172 2202 2221 +4 159 191 212 1557 +4 1401 1419 1420 2336 +4 402 1624 1556 427 +4 160 2412 1521 192 +4 160 195 1518 2327 +4 161 185 210 2518 +4 161 2521 210 193 +4 162 2316 205 177 +4 162 196 205 2509 +4 2420 2035 1784 1917 +4 163 189 192 2531 +4 791 2502 2262 842 +4 1029 1093 1095 2574 +4 164 184 1996 2289 +4 149 197 200 2518 +4 165 204 222 2470 +4 165 222 240 2470 +4 259 195 262 2351 +4 860 2200 929 922 +4 1420 2336 1440 1430 +4 1598 1964 2195 2167 +4 167 199 225 2394 +4 1973 802 1891 2232 +4 167 2394 1515 199 +4 866 858 884 2460 +4 2522 2476 2102 1337 +4 168 180 202 2141 +4 679 2404 702 714 +4 168 2531 202 189 +4 168 202 2531 2141 +4 136 151 2531 1523 +4 169 2509 213 196 +4 169 2509 201 213 +4 170 183 230 1511 +4 170 2394 231 199 +4 170 230 231 2394 +4 170 2096 1511 230 +4 170 230 2394 2096 +4 642 643 667 2516 +4 170 2096 2269 1511 +4 171 1566 217 186 +4 1349 1947 1404 1906 +4 171 186 1525 1566 +4 171 203 217 1566 +4 172 182 2204 2221 +4 172 182 2221 212 +4 182 1562 2221 212 +4 173 187 221 1582 +4 173 1582 1525 187 +4 173 1582 221 206 +4 173 206 1962 1582 +4 1747 2439 2310 839 +4 174 1529 228 201 +4 201 228 241 1529 +4 176 2396 237 207 +4 176 209 237 2396 +4 207 237 255 2396 +4 206 2393 244 209 +4 206 209 1962 2393 +4 773 774 775 2347 +4 177 2316 218 190 +4 177 205 218 2316 +4 178 181 253 1539 +4 178 1539 263 194 +4 178 253 263 1539 +4 713 718 766 2445 +4 180 186 211 2099 +4 180 2141 211 202 +4 181 2429 260 253 +4 181 253 1539 2429 +4 1481 1825 2030 836 +4 1667 2191 2079 2254 +4 182 1562 220 187 +4 182 2567 1562 187 +4 182 212 220 1562 +4 2193 2078 2318 1678 +4 182 2204 2221 2567 +4 183 1511 252 230 +4 183 232 252 1511 +4 1410 2264 1414 1426 +4 184 2131 243 204 +4 184 204 1996 2131 +4 1996 2363 2131 204 +4 112 2518 154 116 +4 185 198 223 2518 +4 185 2518 223 210 +4 186 2099 217 211 +4 186 217 2099 1566 +4 417 2366 394 429 +4 186 1566 2099 1525 +4 187 220 221 1562 +4 1707 2047 917 1543 +4 296 273 2031 2151 +4 188 215 271 1899 +4 720 2497 772 769 +4 189 2531 224 192 +4 189 202 224 2531 +4 190 2316 227 197 +4 190 218 227 2316 +4 2486 2227 1145 1164 +4 1237 2431 1218 2032 +4 601 2473 1799 626 +4 2043 1653 2055 2025 +4 192 224 236 1560 +4 192 1560 2412 224 +4 1634 1679 1956 921 +4 1574 467 2418 2308 +4 192 1555 2412 1560 +4 193 210 239 2157 +4 193 2157 239 215 +4 1636 921 2193 1683 +4 194 1538 254 233 +4 2318 1956 1673 2078 +4 194 263 254 1539 +4 194 254 1538 1539 +4 195 1555 280 262 +4 195 2327 1549 1518 +4 196 2509 234 205 +4 196 213 234 2509 +4 1013 2419 1651 1858 +4 107 2406 152 112 +4 1913 1013 1651 1858 +4 198 2518 229 223 +4 199 2394 245 225 +4 199 231 245 2394 +4 2174 1964 1678 1943 +4 2380 716 731 732 +4 344 347 365 2304 +4 116 2406 112 2518 +4 201 1529 241 213 +4 751 752 2025 691 +4 213 241 257 1529 +4 202 211 238 2001 +4 203 1566 258 217 +4 204 2131 264 222 +4 1766 2552 1926 1773 +4 204 1551 2131 222 +4 204 243 264 2131 +4 1581 2196 1615 1509 +4 1896 2229 1536 1897 +4 204 2363 2131 1551 +4 205 1542 246 218 +4 205 234 246 2509 +4 1013 1889 1651 2419 +4 206 221 273 1582 +4 206 1582 273 244 +4 173 1582 1962 1525 +4 206 1962 1582 2393 +4 207 1529 2396 228 +4 228 255 272 2396 +4 209 2393 268 237 +4 209 237 2396 2393 +4 209 244 268 2393 +4 210 2157 1542 239 +4 210 1542 250 239 +4 211 217 249 2099 +4 1833 2570 2569 1832 +4 211 2001 249 238 +4 212 1562 261 220 +4 2289 2363 1545 2131 +4 212 2158 191 261 +4 212 2158 1557 191 +4 213 1529 257 234 +4 213 2509 1529 234 +4 1464 2184 166 1973 +4 1614 2577 2558 2559 +4 2558 1925 1586 2573 +4 214 216 289 1502 +4 214 2010 288 232 +4 214 232 1511 2010 +4 1595 991 2302 1633 +4 214 1511 1502 2010 +4 1579 1930 1623 1993 +4 216 233 289 1502 +4 166 2313 802 2344 +4 380 2537 2016 428 +4 217 1566 258 249 +4 217 249 2099 1566 +4 218 1542 251 227 +4 218 246 251 1542 +4 219 225 270 1507 +4 219 1545 275 226 +4 219 270 301 1524 +4 219 1524 301 275 +4 1823 1861 1470 1050 +4 2044 1583 2067 1982 +4 220 1562 267 221 +4 220 261 267 1562 +4 221 267 273 1562 +4 222 2008 291 240 +4 222 1551 2008 240 +4 222 278 291 2008 +4 223 229 256 1542 +4 224 1560 265 236 +4 224 238 265 1560 +4 225 245 270 1507 +4 226 1545 275 243 +4 227 1542 256 229 +4 227 251 256 1542 +4 207 2396 255 228 +4 230 2394 269 231 +4 230 252 307 2096 +4 230 2096 1511 252 +4 230 2096 307 269 +4 1576 1912 2023 1577 +4 1950 1818 1215 2111 +4 231 2394 276 245 +4 231 269 276 2394 +4 232 2010 297 252 +4 232 252 1511 2010 +4 232 288 297 2010 +4 233 254 299 1538 +4 233 1538 299 289 +4 1071 1813 1959 1834 +4 234 2509 1529 246 +4 235 2353 290 258 +4 235 266 290 1568 +4 236 265 280 1560 +4 237 2393 283 255 +4 237 255 2396 2393 +4 237 268 283 2393 +4 238 249 277 2001 +4 238 1560 277 265 +4 238 277 1560 2001 +4 240 2011 317 261 +4 240 291 317 2011 +4 240 2011 2008 291 +4 241 2450 281 257 +4 241 281 2450 2396 +4 242 1568 292 266 +4 243 1545 293 264 +4 243 275 293 1545 +4 1332 1988 1872 2040 +4 1332 1872 1781 1940 +4 244 2151 296 268 +4 244 1582 273 2151 +4 245 1507 282 270 +4 245 276 282 1507 +4 246 1542 279 251 +4 1050 1332 2040 1988 +4 248 259 312 2014 +4 249 2001 285 277 +4 89 1489 22 36 +4 22 2094 413 1734 +4 252 2096 316 307 +4 252 297 316 2096 +4 253 260 286 2429 +4 253 1539 287 263 +4 253 286 287 1539 +4 253 286 1539 2429 +4 254 1538 315 299 +4 255 2396 295 272 +4 255 295 2396 2393 +4 255 283 295 2393 +4 257 2450 294 274 +4 257 281 294 2450 +4 259 2034 325 312 +4 259 2034 262 2398 +4 260 2015 322 286 +4 1476 1757 1631 2365 +4 260 310 322 2015 +4 261 2012 317 267 +4 261 240 2158 191 +4 262 280 313 1555 +4 263 1539 302 254 +4 263 287 302 1539 +4 265 277 311 1560 +4 265 1560 311 280 +4 266 1568 319 290 +4 266 292 319 1568 +4 267 2031 324 273 +4 273 324 333 2031 +4 1813 1565 1215 1818 +4 1215 1834 2568 1813 +4 268 2151 321 283 +4 268 296 321 2151 +4 269 2118 305 276 +4 269 2118 307 305 +4 270 1524 303 301 +4 272 281 241 2396 +4 272 295 308 2475 +4 272 2475 308 281 +4 273 2031 333 296 +4 274 2450 304 279 +4 1542 2205 1529 2450 +4 274 294 304 2450 +4 279 2228 1542 2450 +4 275 293 1880 314 +4 276 2334 326 282 +4 276 282 1507 2334 +4 276 305 351 1574 +4 276 1574 1507 2118 +4 276 2334 351 326 +4 277 285 332 1600 +4 277 1560 332 311 +4 254 302 315 1539 +4 254 315 1538 1539 +4 278 2008 367 291 +4 278 355 367 2008 +4 278 2008 264 355 +4 279 304 306 2228 +4 1857 2184 1234 1935 +4 307 316 357 2118 +4 1857 1234 2184 1888 +4 1882 1873 2045 1234 +4 2045 1890 1888 1873 +4 1827 1828 1944 2340 +4 280 2198 1555 1560 +4 1827 1944 1238 2340 +4 1238 1536 2037 2229 +4 281 308 320 2475 +4 282 326 2440 2334 +4 283 2151 334 295 +4 283 321 334 2151 +4 285 300 342 2197 +4 285 1600 342 332 +4 285 342 1600 2197 +4 286 1539 328 287 +4 286 1578 348 328 +4 286 1578 2015 348 +4 2214 1539 2429 2170 +4 287 1539 329 302 +4 287 328 329 1539 +4 288 2090 363 297 +4 289 299 2136 1538 +4 290 300 258 2353 +4 291 1910 386 317 +4 291 367 386 1910 +4 1611 1477 2083 1610 +4 1475 1598 1522 1562 +4 1475 1932 1562 1558 +4 293 1880 336 341 +4 293 341 264 1545 +4 294 2357 327 304 +4 294 320 327 2357 +4 280 311 356 1560 +4 1475 1594 1522 1598 +4 2537 1966 1869 455 +4 280 1560 356 2198 +4 295 2475 339 308 +4 295 334 339 2475 +4 296 1602 358 321 +4 296 321 2151 1602 +4 296 333 358 2031 +4 1475 2104 1932 1558 +4 244 2151 273 296 +4 297 2090 363 316 +4 298 306 323 2277 +4 298 2277 2228 306 +4 300 2197 360 342 +4 301 1524 340 314 +4 302 1539 350 315 +4 302 329 350 1539 +4 1722 1490 1775 1847 +4 2075 1722 1490 1775 +4 2075 1776 1775 1490 +4 1490 1781 1775 1847 +4 304 1570 331 306 +4 1490 1776 1775 1781 +4 304 327 331 1570 +4 305 307 338 2118 +4 305 338 351 1574 +4 305 1574 2118 338 +4 305 1574 276 2118 +4 1738 1371 2244 1929 +4 317 1597 1910 386 +4 1782 2053 1482 1949 +4 2053 1949 1332 1482 +4 306 1570 331 323 +4 1949 2040 1482 1788 +4 730 1526 1463 2369 +4 1680 1463 1630 1526 +4 1949 2040 1332 1482 +4 307 2118 357 338 +4 1782 1949 1482 1788 +4 308 2475 339 345 +4 281 294 2475 320 +4 309 323 337 2181 +4 309 337 292 2181 +4 310 312 391 1585 +4 310 1941 2014 312 +4 310 1585 391 322 +4 310 322 2015 1941 +4 310 322 1941 1585 +4 311 332 370 2247 +4 341 382 1983 1880 +4 311 1596 370 356 +4 311 356 1560 1596 +4 1966 1880 1983 455 +4 2247 1531 1596 1600 +4 312 2528 389 1585 +4 312 2528 2034 325 +4 312 325 389 2528 +4 312 389 391 1585 +4 455 1625 1983 2563 +4 312 2014 2528 1941 +4 313 335 385 1593 +4 313 262 1555 2182 +4 314 2537 352 336 +4 314 340 352 2537 +4 2006 2238 1864 1503 +4 2138 2238 2006 1503 +4 315 350 378 1576 +4 315 1576 1538 1539 +4 316 1961 379 357 +4 316 363 379 1961 +4 1609 1654 1484 2146 +4 316 357 2118 1961 +4 317 1597 386 324 +4 2146 1484 1615 1654 +4 85 1734 1511 28 +4 1654 1484 1615 1659 +4 1794 1493 2310 2051 +4 292 2181 1568 2243 +4 2181 361 319 2457 +4 320 2314 346 327 +4 320 308 345 2475 +4 320 345 346 2314 +4 321 1602 371 334 +4 321 334 2151 1602 +4 321 358 371 1602 +4 2209 2453 1493 2571 +4 286 348 2015 322 +4 2113 1960 401 348 +4 322 391 401 1585 +4 322 401 2113 1585 +4 322 2113 401 348 +4 348 2113 1578 2015 +4 323 331 347 1570 +4 323 2304 347 344 +4 324 1597 399 333 +4 324 333 2031 1597 +4 324 386 399 1597 +4 325 353 402 1556 +4 325 1556 2034 353 +4 402 1556 1585 2528 +4 325 1556 402 2528 +4 2514 2571 1493 1838 +4 325 1556 2528 2034 +4 2528 1585 402 389 +4 326 2506 392 349 +4 392 351 406 2506 +4 326 351 2506 2397 +4 326 2506 351 392 +4 327 1570 346 331 +4 331 346 347 1570 +4 328 2214 359 329 +4 328 348 374 1578 +4 328 1578 374 359 +4 330 361 403 1603 +4 330 2457 319 361 +4 330 1603 403 372 +4 332 342 390 1600 +4 370 1531 1596 2247 +4 333 358 2031 1571 +4 333 399 411 1597 +4 333 1571 1597 411 +4 333 2031 1597 1571 +4 357 397 1961 379 +4 334 1602 381 376 +4 334 339 2475 2093 +4 334 371 381 1602 +4 335 356 409 1593 +4 335 2198 280 356 +4 335 356 1593 2198 +4 335 1593 409 385 +4 336 2537 412 382 +4 2181 1874 365 364 +4 344 2181 365 364 +4 1659 1486 1699 1706 +4 2132 1659 1486 1699 +4 337 364 2181 344 +4 292 1568 2181 319 +4 338 357 375 1574 +4 338 1574 2118 357 +4 1699 1486 1700 1706 +4 339 2093 376 345 +4 320 2314 2475 345 +4 339 345 2475 2093 +4 339 2093 334 376 +4 2003 1936 1487 1887 +4 334 2093 1602 376 +4 1798 1856 2003 1487 +4 341 1983 440 355 +4 1798 1487 2003 1936 +4 341 355 264 1589 +4 341 264 1545 1589 +4 342 360 408 2312 +4 342 360 2312 2197 +4 342 1600 408 390 +4 343 354 383 2016 +4 343 2016 383 380 +4 347 1604 2304 1570 +4 2304 347 365 366 +4 369 1604 368 346 +4 345 2093 376 369 +4 346 1604 366 347 +4 346 347 1570 1604 +4 346 1604 368 366 +4 348 1578 416 374 +4 416 486 1578 1960 +4 350 378 1576 1577 +4 351 338 406 1574 +4 406 338 419 1574 +4 353 385 427 1556 +4 353 1556 427 402 +4 354 2016 396 383 +4 2527 1618 1624 1682 +4 355 2365 452 367 +4 2527 1668 1682 1624 +4 355 440 442 1983 +4 355 442 452 2365 +4 356 370 431 1531 +4 356 1593 431 409 +4 356 431 1593 1531 +4 357 375 1574 397 +4 1609 1484 1614 2146 +4 357 397 1574 2118 +4 358 2259 1602 1571 +4 2146 1614 1615 1484 +4 359 374 400 1578 +4 359 1578 400 377 +4 359 377 1577 1578 +4 1251 2291 1916 2203 +4 360 372 423 2474 +4 360 2474 423 408 +4 1993 1673 1930 1991 +4 361 364 405 1603 +4 361 1603 433 403 +4 361 405 433 1603 +4 362 1575 436 363 +4 1993 1991 1666 1673 +4 1821 2063 2551 1464 +4 363 1961 437 379 +4 1821 1464 2330 1974 +4 364 365 395 1874 +4 365 388 395 1874 +4 366 368 387 1604 +4 367 1910 461 386 +4 367 452 461 2365 +4 368 369 404 1604 +4 368 1604 394 387 +4 368 1604 404 394 +4 369 376 418 2462 +4 369 2462 418 404 +4 370 390 448 1531 +4 370 1531 448 431 +4 1465 1991 1953 2254 +4 371 1602 438 381 +4 358 425 2259 1571 +4 2206 73 24 1508 +4 338 375 419 1574 +4 1634 1465 1930 1679 +4 372 403 451 1603 +4 936 840 1779 1786 +4 372 2474 451 423 +4 373 2517 407 396 +4 373 398 410 2517 +4 936 1824 1786 1779 +4 374 1578 435 400 +4 374 416 435 1578 +4 375 1574 421 419 +4 375 421 1574 397 +4 376 2093 1602 2297 +4 1776 2070 1492 1822 +4 1776 1822 1492 2046 +4 376 2462 2297 418 +4 377 400 457 1578 +4 1963 1826 1827 1512 +4 2551 1550 1512 1827 +4 378 441 1576 1577 +4 1963 1826 1512 2063 +4 2046 1883 1822 1492 +4 1492 1472 1883 1822 +4 1492 1472 1822 2070 +4 386 461 470 1476 +4 379 437 397 1961 +4 357 2118 1961 397 +4 381 2297 438 443 +4 381 438 2297 1602 +4 382 412 462 2537 +4 383 396 430 1740 +4 383 2033 430 428 +4 385 1556 490 427 +4 386 1597 470 399 +4 962 2156 1023 1503 +4 415 414 2466 387 +4 388 415 420 2532 +4 389 1585 464 391 +4 389 402 460 1585 +4 389 460 464 1585 +4 390 1531 465 448 +4 962 1503 1805 2156 +4 391 1585 473 401 +4 1777 1547 1516 1989 +4 391 464 473 1585 +4 392 1573 450 398 +4 392 406 456 2435 +4 419 421 467 1574 +4 395 2532 432 405 +4 364 405 1603 1874 +4 405 2532 432 458 +4 396 407 434 1740 +4 396 1740 2517 407 +4 396 1740 434 430 +4 396 1740 2016 2517 +4 1519 1118 2127 2133 +4 398 2517 445 410 +4 398 1573 450 445 +4 399 411 1597 480 +4 399 470 480 1597 +4 411 1639 1597 480 +4 400 435 446 1578 +4 400 446 457 1578 +4 401 473 486 1960 +4 402 427 469 1624 +4 402 1585 463 460 +4 402 1624 469 463 +4 402 463 1585 1624 +4 402 1585 1556 1624 +4 403 433 478 2469 +4 403 2469 1603 433 +4 403 2469 478 451 +4 403 451 1603 2469 +4 404 418 444 1644 +4 404 2377 2462 418 +4 404 1644 444 429 +4 404 429 394 2377 +4 405 433 1603 2284 +4 1627 1590 1594 2167 +4 406 2397 466 2435 +4 406 2397 2506 351 +4 406 2435 466 456 +4 407 422 439 1740 +4 407 1740 439 434 +4 411 1639 489 425 +4 411 425 358 1571 +4 411 480 489 1639 +4 411 1639 1571 1597 +4 412 424 462 2537 +4 414 2403 453 415 +4 387 415 388 2466 +4 414 417 453 2403 +4 414 2403 2366 417 +4 395 420 432 2532 +4 415 420 2532 454 +4 415 453 454 2403 +4 416 1578 493 435 +4 416 486 493 1578 +4 401 486 416 1960 +4 417 429 475 2403 +4 414 2366 394 417 +4 417 2403 475 484 +4 418 443 485 1644 +4 418 2297 381 443 +4 418 1644 485 444 +4 376 381 2297 1602 +4 419 1574 467 466 +4 419 466 406 1574 +4 420 487 479 2525 +4 388 1874 2532 395 +4 421 459 467 2308 +4 421 459 2308 397 +4 422 1740 449 439 +4 422 447 449 1740 +4 1809 1856 1851 1534 +4 1808 1851 1534 1809 +4 423 451 491 2145 +4 423 2145 2474 451 +4 801 841 1504 1797 +4 424 2033 2537 426 +4 468 1552 522 527 +4 462 424 468 1552 +4 1744 1745 1864 1504 +4 371 438 1602 2259 +4 426 428 471 2033 +4 426 2033 471 468 +4 427 1624 490 469 +4 2118 1507 1580 1574 +4 428 430 472 2033 +4 428 2033 472 471 +4 1835 1509 2308 1580 +4 1783 1535 1707 1701 +4 429 444 474 1644 +4 429 474 475 2403 +4 1783 2179 1707 1535 +4 430 434 476 1740 +4 476 434 482 1740 +4 430 2033 476 472 +4 430 2033 1740 476 +4 1506 2238 1829 2040 +4 2231 1506 2238 2534 +4 2532 1646 483 458 +4 1788 1506 2040 2238 +4 433 458 494 1646 +4 433 1646 494 478 +4 433 478 2469 1646 +4 433 2284 2469 1603 +4 482 439 488 1740 +4 435 446 1578 504 +4 435 504 1578 493 +4 1830 2042 1700 1510 +4 1700 2042 1706 1510 +4 2053 1332 2070 1776 +4 2053 1949 1050 1332 +4 812 1026 925 2013 +4 437 459 397 2308 +4 437 459 1609 2356 +4 438 1642 520 443 +4 438 2297 1602 1642 +4 438 508 520 1642 +4 2070 1776 1332 1822 +4 439 1740 449 492 +4 439 1740 492 488 +4 1949 2040 1050 1332 +4 440 1625 545 442 +4 440 442 1983 1625 +4 440 462 2168 1625 +4 341 382 440 1983 +4 1251 2203 2448 1309 +4 1638 1491 1688 1641 +4 1641 1687 1491 1688 +4 442 2365 549 452 +4 442 1625 1730 2365 +4 549 442 1730 2365 +4 442 1983 1625 2365 +4 443 1644 520 485 +4 443 1644 1642 520 +4 443 438 1642 2297 +4 444 1644 499 474 +4 444 485 499 1644 +4 445 1607 500 447 +4 445 450 506 1607 +4 445 1607 1573 450 +4 445 1607 506 500 +4 1715 1952 1469 2186 +4 1715 1469 1952 2024 +4 446 1612 510 457 +4 446 457 1578 1612 +4 447 1740 495 449 +4 447 1607 500 495 +4 448 465 543 1531 +4 448 1531 543 524 +4 449 1740 495 492 +4 450 456 512 1607 +4 450 1607 512 506 +4 451 478 517 2536 +4 451 2145 517 491 +4 451 517 2145 2536 +4 462 527 2168 1552 +4 462 1625 1552 2168 +4 452 1757 554 461 +4 452 461 2365 1757 +4 452 549 554 1757 +4 453 417 484 2403 +4 453 1648 484 477 +4 2403 453 454 1648 +4 454 2525 487 420 +4 454 481 487 1648 +4 378 514 1577 457 +4 378 441 1577 514 +4 2051 1864 2329 1805 +4 457 510 2120 1612 +4 1744 1864 1929 2051 +4 2074 1791 1929 1864 +4 458 483 511 1646 +4 458 1646 511 494 +4 459 1608 579 467 +4 1823 1470 2070 1050 +4 466 1608 2418 467 +4 1534 2542 1809 1856 +4 2074 1929 1744 1864 +4 459 578 579 1608 +4 459 578 1608 1609 +4 421 1574 397 2308 +4 460 463 538 1618 +4 460 1618 1585 463 +4 460 1618 541 464 +4 460 464 1585 1618 +4 460 538 541 1618 +4 461 1757 562 470 +4 461 470 1476 1757 +4 461 554 562 1757 +4 463 469 534 1624 +4 463 534 538 1624 +4 463 538 1618 1624 +4 463 1624 1618 1585 +4 464 1618 544 473 +4 464 473 1585 1618 +4 464 541 544 1618 +4 465 1919 567 543 +4 465 543 1531 1919 +4 466 467 2418 1574 +4 466 2435 2397 2418 +4 459 467 2308 1608 +4 468 471 522 2033 +4 469 490 525 1624 +4 469 525 534 1624 +4 382 1983 1880 455 +4 470 2107 562 480 +4 470 2107 1757 562 +4 382 455 2537 462 +4 471 518 522 2033 +4 472 2033 519 518 +4 473 1618 550 486 +4 473 486 1960 1618 +4 473 544 550 1618 +4 474 2403 516 515 +4 474 499 516 1644 +4 475 2403 507 484 +4 475 2403 515 507 +4 475 2403 474 515 +4 523 482 529 2375 +4 476 2375 523 519 +4 476 2375 482 523 +4 477 1648 498 481 +4 477 484 501 1648 +4 477 496 498 1648 +4 477 1648 501 496 +4 478 494 548 1646 +4 478 2536 537 517 +4 478 1646 548 537 +4 478 537 2536 1646 +4 479 487 513 2525 +4 479 2525 521 2532 +4 479 513 521 2525 +4 480 1639 574 489 +4 480 562 568 2107 +4 480 568 574 1639 +4 480 1639 2107 568 +4 480 1597 1635 1639 +4 481 1648 505 487 +4 481 498 505 1648 +4 482 488 529 1740 +4 529 488 539 1740 +4 482 2375 1740 529 +4 1658 1710 2543 1705 +4 432 483 458 2532 +4 483 1646 526 511 +4 484 1648 507 501 +4 485 1644 547 499 +4 485 520 536 1644 +4 485 536 547 1644 +4 486 1612 563 493 +4 486 493 1578 1612 +4 486 550 563 1612 +4 2569 2570 2530 1652 +4 2340 1832 2569 1652 +4 1832 2570 2569 1652 +4 487 505 513 1648 +4 488 492 546 1740 +4 488 1740 546 539 +4 489 574 582 1639 +4 490 503 620 1970 +4 2569 2229 1652 2530 +4 606 1668 1624 525 +4 490 2320 620 525 +4 490 620 2320 1970 +4 491 517 584 1641 +4 2340 2229 1652 2569 +4 492 1740 552 546 +4 1763 1813 1496 2072 +4 494 511 553 1646 +4 494 1646 553 548 +4 479 2532 521 483 +4 495 500 561 1607 +4 495 1740 561 552 +4 495 1740 1607 561 +4 496 1648 531 498 +4 496 501 528 1648 +4 496 528 531 1648 +4 578 2132 1609 2356 +4 497 632 636 1654 +4 1762 1474 1471 1784 +4 1489 85 1734 1502 +4 1510 2042 1535 1830 +4 498 1648 533 505 +4 498 531 533 1648 +4 499 1644 551 516 +4 499 547 551 1644 +4 1510 2179 1535 2042 +4 500 506 569 1607 +4 500 1607 569 561 +4 530 507 532 1648 +4 501 1648 530 528 +4 501 1648 507 530 +4 502 632 1610 1728 +4 1606 1802 1808 1809 +4 502 632 1728 2137 +4 2111 1470 2070 1823 +4 502 1610 1611 1728 +4 503 524 628 1970 +4 503 1970 628 620 +4 1472 2232 1537 1855 +4 1071 1215 1813 1834 +4 505 1648 540 513 +4 505 533 540 1648 +4 506 512 575 1607 +4 506 1607 575 569 +4 507 515 532 2500 +4 508 2278 1642 1691 +4 508 520 1642 2278 +4 508 582 590 1691 +4 1472 2069 1537 1860 +4 441 514 2120 1577 +4 511 526 553 1646 +4 515 516 535 2500 +4 515 2500 535 532 +4 516 2500 559 535 +4 516 551 559 2500 +4 516 2315 1644 551 +4 517 537 604 1997 +4 517 1997 2536 537 +4 1480 1532 2545 692 +4 517 1997 599 584 +4 517 584 1641 1997 +4 517 1997 604 599 +4 517 1641 2536 1997 +4 512 1608 579 575 +4 518 572 2488 519 +4 518 2488 572 522 +4 519 571 572 2488 +4 519 523 571 2375 +4 1480 1532 1663 2545 +4 590 598 2278 1691 +4 520 1644 2278 536 +4 520 598 2278 590 +4 522 2488 581 527 +4 522 572 581 2488 +4 523 529 576 2375 +4 2375 2468 583 1657 +4 2375 1657 576 571 +4 524 543 628 1680 +4 524 628 1970 1680 +4 525 1624 606 534 +4 606 1668 525 608 +4 526 2473 565 553 +4 1528 2321 1567 1568 +4 1528 1568 1567 1899 +4 527 1552 1480 2168 +4 994 1846 1845 2499 +4 527 581 597 2488 +4 528 530 555 1648 +4 528 1648 555 557 +4 1912 2120 2023 1577 +4 529 539 580 2375 +4 441 2120 1611 1912 +4 580 539 583 2375 +4 1811 2499 1845 1853 +4 441 2120 1912 1577 +4 556 532 558 1648 +4 530 1648 556 555 +4 530 1648 532 556 +4 531 2524 560 533 +4 531 528 557 1648 +4 531 557 560 2524 +4 558 535 559 2500 +4 532 2500 535 558 +4 540 1648 533 2523 +4 540 533 564 2523 +4 534 1624 607 538 +4 534 606 607 1624 +4 536 1644 594 547 +4 536 1644 596 594 +4 537 548 603 1646 +4 537 603 604 2374 +4 537 1997 2374 604 +4 538 1618 609 541 +4 538 607 609 1618 +4 538 607 1618 1624 +4 583 546 600 2468 +4 539 2468 546 583 +4 542 564 566 2523 +4 1514 1617 1682 1661 +4 545 1625 1480 1669 +4 541 1618 610 544 +4 541 609 610 1618 +4 1131 1177 1199 2129 +4 543 567 647 2207 +4 543 2207 1919 567 +4 543 1680 647 628 +4 1762 1938 1474 1513 +4 544 550 2538 624 +4 544 1618 2538 550 +4 250 256 1542 223 +4 1999 1661 1617 1514 +4 2566 1857 1855 1854 +4 546 552 600 2468 +4 592 1693 2315 594 +4 548 553 602 1646 +4 548 602 603 1646 +4 549 1967 650 554 +4 549 554 1757 1967 +4 1514 1612 1682 1617 +4 544 610 624 2538 +4 551 2500 592 591 +4 551 2315 1644 547 +4 552 2468 605 600 +4 1999 1617 1612 1514 +4 554 2107 653 562 +4 554 562 1757 2107 +4 554 650 653 2119 +4 2040 1829 1866 1466 +4 2238 1829 2040 1466 +4 555 556 585 1648 +4 555 1648 587 557 +4 555 585 587 1648 +4 1728 2083 1660 2222 +4 1611 1728 2083 1660 +4 1728 1616 2083 2222 +4 2083 1728 1611 1610 +4 587 2524 1648 2520 +4 587 589 2524 2520 +4 2083 1616 1728 1610 +4 588 559 591 2500 +4 558 2500 559 588 +4 553 565 601 2473 +4 553 601 602 2473 +4 559 2500 551 591 +4 560 2524 593 564 +4 560 589 593 2524 +4 561 629 1607 569 +4 561 629 617 1607 +4 552 561 605 2468 +4 562 2107 653 568 +4 563 570 1612 1514 +4 563 1514 550 624 +4 564 2523 593 566 +4 566 593 595 2523 +4 565 566 595 2523 +4 567 584 660 1729 +4 1598 2561 2066 2054 +4 2300 1640 2561 2066 +4 568 1685 654 574 +4 568 574 1639 1685 +4 568 653 654 2107 +4 568 1685 1639 2107 +4 569 631 629 1653 +4 569 1653 1607 575 +4 629 617 1607 1653 +4 210 223 1542 2518 +4 570 573 1612 1514 +4 570 563 693 1514 +4 619 576 623 1657 +4 571 1657 576 619 +4 622 1657 630 2488 +4 572 571 622 2488 +4 573 1514 693 696 +4 574 1685 658 582 +4 574 582 1639 1685 +4 574 654 658 1685 +4 575 579 635 1653 +4 575 1653 1608 579 +4 575 1653 631 569 +4 575 1653 635 631 +4 1611 633 502 1783 +4 1810 2335 1798 1816 +4 576 580 623 1657 +4 577 573 696 1572 +4 577 696 759 1702 +4 584 1729 669 660 +4 577 1572 696 1702 +4 577 1572 1702 1999 +4 1572 1702 1661 2550 +4 696 2550 1702 1572 +4 578 2106 635 579 +4 1999 1572 1702 1661 +4 578 579 1608 2106 +4 578 2106 698 635 +4 578 636 698 2132 +4 578 2132 2356 636 +4 578 1608 1609 2132 +4 579 635 1653 2106 +4 579 2106 1653 1608 +4 580 583 709 1657 +4 580 1657 709 623 +4 581 2488 630 597 +4 581 622 630 2488 +4 582 1691 666 590 +4 582 658 666 1685 +4 582 1691 1685 666 +4 582 1639 1685 2279 +4 1692 2076 2555 1744 +4 584 599 674 1997 +4 584 2028 674 669 +4 1471 1472 1883 1492 +4 1556 1593 2061 2182 +4 585 614 612 2355 +4 585 2355 611 587 +4 585 587 1648 2520 +4 585 2355 612 611 +4 586 615 614 2491 +4 586 2491 614 585 +4 587 2355 611 589 +4 531 557 2524 1648 +4 613 2511 2520 1695 +4 588 591 618 2491 +4 588 2491 2500 591 +4 588 2491 615 586 +4 588 2491 618 615 +4 589 2511 613 593 +4 589 593 2524 2511 +4 593 613 616 2511 +4 590 1691 672 598 +4 590 666 672 1691 +4 592 594 625 1693 +4 551 2315 547 592 +4 1645 1927 1922 2478 +4 592 1901 625 618 +4 1645 1694 1922 1927 +4 2046 1883 1492 1471 +4 592 2500 2315 1901 +4 593 2511 616 595 +4 593 595 2523 2511 +4 2184 1974 166 1890 +4 594 596 649 1693 +4 1701 1939 1535 1707 +4 595 1799 621 601 +4 565 595 2057 2523 +4 598 2278 1691 671 +4 1525 1714 1582 1656 +4 520 536 2278 598 +4 596 1693 2278 649 +4 598 1691 672 671 +4 596 649 2278 598 +4 2278 1644 596 536 +4 599 604 673 1997 +4 601 621 626 1799 +4 2473 2458 2057 1799 +4 1827 1968 1832 1902 +4 2052 1968 1831 1832 +4 1968 1831 1832 1902 +4 637 2578 651 2374 +4 603 2374 651 604 +4 637 2374 651 603 +4 604 651 673 2374 +4 651 673 2374 704 +4 561 2468 1607 617 +4 606 1668 681 607 +4 606 607 1624 1668 +4 606 608 683 1668 +4 490 1624 2320 525 +4 606 1668 683 681 +4 607 2527 680 609 +4 607 609 1618 2527 +4 607 2527 681 680 +4 607 681 2527 1668 +4 607 1618 1624 2527 +4 607 1668 2527 1624 +4 608 1668 699 683 +4 1910 2365 1631 1708 +4 609 2538 682 610 +4 609 610 1618 2538 +4 1708 1631 1910 1590 +4 609 680 682 2527 +4 2365 1626 1631 1708 +4 610 2538 686 624 +4 610 682 686 2538 +4 611 612 641 2355 +4 640 1695 639 613 +4 611 1695 640 613 +4 611 1695 641 640 +4 641 614 642 2382 +4 613 1695 639 2511 +4 614 615 643 2516 +4 614 2382 2516 642 +4 615 618 643 2516 +4 613 2511 639 616 +4 2511 638 644 1799 +4 617 629 678 1653 +4 2420 1719 1895 994 +4 1607 1653 569 629 +4 617 1653 2468 1607 +4 618 625 645 1901 +4 618 2516 645 643 +4 619 1657 657 622 +4 619 623 659 1657 +4 619 1657 659 657 +4 620 2253 726 699 +4 620 699 608 2253 +4 620 628 726 2371 +4 621 1799 644 648 +4 595 2511 621 1799 +4 622 1657 656 630 +4 622 1657 657 656 +4 623 709 661 1657 +4 623 1657 661 659 +4 2359 1936 1881 1798 +4 624 2538 686 690 +4 1844 2359 1798 1936 +4 624 550 2538 1514 +4 2359 1936 1844 1875 +4 1901 675 655 645 +4 2359 1936 1875 1881 +4 626 621 648 1799 +4 2150 1538 1982 1725 +4 628 647 2369 1680 +4 1499 1725 2411 956 +4 2371 1463 1785 1680 +4 57 1518 1750 1605 +4 57 1605 1750 2362 +4 2362 1750 1478 1605 +4 1499 2150 2411 1725 +4 1538 1982 1725 1576 +4 563 690 693 1514 +4 629 691 688 1653 +4 629 1653 688 678 +4 583 634 706 1657 +4 583 706 709 1657 +4 631 635 695 1653 +4 631 1653 691 629 +4 631 1653 695 691 +4 632 1654 700 636 +4 632 697 700 1830 +4 632 697 1728 2137 +4 632 497 1610 1654 +4 760 801 1504 785 +4 1550 1973 2343 1464 +4 634 652 694 1657 +4 634 694 706 1657 +4 760 2445 1504 1697 +4 635 2173 698 695 +4 635 695 1653 2173 +4 636 1486 764 698 +4 2343 2232 1973 1860 +4 636 698 2132 1486 +4 636 700 764 1700 +4 636 1700 1654 700 +4 636 764 1486 1700 +4 649 1693 677 655 +4 549 1757 1730 1967 +4 646 758 1532 753 +4 1730 1676 1670 1669 +4 1730 1757 1626 1676 +4 549 1730 2323 1967 +4 638 639 664 1695 +4 664 640 668 1695 +4 639 1695 640 664 +4 668 641 670 1695 +4 640 1695 641 668 +4 641 642 670 2382 +4 642 667 670 2382 +4 614 2516 643 642 +4 643 645 665 2516 +4 643 2516 665 663 +4 667 2516 663 685 +4 644 1799 662 648 +4 645 2516 675 665 +4 646 1755 761 650 +4 545 646 2323 1669 +4 646 758 761 1755 +4 647 730 2369 1526 +4 648 2578 662 676 +4 649 705 1693 2381 +4 649 1693 705 677 +4 545 646 650 2323 +4 651 2578 704 2374 +4 651 676 704 2578 +4 652 678 694 1657 +4 650 2119 755 653 +4 650 2119 761 755 +4 650 2119 1755 761 +4 650 1967 1755 2119 +4 653 1731 749 654 +4 653 654 2107 1731 +4 653 1731 755 749 +4 654 2378 742 658 +4 654 658 1685 2378 +4 749 2273 1731 835 +4 742 2273 749 835 +4 654 1685 2276 2378 +4 710 2487 729 2498 +4 655 703 1693 677 +4 656 657 737 2545 +4 1760 1811 1804 1810 +4 656 2545 1657 657 +4 656 2545 743 692 +4 656 737 743 2545 +4 657 659 735 1703 +4 657 1703 1657 659 +4 657 735 737 1703 +4 657 2545 1703 737 +4 657 1657 1703 2545 +4 2551 1512 1464 2063 +4 658 2378 741 666 +4 2551 1464 1512 1550 +4 658 666 1685 2378 +4 1811 1760 2541 1810 +4 658 2378 742 741 +4 16 2430 2362 23 +4 659 661 735 1703 +4 659 1703 1657 661 +4 661 709 734 1703 +4 661 1703 1657 709 +4 661 734 735 1703 +4 663 665 710 2498 +4 2516 1695 685 2382 +4 663 2498 710 685 +4 684 668 687 1695 +4 664 1695 668 684 +4 665 675 712 2498 +4 665 712 710 2498 +4 666 1736 741 672 +4 666 672 1691 1736 +4 2137 697 1728 1783 +4 672 741 748 1741 +4 672 1741 1736 741 +4 666 1736 1691 1685 +4 672 1691 1736 1741 +4 697 1728 1783 1701 +4 2516 2382 685 667 +4 2382 689 670 1695 +4 687 670 689 1695 +4 668 1695 670 687 +4 1544 1548 1588 1583 +4 1544 1483 1583 1588 +4 1544 1548 1549 1588 +4 671 672 748 1741 +4 671 1741 1691 672 +4 671 2381 757 705 +4 1544 1483 1588 1549 +4 671 705 649 2381 +4 671 748 757 1741 +4 671 2381 1741 757 +4 671 2381 2278 1691 +4 671 1691 1741 2381 +4 673 674 1697 750 +4 673 704 750 1697 +4 674 1745 1697 750 +4 674 1745 750 747 +4 676 662 701 2578 +4 676 701 713 2578 +4 676 2578 713 704 +4 677 705 715 1693 +4 1632 1965 2318 1628 +4 678 2055 1653 688 +4 678 745 2055 688 +4 2318 1965 1672 1628 +4 678 739 2055 745 +4 679 684 702 2282 +4 711 714 2404 679 +4 680 681 725 2101 +4 680 2101 2527 681 +4 680 2101 727 682 +4 545 1480 2168 646 +4 680 682 2527 2101 +4 680 725 727 2101 +4 681 683 723 1716 +4 681 1716 1668 683 +4 681 723 725 2101 +4 681 723 2101 1716 +4 681 2527 1668 2101 +4 681 1716 2101 1668 +4 662 2578 711 701 +4 682 2101 733 686 +4 682 686 1500 2101 +4 682 727 733 2101 +4 683 699 722 1716 +4 683 1716 1668 699 +4 683 1716 722 721 +4 683 721 723 1716 +4 1667 1465 1674 1953 +4 684 687 707 1695 +4 684 2282 707 702 +4 685 710 2389 2498 +4 685 2498 2389 708 +4 686 2134 733 746 +4 1465 1953 1689 1674 +4 686 690 1500 2134 +4 675 2498 2487 712 +4 687 689 707 1695 +4 688 751 745 2055 +4 688 2055 1653 691 +4 685 2282 2498 708 +4 690 2134 746 754 +4 690 693 1514 2134 +4 690 686 746 2134 +4 691 695 752 1653 +4 691 2055 751 688 +4 692 743 753 2545 +4 693 2134 754 696 +4 693 696 1514 2134 +4 693 690 754 2134 +4 527 2488 597 1480 +4 2168 1625 1552 1480 +4 1728 1510 1535 1830 +4 694 1703 738 706 +4 1728 2179 1535 1510 +4 694 706 1657 1703 +4 2374 2458 2292 1646 +4 694 2055 739 738 +4 2292 2445 1697 2249 +4 695 698 756 2173 +4 1697 2445 2292 2374 +4 695 2173 756 752 +4 695 752 1653 2173 +4 1480 597 646 692 +4 696 754 809 2550 +4 761 2119 2020 1754 +4 696 809 1702 2550 +4 2119 2039 2020 1754 +4 1500 1618 2527 1682 +4 1500 1668 1682 2527 +4 1724 1481 1675 1463 +4 697 1701 818 700 +4 697 700 1830 1701 +4 697 815 818 1701 +4 697 815 1701 763 +4 2137 1783 633 763 +4 698 756 2173 1699 +4 698 1699 2173 2132 +4 699 1716 726 722 +4 699 726 1716 2253 +4 700 1700 816 764 +4 700 1700 818 816 +4 700 818 1700 1701 +4 701 711 718 2578 +4 701 2578 718 713 +4 702 707 731 2282 +4 2170 2443 2023 1544 +4 760 801 750 1504 +4 706 1703 736 709 +4 706 709 1657 1703 +4 706 1703 738 736 +4 707 708 731 2282 +4 708 2389 716 2498 +4 709 1703 736 734 +4 710 2487 719 729 +4 718 769 2266 720 +4 712 717 719 2487 +4 712 719 710 2487 +4 677 703 1693 715 +4 712 2498 2487 710 +4 625 655 645 1901 +4 2445 1748 2266 718 +4 713 2445 2578 718 +4 766 1748 760 2445 +4 714 702 728 2489 +4 715 717 2252 767 +4 702 2489 731 728 +4 717 768 2391 767 +4 1635 1639 2066 1685 +4 1635 1943 1685 2066 +4 2066 1943 1685 1686 +4 1639 1685 2279 2066 +4 2066 1686 1685 2279 +4 718 1748 769 766 +4 719 2487 717 768 +4 1769 1950 1813 1800 +4 1071 2111 1769 1800 +4 1071 1769 1813 1800 +4 769 2497 778 1748 +4 769 772 778 2497 +4 1769 1950 1800 2111 +4 721 722 794 1716 +4 721 1716 794 797 +4 722 726 782 1716 +4 722 782 794 1716 +4 723 2101 797 725 +4 723 721 797 1716 +4 723 797 2101 1716 +4 724 2142 852 726 +4 1777 1718 1516 1547 +4 1134 2133 2452 1204 +4 724 836 852 2142 +4 1204 1890 2133 2452 +4 1966 455 1983 2563 +4 2086 1592 1690 1588 +4 2097 1890 2133 1974 +4 1859 2097 2133 1974 +4 725 2101 799 727 +4 725 797 799 2101 +4 726 782 1716 2245 +4 727 2101 800 733 +4 727 799 800 2101 +4 728 731 773 2489 +4 2489 2497 773 772 +4 2237 2052 1831 1832 +4 2237 2465 1832 1831 +4 730 833 836 1497 +4 730 1463 724 2369 +4 1793 2052 1831 2237 +4 1793 2465 2237 1831 +4 729 2498 732 716 +4 771 1747 774 2347 +4 733 2122 803 746 +4 733 800 803 2101 +4 734 1703 786 735 +4 735 1703 789 737 +4 735 786 789 1703 +4 736 738 787 1703 +4 737 2130 831 743 +4 737 2130 1703 831 +4 738 739 795 2055 +4 738 1703 795 787 +4 739 745 819 2055 +4 1482 1940 1781 1788 +4 740 744 830 1739 +4 1929 1791 1681 2329 +4 741 742 826 1736 +4 741 1741 822 748 +4 741 1736 826 822 +4 741 1741 1736 822 +4 654 1731 749 2378 +4 742 2273 835 826 +4 1681 1828 1832 1833 +4 654 2378 749 742 +4 743 2545 2358 753 +4 743 831 857 2130 +4 744 747 824 1745 +4 744 824 830 1739 +4 744 824 1739 1745 +4 745 751 814 2055 +4 745 814 819 2055 +4 739 795 2055 819 +4 746 2122 808 754 +4 746 803 808 2122 +4 1724 1785 1463 1675 +4 747 750 827 1745 +4 747 1745 827 824 +4 1640 2065 1692 2076 +4 748 1741 828 757 +4 748 822 828 1741 +4 749 755 835 1731 +4 1718 1557 1520 1584 +4 96 1557 1520 129 +4 704 2445 760 1697 +4 704 1697 760 750 +4 752 756 804 2025 +4 753 1975 849 758 +4 753 2358 851 1975 +4 753 1975 2545 2358 +4 753 1975 851 849 +4 1645 2029 2315 1694 +4 2029 1693 1694 2554 +4 754 808 810 2122 +4 754 2550 810 809 +4 2278 2554 1693 2029 +4 755 1731 840 835 +4 756 2148 805 804 +4 1150 1887 2003 1487 +4 849 2020 844 761 +4 758 2020 849 761 +4 1150 2003 1856 1487 +4 759 809 812 1702 +4 759 809 1702 696 +4 760 766 785 1748 +4 1728 1510 1830 1654 +4 764 816 1699 1700 +4 805 1752 1699 816 +4 765 1746 788 767 +4 766 769 780 1748 +4 766 780 785 1748 +4 767 2391 781 768 +4 767 1746 788 781 +4 768 2274 781 779 +4 769 778 780 1748 +4 770 1747 776 771 +4 770 1747 779 776 +4 771 2347 774 773 +4 2347 1747 775 2497 +4 771 1747 776 774 +4 772 773 777 2497 +4 772 777 778 2497 +4 773 775 777 2497 +4 774 1747 790 775 +4 774 776 793 1747 +4 774 790 1747 793 +4 1665 1712 1510 1711 +4 1510 1712 1706 1711 +4 777 2510 796 778 +4 777 792 2510 775 +4 777 2497 2510 778 +4 777 796 2510 792 +4 778 1748 807 780 +4 811 798 2240 2460 +4 780 1748 820 785 +4 780 807 820 1748 +4 781 788 821 2490 +4 781 2490 1746 788 +4 781 2490 821 811 +4 782 1771 861 794 +4 782 794 1716 1771 +4 782 852 861 1771 +4 1941 322 2015 2113 +4 782 852 2245 726 +4 1941 322 2113 1585 +4 783 784 903 1758 +4 875 1758 829 786 +4 783 1758 875 786 +4 783 907 875 1758 +4 1582 2054 1934 2031 +4 784 787 823 1758 +4 785 1797 834 801 +4 1562 1582 1934 2031 +4 785 820 834 1797 +4 1714 1562 1582 1934 +4 786 1758 829 789 +4 786 789 1703 1758 +4 1582 1656 1934 2054 +4 1714 1582 1656 1934 +4 787 795 825 2483 +4 787 2483 1703 795 +4 788 2490 838 821 +4 1839 2568 1959 1813 +4 789 737 1703 831 +4 789 831 1703 1758 +4 789 829 831 1758 +4 1813 1834 2568 1959 +4 80 1726 181 43 +4 790 2219 793 817 +4 791 2502 832 792 +4 842 1796 832 2502 +4 791 842 832 2502 +4 43 1726 181 178 +4 792 2502 832 796 +4 793 798 845 2219 +4 794 1771 862 797 +4 794 797 1716 1771 +4 794 861 862 1771 +4 795 819 837 2201 +4 795 2483 837 825 +4 778 2493 2497 2510 +4 797 1764 865 799 +4 797 799 2101 1764 +4 797 862 865 1771 +4 797 865 1764 1771 +4 797 2101 1716 2187 +4 797 1771 2187 1716 +4 799 1764 868 800 +4 799 800 2101 1764 +4 799 865 868 1764 +4 800 1764 863 803 +4 800 803 2101 1764 +4 800 1764 868 863 +4 1341 1873 1812 1317 +4 1341 1873 1907 1812 +4 2223 1873 1812 1907 +4 737 743 2545 2130 +4 2138 2006 2238 2534 +4 2231 1789 1506 2534 +4 737 2130 2545 1703 +4 1703 2545 2188 2130 +4 827 1745 1504 1805 +4 801 750 1504 827 +4 801 834 841 1797 +4 1504 1805 841 827 +4 803 2200 867 808 +4 803 808 2122 2200 +4 803 863 867 1764 +4 804 805 853 2114 +4 804 2114 2148 805 +4 804 1751 855 806 +4 1721 1749 1774 1720 +4 804 806 752 2025 +4 804 853 855 1751 +4 804 853 1751 2114 +4 1721 2022 1774 1749 +4 804 2114 1751 2025 +4 805 816 869 1752 +4 805 2114 856 853 +4 805 1752 869 856 +4 1749 1780 2022 1774 +4 805 856 2152 1752 +4 806 1751 855 859 +4 806 814 751 2025 +4 1744 2310 2051 1743 +4 1938 2566 2290 1817 +4 808 810 2122 860 +4 1883 1857 1855 2566 +4 2443 1544 1549 1483 +4 2443 2182 1483 1549 +4 808 2200 860 2122 +4 809 810 860 1756 +4 809 1756 2550 810 +4 809 1756 918 812 +4 809 812 1702 2059 +4 809 812 2059 1756 +4 809 1756 860 918 +4 809 1702 2550 2059 +4 809 1756 2059 2550 +4 810 1756 2122 860 +4 1744 2249 2310 1743 +4 811 821 2460 1795 +4 2527 682 1500 2101 +4 2538 2527 682 1500 +4 812 918 2013 1756 +4 1943 1685 1686 1850 +4 920 2236 859 1751 +4 814 819 2055 2201 +4 814 806 859 1751 +4 814 2025 2201 2055 +4 2096 2118 1540 1835 +4 2096 1961 2118 1835 +4 1635 1850 1685 1943 +4 762 763 1702 2373 +4 812 2059 2373 1702 +4 815 2128 2420 818 +4 2420 1837 994 1895 +4 815 818 1701 2128 +4 2420 1837 1895 1784 +4 1895 1513 1784 1837 +4 994 1846 1895 1837 +4 815 1917 1479 925 +4 1895 1846 1513 1837 +4 1489 1502 216 85 +4 815 1701 1939 2128 +4 816 818 1719 1753 +4 816 1753 1700 818 +4 816 1752 1719 869 +4 817 1796 843 842 +4 817 1796 845 843 +4 818 1719 1753 2128 +4 818 1700 1701 1753 +4 818 2128 1753 1701 +4 819 2201 876 837 +4 920 2236 876 859 +4 820 1797 2281 834 +4 2493 820 1748 1797 +4 821 838 854 1795 +4 811 821 858 2460 +4 796 807 778 2493 +4 1598 1636 2066 2561 +4 1598 1636 2561 2084 +4 1598 2084 2195 1636 +4 822 826 894 2437 +4 822 2437 1736 826 +4 1598 2195 1964 1636 +4 822 2437 893 828 +4 822 828 1741 2437 +4 822 2437 894 893 +4 1598 1636 1964 2066 +4 2070 1332 1050 1988 +4 1606 1803 1809 1810 +4 1606 1810 1809 2542 +4 824 1805 1745 827 +4 824 2006 899 830 +4 824 830 1739 2006 +4 824 895 899 2006 +4 1759 1803 1606 1810 +4 824 1739 1745 2006 +4 1759 1810 1606 2542 +4 826 900 2273 835 +4 826 1495 900 894 +4 822 2437 1741 1736 +4 1846 2499 2172 1845 +4 811 847 2460 858 +4 592 1901 1693 625 +4 827 841 890 1805 +4 827 890 824 1805 +4 625 1901 1693 655 +4 592 2315 1693 1901 +4 2315 1901 1694 1693 +4 2499 1853 2172 1845 +4 829 1758 871 831 +4 829 1758 875 871 +4 632 1830 700 1654 +4 830 2534 911 833 +4 830 833 1497 2534 +4 830 899 911 2006 +4 830 911 2534 2006 +4 1679 1953 1723 2038 +4 831 1758 871 857 +4 831 2130 1758 857 +4 832 842 870 1796 +4 832 2213 870 846 +4 833 911 923 2534 +4 833 923 836 2030 +4 833 2030 836 1497 +4 834 1797 864 841 +4 834 2281 881 1797 +4 835 840 927 1786 +4 835 1786 1731 840 +4 837 876 880 2201 +4 838 2490 2364 1795 +4 1736 2185 2052 1495 +4 858 2460 854 879 +4 821 1795 854 2460 +4 840 1786 936 927 +4 1607 2468 1862 1653 +4 1607 1740 1869 1862 +4 841 864 891 1797 +4 841 1805 891 890 +4 1740 1637 1869 1862 +4 2468 2043 1862 1653 +4 844 1779 840 1754 +4 844 840 1779 936 +4 842 843 874 1796 +4 842 1796 873 870 +4 842 1796 874 873 +4 843 845 872 1796 +4 843 872 874 1796 +4 844 849 950 1778 +4 844 1778 2020 849 +4 968 978 1836 1793 +4 2468 2043 1637 1862 +4 1796 866 872 884 +4 866 2460 845 847 +4 849 851 959 1778 +4 849 1778 959 950 +4 838 2490 850 2364 +4 834 1797 881 864 +4 815 1939 1479 2128 +4 851 2164 964 959 +4 851 2117 969 964 +4 2057 1927 2458 1646 +4 852 1517 988 949 +4 852 941 988 1517 +4 852 941 2142 836 +4 852 949 1771 1517 +4 853 1751 2017 855 +4 853 856 912 1803 +4 853 912 975 2017 +4 853 912 2017 1803 +4 1795 2505 928 897 +4 892 1795 928 897 +4 853 2017 975 855 +4 856 869 972 1804 +4 856 1804 1752 869 +4 856 1803 972 912 +4 856 972 1803 1804 +4 856 2152 1752 1804 +4 857 871 904 1758 +4 918 860 922 1756 +4 866 858 2460 847 +4 814 1751 859 2201 +4 859 855 920 1751 +4 922 1807 1756 2200 +4 922 1807 2200 929 +4 861 1771 949 862 +4 861 1771 852 949 +4 903 1758 907 783 +4 862 1771 944 865 +4 862 1771 949 944 +4 863 1764 939 867 +4 863 868 942 1764 +4 863 1764 942 939 +4 808 867 934 2200 +4 808 2200 934 929 +4 864 881 901 1797 +4 864 1797 901 891 +4 865 1764 943 868 +4 865 1771 944 943 +4 865 943 1764 1771 +4 884 2505 2460 879 +4 845 866 872 1796 +4 868 1764 943 942 +4 869 1804 994 972 +4 2421 2344 802 2451 +4 2313 2344 1806 802 +4 1752 1804 1761 1895 +4 870 873 887 1796 +4 567 2207 660 647 +4 870 1796 887 885 +4 871 916 914 1758 +4 871 1758 914 904 +4 872 1796 886 874 +4 872 884 886 1796 +4 873 874 888 1796 +4 873 1796 888 887 +4 874 886 888 1796 +4 875 907 916 1758 +4 875 1758 916 871 +4 2344 1806 802 2451 +4 1500 690 2538 1514 +4 2236 920 924 2337 +4 877 898 908 2364 +4 2138 2002 1829 2238 +4 2538 682 686 1500 +4 1719 869 1895 994 +4 2420 1006 994 1837 +4 878 2453 902 896 +4 879 2505 897 884 +4 854 1795 879 2460 +4 880 2236 931 889 +4 880 924 931 2236 +4 881 896 915 1797 +4 881 1797 915 901 +4 884 897 905 2505 +4 885 887 910 1796 +4 885 2220 910 906 +4 886 1796 909 888 +4 887 888 913 1796 +4 887 1796 913 910 +4 888 909 913 1796 +4 1884 2564 1909 2549 +4 1981 1500 1661 2123 +4 1884 1889 2549 1909 +4 1884 1911 1889 1909 +4 889 931 940 2236 +4 889 940 945 2236 +4 890 891 951 1805 +4 890 1805 962 895 +4 890 951 962 1805 +4 1884 1911 1909 2041 +4 1884 2564 2041 1909 +4 2532 2284 1645 1646 +4 405 2284 2532 458 +4 854 1795 892 879 +4 892 919 928 1795 +4 879 1795 897 2505 +4 1541 1509 1581 1575 +4 363 1770 437 2056 +4 893 2230 968 898 +4 1770 2056 497 437 +4 894 1831 1495 900 +4 894 1831 900 978 +4 895 2138 973 899 +4 895 899 2006 2138 +4 895 962 973 1805 +4 926 902 930 2571 +4 896 1797 926 915 +4 12 1717 2026 2352 +4 2288 509 1772 1750 +4 898 2364 2230 908 +4 898 2230 968 961 +4 899 2138 990 911 +4 899 911 2006 2138 +4 899 973 990 2138 +4 900 927 1008 1831 +4 826 2437 1736 1495 +4 948 2121 2156 915 +4 915 901 1797 2156 +4 901 948 2156 915 +4 902 906 933 2571 +4 902 2571 933 930 +4 903 2454 957 907 +4 903 2454 945 957 +4 907 957 967 2454 +4 925 1479 1496 1917 +4 904 2117 1758 914 +4 905 909 886 2514 +4 932 909 905 2514 +4 1711 1995 1721 1712 +4 906 910 937 2571 +4 906 2571 937 933 +4 1712 1722 1995 1721 +4 907 2454 967 916 +4 2454 967 970 1808 +4 908 1795 955 919 +4 898 2230 961 908 +4 910 2571 938 937 +4 911 2534 1001 923 +4 911 990 1001 2138 +4 730 1497 1526 740 +4 730 833 1497 740 +4 1477 2044 2083 1616 +4 1477 2083 1610 1616 +4 1803 1017 2017 2027 +4 2117 1028 1035 1808 +4 1672 1721 1712 1711 +4 1672 1712 1721 1722 +4 915 946 948 2121 +4 916 967 970 2454 +4 1389 2175 2000 1498 +4 2006 1864 1745 1805 +4 918 1026 2013 2089 +4 918 1019 1026 2089 +4 918 922 982 1807 +4 918 1807 1756 922 +4 918 982 1019 1807 +4 918 1019 2089 1807 +4 918 2013 1756 2089 +4 918 1807 2089 1756 +4 919 1795 952 928 +4 919 1795 955 952 +4 920 2337 981 985 +4 1751 920 2236 2017 +4 922 929 995 1807 +4 2122 1756 2200 860 +4 922 1807 995 982 +4 923 1825 1033 941 +4 1642 1790 2279 2065 +4 923 1001 1015 2163 +4 923 1015 1033 2163 +4 1790 1686 2066 2279 +4 923 1033 1825 2163 +4 2279 1790 1686 2065 +4 2488 1480 1663 2545 +4 509 413 2411 1499 +4 2337 985 989 1802 +4 924 920 985 2337 +4 924 985 989 2337 +4 925 1026 1052 1839 +4 926 947 915 2121 +4 927 936 1025 1826 +4 927 1826 1786 936 +4 927 1826 1025 1008 +4 927 1831 1826 1008 +4 927 835 1698 900 +4 927 1826 1698 1786 +4 927 1698 1826 1831 +4 953 932 2354 958 +4 929 934 1009 1807 +4 929 1807 1009 995 +4 931 1802 989 940 +4 940 989 992 1802 +4 913 935 938 2514 +4 933 937 965 2571 +4 960 2571 983 954 +4 934 939 1016 1814 +4 934 1814 1016 1009 +4 934 1009 1807 1814 +4 934 2200 867 939 +4 440 2168 545 1625 +4 1480 1669 1532 646 +4 936 1826 1039 1025 +4 936 1826 1824 1039 +4 2571 938 937 966 +4 2571 966 937 965 +4 938 963 966 2514 +4 939 942 1029 1814 +4 939 1814 1764 942 +4 939 1814 1029 1016 +4 940 1802 992 945 +4 941 2005 1056 988 +4 941 988 1517 2005 +4 941 1033 1056 1825 +4 941 1056 2005 1825 +4 941 2142 836 1825 +4 2404 1937 2578 1799 +4 942 943 1027 1814 +4 942 1814 1764 943 +4 942 1027 1029 1814 +4 943 944 1018 2140 +4 943 2140 1771 944 +4 943 1018 1027 1814 +4 943 1018 1814 2140 +4 944 949 1011 2140 +4 944 2140 1771 949 +4 944 1011 1018 2140 +4 27 16 1717 1801 +4 945 1802 1000 957 +4 945 992 1000 1802 +4 946 2121 993 948 +4 2392 2422 2479 1493 +4 946 977 993 2121 +4 2121 2571 954 2492 +4 2121 2492 954 974 +4 948 2156 993 1004 +4 948 951 901 2156 +4 949 988 1011 2140 +4 949 2140 1517 988 +4 1801 1520 92 87 +4 950 2176 1060 1058 +4 950 1779 2176 1824 +4 951 948 1004 2156 +4 952 997 976 2484 +4 1500 690 1514 2134 +4 955 1012 2230 961 +4 997 2230 955 1012 +4 950 959 1060 2176 +4 950 2176 1778 959 +4 2298 1808 1802 1059 +4 957 1000 1010 1802 +4 957 2298 1802 1010 +4 958 976 980 1838 +4 959 964 1047 1819 +4 2452 1890 2133 2097 +4 959 1819 2164 964 +4 959 1047 1061 1819 +4 1637 1663 455 2007 +4 2007 1533 1637 1663 +4 960 965 986 2571 +4 960 2571 986 983 +4 2230 968 1012 1836 +4 961 968 1012 2230 +4 455 1869 1637 2007 +4 962 1503 1023 973 +4 962 973 1805 1503 +4 1869 1637 2007 1533 +4 964 2165 2117 1035 +4 964 2165 1047 1819 +4 1500 1514 1618 1682 +4 965 966 987 1838 +4 965 1838 987 986 +4 967 1808 1014 970 +4 1010 2298 1802 1059 +4 969 1028 1035 2117 +4 964 1035 1047 2165 +4 971 2117 1808 1022 +4 968 978 1034 1836 +4 968 1836 1034 1012 +4 971 2117 1022 969 +4 2117 1022 1028 1808 +4 970 1808 1020 971 +4 970 1014 1020 1808 +4 971 1020 1022 1808 +4 972 1077 1089 1845 +4 972 1845 1804 994 +4 972 1844 1089 1054 +4 972 1054 1803 1844 +4 972 1089 1844 1845 +4 973 2138 1045 990 +4 973 1023 1045 1503 +4 973 1045 2138 1503 +4 974 2492 998 977 +4 974 996 998 2492 +4 977 2121 1024 993 +4 977 998 1024 2338 +4 978 1008 1048 1831 +4 978 1836 1048 1034 +4 978 2465 1831 1048 +4 979 983 1002 2385 +4 979 2385 1002 996 +4 976 997 999 2484 +4 976 999 980 2504 +4 1965 1671 1672 1628 +4 2027 1802 1043 985 +4 982 995 1057 1807 +4 982 1807 1036 1019 +4 982 1807 1057 1036 +4 985 1802 1040 989 +4 985 1802 1043 1040 +4 2039 1720 1779 1749 +4 1719 1753 2128 1895 +4 988 2140 1055 1011 +4 988 2005 1087 1055 +4 988 1055 2140 2005 +4 988 1056 1087 2005 +4 949 1771 1517 2140 +4 988 2005 2140 1517 +4 2420 1784 1895 2128 +4 989 1802 1038 992 +4 989 1802 1040 1038 +4 990 2138 1063 1001 +4 1008 1831 1065 1048 +4 992 1802 1038 1000 +4 994 1077 972 1845 +4 994 1077 1845 1846 +4 1503 1045 2002 1696 +4 995 1009 1076 1807 +4 995 1807 1076 1057 +4 996 1002 1021 2385 +4 1503 2329 2238 1864 +4 997 1012 1053 1836 +4 955 952 1795 2230 +4 1480 1669 1663 1532 +4 1552 1480 1663 2488 +4 1051 2504 1041 980 +4 999 2504 1051 980 +4 1000 1802 1046 1010 +4 1000 1038 1046 1802 +4 1001 1829 1078 1015 +4 1001 1063 1078 2138 +4 1002 1005 1030 1838 +4 1030 1838 2360 2296 +4 1003 1041 1031 1838 +4 1005 1838 1031 1030 +4 1006 1077 994 1846 +4 815 2420 1917 925 +4 815 2420 2128 1917 +4 2367 509 1516 2026 +4 2420 1784 2128 1917 +4 1008 1025 1085 1826 +4 1008 1831 1085 1065 +4 1008 1831 1826 1085 +4 1009 1016 1088 2574 +4 1009 2574 1088 1076 +4 1009 1076 1807 2574 +4 2298 1808 1014 967 +4 1010 1046 1059 1802 +4 2298 1014 1010 967 +4 1809 1798 1851 1856 +4 1011 2140 1055 1018 +4 1012 1034 1053 1836 +4 980 1838 1041 1003 +4 1014 1808 1064 1020 +4 1014 1059 1064 1808 +4 1015 1829 1096 1033 +4 1015 1033 2163 1829 +4 1015 1078 1096 1829 +4 1096 1866 1829 1078 +4 2023 1912 1617 2120 +4 1016 1029 2574 1814 +4 1016 2574 1095 1088 +4 1017 2027 1054 1037 +4 1017 1037 975 2027 +4 2083 1912 1617 2023 +4 1576 1912 1976 2023 +4 1018 1055 1081 2149 +4 1251 2116 2431 1916 +4 1020 1808 1069 1022 +4 1020 1064 1069 1808 +4 1021 1030 2360 2296 +4 1022 1808 1072 1028 +4 1022 1069 1072 1808 +4 1024 2156 1049 1044 +4 1025 1039 1112 2127 +4 1025 2127 1826 1039 +4 1025 2127 1112 1085 +4 1025 1085 1826 2127 +4 1026 1839 1083 1052 +4 1026 1083 1839 1848 +4 1026 1019 1083 1848 +4 1026 1848 2089 1019 +4 1027 1814 1093 1029 +4 941 1517 1825 2005 +4 1028 1808 1073 1035 +4 1028 1072 1073 1808 +4 1016 1029 1095 2574 +4 1030 1031 1066 1838 +4 1021 2360 1062 2338 +4 1031 1041 1066 1838 +4 1033 1109 2526 1096 +4 1033 2163 1829 2526 +4 1033 1096 2526 1829 +4 1034 1048 1082 1836 +4 1034 1836 1082 1053 +4 1035 1856 1086 1047 +4 1036 1849 1807 1057 +4 1037 2027 1084 1042 +4 1037 1042 975 2027 +4 1037 1054 1084 2027 +4 1038 1040 1070 1802 +4 1038 1802 1070 1046 +4 2223 1840 1908 1907 +4 1039 2127 1118 1112 +4 1514 1612 1618 1682 +4 1039 2127 1826 1824 +4 1494 1612 1617 1682 +4 1040 1043 1079 1802 +4 1040 1802 1079 1070 +4 1033 2526 1116 1056 +4 1033 1109 1116 2526 +4 1900 1845 1844 1853 +4 1811 1845 1900 1853 +4 1042 2027 1091 1043 +4 1042 1043 981 2027 +4 1042 2027 1100 1091 +4 1043 2027 1091 1079 +4 1043 1079 1802 2027 +4 1999 1702 1928 1661 +4 1044 1049 1501 2156 +4 1044 1090 1501 1049 +4 1044 1068 1501 1090 +4 1045 2002 1092 1063 +4 1195 1013 1232 1240 +4 1232 1889 1013 2419 +4 1045 1092 2002 1696 +4 1046 1802 1080 1059 +4 1046 1070 1080 1802 +4 1047 1856 1114 1061 +4 1047 1061 1819 1856 +4 1047 1086 1114 1856 +4 1048 1065 1097 2465 +4 1048 2465 1831 1065 +4 1048 2465 1097 1082 +4 1804 1811 1845 1900 +4 2188 2542 1606 2117 +4 1049 1501 1101 1090 +4 1801 1520 87 2362 +4 16 2362 1801 49 +4 1039 1058 1118 1519 +4 250 256 2350 2263 +4 1051 1053 1098 1505 +4 1051 1053 1505 999 +4 1051 2479 1505 1041 +4 251 2263 2350 256 +4 251 279 2350 2263 +4 298 306 2228 2263 +4 279 2263 2228 306 +4 1052 2035 1102 1075 +4 1052 1083 1102 1839 +4 1019 1848 1103 1083 +4 1019 2089 1807 1849 +4 1053 1082 1098 1505 +4 1054 1084 2027 1844 +4 1055 1858 1117 1081 +4 1055 1081 2149 1858 +4 1055 1087 1117 1858 +4 1055 1087 1858 2005 +4 1055 2149 2005 1858 +4 1087 2147 1858 2005 +4 1056 2147 1116 1087 +4 1056 1087 2005 2147 +4 1056 2341 2526 1116 +4 1056 2005 1825 2341 +4 1058 1060 1134 1859 +4 1058 1859 2533 1060 +4 1058 1519 1134 1118 +4 2188 1765 2542 2117 +4 1058 1060 2533 2176 +4 1058 1859 1824 2533 +4 1077 1845 1113 1089 +4 1059 1080 1094 1802 +4 1060 1061 1150 2331 +4 1061 1114 1150 1856 +4 1061 2331 1856 1150 +4 2333 2414 1743 839 +4 2414 1746 2274 839 +4 1062 2360 1021 1067 +4 437 459 2308 1609 +4 1063 1078 2138 2002 +4 1063 1121 2002 1092 +4 1064 1808 1105 1069 +4 632 697 1830 1728 +4 1065 1902 1831 1085 +4 697 1830 1728 1701 +4 1065 1867 1119 1097 +4 1066 1041 2479 1838 +4 632 1728 1830 1654 +4 1580 1614 2196 1509 +4 1069 1808 1110 1072 +4 1069 1105 1110 1808 +4 1597 1635 2167 1476 +4 1070 1079 1080 1802 +4 1054 1844 1128 1084 +4 1054 1089 1128 1844 +4 1072 1534 1099 1073 +4 1808 1851 1106 1534 +4 1072 1808 1110 1106 +4 1910 1522 2167 1597 +4 442 545 2323 1625 +4 1075 1102 1131 2035 +4 2365 1625 1730 1626 +4 1637 2043 1657 1663 +4 1657 2043 2545 1663 +4 1077 1137 1113 1846 +4 1078 1866 1141 1096 +4 1078 1121 1141 1866 +4 1078 2002 1866 1829 +4 1079 2108 1115 1080 +4 1079 1080 1802 2108 +4 1079 1091 1115 2027 +4 2023 1617 1494 2120 +4 1080 2108 1115 1094 +4 1080 1094 1802 2108 +4 1081 2472 1138 1093 +4 1081 1117 1138 1858 +4 1081 1138 2472 1858 +4 1081 1858 2472 2149 +4 1082 1097 1152 2143 +4 1082 2143 2465 1097 +4 1082 2143 1152 1098 +4 1082 1098 1505 2143 +4 1098 1152 1127 2143 +4 2546 1738 1735 1843 +4 1083 1485 1157 1102 +4 1083 1103 1157 1848 +4 2546 1738 1843 1733 +4 1084 2359 1132 1100 +4 1084 1128 1132 1844 +4 1084 1132 2359 1844 +4 1085 1112 1146 1902 +4 1085 1902 1146 1119 +4 1085 1065 1902 1119 +4 1085 1902 1831 1826 +4 1086 1099 1120 1851 +4 1086 1856 1120 1114 +4 1086 1856 1851 1120 +4 761 1754 2020 844 +4 844 1779 1754 2020 +4 1754 1779 2039 2020 +4 1088 1095 1158 2463 +4 2329 1805 1864 1503 +4 1088 2463 2574 1095 +4 1332 1776 1781 1822 +4 1088 2463 1158 1148 +4 1088 1148 1849 2463 +4 2006 1503 1864 1805 +4 1490 1776 1781 1782 +4 1482 1940 1332 1781 +4 1089 1845 1113 1128 +4 1089 1128 1844 1845 +4 1090 1101 1126 1871 +4 1090 1871 1126 1122 +4 1091 1100 1136 2359 +4 1091 2359 1136 1115 +4 1092 1868 1151 1121 +4 1092 1122 1151 2235 +4 1092 2235 1868 1696 +4 1093 2472 1156 1095 +4 2472 1093 1814 2574 +4 1093 1138 1156 2472 +4 1094 2467 1129 1105 +4 1642 1643 1790 2065 +4 1094 1115 1129 2108 +4 380 428 2016 383 +4 1095 1156 1158 2463 +4 2300 1790 1642 1643 +4 1096 1866 1169 1109 +4 1096 1141 1169 1866 +4 1097 1119 1133 1867 +4 1097 1867 1133 1152 +4 1098 1870 1125 1107 +4 1098 1870 1127 1125 +4 1100 1132 1165 2359 +4 1100 2359 1165 1136 +4 462 1552 468 527 +4 2537 384 426 428 +4 1101 1108 1124 1871 +4 1101 1124 1126 1871 +4 462 455 1552 1625 +4 1103 1142 1180 1879 +4 1103 1879 1180 1157 +4 1103 1157 1848 1879 +4 1104 1130 1142 1849 +4 1105 1129 1140 2467 +4 1106 1851 1808 1110 +4 1107 1870 1125 1111 +4 1108 1111 1123 1870 +4 1108 1871 1870 2368 +4 1108 1871 2368 1124 +4 1109 1863 1170 1116 +4 1109 1169 1170 1863 +4 1109 1169 1863 1866 +4 1111 1870 1125 1123 +4 1113 1876 1187 1162 +4 1113 1162 1128 1876 +4 1114 1120 1154 1856 +4 1781 1944 1828 1872 +4 1944 1865 1872 1238 +4 1114 1856 1154 1150 +4 1115 2359 1136 1129 +4 636 1700 1486 1654 +4 1116 1170 1179 1863 +4 1659 1654 1486 1510 +4 1117 1858 1176 1138 +4 1117 1159 1176 1858 +4 1486 1654 1700 1510 +4 1222 1251 1261 2425 +4 1670 1721 2087 1720 +4 1119 1867 1155 1133 +4 1251 2425 1279 1261 +4 1119 1155 1902 1146 +4 2087 2166 1710 1720 +4 2087 1721 2166 1720 +4 1120 1856 1851 1154 +4 1121 1868 1172 1141 +4 1121 1151 1172 1868 +4 1670 2087 1710 1720 +4 1889 1013 1909 1240 +4 1013 2549 1889 1909 +4 1760 1804 1803 1810 +4 1152 2143 2227 1127 +4 1122 1126 1153 1871 +4 1122 1160 1151 2235 +4 1471 1883 1855 1474 +4 1471 1813 1959 1071 +4 1116 1179 2455 1863 +4 1123 1143 2368 1870 +4 1123 1125 1145 1870 +4 1123 1870 1145 1143 +4 1124 1871 1147 1126 +4 1124 1143 1147 2368 +4 1124 1871 2368 1147 +4 1125 1127 1149 2227 +4 1125 2227 1149 1145 +4 1126 1147 1153 1871 +4 1127 1870 2227 1125 +4 1128 1875 1174 1132 +4 1128 1132 1844 1875 +4 1128 1162 1174 1875 +4 1128 1876 1845 1113 +4 1128 1162 1875 1876 +4 1128 1844 1845 1876 +4 1738 1681 1371 1929 +4 1129 1136 1167 2359 +4 1738 1929 1791 1681 +4 1130 1849 1183 1142 +4 1130 1148 1203 1849 +4 1130 1849 1203 1183 +4 1131 1878 1199 1139 +4 1131 1139 2494 1878 +4 1006 1846 1837 2019 +4 1132 1875 1219 1165 +4 1132 1165 2359 1875 +4 2044 1576 1583 1982 +4 1132 1174 1219 1875 +4 1132 2359 1844 1875 +4 1133 1867 1161 1152 +4 1133 1155 1161 1867 +4 1513 1846 2499 1854 +4 1513 1854 2019 1846 +4 1135 1188 1173 1881 +4 1136 1165 1167 2359 +4 1137 1877 1207 1187 +4 314 293 1880 336 +4 1138 1176 1195 1858 +4 1156 2472 2160 1885 +4 1880 2537 1966 1524 +4 314 2537 1880 1524 +4 1139 1199 1213 1878 +4 1140 1881 1186 1144 +4 1140 1167 1186 1881 +4 1141 2091 1205 1169 +4 1141 1169 1866 1841 +4 1141 1172 1205 2091 +4 1141 1841 1868 1172 +4 2427 2299 2004 509 +4 1142 1879 1183 1180 +4 1137 1877 1217 1207 +4 1137 1217 1877 1139 +4 1143 1145 1163 2384 +4 1143 1147 2368 1166 +4 1143 2368 1163 1166 +4 1144 1881 1188 1135 +4 1144 1186 1188 1881 +4 2100 2239 1775 1776 +4 1125 1145 1870 2227 +4 1149 1164 1145 2227 +4 2100 1776 2046 2239 +4 2004 509 1772 2427 +4 2026 509 1717 1772 +4 1163 2368 2384 2260 +4 1163 1166 2368 2260 +4 1148 1158 1212 1885 +4 1148 1885 2463 1158 +4 1148 1885 1212 1203 +4 1148 1203 1849 1885 +4 1148 1849 2463 1885 +4 1149 1152 1168 2227 +4 1149 2227 1127 1152 +4 1149 2227 1168 1164 +4 1145 2384 2260 1163 +4 1150 1194 1227 1887 +4 524 1680 1531 543 +4 1150 1856 2003 2331 +4 1629 1680 1689 1531 +4 524 1680 1629 1531 +4 1151 1160 1175 2256 +4 543 1531 2576 1680 +4 1151 1898 1175 1172 +4 1531 1680 1689 2576 +4 1151 1172 1868 1898 +4 1152 1161 1178 1896 +4 1152 1896 1867 1161 +4 1152 2227 1178 1168 +4 1152 2227 1896 1178 +4 1152 2143 1867 2227 +4 1153 1166 1171 2226 +4 1153 2226 1871 1147 +4 1154 1173 1194 1881 +4 1934 2054 1598 2031 +4 1332 1872 1940 2040 +4 1482 2040 1940 1788 +4 1155 1896 1184 1161 +4 1155 1161 1867 1896 +4 1155 1181 1184 1896 +4 1482 2040 1332 1940 +4 1701 1762 1753 2042 +4 1788 1828 2040 1940 +4 1156 1885 1208 1158 +4 1156 1158 2463 1885 +4 1156 2160 1195 1208 +4 1562 1934 1598 2031 +4 1932 1562 1934 1598 +4 1157 1180 1209 1879 +4 1157 1209 1177 1879 +4 1158 1208 1212 1885 +4 1569 1696 1501 1503 +4 1940 1872 1828 2040 +4 1159 2419 1200 1176 +4 1159 1176 1858 2419 +4 1934 1656 1598 2054 +4 1932 1934 1656 1598 +4 1160 2256 1182 1175 +4 1161 1896 1193 1178 +4 1161 1184 1193 1896 +4 1162 1875 1214 1174 +4 1162 1187 1214 1876 +4 1162 1214 1875 1876 +4 1163 1164 1185 2486 +4 1145 2486 1164 1163 +4 1163 2486 1185 1166 +4 1153 2226 1147 1166 +4 1164 1168 1189 2486 +4 1164 2486 2227 1168 +4 1164 2486 1189 1185 +4 1165 2359 1211 1167 +4 1165 1875 1219 1211 +4 1165 1211 2359 1875 +4 1166 2325 1191 1171 +4 1166 1171 2226 2325 +4 1166 1185 1191 2486 +4 1167 1881 1211 1186 +4 1167 1881 2359 1211 +4 1168 1178 1196 2227 +4 1168 2486 1196 1189 +4 1169 2535 1231 1170 +4 1169 1170 1863 2535 +4 1169 1205 1231 2535 +4 1169 1863 1866 2535 +4 1170 2535 1228 1179 +4 1170 1179 1863 2535 +4 1170 2535 1231 1228 +4 1171 2495 1198 1182 +4 1171 1191 1198 2325 +4 1172 1175 1201 1898 +4 1172 1201 1205 2091 +4 1172 1898 1841 1868 +4 1173 1188 1220 1881 +4 1173 1881 1220 1194 +4 1174 1214 1219 1875 +4 1175 1182 1202 2256 +4 1640 1687 1886 2080 +4 1175 1898 1202 1201 +4 1640 2080 1688 1687 +4 1886 1692 1687 1640 +4 1553 1588 1587 1591 +4 1640 1688 2076 1687 +4 1176 1200 1232 2419 +4 1640 1692 1687 2076 +4 1547 2048 2049 1553 +4 1178 1193 1206 1896 +4 1178 2227 1206 1196 +4 1178 2227 1896 1206 +4 1548 1553 1588 1587 +4 1863 2535 2339 1986 +4 1863 2339 1892 1986 +4 1180 1183 1223 1879 +4 1180 1879 1223 1209 +4 1181 1896 1216 1184 +4 2120 2103 1999 514 +4 2103 441 514 2120 +4 1611 2103 1999 2120 +4 2103 441 2120 1611 +4 1181 2032 1226 1216 +4 348 1960 416 1578 +4 1578 1494 1960 1612 +4 1960 1682 1612 1494 +4 401 1960 2113 1585 +4 1182 1198 1210 2495 +4 1182 2495 1210 1202 +4 1183 1203 1245 1885 +4 1183 1885 1849 1203 +4 1183 1879 1245 1223 +4 1184 1896 1218 1193 +4 1184 1216 1218 1896 +4 1517 2245 2142 2024 +4 1517 1815 2024 2142 +4 1185 2155 2486 1189 +4 1186 1881 1229 1188 +4 1186 1211 1229 1881 +4 1179 1892 1235 1200 +4 1179 1230 1235 1892 +4 1187 1207 1244 1877 +4 1187 1876 1244 1214 +4 1187 1244 1876 1877 +4 1188 1881 1233 1220 +4 1188 1229 1233 1881 +4 1189 1196 1246 2155 +4 1189 2155 2486 1196 +4 1189 2155 1246 1185 +4 2444 1190 1192 2512 +4 1191 2325 2349 1198 +4 1475 1598 1562 1932 +4 1475 1594 1598 1932 +4 1932 1563 1595 2084 +4 1193 1896 1221 1206 +4 1193 1218 1221 1896 +4 1194 1220 1247 1887 +4 1932 2195 1595 1594 +4 1194 1887 1247 1227 +4 1013 1885 1240 1208 +4 130 1962 209 2446 +4 131 2415 1525 1962 +4 1962 209 2446 2393 +4 1962 2162 2415 1525 +4 1196 2155 1222 1246 +4 1196 1251 1206 1222 +4 2436 2434 2503 166 +4 2436 166 2133 2434 +4 1962 1528 2162 2446 +4 131 1528 1962 97 +4 1198 1210 2268 2349 +4 1199 1209 1260 1906 +4 1199 1906 1177 1209 +4 1199 2105 1260 1213 +4 1199 1213 1878 2105 +4 1200 1889 1242 1232 +4 1200 1235 1242 1892 +4 1200 1242 1889 1892 +4 763 1707 1701 1783 +4 1201 2091 1225 1205 +4 1701 1939 1707 763 +4 1202 1210 1224 2495 +4 763 1939 1707 1479 +4 1202 1898 1239 1201 +4 1202 1224 1239 1898 +4 1203 1212 1258 1885 +4 1203 1885 1258 1245 +4 1594 1627 2167 1632 +4 1551 2169 1522 2158 +4 2169 1594 1522 1475 +4 1522 2167 1594 1590 +4 1204 2424 2088 2485 +4 1707 1479 1702 763 +4 1205 1225 1236 2091 +4 1205 2535 1236 1231 +4 763 1702 1707 1783 +4 1207 1217 1281 1905 +4 1207 1905 1877 1217 +4 1207 1905 1281 1244 +4 1207 1244 1877 1905 +4 1208 1885 1257 1212 +4 1208 1240 1257 1885 +4 1209 1223 1289 1879 +4 1209 1906 1289 1260 +4 1209 1906 1879 1289 +4 1209 1177 1879 1906 +4 1210 1224 2495 2224 +4 1698 1968 1826 1831 +4 1211 1219 1255 1875 +4 1787 1827 1963 1968 +4 1211 2359 1875 1881 +4 1212 1257 1258 1885 +4 1213 2105 1291 1217 +4 1213 1217 1878 2105 +4 1213 1260 1291 2105 +4 1214 1875 1259 1219 +4 1259 1904 1876 1244 +4 1214 1259 1875 1876 +4 1214 1259 1876 1244 +4 1204 1890 2452 1227 +4 1218 1251 2431 1270 +4 1216 1226 1250 2032 +4 1216 2032 1250 1237 +4 1217 1905 1300 1281 +4 1217 1291 1300 2105 +4 1217 1300 1905 2105 +4 1217 1877 1878 2105 +4 1218 1896 2293 1251 +4 1237 1218 2431 1270 +4 1541 1575 1581 2044 +4 1219 1875 1259 1255 +4 1220 1887 1264 1247 +4 1201 2091 1241 1225 +4 1201 1239 1241 1898 +4 1222 1206 1261 1251 +4 1222 2425 1294 1246 +4 1222 1261 1294 2425 +4 1664 1711 1658 1710 +4 1658 2543 1710 1711 +4 1223 1245 1286 1879 +4 1664 1711 1659 1658 +4 1223 1286 1289 1879 +4 1659 2543 1658 1711 +4 1224 1898 2428 1239 +4 1224 1280 1271 2428 +4 1224 2428 1271 1239 +4 1225 2091 1254 1236 +4 1225 1241 1254 2091 +4 1227 1247 1282 1873 +4 1227 1873 1887 1247 +4 1227 1204 1890 2088 +4 1227 1873 1890 1887 +4 1228 2339 1265 1230 +4 1228 1230 1179 2339 +4 1228 1231 1268 1894 +4 1228 1894 1268 1265 +4 1230 2068 1269 1235 +4 1230 1892 2068 1235 +4 1230 1265 2068 2339 +4 1230 1265 1269 2068 +4 1230 2068 1892 2339 +4 1231 1236 1268 1894 +4 1232 1242 1276 1889 +4 503 524 1970 1629 +4 524 1970 1629 1680 +4 1206 1221 1279 1251 +4 1206 1251 1279 1261 +4 1970 1680 1674 1629 +4 1971 1590 2048 1586 +4 1547 2048 1971 2049 +4 1235 1269 1278 2068 +4 1235 1892 2068 1242 +4 1236 1254 1275 1894 +4 1236 1894 1275 1268 +4 1237 1250 1273 2032 +4 1237 2431 1273 1267 +4 1237 2431 2032 1273 +4 1671 1676 2018 1721 +4 1626 2018 1671 1676 +4 730 1497 1463 1526 +4 802 166 2344 2409 +4 1239 2144 1271 1241 +4 1239 1241 1898 2144 +4 1670 1721 1676 1671 +4 1626 1676 1671 1670 +4 1240 1909 1297 1257 +4 1240 1257 1885 1909 +4 1240 1276 1297 1909 +4 647 740 1526 660 +4 647 730 1526 740 +4 1678 1673 1527 2078 +4 1241 1254 2091 2405 +4 1242 2426 1315 1276 +4 1678 1722 1727 1527 +4 1242 1290 1315 2426 +4 1599 2301 1601 1948 +4 1662 2421 802 2102 +4 1946 1601 1948 1599 +4 1946 1948 1601 2197 +4 2474 1948 1601 2301 +4 1244 1904 1328 1259 +4 1244 1328 1904 1905 +4 2197 1948 1601 2474 +4 1245 1258 1310 1909 +4 1245 1909 1879 1885 +4 436 1575 1576 1477 +4 1245 1909 1310 1286 +4 436 1575 1477 1610 +4 436 441 502 1477 +4 436 1477 1576 441 +4 436 502 1610 1477 +4 1247 1873 1317 1282 +4 1248 2248 1287 1293 +4 1250 1266 1283 2032 +4 1250 2032 1283 1273 +4 1280 2428 1311 1271 +4 1254 1894 1285 1275 +4 1255 1259 1316 2062 +4 1255 2062 1316 1274 +4 1256 2433 1314 1262 +4 1256 1293 1314 2433 +4 1257 1909 1319 1258 +4 465 1638 567 1919 +4 1257 1297 1319 1909 +4 465 1919 1531 1638 +4 1919 2207 1638 567 +4 1919 1531 1638 2576 +4 1919 2576 1638 2207 +4 1701 2042 1753 1700 +4 1258 1909 1319 1310 +4 1259 1904 1328 1316 +4 1259 1316 2062 1904 +4 1260 1289 1355 1906 +4 1260 2105 1355 1291 +4 1261 1333 1318 2425 +4 1261 2425 1318 1294 +4 1262 2433 1331 1280 +4 1262 1314 1331 2433 +4 2301 465 1638 1641 +4 465 567 1638 1641 +4 1641 465 491 423 +4 465 1641 491 567 +4 1263 1351 2456 1662 +4 1890 1873 1227 1282 +4 423 465 2301 1641 +4 1263 2409 1252 2424 +4 66 81 1921 1528 +4 1264 1277 1354 2062 +4 1264 2062 1220 1277 +4 1921 1525 109 2415 +4 66 1921 109 1528 +4 1264 2062 1887 1220 +4 2557 1623 2083 2222 +4 1265 1268 1304 2513 +4 1265 2513 1305 1269 +4 2068 2513 2348 1894 +4 1265 1304 1305 2513 +4 1269 1305 2348 2513 +4 2557 1622 1623 2222 +4 2575 1296 1306 1914 +4 1266 1296 1306 2575 +4 2575 1306 1320 1914 +4 1241 2144 1298 1272 +4 1241 2144 1301 1298 +4 1922 2057 2520 1648 +4 1267 2431 1302 1270 +4 1267 1273 1299 2431 +4 1267 1299 1302 2431 +4 1268 1275 1304 2449 +4 1268 1304 2513 2449 +4 1269 2348 1313 1278 +4 1269 1305 1313 2348 +4 1270 1302 1347 2448 +4 1270 2448 1347 1309 +4 1307 1323 2447 2092 +4 1272 1285 1254 2405 +4 1272 1298 1307 2092 +4 1273 1283 1308 2431 +4 1273 2431 2032 1283 +4 1273 2431 1308 1299 +4 1665 1672 1942 1666 +4 1274 1350 2062 1316 +4 1275 1285 1312 2449 +4 1275 2449 1312 1304 +4 1276 1909 1343 1297 +4 1666 1942 1673 1672 +4 1276 1315 1343 2426 +4 1622 1666 1665 1942 +4 1276 1343 1909 2426 +4 1622 1666 1942 1993 +4 1276 2426 1909 1889 +4 1278 2021 1322 1290 +4 1278 2068 2021 1242 +4 1942 1993 1666 1673 +4 1279 2425 1333 1261 +4 1279 2425 1358 1333 +4 1280 1331 1359 2433 +4 1281 1300 1391 1905 +4 1281 1905 1391 1328 +4 1281 1328 1244 1905 +4 1282 1317 1378 1812 +4 1282 1662 1351 1263 +4 1645 2292 1694 1927 +4 1283 1306 1320 2575 +4 1283 2098 1320 1308 +4 2383 2241 1893 2575 +4 1927 2292 2458 1646 +4 1284 1918 1330 1287 +4 1922 1937 1695 1799 +4 1284 1288 1336 2225 +4 1284 1329 1330 1918 +4 1645 2292 1927 1646 +4 1285 1323 2447 1307 +4 1285 2447 1323 1312 +4 1285 1312 2449 2447 +4 1286 1310 1349 1909 +4 1287 1918 1330 1338 +4 1288 1346 1336 2225 +4 1802 2108 1809 2027 +4 1289 1349 1355 1906 +4 1290 1911 1345 1315 +4 1290 1322 1345 2021 +4 1278 1242 2021 1290 +4 844 936 1779 950 +4 1292 1295 2522 2413 +4 1292 2413 2421 1295 +4 1292 2413 1325 1296 +4 1292 1296 2575 2413 +4 1292 2413 2522 1325 +4 1293 2433 1353 1314 +4 1293 1338 1353 2401 +4 1346 1318 1356 2425 +4 1294 2425 1346 1288 +4 1294 2425 1318 1346 +4 1295 2413 2421 1303 +4 1296 1914 1324 1306 +4 1296 1914 1325 1324 +4 1297 1909 1366 1319 +4 1297 1343 1366 1909 +4 1298 2092 1367 1307 +4 1298 2441 1340 1367 +4 1299 2431 1344 1302 +4 1299 1308 1335 2431 +4 1299 1335 1344 2431 +4 1300 1394 1409 1650 +4 1301 2441 1348 1340 +4 997 999 1505 1053 +4 1302 1344 1347 1916 +4 1303 2102 1662 1321 +4 1303 2421 2102 2413 +4 1304 1914 1324 1305 +4 1304 1305 2513 1914 +4 1304 1914 1326 1324 +4 1305 2482 1325 1313 +4 1305 1313 2348 2482 +4 1305 1324 1325 1914 +4 1305 2348 2513 1914 +4 1306 1914 1326 1320 +4 1306 1324 1326 1914 +4 1307 2092 1342 1323 +4 1307 1367 1342 2092 +4 1308 1320 1339 2098 +4 1308 2098 1339 1335 +4 1309 1347 1380 2448 +4 1309 2448 1380 1358 +4 1310 1319 1377 1909 +4 1310 1909 1370 1349 +4 1310 1909 1377 1370 +4 1311 2442 1381 1348 +4 1311 1359 1381 2442 +4 1313 2482 1327 1322 +4 1313 1322 2348 2482 +4 1313 1325 1327 2482 +4 1314 2433 1369 1331 +4 1314 1353 1369 2433 +4 1315 1911 1364 1343 +4 1315 1345 1364 1911 +4 1316 1328 1393 1904 +4 1316 1904 1393 1350 +4 1667 1980 1715 1981 +4 1317 1407 1378 1812 +4 1667 1980 1990 1715 +4 1667 1715 1990 1674 +4 1318 1373 1356 2425 +4 1667 1981 1715 1674 +4 1862 1653 1533 2217 +4 1319 1366 1377 1909 +4 1608 2106 1653 1533 +4 1320 1326 1334 2036 +4 1320 2036 1914 1326 +4 1321 1303 2102 1357 +4 1322 1327 1337 2482 +4 1322 1345 2021 2000 +4 700 1701 1700 1830 +4 1322 2000 2021 2348 +4 1533 2043 2106 1653 +4 1323 2098 1352 1334 +4 1328 1391 1393 2171 +4 1328 1393 1904 2171 +4 2084 1932 1656 1598 +4 1329 1918 1361 1330 +4 1329 1918 1362 1361 +4 1598 2561 2054 1656 +4 1330 1918 1360 1338 +4 1360 1361 1379 1918 +4 1656 2561 2084 1598 +4 1331 1369 1384 2433 +4 1367 2092 1385 1342 +4 1333 2425 1373 1318 +4 1334 2098 1352 1339 +4 1335 1339 1387 2098 +4 1335 2431 1368 1344 +4 1335 2431 1387 1368 +4 1336 1346 1365 2225 +4 1337 2000 1357 1322 +4 437 2146 1609 1509 +4 1338 2401 1360 1353 +4 1339 1352 1387 2098 +4 1340 2441 1374 1367 +4 1341 1424 1407 1907 +4 1341 1812 1407 1317 +4 1341 1812 1907 1407 +4 1480 1532 692 646 +4 1342 2098 1385 1352 +4 1685 2189 1732 1736 +4 1343 1364 1392 1911 +4 1343 1911 1392 1366 +4 1344 1916 1375 1347 +4 1344 1368 1375 1916 +4 1345 1357 1364 2000 +4 2189 1732 1736 1737 +4 2053 1482 1332 1776 +4 1346 1356 1365 2225 +4 1586 1931 2048 2196 +4 1380 1375 1401 2480 +4 1347 2480 1375 1380 +4 1348 2442 1381 1374 +4 1374 1381 1402 2442 +4 1349 1906 1404 1355 +4 1349 1370 1404 1947 +4 1349 1370 1947 1909 +4 2196 1621 1931 2048 +4 2048 1627 1621 1931 +4 1350 2171 1423 1354 +4 1350 1393 1423 2171 +4 1782 1776 1482 2053 +4 1995 1775 1774 2022 +4 1283 2383 2032 1266 +4 1353 2264 1386 1369 +4 1360 2401 1379 1372 +4 1354 1907 1424 1341 +4 1354 1423 1424 2171 +4 1283 2383 1266 2575 +4 441 1912 1611 1477 +4 1365 1376 1382 2225 +4 1357 1364 2000 1389 +4 1477 1611 2083 1912 +4 1358 1380 1408 2336 +4 1358 2336 1408 1388 +4 1359 2442 1405 1381 +4 1353 1372 1386 2401 +4 1361 1918 1360 1330 +4 1361 1918 1362 1379 +4 1362 1918 1383 1379 +4 1241 1272 2405 2144 +4 1998 2429 148 80 +4 1241 1903 1898 2144 +4 2429 1998 1726 80 +4 1336 2225 1365 1363 +4 148 2351 2429 1998 +4 1998 2351 2429 1544 +4 1364 1389 1431 2175 +4 1272 2092 1307 2405 +4 1364 2175 1431 1392 +4 1777 1546 1547 1989 +4 2423 1987 1884 1537 +4 1367 1374 1395 2441 +4 1367 2441 1395 1385 +4 2529 1387 1396 1413 +4 1368 1916 2529 1375 +4 1368 2529 1387 1396 +4 1627 1631 1632 2018 +4 1369 2264 1403 1384 +4 1369 1386 1403 2264 +4 1370 1377 1442 1947 +4 1477 441 502 1611 +4 1370 1947 1432 1404 +4 1370 1947 1442 1432 +4 1352 1385 1397 2098 +4 1352 2098 1397 1387 +4 1353 1360 1372 2401 +4 1373 1388 1406 2295 +4 1477 502 1610 1611 +4 1356 2295 1390 1376 +4 1374 2442 1402 1395 +4 2062 1907 1354 1264 +4 1401 1396 1419 2529 +4 1375 2529 1396 1401 +4 1356 2225 1376 1365 +4 1377 1421 1442 1947 +4 1378 1407 1453 1923 +4 1378 1923 1453 1427 +4 2062 1873 1907 1264 +4 1264 1907 1354 1341 +4 1908 1923 1840 1649 +4 1398 1383 1400 1918 +4 1379 1918 1383 1398 +4 2150 1539 2109 1544 +4 1264 1873 1907 1341 +4 1380 2336 1401 1408 +4 1381 2442 1405 1402 +4 1402 1405 1418 2442 +4 1382 1918 1400 1383 +4 1382 1399 1400 1918 +4 1384 1403 1415 2264 +4 1384 2264 1415 1405 +4 1385 1395 1412 2441 +4 1385 2441 1412 1397 +4 1386 1398 1410 2401 +4 1386 2264 1410 1403 +4 1416 2336 1430 2417 +4 1388 1408 1416 2336 +4 1389 1427 1450 1649 +4 1389 1649 1498 1427 +4 1389 1649 1450 1431 +4 1767 1712 1706 1768 +4 1356 1373 1390 2295 +4 1391 2379 1452 1393 +4 1391 1393 2171 2379 +4 1391 1409 1452 2379 +4 1391 2379 1300 1409 +4 1392 2175 1431 1421 +4 1392 1421 1366 2175 +4 1392 1366 1911 2175 +4 1864 1745 1805 1504 +4 1767 1768 1995 1712 +4 1976 1912 2083 2023 +4 1976 2083 1583 2023 +4 1976 1477 2083 1912 +4 1394 1404 1451 2432 +4 1394 2432 1355 1404 +4 1976 1477 2044 2083 +4 1395 1402 1417 2442 +4 1395 2442 1417 1412 +4 1976 2044 1583 2083 +4 1396 1413 1436 2529 +4 1396 2529 1436 1419 +4 1397 1412 1422 2529 +4 1410 1400 1414 1918 +4 1398 1918 1400 1410 +4 1399 2295 1411 1414 +4 1400 1399 1414 1918 +4 1408 1401 1420 2336 +4 1434 1436 2417 2529 +4 1402 2442 1418 1417 +4 215 2157 1933 1899 +4 1415 2264 1426 2417 +4 1404 1432 1451 2432 +4 2534 2438 2231 1789 +4 1405 1415 1418 2264 +4 1405 1418 2442 2264 +4 1406 2295 1416 1411 +4 1407 1424 1459 1923 +4 1407 1840 1907 1424 +4 2097 1887 2003 1150 +4 1407 1923 1459 1453 +4 1408 2336 1420 1416 +4 1409 2379 1455 1452 +4 830 2006 2534 2231 +4 1426 1414 1428 2417 +4 1415 1410 1426 2264 +4 1411 2295 1425 1414 +4 1412 2529 1443 1422 +4 1412 1435 1443 2529 +4 830 2438 2231 2534 +4 1413 1422 1443 2529 +4 1413 2529 1443 1436 +4 1414 1425 1428 2417 +4 1415 2417 1429 1418 +4 1415 1426 1429 2417 +4 1416 1420 1430 2336 +4 1416 2417 1430 1425 +4 1417 1418 1433 2442 +4 1780 1821 1820 1824 +4 1417 2442 1433 1435 +4 1418 1429 1439 2417 +4 1418 2417 1439 1433 +4 1774 1780 1821 1820 +4 1419 1436 1434 2529 +4 1434 1436 1447 2417 +4 1440 2336 1434 2417 +4 1420 2336 1434 1440 +4 1421 2432 1454 1442 +4 1423 1923 1457 1424 +4 1423 1424 2171 1923 +4 1424 1457 1459 1923 +4 1425 2417 1437 1428 +4 1425 1430 1437 2417 +4 1426 1428 1438 2417 +4 1426 2417 1438 1429 +4 1427 1924 1453 1456 +4 1427 1924 1923 1453 +4 1428 1437 1441 2417 +4 1428 2417 1441 1438 +4 1429 1438 1439 2417 +4 1430 2417 1440 1437 +4 1431 1450 1454 1924 +4 1432 1442 1460 2432 +4 1432 2432 1458 1451 +4 1432 2432 1460 1458 +4 1433 1439 1446 2417 +4 1439 1444 1446 2417 +4 1447 2417 1445 1440 +4 1434 2417 1447 1440 +4 2529 1443 1449 1435 +4 1435 1449 2529 2417 +4 1435 1446 1449 2417 +4 1437 1440 1445 2417 +4 1437 2417 1445 1441 +4 1438 2417 1444 1439 +4 1438 1441 1444 2417 +4 1441 2417 1448 1444 +4 1441 1445 1448 2417 +4 1442 1454 1460 2432 +4 1444 2417 1448 1449 +4 1978 2042 1712 1713 +4 1445 1449 1448 2417 +4 2417 1447 1445 1449 +4 1446 2417 1444 1449 +4 1436 2417 1449 1447 +4 1978 1713 1666 2179 +4 1450 1427 1456 1924 +4 1450 1924 1456 1454 +4 1545 1966 1880 1983 +4 341 1545 1880 1983 +4 1451 2115 1461 1455 +4 275 301 314 1524 +4 1545 1880 1966 1524 +4 1451 1458 1461 1924 +4 1978 2179 2042 1713 +4 293 341 1545 1880 +4 1452 1455 1457 2379 +4 1453 1924 1462 1456 +4 1453 1459 1462 1923 +4 1453 1924 1923 1462 +4 1783 1728 1535 1701 +4 1454 1456 1460 1924 +4 1783 2179 1535 1728 +4 1455 2379 1461 1457 +4 1455 1461 2379 2115 +4 1917 1839 2035 1784 +4 1456 1924 1462 1460 +4 1937 2292 2578 1799 +4 925 1839 2035 1917 +4 1676 1720 2039 1721 +4 1457 1923 1461 1459 +4 1922 1694 1937 1927 +4 1937 2292 1799 1927 +4 1458 1460 1462 1924 +4 1694 2292 1937 1927 +4 1721 2039 1749 1720 +4 1458 1924 1462 1461 +4 1721 1727 1749 2039 +4 627 2039 1727 1721 +4 627 2039 1721 1676 +4 1459 1461 1462 1923 +4 1461 1462 1923 1924 +4 1632 1965 2018 1678 +4 2064 2343 1464 1550 +4 1550 1944 1872 1238 +4 2537 1880 382 336 +4 2551 1963 1827 1512 +4 2551 1963 1512 2063 +4 1963 1827 1787 2551 +4 1780 1963 2551 2063 +4 2539 1963 2050 1780 +4 424 426 468 2033 +4 527 1552 2488 1480 +4 2033 1637 2488 1552 +4 1552 455 2537 2033 +4 2007 1663 455 1619 +4 1967 1755 1676 1669 +4 1967 1676 1755 2119 +4 1791 1739 1864 2074 +4 2006 1791 1739 1864 +4 2006 1791 2231 1739 +4 1735 1739 2231 1791 +4 1735 1791 2074 1739 +4 1698 2052 1968 1831 +4 470 1597 1476 1635 +4 470 1476 2107 1635 +4 1888 1564 802 2232 +4 470 1635 2107 480 +4 1597 1635 470 480 +4 1585 1624 1618 1682 +4 1483 1690 2261 1588 +4 1588 2562 1690 2261 +4 2261 2192 1690 1561 +4 1137 1187 1876 1877 +4 1137 1877 1876 1846 +4 2086 1992 1579 1596 +4 2086 1690 1579 1992 +4 1678 1527 1683 2078 +4 1678 1527 1733 1683 +4 1943 2193 1678 1683 +4 2193 1683 2078 1678 +4 1884 1979 1915 1958 +4 1840 1498 1564 1908 +4 908 1795 2230 955 +4 1813 2568 1215 1565 +4 1807 1951 1565 2089 +4 2542 2165 1819 1856 +4 1565 1849 2568 1913 +4 2546 1735 2556 2459 +4 1096 1109 2526 1866 +4 2556 1738 1735 2546 +4 1576 1575 2044 1477 +4 1575 2044 1477 1616 +4 1575 1477 1610 1616 +4 2017 1017 975 2027 +4 1096 1866 2526 1829 +4 2017 1803 2027 1809 +4 2017 2027 1802 1809 +4 1564 2451 802 1891 +4 1597 1635 1571 1598 +4 1597 1571 1635 1639 +4 1571 1635 1639 2066 +4 1571 2066 1598 1635 +4 1263 1282 1662 1890 +4 1888 1890 1662 1873 +4 2561 1640 1636 2066 +4 1592 1690 1579 2086 +4 1672 1722 1721 1965 +4 2068 2348 1986 1894 +4 2018 1727 1965 1721 +4 1965 1722 1721 1727 +4 1584 2049 1553 1547 +4 2022 1775 1847 1722 +4 1721 1995 1774 2022 +4 1712 2100 1995 1722 +4 1727 1749 2039 2073 +4 2039 1749 1779 1780 +4 1774 1749 1780 1773 +4 1749 1773 1779 1780 +4 1850 1731 1727 627 +4 1850 1727 1731 1732 +4 1727 1731 1732 2539 +4 1501 1696 1569 2303 +4 627 1731 1727 2039 +4 133 100 179 1899 +4 69 2060 100 133 +4 1727 1731 2539 2039 +4 1777 1546 1989 1515 +4 1777 1546 1515 1996 +4 133 179 208 1899 +4 2298 1808 1606 1802 +4 889 823 2236 945 +4 1515 1540 2289 1546 +4 1515 1989 1540 1546 +4 1996 1515 2289 1546 +4 815 1939 763 1479 +4 815 1701 763 1939 +4 1837 1846 1513 2019 +4 1784 2019 1837 1513 +4 1155 1181 1896 1902 +4 1902 1896 2229 2037 +4 1793 1836 2230 2237 +4 455 1966 1869 2007 +4 1869 1533 2007 1920 +4 1681 1833 2238 1828 +4 1788 1828 1681 2238 +4 1843 1828 1681 1788 +4 1624 2320 1682 1556 +4 1682 2320 2319 1556 +4 1561 2319 1556 1682 +4 1910 2167 1476 1597 +4 2101 1500 1668 1981 +4 2101 1716 1981 1668 +4 2101 2123 1981 2187 +4 1910 2167 1590 1631 +4 2101 1500 1981 2123 +4 2101 1981 1716 2187 +4 470 1476 1757 2107 +4 2371 1463 1724 1785 +4 2371 1674 1785 1724 +4 1734 85 1511 1502 +4 1581 2309 2196 2048 +4 1581 2557 2196 2309 +4 2040 1863 1969 1866 +4 2040 1969 1863 1988 +4 2557 1621 2196 2309 +4 2040 2112 1863 1866 +4 1050 1863 2040 2112 +4 1050 1863 1988 2040 +4 2309 1621 2196 2048 +4 1970 2371 1674 1680 +4 6 8 19 2004 +4 6 2004 19 12 +4 12 19 2352 2004 +4 2004 8 19 2376 +4 2004 2376 19 2352 +4 1627 2302 1628 1632 +4 1601 2080 1599 2561 +4 2048 1628 1627 2302 +4 1780 1826 2063 1824 +4 1643 1692 2065 2029 +4 1487 1851 1856 1154 +4 1150 1487 1856 1154 +4 1939 2042 1543 1762 +4 2127 1512 1826 2063 +4 1939 1543 2072 1762 +4 2127 1512 2063 2133 +4 2067 1547 1553 2048 +4 1585 1960 1682 1618 +4 2067 1587 2048 1553 +4 1738 2244 1371 1737 +4 2067 1581 2048 1587 +4 1737 2244 1371 2052 +4 2067 1547 2048 2159 +4 2067 2159 2048 1581 +4 1685 1686 1850 1732 +4 1975 2009 2020 1755 +4 1755 2009 2190 1975 +4 1698 1826 1968 1963 +4 1963 1827 1826 1968 +4 1698 1963 1786 1826 +4 1607 2468 1740 1862 +4 2468 1637 1740 1862 +4 2375 2468 1637 1740 +4 1855 1473 1984 1884 +4 1965 1722 1678 1673 +4 2423 1537 1884 1855 +4 2318 1678 1673 1965 +4 1855 1979 1537 1884 +4 1855 2423 1473 1884 +4 1855 1979 1884 1984 +4 1554 1555 1588 1592 +4 1549 1588 1555 2086 +4 1549 1554 1555 1588 +4 1647 2283 1920 2007 +4 1966 1647 2007 2283 +4 1555 2086 1588 1592 +4 2223 1812 1840 1907 +4 1378 1812 1840 1351 +4 601 2473 2057 1799 +4 1731 1786 2273 2539 +4 2076 2065 1692 2555 +4 2539 1698 1786 2273 +4 1613 1468 2085 1595 +4 1613 1596 2085 2194 +4 1613 1596 2194 1600 +4 1686 2065 2076 2555 +4 2455 1179 1892 1863 +4 2455 1863 1892 2147 +4 2455 1159 2147 1200 +4 2455 2147 1892 1200 +4 1200 2455 1179 1892 +4 2181 364 1603 1874 +4 1874 1603 1994 2284 +4 2154 1994 1874 1603 +4 1782 1776 1781 1482 +4 1723 2053 1776 1782 +4 1643 1886 1645 2284 +4 1541 2044 1581 2067 +4 2067 2044 1581 1587 +4 1626 2280 1619 2563 +4 1626 1625 2280 2563 +4 1505 1098 1107 1870 +4 1041 1098 1107 1505 +4 1664 2559 1659 1711 +4 2011 1597 1910 317 +4 2011 1597 1522 1910 +4 74 52 2157 100 +4 1679 2540 1467 1630 +4 1679 2077 2038 1630 +4 2540 1735 2572 1630 +4 1630 2438 1735 2572 +4 267 2031 2012 324 +4 2012 1597 1598 1522 +4 2012 2031 1598 1597 +4 100 2157 1899 2060 +4 1888 1564 1662 802 +4 802 1564 1662 2102 +4 1985 1769 1950 1813 +4 1952 1985 1769 1950 +4 1952 1769 1985 917 +4 917 1769 1985 2072 +4 1985 1813 2072 1769 +4 289 299 362 2136 +4 455 1966 2007 1619 +4 1427 1649 1923 1924 +4 1409 1300 1650 2379 +4 1650 1908 1649 1923 +4 1650 1924 1923 1649 +4 2569 1466 2002 2238 +4 1350 2062 1904 1907 +4 2062 1882 1904 1907 +4 2423 1834 1884 1651 +4 1884 1889 1987 1651 +4 1651 1889 2549 1884 +4 2367 2026 1516 2352 +4 2352 2026 1516 1717 +4 1642 2065 2029 1643 +4 1642 2278 2029 2065 +4 952 1795 2230 2392 +4 2275 2026 2352 2004 +4 952 2230 997 2392 +4 160 1518 1605 2327 +4 997 2230 1505 2392 +4 1655 2561 1994 1601 +4 1655 1567 1568 2154 +4 1627 2018 1632 1965 +4 1627 2018 1965 1671 +4 408 465 2301 423 +4 2097 2003 1859 1150 +4 1999 633 1611 1783 +4 2103 633 1611 1999 +4 1538 1982 1576 2136 +4 2136 1982 1576 1575 +4 1060 2331 1150 1859 +4 1150 2331 2003 1859 +4 2452 2097 1859 1150 +4 1060 1859 1150 1134 +4 1134 2452 1859 1150 +4 2158 240 2011 1551 +4 2470 1551 240 2158 +4 2470 2158 1718 1551 +4 1525 1655 2162 2321 +4 1656 1655 1525 2321 +4 1476 1635 2167 1631 +4 1910 2167 1631 1476 +4 1890 1662 1873 1282 +4 1282 1351 1812 1378 +4 1464 2232 2184 1973 +4 2330 1464 2232 2184 +4 2330 2343 2232 1464 +4 1464 2232 1973 2343 +4 2100 2042 1768 2046 +4 2100 1543 2042 2046 +4 2100 1543 2046 1776 +4 1861 1892 1987 1986 +4 1655 1602 1994 2054 +4 2151 1602 1655 2054 +4 1486 1699 764 698 +4 1486 698 2132 1699 +4 1486 764 1699 1700 +4 1545 1925 1966 2563 +4 2051 1493 2310 1797 +4 95 160 1605 1521 +4 160 1605 1521 2327 +4 1605 1478 1521 2327 +4 1675 1782 1789 1949 +4 1723 1677 2553 2053 +4 1677 1769 2053 1950 +4 1715 1990 1677 1952 +4 1715 2024 1952 1677 +4 1593 1629 2061 1992 +4 2009 1765 2544 2188 +4 1674 1689 2077 1953 +4 1674 1724 1953 1785 +4 1593 2061 2086 1992 +4 1953 2038 1675 1723 +4 1678 1722 1527 1673 +4 1975 2009 2188 1765 +4 2051 1864 1929 2329 +4 2329 1569 1929 2051 +4 2216 1661 1667 1981 +4 1726 1998 1508 73 +4 1726 1499 1508 1998 +4 1489 1538 1502 2150 +4 1878 1877 1684 2105 +4 1877 1684 1905 1908 +4 1684 1650 2105 1905 +4 1137 1139 1877 1846 +4 1006 1139 1137 1846 +4 1824 2063 1859 1519 +4 1688 2076 2556 1683 +4 1467 1689 1638 2194 +4 1634 1689 1465 1679 +4 1592 2562 1579 1690 +4 1690 1465 1623 1579 +4 2168 1480 597 646 +4 527 1480 597 2168 +4 2367 1982 1541 2067 +4 401 473 1960 1585 +4 473 1960 1585 1618 +4 2005 1818 1823 2342 +4 1951 1818 2149 1565 +4 2005 1823 2341 2342 +4 2178 1951 1818 2149 +4 2140 1818 2149 2178 +4 502 1783 1728 1611 +4 1678 1850 1733 1727 +4 1678 1527 1727 1733 +4 1632 1678 2318 1965 +4 1787 1832 1828 1827 +4 1787 1832 1827 1968 +4 53 69 1528 2060 +4 1500 1514 1661 2550 +4 98 36 413 1489 +4 98 1489 413 1726 +4 2200 1814 1951 1764 +4 2200 1807 1951 1814 +4 1537 1987 1891 2069 +4 2069 1891 1986 1987 +4 2026 509 1516 1717 +4 1511 2010 2367 1502 +4 1511 2010 2269 2367 +4 22 17 36 2094 +4 22 2094 36 413 +4 17 2094 43 36 +4 22 2094 1734 9 +4 2394 1507 276 245 +4 1476 1631 2107 1635 +4 1476 1631 1757 2107 +4 1631 2174 2107 1635 +4 1998 73 1726 80 +4 1631 2018 2107 2174 +4 1998 2206 1508 73 +4 1521 2327 1554 2412 +4 1729 1687 1491 1641 +4 85 89 216 1489 +4 7 2004 1734 13 +4 1523 1557 2565 1520 +4 1523 1558 2531 2565 +4 1523 2565 1557 1558 +4 2141 1563 1559 1558 +4 1523 2221 1558 1557 +4 2342 1823 2341 1861 +4 2127 2133 2063 1519 +4 17 25 43 2094 +4 383 1740 430 2033 +4 1525 2321 2162 2415 +4 1525 1563 1714 1656 +4 1631 2018 1676 2107 +4 1757 1676 2107 1631 +4 1757 1676 1631 1626 +4 1528 1567 2321 2162 +4 80 2429 181 1726 +4 1726 1539 181 178 +4 43 178 98 1726 +4 2040 1969 1865 1466 +4 2040 1969 1466 1866 +4 2184 1888 802 2232 +4 1364 1911 2175 1392 +4 2100 1775 1722 2075 +4 2075 1775 1776 2100 +4 549 1730 1757 2365 +4 2365 1730 1757 1626 +4 1659 1510 1486 1706 +4 1486 1510 1700 1706 +4 1561 2319 2061 1556 +4 674 1997 673 1697 +4 604 673 1997 2374 +4 2374 2292 1886 1646 +4 1538 1576 2109 1539 +4 1539 2170 2109 1544 +4 758 1975 1532 753 +4 1545 1507 1966 2161 +4 1835 1541 1509 2159 +4 514 577 2103 1999 +4 1544 2023 2170 2109 +4 1545 1546 2161 1925 +4 1545 2161 1966 1925 +4 2131 1551 2199 2008 +4 1546 2159 1925 1586 +4 1548 1588 1554 1549 +4 1555 1592 2548 2086 +4 1549 2182 2086 1555 +4 166 2503 1893 2344 +4 2103 577 633 1999 +4 1790 1643 1640 2065 +4 2285 1640 2300 1643 +4 2300 1640 1790 1643 +4 2300 1790 1640 2066 +4 1554 2548 2412 1555 +4 1555 2412 1560 2548 +4 816 1753 1719 1752 +4 1753 1719 1752 1895 +4 815 1917 2128 1479 +4 2082 1762 2072 1471 +4 1557 2169 1522 1475 +4 1559 1613 2001 1560 +4 1778 1819 2164 959 +4 2411 509 1499 956 +4 509 1499 1478 1750 +4 1013 1885 1909 1240 +4 1232 1013 1176 2419 +4 289 2136 2010 1502 +4 2010 288 2090 2136 +4 289 288 2010 2136 +4 2010 2136 2090 1982 +4 1563 1468 1613 1595 +4 1563 1613 1468 1946 +4 502 2137 1728 1783 +4 1868 1898 2110 2233 +4 1897 2530 2229 2110 +4 2110 1898 1897 2233 +4 1566 2321 2353 1656 +4 2068 1269 1278 2348 +4 2367 2269 1989 1541 +4 1541 2269 1989 1540 +4 1912 1611 1617 2120 +4 1513 2019 1854 1855 +4 1049 1062 1501 2338 +4 2156 1049 1501 2338 +4 2050 1963 2551 1780 +4 2050 1787 2551 1963 +4 1997 1641 1886 1687 +4 2050 1787 1847 2551 +4 2080 1687 1886 1641 +4 2145 1886 1641 2080 +4 2536 1641 1886 1997 +4 2082 1762 1471 1784 +4 2145 2536 1641 1886 +4 2128 1784 1762 2082 +4 1917 1784 2128 2082 +4 2443 1544 1483 2023 +4 2023 1561 1617 2261 +4 1483 1588 2261 1583 +4 1364 1911 2000 2175 +4 2373 2059 1479 1702 +4 2373 925 1479 2059 +4 2361 1569 2329 2051 +4 1929 1794 2051 1569 +4 1792 2383 2241 2461 +4 1285 2447 2449 1894 +4 2112 1506 1829 2040 +4 1846 1139 1877 2019 +4 1006 1139 1846 2019 +4 2005 1823 1818 1815 +4 1715 2187 2245 1716 +4 1211 1881 1875 1229 +4 1229 1233 2062 1274 +4 1716 1771 2187 2245 +4 2054 2300 2561 2066 +4 1815 1823 1818 1950 +4 1994 2561 2054 2300 +4 1664 1710 2087 1711 +4 1574 1580 1647 1507 +4 1541 2159 1581 1509 +4 1664 1710 1670 2087 +4 2087 1671 1711 1721 +4 1664 1711 2087 1671 +4 1577 514 2120 457 +4 457 510 514 2120 +4 1966 1580 1647 2283 +4 2461 2383 1536 1792 +4 1580 1966 1925 2283 +4 1792 1903 2036 1536 +4 1580 1925 2558 2283 +4 1580 1925 1586 2558 +4 1706 1761 2042 1753 +4 2042 1761 1762 1753 +4 1768 1761 1762 2042 +4 1563 1932 1656 2084 +4 1575 1616 2286 2044 +4 1768 1761 2042 1706 +4 2113 1494 1578 2015 +4 1941 2113 2015 1494 +4 1941 2113 1494 1585 +4 1585 1556 1488 2528 +4 956 1725 1982 2067 +4 2067 1583 1725 1982 +4 1982 1583 1725 1576 +4 2159 2196 2048 1581 +4 1586 2579 1590 2306 +4 1581 1587 2309 2048 +4 2159 1509 2196 1581 +4 1581 1615 2196 2557 +4 1587 2048 1591 2305 +4 1588 2562 1592 1690 +4 363 1770 2056 1575 +4 1770 2058 497 2056 +4 363 2056 1961 1575 +4 2056 1509 1961 1575 +4 2115 1451 1461 1924 +4 2115 1461 2379 1924 +4 2056 2146 1509 1575 +4 2115 1924 2379 1650 +4 2056 497 2146 2058 +4 1830 1510 1700 1654 +4 1589 2563 1625 1626 +4 1932 2084 1595 2195 +4 2048 1590 1594 1627 +4 1591 991 2562 1993 +4 1591 1594 1595 2302 +4 1592 1579 1596 2086 +4 1592 1579 1955 1596 +4 437 2308 397 1961 +4 437 2308 1509 1609 +4 565 595 601 2057 +4 595 2057 2523 1799 +4 1589 1708 1910 1590 +4 1556 2320 2319 1629 +4 1770 1575 2058 2056 +4 2056 2058 2146 1575 +4 436 2058 1575 1610 +4 1575 2146 1610 2058 +4 1594 1595 2302 2195 +4 436 1575 2058 1770 +4 1595 1955 1468 2085 +4 1595 2085 991 1955 +4 1595 2302 2195 1633 +4 490 2320 1556 1629 +4 1596 2085 2194 1955 +4 1593 1629 1556 2061 +4 2061 2319 1629 1556 +4 1596 1579 1955 1992 +4 1596 1531 2194 1600 +4 1407 1923 1840 1424 +4 2171 1424 1840 1923 +4 2171 1923 1840 1908 +4 1597 1598 2167 1635 +4 852 941 1517 2142 +4 941 1517 2142 1825 +4 1599 1600 2194 2301 +4 1600 1638 1531 2194 +4 2064 2343 1550 1822 +4 1781 1550 1944 1872 +4 1602 1571 2259 2300 +4 1371 2052 1832 1787 +4 1602 2300 2054 1571 +4 1601 1994 1603 2285 +4 1601 2080 2301 1599 +4 1601 2301 2080 2474 +4 2155 2425 1251 1222 +4 2155 2425 1222 1246 +4 1563 1932 1714 1656 +4 1602 2093 1994 2297 +4 1602 1642 2300 2259 +4 2123 1500 1661 2550 +4 2101 2550 2123 2187 +4 2101 1500 2123 2550 +4 1661 2550 1980 2123 +4 1604 2377 2183 2297 +4 1604 1874 2183 2466 +4 2550 2187 2186 2123 +4 1980 2186 2123 2550 +4 436 1610 502 2124 +4 2124 502 632 1610 +4 2547 2548 1591 2085 +4 2547 1559 2548 2085 +4 1554 2547 2548 1591 +4 1895 1513 1762 1784 +4 1895 1513 1938 1762 +4 2128 1753 1762 1895 +4 2128 1784 1895 1762 +4 1554 2547 1559 2548 +4 2201 1759 1606 2188 +4 20 1717 12 2352 +4 1713 1723 2553 1776 +4 2047 1713 1723 2553 +4 2011 291 317 1910 +4 2011 1910 2008 291 +4 2011 1551 1910 1522 +4 2011 1551 2008 1910 +4 1516 2367 1547 1957 +4 2367 1989 1516 1547 +4 1815 1949 1825 1823 +4 2005 1815 1825 1823 +4 1547 2367 2067 1957 +4 1608 2294 1920 1609 +4 1777 1718 1547 1546 +4 2356 1654 2146 497 +4 1609 1920 1614 2294 +4 1609 1484 2294 1614 +4 497 1654 2146 1610 +4 1546 1718 2049 1551 +4 1610 2146 1616 1654 +4 2470 1551 1718 1546 +4 1996 1718 1777 1546 +4 573 1999 2120 1612 +4 1996 2470 1718 1546 +4 1547 1718 2049 1546 +4 100 144 1899 2157 +4 144 2157 188 1899 +4 52 100 2060 2157 +4 1619 1533 2007 1663 +4 133 100 1899 2060 +4 1619 1663 2560 1533 +4 1614 2559 2196 1615 +4 2283 2558 2577 1620 +4 1615 1616 1654 1510 +4 1615 2196 1621 2559 +4 1615 1665 2559 1621 +4 1615 1654 1659 1510 +4 1619 1620 2559 1664 +4 1619 2560 1663 1664 +4 1620 1671 1627 1621 +4 1620 1621 2559 1671 +4 1620 2559 1664 1671 +4 1621 1665 1628 1622 +4 1621 1671 1665 2559 +4 1622 1628 1621 2305 +4 1786 1963 1780 1826 +4 1786 2539 1780 1963 +4 1995 1767 2166 1774 +4 1995 2166 1721 1774 +4 1626 1676 1670 1730 +4 1658 1709 1705 1704 +4 755 2039 1754 840 +4 840 1731 2039 1786 +4 1765 1766 1816 2552 +4 1628 1627 1632 1965 +4 840 1779 2039 1754 +4 755 2039 840 1731 +4 840 2039 1779 1786 +4 1765 2552 1816 1819 +4 2423 1987 1651 1884 +4 1834 2568 1485 2549 +4 1629 1674 2320 2319 +4 1513 1855 1854 2566 +4 1625 2280 1669 1730 +4 1631 1632 2018 2174 +4 1632 2193 1964 1633 +4 1632 1633 2318 2193 +4 1757 1626 1631 2365 +4 1640 1683 1943 1686 +4 1633 1634 1930 1956 +4 1633 1964 1636 2193 +4 2061 1465 1690 1992 +4 2061 2192 1690 1465 +4 1640 1943 1683 1636 +4 1992 1689 1531 1629 +4 2066 1640 1943 1686 +4 2066 1943 1640 1636 +4 1634 1689 1467 2194 +4 599 673 674 1997 +4 1634 1930 1956 1679 +4 1697 674 2028 1745 +4 1629 1674 1689 1680 +4 1983 1625 455 462 +4 2365 1626 1708 1589 +4 440 1625 1983 462 +4 1655 2353 2154 1568 +4 1568 2353 2154 2457 +4 330 2457 2353 290 +4 2359 1809 1798 1851 +4 1635 1943 2066 1964 +4 1635 1964 2174 1943 +4 2108 2359 1851 1809 +4 1635 2174 1850 1943 +4 1636 1688 2080 2081 +4 1636 2081 921 1688 +4 2150 1538 1502 1982 +4 2068 1269 2348 2513 +4 1638 2080 1641 1688 +4 1638 2207 1491 1641 +4 844 761 1754 840 +4 1794 1569 2422 1493 +4 1794 2422 1569 2237 +4 1083 1485 1839 1848 +4 2035 1485 1473 1839 +4 1496 1839 1917 2082 +4 925 1839 1917 1496 +4 925 1052 2035 1839 +4 1083 1485 1102 1839 +4 1701 2128 1753 1762 +4 1701 2128 1762 1939 +4 98 1489 1726 194 +4 1642 2029 1644 2297 +4 1642 2029 2297 1643 +4 2377 1644 2183 2297 +4 2285 1886 1643 2284 +4 972 1900 1845 1844 +4 2377 1644 1645 2183 +4 972 1900 1804 1845 +4 1886 1645 1646 2292 +4 261 2012 2011 317 +4 1910 1522 1590 2167 +4 1644 1645 2029 2315 +4 1645 1922 2315 2478 +4 1507 1540 2118 1580 +4 1475 1594 1932 2104 +4 2104 2547 2169 1594 +4 2104 2547 1594 1595 +4 1557 2547 2169 2104 +4 2104 1932 1595 1594 +4 1586 2306 1590 1931 +4 1590 1931 2306 1627 +4 1673 1723 1679 1991 +4 1238 1536 2229 1865 +4 1930 1991 1673 1679 +4 2438 1735 2231 1789 +4 1141 2091 1841 1172 +4 1841 1903 1969 1865 +4 1466 1841 2110 1868 +4 2569 1466 2110 1868 +4 1986 1891 1860 1842 +4 2569 2233 1868 2110 +4 2451 1806 802 1891 +4 1973 1891 1806 1842 +4 1973 1806 1891 802 +4 2188 2130 2117 1758 +4 934 2200 939 1814 +4 939 2200 1764 1814 +4 1735 1788 1782 1843 +4 1847 2551 1775 2022 +4 1847 2551 1781 1775 +4 2043 2106 1653 2173 +4 1850 1733 1727 1732 +4 2043 2173 2025 1704 +4 2073 1749 2039 1780 +4 2073 2050 1780 2539 +4 2073 2022 1780 2050 +4 2073 1780 2022 1749 +4 2073 1780 2039 2539 +4 1660 2191 1667 1661 +4 1660 2179 2079 2047 +4 1660 2191 2047 2079 +4 1854 2019 1852 1855 +4 14 1772 5 2430 +4 1852 1877 2270 2135 +4 441 1912 1477 1576 +4 1663 2190 1532 1669 +4 1664 1710 2190 1670 +4 1664 1709 1658 1663 +4 1664 1658 1709 1710 +4 1665 1672 1628 1942 +4 1665 1671 1672 1711 +4 1665 1711 1510 1659 +4 1666 2047 1991 2079 +4 1666 1713 1672 1673 +4 2465 1832 1867 2570 +4 1660 2191 2079 1667 +4 2465 2570 1867 2143 +4 1667 1980 1981 1661 +4 1668 2253 1981 2320 +4 1669 1670 2190 1755 +4 1670 1720 1710 2190 +4 1671 1672 1711 1721 +4 1672 1722 1965 1673 +4 1673 1722 1713 1672 +4 1502 1538 289 2136 +4 1991 1953 1679 1465 +4 2136 1575 2090 1982 +4 1673 1722 2075 1713 +4 1674 1689 1680 2077 +4 1979 1915 1537 1884 +4 2232 1891 1860 1537 +4 2018 1676 2107 627 +4 1679 1630 1467 2077 +4 2102 1498 2000 1564 +4 1676 2107 627 2119 +4 1685 1850 2276 1732 +4 1545 2563 1966 1983 +4 1545 2563 1983 1589 +4 1683 1733 2546 1527 +4 1680 1526 1630 2576 +4 1550 1872 1860 1973 +4 1822 1550 1872 1860 +4 1872 1842 1988 1860 +4 2088 1282 1263 1890 +4 1685 1736 1732 2276 +4 1479 1939 2072 2082 +4 1227 2088 1890 1282 +4 1479 2082 2072 1496 +4 296 1602 2031 358 +4 296 1602 2151 2031 +4 2031 1571 1598 1597 +4 97 2446 1962 130 +4 130 2446 209 2396 +4 1692 2029 1694 2554 +4 97 2446 1528 1962 +4 1628 1627 1965 1671 +4 1692 2555 1743 1744 +4 2113 1960 1578 1494 +4 2113 1960 1494 1585 +4 128 2470 1996 204 +4 128 1718 1777 1996 +4 1882 1907 1873 1234 +4 1234 1873 1888 2223 +4 1873 1888 2223 1662 +4 2100 1768 2042 1712 +4 2367 509 2411 956 +4 2367 2411 1982 956 +4 1807 1565 1814 2574 +4 1999 1612 1617 2120 +4 1565 1814 2574 2472 +4 1494 2120 1617 1612 +4 2083 1660 1623 2125 +4 2261 1623 2125 2083 +4 2125 2261 1561 2192 +4 1623 2125 1660 1667 +4 2125 2192 1561 1667 +4 1150 1887 1487 1194 +4 1611 2083 1617 1660 +4 2083 1611 1617 1912 +4 925 1496 1479 2059 +4 925 2013 1496 2059 +4 925 2013 1026 1496 +4 1516 1584 1547 1718 +4 1718 1584 1547 2049 +4 1476 2365 1631 1910 +4 461 1476 1910 2365 +4 2179 1707 1543 2047 +4 2179 1543 1713 2047 +4 1949 1506 2112 2040 +4 1506 2112 2163 1949 +4 1671 1721 1965 1672 +4 2018 1721 1965 1671 +4 2018 1727 1678 1965 +4 1678 1722 1965 1727 +4 1702 1763 1707 1980 +4 1702 1763 1479 1707 +4 1703 2188 2545 1704 +4 1704 2544 1709 1705 +4 1704 2545 1709 2188 +4 1704 2544 2188 1709 +4 1705 1709 1710 2544 +4 1699 1761 2543 1706 +4 1706 1768 1712 2042 +4 1713 2100 2042 1712 +4 1707 2047 1980 917 +4 1707 1763 917 1980 +4 2123 2187 2186 1715 +4 1071 1472 1855 1471 +4 2123 1715 1981 2187 +4 1471 1472 1855 1883 +4 2545 1709 2188 1975 +4 1709 2009 2190 1710 +4 1709 1710 2544 2009 +4 1883 2232 1855 1857 +4 1709 2009 2544 2188 +4 1883 2232 1472 1855 +4 1466 1841 1865 2110 +4 1710 2166 2009 1720 +4 1710 2544 2009 1766 +4 2569 1466 1865 2110 +4 1712 1768 1995 2100 +4 1995 1775 2022 1722 +4 1713 2100 1722 2075 +4 1713 2553 1543 1776 +4 1332 1860 1872 1988 +4 1997 1697 1687 1886 +4 1715 1990 1724 1677 +4 1332 1860 1988 2070 +4 1715 2245 2187 2024 +4 1715 2024 1677 1724 +4 1715 1469 2187 2186 +4 1715 2187 1469 2024 +4 2245 2187 2024 1771 +4 2317 1921 142 125 +4 1994 2561 2285 1601 +4 1602 1994 2300 2297 +4 1767 2177 1774 1995 +4 1995 1774 1775 2177 +4 2075 2100 1776 1713 +4 1929 2329 1681 1833 +4 1503 1833 2238 2329 +4 2329 1833 2238 1681 +4 1724 1677 1675 1815 +4 1724 1815 2024 1677 +4 1970 1674 2320 1629 +4 1701 1939 2042 1535 +4 1727 1732 1733 2539 +4 1727 1847 2539 1733 +4 1535 2042 1543 1939 +4 2179 1535 2042 1543 +4 1841 2110 1903 1865 +4 1841 1898 1903 2110 +4 188 215 1899 2157 +4 2096 2394 2269 1540 +4 170 2394 2269 2096 +4 1733 1787 1847 2539 +4 1733 1787 1843 1847 +4 1735 1789 1782 1788 +4 2020 1720 2009 1926 +4 222 1551 2131 2008 +4 1674 1724 2253 1715 +4 1674 1715 2253 1981 +4 1674 1715 1990 1724 +4 1736 2185 2189 1737 +4 1736 1737 2052 2185 +4 1738 1371 1843 1733 +4 1738 1843 1371 1681 +4 1738 1681 1791 1843 +4 1551 1522 1590 1910 +4 1910 1551 2008 1590 +4 1725 2109 1583 1544 +4 2165 2542 1534 1856 +4 212 1562 2158 261 +4 212 1562 1557 2158 +4 1774 1821 1780 2153 +4 1774 2153 2177 1821 +4 1780 2153 1821 2551 +4 2153 2551 2064 1821 +4 2177 2153 2064 1821 +4 1525 1563 1656 1566 +4 2099 1566 1563 1525 +4 1146 1155 1902 1181 +4 1181 2037 1896 1902 +4 2371 2142 2245 1724 +4 2253 2371 2245 1724 +4 1970 1674 2371 2253 +4 1970 2253 2320 1674 +4 1185 1191 2486 2155 +4 1752 1895 1761 1753 +4 1466 1829 1866 2002 +4 1756 1763 2071 1951 +4 1751 1803 853 2017 +4 920 981 2337 2017 +4 1760 1810 1759 1766 +4 1760 1803 1759 1810 +4 2239 2177 1775 2064 +4 2239 2177 2064 1817 +4 1761 1767 1768 2541 +4 1895 2499 994 1804 +4 1763 1951 1469 2071 +4 568 1685 2107 654 +4 654 2276 1685 2107 +4 2107 1685 1850 2276 +4 1764 2071 2178 1951 +4 1635 1850 2107 1685 +4 2552 1765 1926 1819 +4 1766 2552 1774 1767 +4 1766 1767 2541 2552 +4 1766 1765 1926 2552 +4 1773 2176 2552 1926 +4 1767 2177 1995 1768 +4 1767 1768 2541 2177 +4 1768 2239 1775 2100 +4 1768 2046 1762 1938 +4 1768 1995 1775 2177 +4 1501 1569 2361 1493 +4 543 1531 1919 2576 +4 2081 1467 1688 1638 +4 1531 2576 1689 1638 +4 1647 1920 1608 2217 +4 2217 1533 1920 1608 +4 1773 1774 2552 1820 +4 1773 1820 2176 1779 +4 2009 1926 1766 1765 +4 1773 2552 2176 1820 +4 1774 2153 2022 1775 +4 1774 1775 2177 2153 +4 1774 2177 2552 1821 +4 1775 1776 2239 1822 +4 1640 1686 2066 1790 +4 1790 1640 1686 2065 +4 1683 1686 1640 2076 +4 1256 1248 1293 2248 +4 1546 1586 2199 1971 +4 1971 1586 2199 1590 +4 1779 1824 1820 2176 +4 2022 1775 2153 2551 +4 1780 1821 1824 2063 +4 1775 2551 2064 2153 +4 1782 1482 1781 1788 +4 1782 1788 1789 1949 +4 1565 1858 2472 1913 +4 1232 1013 1195 1176 +4 628 724 726 2371 +4 1541 1547 2067 2159 +4 2367 1989 1547 1541 +4 1781 1828 1843 1788 +4 1781 1787 1828 1944 +4 1781 1828 1787 1843 +4 1547 2367 1541 2067 +4 1788 1791 1506 2238 +4 1788 1789 1949 1506 +4 1547 2159 1541 1989 +4 1788 1828 1940 1781 +4 1789 1506 2163 1949 +4 1557 2565 1520 1584 +4 1586 1931 1590 2048 +4 2232 1891 1537 1915 +4 1929 2244 1794 2237 +4 1371 1828 1832 1681 +4 1791 2329 2238 1681 +4 1651 1889 1987 1892 +4 1651 2419 1889 1892 +4 261 240 2011 2158 +4 646 1532 692 753 +4 1794 1569 1493 2051 +4 2176 959 1060 1819 +4 2176 1819 1778 959 +4 1580 1920 2283 1614 +4 1920 2577 1614 2560 +4 2201 2236 1758 1606 +4 81 1528 141 1921 +4 1706 1761 2543 1767 +4 2201 880 2483 2236 +4 2415 1525 141 1921 +4 1539 2170 1576 2109 +4 2109 2023 2170 1576 +4 1725 1576 1583 2109 +4 2023 1583 1576 2109 +4 1627 1626 2018 1671 +4 1545 1546 1925 2199 +4 1546 1925 2199 1586 +4 1925 2579 1586 2573 +4 1615 1665 1622 1616 +4 1616 1665 1622 2222 +4 1615 1510 1665 1616 +4 1616 1510 1665 2222 +4 1728 1783 2179 1660 +4 1720 1779 1773 1926 +4 2020 1720 1926 1779 +4 1728 2179 2222 1660 +4 1926 2176 1779 1773 +4 1248 2248 2155 1243 +4 1974 1890 2133 166 +4 1804 1845 2499 994 +4 333 358 1571 411 +4 411 1639 425 1571 +4 2133 166 1890 2434 +4 1807 1951 1814 1565 +4 1035 2165 1808 1534 +4 1810 1809 2542 1798 +4 1762 1784 1513 1474 +4 1950 1818 1813 1215 +4 1035 2165 1534 1856 +4 2335 2003 2345 1954 +4 1816 2003 2345 2335 +4 2031 1602 2151 2054 +4 1816 2345 2331 1820 +4 1816 2335 1798 2003 +4 1817 2177 2330 1954 +4 1540 1541 1835 2159 +4 1817 2290 1954 1857 +4 1540 1835 2118 1580 +4 1540 2159 1835 1580 +4 1817 1857 2566 2290 +4 1823 1818 2111 2342 +4 1823 2111 1470 2342 +4 1819 1820 2331 2533 +4 1820 1859 2345 2331 +4 1821 1464 2551 2064 +4 1821 2064 2330 1464 +4 96 1523 1520 1557 +4 1776 1775 1781 1822 +4 1822 1860 1883 2343 +4 1823 2341 1949 1825 +4 1823 2342 1470 1861 +4 1776 2070 1769 1492 +4 1776 2070 2053 1769 +4 2352 2367 1989 1516 +4 2352 1516 1989 1777 +4 1512 1826 1827 1902 +4 1512 2133 1464 2063 +4 2040 1050 2112 1949 +4 1827 1944 1550 1238 +4 1827 1826 1968 1902 +4 1827 1550 1512 1238 +4 1828 2569 1832 1833 +4 1828 2238 2040 1466 +4 1701 1762 2042 1939 +4 2555 2076 1738 1929 +4 2237 1832 2465 2570 +4 2076 1929 2074 1738 +4 2555 2076 1929 1744 +4 2076 1744 2074 1929 +4 1569 1833 2237 2570 +4 1833 2303 1696 2569 +4 1753 1895 1761 1762 +4 1761 1895 1938 1762 +4 1761 1762 1938 1768 +4 1627 1626 1631 2018 +4 1626 1631 2018 1676 +4 991 1930 1633 1634 +4 1658 1699 1705 2543 +4 1688 1687 2556 2076 +4 206 2393 1582 244 +4 2031 2054 2151 1582 +4 390 408 465 1600 +4 1692 1744 1697 1687 +4 1886 1697 1687 1692 +4 408 465 1600 2301 +4 1692 1687 2076 1744 +4 2301 465 1600 1638 +4 1585 1960 1494 1682 +4 465 1638 1531 1600 +4 390 1600 465 1531 +4 1077 1113 1845 1846 +4 1113 1876 1845 1846 +4 2474 423 2301 1641 +4 1844 1876 1853 1845 +4 2559 1665 1659 1711 +4 1846 2172 1854 2019 +4 1846 2499 1854 2172 +4 1665 1671 1711 2559 +4 2559 1711 1664 1671 +4 1686 2076 1683 1738 +4 2463 1885 1913 2472 +4 1686 1738 1737 2555 +4 1686 1738 2555 2076 +4 1686 1683 1733 1738 +4 1686 1733 1737 1738 +4 1853 1935 1857 1854 +4 1853 1935 1954 1857 +4 1854 1852 1857 1855 +4 1854 1852 1935 1857 +4 1944 1828 1872 1865 +4 1700 2042 1753 1706 +4 1828 1944 2340 1865 +4 1828 1865 2040 1872 +4 1157 2129 1879 1177 +4 1828 2040 1865 1466 +4 1195 1013 1240 1208 +4 1828 1865 2340 2569 +4 2003 1935 1974 1954 +4 2003 2335 1936 1935 +4 2170 2015 2443 1544 +4 2014 1544 2443 2015 +4 1857 2184 1935 1974 +4 1857 1852 2232 1855 +4 1857 1974 2330 2184 +4 1857 1234 1852 1935 +4 1857 1852 1234 1888 +4 1855 1979 1984 2019 +4 1849 1848 2549 1879 +4 1849 1885 1879 2549 +4 1537 2069 1891 1860 +4 2429 2170 1544 2015 +4 1849 1848 2568 2549 +4 1849 2549 1913 1885 +4 2160 1195 1013 1858 +4 1849 2568 1913 2549 +4 2429 1544 2014 2015 +4 1765 1810 2542 1816 +4 1759 2542 1765 1810 +4 1765 1766 1810 1816 +4 1759 1810 1765 1766 +4 2381 2554 1693 2278 +4 567 1638 1641 2207 +4 1860 1986 1988 2069 +4 1861 1892 1986 1863 +4 1863 2535 1969 1866 +4 1863 1986 1969 2535 +4 2535 1228 1179 2339 +4 1679 2077 1953 2038 +4 2077 2038 1675 1953 +4 1479 2072 1939 1707 +4 1707 1543 917 2072 +4 1707 1535 1543 1939 +4 1706 1761 1767 1768 +4 2550 2122 2071 2187 +4 2330 1974 1464 2184 +4 2101 2550 2187 2122 +4 2550 1756 2071 2122 +4 1857 1888 2184 2232 +4 2231 1789 1791 1506 +4 1735 2231 1789 1791 +4 1788 1789 1506 1791 +4 1735 1788 1791 1789 +4 2003 1935 1936 1887 +4 1103 1879 1848 1849 +4 1142 1879 1849 1183 +4 1142 1103 1849 1879 +4 1183 1885 1879 1849 +4 1844 1809 1798 2359 +4 1803 1809 1810 1900 +4 1803 1844 2027 1809 +4 1900 1809 1810 1798 +4 2027 1844 2359 1809 +4 1709 1658 2043 1704 +4 1709 2043 2545 1704 +4 1576 1976 1583 2023 +4 1761 1895 1811 1938 +4 1895 1811 1938 2499 +4 1761 1938 2541 1768 +4 1576 1477 1976 1912 +4 1768 1817 1938 2541 +4 1576 1477 2044 1976 +4 1576 2044 1583 1976 +4 1962 1582 2162 1525 +4 2261 1623 1690 2192 +4 1962 2162 1582 2393 +4 1582 1655 2162 1525 +4 2125 2261 2192 1623 +4 2162 1655 1567 2321 +4 2125 1623 2192 1667 +4 1690 2192 1623 1465 +4 2192 1623 1465 1667 +4 1778 1819 1765 2164 +4 2130 2117 2164 1765 +4 1946 1601 1599 1656 +4 2165 1819 1765 2542 +4 2117 1765 2542 2165 +4 1711 1767 2166 1995 +4 1199 1906 2129 1177 +4 1878 1877 1984 1684 +4 1878 2564 1684 1984 +4 1177 1906 2129 1879 +4 1879 2129 2549 2564 +4 2166 1767 1766 1774 +4 2472 1885 1913 2160 +4 1913 2160 1013 1858 +4 2472 2160 1913 1858 +4 1913 1885 1013 2160 +4 2103 633 502 1611 +4 1877 1984 1684 2135 +4 1877 1908 2270 2135 +4 1877 1905 2270 1908 +4 310 1585 1941 312 +4 312 1941 2528 1585 +4 1488 1941 1494 1585 +4 1821 1974 2063 1464 +4 1967 1757 1730 1676 +4 1967 1730 1669 1676 +4 2063 2133 1464 1974 +4 1821 1859 2063 1974 +4 2063 2133 1974 1859 +4 1484 1659 2294 1614 +4 26 19 2352 12 +4 2132 1659 2294 1484 +4 26 20 12 2352 +4 436 497 2058 1610 +4 1642 2278 1644 2029 +4 1642 2065 2279 1691 +4 1889 1987 1892 2426 +4 2058 2146 1610 497 +4 1943 1636 2193 1683 +4 1842 1238 1865 1792 +4 1842 1865 1969 1792 +4 2352 2367 2269 1989 +4 2352 2376 2269 2367 +4 1803 1809 1900 1844 +4 1844 1809 1900 1798 +4 1946 1613 1599 1600 +4 1900 1844 1798 1853 +4 895 2138 1805 973 +4 973 1503 2138 1805 +4 895 2138 2006 1805 +4 2138 1503 2006 1805 +4 2351 2034 2443 1549 +4 2351 2443 2034 2014 +4 1865 1969 1792 1903 +4 1366 1421 1947 2175 +4 1628 1665 1671 1672 +4 1889 1987 2426 1911 +4 1366 1947 1911 2175 +4 1404 2432 1947 1432 +4 1421 1442 1947 2432 +4 1432 2432 1947 1442 +4 2050 2551 2022 1780 +4 1774 2153 1780 2022 +4 1780 2022 2153 2551 +4 363 437 1961 2056 +4 437 1509 1961 2056 +4 437 2146 1509 2056 +4 437 497 2146 2056 +4 363 436 1770 1575 +4 436 2058 497 1770 +4 1033 1825 2526 1056 +4 1056 2341 1825 2526 +4 2373 763 1702 1479 +4 2289 2161 1545 1546 +4 1507 2161 1545 2289 +4 1274 1277 2062 1350 +4 1316 1350 2062 1904 +4 2150 2109 1725 1544 +4 1538 1576 1725 2109 +4 2150 2109 1538 1725 +4 1262 1256 2267 2268 +4 1958 2175 2000 1911 +4 2468 678 2043 1653 +4 2260 1871 1870 2530 +4 2468 1657 2043 678 +4 1685 1686 1732 2189 +4 1860 1891 1986 2069 +4 2279 1691 2189 1685 +4 2279 2065 2189 1691 +4 1987 2348 1891 1986 +4 1686 1732 2189 1737 +4 1861 1651 1987 1892 +4 1987 2068 2348 1986 +4 1987 2348 2068 2021 +4 669 674 747 1745 +4 669 1745 2028 674 +4 1904 2171 2270 1905 +4 669 1745 747 744 +4 1906 2432 1650 2041 +4 669 744 1739 1745 +4 669 1745 1739 2028 +4 2292 2249 1697 1692 +4 1886 2292 1697 1692 +4 1655 1601 1994 2154 +4 2154 1601 1994 1603 +4 1692 1744 2249 1697 +4 1655 1994 1945 2154 +4 2158 1562 1522 261 +4 1788 1681 1791 2238 +4 1788 2238 2040 1828 +4 2042 1543 1762 2046 +4 1949 2163 1789 1481 +4 1776 1822 2046 2239 +4 1762 1938 2046 1474 +4 1817 1883 2239 2046 +4 1817 2046 1474 1883 +4 2183 1994 2297 1643 +4 2183 1643 2297 2029 +4 1469 1950 1818 1813 +4 2284 1994 2183 1643 +4 2284 1643 2183 1645 +4 1071 2111 1800 1215 +4 1763 1813 1469 1951 +4 1951 1469 1818 1813 +4 1978 1712 1672 1713 +4 1978 1713 1672 1666 +4 2549 1884 2129 1834 +4 1485 2549 2129 1834 +4 2100 1775 1995 1722 +4 2100 1768 1995 1775 +4 1952 1950 1769 1677 +4 1952 1985 1763 917 +4 2115 1650 2432 1924 +4 2115 2432 1451 1924 +4 1691 2554 2278 2065 +4 2381 2554 2278 1691 +4 1691 1741 2381 2189 +4 1707 1543 2072 1939 +4 1606 1802 2017 2236 +4 1667 1465 1953 2254 +4 876 920 924 2236 +4 920 2337 2236 2017 +4 1660 1707 2179 2047 +4 1666 1713 1673 1991 +4 1991 1723 1713 1673 +4 2065 2555 2189 2554 +4 2065 2189 1691 2554 +4 1349 1947 1906 1909 +4 1286 1349 1906 1909 +4 1879 1909 1906 2564 +4 1286 1909 1906 1879 +4 2564 1906 2041 1909 +4 1701 2042 1700 1830 +4 1830 2042 1535 1701 +4 1728 1830 1535 1701 +4 2188 1765 1759 2542 +4 2188 2542 1759 1606 +4 2488 1637 1657 1663 +4 2488 1657 2545 1663 +4 2061 1561 1690 2192 +4 1561 2192 2061 2319 +4 1561 2192 2319 1667 +4 1687 1739 1745 2028 +4 2438 1735 1739 2231 +4 1732 1733 2539 2052 +4 1737 2052 1733 1732 +4 1733 2052 1371 1787 +4 2052 1733 2539 1787 +4 1733 1737 1371 2052 +4 2168 1625 1480 545 +4 1060 1819 2533 2176 +4 1793 2265 2387 1742 +4 1274 1277 1233 2062 +4 1220 2062 1233 1277 +4 1657 2043 2055 1703 +4 2043 2055 1703 1704 +4 2345 2541 2335 1954 +4 1657 2545 2043 1703 +4 2545 2043 1703 1704 +4 1595 1633 1468 1955 +4 2411 1502 2367 1982 +4 1595 1955 991 1633 +4 2194 1468 1599 2180 +4 1955 2194 2180 1468 +4 1955 991 1633 1634 +4 2539 1787 2050 1963 +4 1698 2539 1786 1963 +4 2052 2539 1968 1787 +4 2052 2539 1698 1968 +4 2539 1963 1968 1787 +4 2562 1623 1993 1579 +4 1591 2302 1595 991 +4 2562 1993 1623 1622 +4 2555 1738 2244 1929 +4 2258 2244 1742 1743 +4 2023 1561 1494 1617 +4 1494 1682 1617 1561 +4 1578 2120 1494 1612 +4 1220 2062 1887 1881 +4 1881 1936 2062 1887 +4 1487 1936 1881 1887 +4 1194 1887 1881 1220 +4 1194 1887 1487 1881 +4 490 1629 1556 1593 +4 385 409 490 1593 +4 490 1593 409 503 +4 490 1629 1593 503 +4 385 1593 490 1556 +4 1636 1688 921 1683 +4 1956 1636 921 2193 +4 1633 2193 1636 1956 +4 1633 1956 2318 2193 +4 2318 2078 1673 1678 +4 1711 2166 1710 2087 +4 1711 1721 2166 2087 +4 2166 1720 1721 1774 +4 2064 1781 1550 2551 +4 1775 1781 2064 2551 +4 1822 1781 1550 2064 +4 1112 1118 2287 2127 +4 1660 2079 2222 1623 +4 1902 1112 2287 2127 +4 2127 2133 1118 2287 +4 1775 1781 1822 2064 +4 1981 1500 1682 1661 +4 1500 1514 1682 1661 +4 1839 1813 1959 1471 +4 1496 1813 1839 1471 +4 1906 2041 1947 2432 +4 1839 1959 1473 1471 +4 1496 1839 2082 1471 +4 1217 1877 2105 1905 +4 2105 1877 1684 1905 +4 617 2468 678 652 +4 652 1657 2468 678 +4 1784 1839 1473 1471 +4 2082 1839 1784 1471 +4 617 1653 678 2468 +4 1751 1803 1759 2114 +4 1678 1943 1683 1733 +4 1678 1850 1943 1733 +4 2114 1803 1759 1760 +4 1943 1683 1733 1686 +4 1943 1686 1733 1850 +4 2207 2576 1491 1526 +4 2207 1491 1729 1739 +4 2207 1526 1491 1739 +4 898 2230 2387 893 +4 1259 1875 1876 2062 +4 1876 2062 1882 1904 +4 1936 2062 1876 1875 +4 1936 1876 2062 1882 +4 1957 2322 1520 1478 +4 1259 2062 1876 1904 +4 1957 1478 956 1548 +4 1611 1783 1728 1660 +4 1611 1783 1660 1999 +4 1543 1762 2046 2072 +4 1543 2072 2046 1769 +4 1244 1876 1877 1904 +4 1244 1905 1904 1877 +4 1877 2270 1905 1904 +4 1876 1904 2270 1877 +4 2285 1640 1643 1886 +4 486 550 1612 1618 +4 2285 1886 2080 1640 +4 1960 1618 1612 1682 +4 1643 1692 1886 1640 +4 486 1618 1612 1960 +4 550 1612 1618 1514 +4 1958 1649 1908 1498 +4 1877 2135 1684 1908 +4 2041 1650 1906 1684 +4 225 2289 1507 219 +4 225 2394 1507 2289 +4 2061 1465 1629 2319 +4 2061 1629 1465 1992 +4 1629 2319 1465 1674 +4 1992 1629 1465 1689 +4 1629 1689 1674 1465 +4 286 328 2214 1578 +4 328 359 2214 1578 +4 359 1578 1577 2214 +4 286 1539 2429 2214 +4 2214 1578 1577 2170 +4 1932 1562 1714 1934 +4 1932 1714 1656 1934 +4 2371 2142 1724 1463 +4 1784 2019 2035 1837 +4 2420 2035 1837 1784 +4 830 2006 2231 1739 +4 830 2438 1739 2231 +4 1466 1969 1865 1841 +4 1466 1969 1841 1866 +4 2200 2071 1764 1951 +4 2122 2200 2071 1764 +4 1755 2039 1720 2020 +4 1755 1676 2039 2119 +4 2119 2039 1755 2020 +4 1755 1676 1720 2039 +4 1113 1187 1876 1137 +4 1113 1137 1876 1846 +4 324 2031 2012 1597 +4 2012 1597 317 324 +4 757 765 2381 813 +4 2158 2169 1522 1557 +4 2049 2158 1557 2169 +4 1472 2070 2069 1860 +4 1718 2049 2158 1557 +4 92 117 1521 1523 +4 92 1523 1521 1520 +4 1696 2569 2002 2238 +4 147 1521 117 2531 +4 1520 2565 1523 1521 +4 1071 1959 1855 2423 +4 1521 2531 2565 1523 +4 1696 1868 2002 2569 +4 1471 1959 1855 1071 +4 1855 1959 1473 2423 +4 64 1520 1718 129 +4 129 1557 1520 1718 +4 363 1961 2090 1575 +4 1961 1509 1541 1575 +4 1489 98 120 194 +4 997 1836 2230 1012 +4 997 2230 1836 1505 +4 2441 2442 1916 2291 +4 2569 2530 2233 2110 +4 2235 2530 2233 2569 +4 2303 2530 2235 2569 +4 2235 2233 1868 2569 +4 2303 2235 1696 2569 +4 1696 2235 1868 2569 +4 2567 1558 1932 1563 +4 1544 1998 1726 2429 +4 1726 1544 1499 1998 +4 1726 1544 2429 1539 +4 2208 2422 1111 1870 +4 1726 2150 1499 1544 +4 2208 2303 2422 1870 +4 1726 1539 2150 1544 +4 1108 2208 1111 1870 +4 1108 1871 2208 1870 +4 2208 2303 1870 1871 +4 1874 2284 2183 2466 +4 2567 1563 1932 1714 +4 2284 1994 1874 2183 +4 1092 1122 2235 2211 +4 2184 2045 1935 1974 +4 2061 1690 2086 1992 +4 1092 2211 2235 1696 +4 2211 1122 2235 1871 +4 2182 2061 1690 2086 +4 2211 1871 2235 1696 +4 2567 1932 1562 1714 +4 2567 1558 1562 1932 +4 2054 1571 1598 2031 +4 1759 1803 1751 1606 +4 1606 1803 2017 1809 +4 262 1549 1555 2182 +4 262 2034 1549 2182 +4 195 262 1549 1555 +4 2351 195 262 1549 +4 2351 262 2034 1549 +4 1751 1803 2017 1606 +4 1309 1279 2203 1358 +4 2203 2291 1916 2210 +4 2203 2336 2448 1358 +4 1358 1279 2203 2425 +4 2203 2425 2291 2210 +4 2203 2336 1916 2448 +4 129 102 191 1718 +4 129 1557 1718 191 +4 1718 102 191 165 +4 165 191 1718 2470 +4 2470 191 1718 2158 +4 2132 1484 1654 1659 +4 636 2132 1654 1486 +4 2132 1659 1654 1486 +4 636 2356 1654 2132 +4 2356 1609 1654 2132 +4 2132 1609 1654 1484 +4 191 1718 2158 1557 +4 2352 65 1515 2376 +4 1501 1696 1871 2211 +4 1501 2211 1871 1090 +4 1090 1871 1122 2211 +4 2428 2442 2441 2291 +4 2441 2428 1348 2442 +4 2428 2442 2291 2433 +4 1311 2442 2428 2433 +4 1311 2428 2442 1348 +4 2208 2422 2360 1111 +4 1108 2208 2360 1111 +4 2479 1111 2360 2422 +4 1583 2242 2083 2557 +4 2557 1623 2242 2083 +4 1206 2227 1896 1251 +4 1206 1196 2227 1251 +4 1196 2486 2227 1251 +4 2486 1251 2246 2227 +4 2227 1251 2246 1896 +4 896 1797 2453 926 +4 1665 2222 1978 1666 +4 2222 1666 2179 1978 +4 2121 2453 1493 1797 +4 2121 2453 1797 926 +4 889 2236 2483 880 +4 1229 1881 1875 2062 +4 1220 2062 1881 1233 +4 1229 1881 2062 1233 +4 1936 1881 2062 1875 +4 187 1525 2567 1582 +4 2567 1714 1582 1525 +4 2053 1050 2070 1332 +4 2567 1714 1562 1582 +4 187 1582 2567 1562 +4 1050 1823 2053 2070 +4 1343 1366 1909 1911 +4 2426 1911 1909 1889 +4 2041 1911 1909 1947 +4 1366 1909 1911 1947 +4 2426 1343 1909 1911 +4 1957 2067 1547 1553 +4 117 2531 1523 136 +4 117 1521 1523 2531 +4 2155 1251 2486 1196 +4 1557 1475 1522 1562 +4 943 1764 2178 1814 +4 943 2140 1814 2178 +4 943 1764 1771 2178 +4 943 2140 2178 1771 +4 2158 1562 1557 1522 +4 2440 1869 1573 2416 +4 2486 2155 2257 1251 +4 2486 2257 2246 1251 +4 2440 1524 1869 2416 +4 2234 1933 284 271 +4 311 2247 370 1596 +4 332 390 2247 1600 +4 311 1596 1560 2247 +4 2247 1600 1596 1560 +4 2218 2205 2450 2370 +4 2060 2370 2205 1933 +4 1828 2238 1466 2569 +4 1828 1466 1865 2569 +4 382 1983 455 462 +4 1598 2167 1635 1964 +4 440 1983 382 462 +4 2218 1933 2205 2370 +4 2560 2559 1659 1664 +4 2433 2248 2291 2267 +4 2267 2248 1256 2433 +4 2167 1635 1964 2174 +4 96 1523 2202 119 +4 135 2204 2202 172 +4 2202 172 2204 2221 +4 2202 1557 1523 96 +4 2202 2221 1523 1557 +4 1594 2167 1598 2195 +4 900 1495 1698 1831 +4 2117 1808 2454 971 +4 2454 1808 1606 2298 +4 2454 2117 1606 1808 +4 1816 1798 1856 2003 +4 1798 1856 1487 1851 +4 1309 1358 2203 2448 +4 2336 1358 2203 2425 +4 2569 2110 2229 2530 +4 1554 1588 1553 1591 +4 215 1933 2234 271 +4 1548 1554 1588 1553 +4 2203 2210 1916 2336 +4 1121 1141 1866 1868 +4 1141 1841 1866 1868 +4 1466 2002 1866 1868 +4 1121 1868 1866 2002 +4 341 1589 1983 355 +4 1466 1841 1868 1866 +4 2203 2425 2210 2336 +4 1587 2557 2309 1622 +4 1587 2048 2305 2309 +4 1587 1622 2309 2305 +4 2060 1933 2205 2157 +4 2157 1933 2205 1542 +4 1501 1871 2208 1101 +4 1860 1988 1986 1842 +4 1062 1501 2360 2208 +4 1062 1501 2208 1101 +4 129 1557 191 159 +4 2116 2291 1916 1251 +4 25 43 1726 80 +4 80 247 181 2429 +4 2289 164 226 219 +4 243 2289 1545 2131 +4 226 243 2289 1545 +4 2530 2227 1896 1867 +4 2001 1946 1613 1563 +4 1896 1897 2246 2530 +4 2530 2229 1867 1896 +4 1896 2530 2229 1897 +4 1880 341 382 336 +4 384 352 2537 393 +4 1051 999 1505 2479 +4 1550 1512 1973 1464 +4 759 577 1702 762 +4 997 2484 1505 999 +4 2428 2441 2116 2291 +4 215 1933 2157 239 +4 824 890 895 1805 +4 1821 1820 2345 2552 +4 1774 2552 1820 1821 +4 1640 1683 1688 1636 +4 928 932 2354 953 +4 930 926 2571 954 +4 2110 2233 1897 2530 +4 972 1017 1803 1054 +4 234 1529 274 246 +4 1683 1640 1688 2076 +4 234 257 274 1529 +4 246 274 1542 1529 +4 2472 1138 2160 1858 +4 2530 1897 2251 2233 +4 274 1542 1529 2450 +4 239 1933 2157 1542 +4 257 1529 2450 274 +4 2027 1042 1100 1084 +4 1074 1103 1849 1104 +4 2072 1762 2046 1471 +4 2072 1471 2046 1769 +4 2037 1226 1893 1977 +4 2303 2235 2530 1871 +4 1532 1755 2190 1975 +4 1975 2009 2190 1709 +4 378 362 1576 441 +4 23 2362 16 49 +4 2016 2517 1869 2416 +4 2354 2514 2209 1493 +4 1958 2175 1498 2000 +4 896 2453 902 926 +4 956 1548 1725 2067 +4 2067 1583 1548 1725 +4 1928 1707 1702 1783 +4 1783 1702 1928 1999 +4 1957 956 2067 1548 +4 633 1702 1783 1999 +4 633 1702 763 1783 +4 2564 1906 1684 2041 +4 1581 2557 2309 1587 +4 2232 1979 1888 1564 +4 1855 1852 1979 2019 +4 1855 1979 1852 2232 +4 2121 2571 1493 2453 +4 2121 2571 2453 926 +4 1980 2186 1715 2123 +4 1980 1990 1715 1952 +4 1980 2186 1952 1715 +4 1500 1668 1981 1682 +4 1556 1585 1682 1624 +4 1827 1512 1902 1238 +4 1902 1512 2287 1238 +4 1238 2287 1902 2037 +4 1902 2229 1238 2037 +4 1827 2340 1238 1902 +4 214 289 2010 1502 +4 288 363 2090 362 +4 363 1575 2090 362 +4 2010 2367 1502 1982 +4 2340 1238 1902 2229 +4 2060 2205 2271 2157 +4 1684 1908 1650 1905 +4 1958 1908 1650 1684 +4 1958 1650 1908 1649 +4 1984 1958 1979 1884 +4 1502 2411 2275 413 +4 413 2411 2275 509 +4 2275 2367 2411 1502 +4 2411 2367 2275 509 +4 2157 2205 2271 1542 +4 2429 260 247 181 +4 2018 1721 627 1727 +4 135 124 2204 150 +4 2518 2271 1542 2157 +4 2518 2521 2271 2157 +4 2224 2428 1280 1224 +4 1478 1520 1521 2322 +4 236 1560 1555 192 +4 2204 1523 2221 2567 +4 354 2016 2517 396 +4 1915 1987 1891 1537 +4 1915 1891 1987 2000 +4 1987 1891 2348 2000 +4 236 1555 280 195 +4 2224 1280 2428 1262 +4 354 2016 2416 2517 +4 1050 1863 1861 1988 +4 1988 1986 1863 1861 +4 1988 1863 1986 1969 +4 2555 2244 2258 1743 +4 1092 1122 2211 1068 +4 2189 2555 2185 2258 +4 2555 2185 2258 2244 +4 1092 1068 2211 1696 +4 1122 1160 2235 1153 +4 1160 2235 1153 2226 +4 236 280 1555 1560 +4 2235 2530 1871 2226 +4 1503 1696 2238 1833 +4 2554 2555 2189 2258 +4 2555 1743 2258 2554 +4 1828 2569 1833 2238 +4 247 248 312 2014 +4 1546 1971 1551 2049 +4 247 2015 310 260 +4 314 336 1880 2537 +4 247 2014 312 310 +4 1621 1627 1628 1671 +4 1621 1665 1671 1628 +4 1990 1723 1677 2553 +4 1990 1723 1675 1677 +4 1667 1990 2254 1953 +4 1953 1990 1723 1675 +4 2336 2295 2210 2417 +4 972 1803 1900 1844 +4 2425 2295 2210 2336 +4 1465 1953 1679 1689 +4 1689 1679 2077 1953 +4 1974 2097 2045 2003 +4 1636 1688 1640 2080 +4 1955 1992 1634 2194 +4 2003 2045 1887 2097 +4 1579 1930 1465 1623 +4 1955 1634 1992 1579 +4 1634 1689 2194 1992 +4 1634 1992 1465 1689 +4 1622 1628 2305 1993 +4 761 755 1754 840 +4 1628 1942 2318 1993 +4 1587 2305 1993 1622 +4 313 2182 2198 1593 +4 2192 1465 2061 2319 +4 2182 1593 2086 2198 +4 1538 1576 315 2136 +4 1602 1994 2054 2300 +4 1945 2093 1994 1602 +4 2228 2218 2450 1570 +4 315 1576 362 2136 +4 124 1523 2204 140 +4 135 119 2202 1523 +4 135 1523 2202 2204 +4 350 1577 1539 329 +4 2202 2204 1523 2221 +4 1656 1655 1582 1525 +4 329 1577 2214 359 +4 318 303 2440 2416 +4 128 184 1996 1777 +4 1826 1831 1968 1902 +4 1997 584 1641 1729 +4 436 1576 1575 362 +4 457 1578 1577 377 +4 2031 2054 1571 1602 +4 282 1524 2440 303 +4 2060 2157 2271 2496 +4 384 426 393 2537 +4 282 2440 318 303 +4 1939 1762 2072 2082 +4 856 2152 1804 1803 +4 2128 2082 1762 1939 +4 303 1524 2440 2416 +4 2152 1760 1804 1803 +4 1518 1549 1499 2327 +4 1518 1998 1499 1549 +4 2537 393 424 426 +4 1499 1544 1548 1549 +4 1998 1544 1499 1549 +4 2537 412 424 393 +4 1499 1549 1548 2327 +4 1505 1870 1111 2422 +4 1617 1660 1661 1999 +4 1505 2422 2570 1870 +4 1357 2000 1498 1389 +4 1542 2228 2205 2450 +4 2277 2218 1933 2228 +4 2303 2570 2422 1870 +4 570 1514 693 573 +4 2243 2218 1933 2277 +4 2243 2218 2370 1933 +4 1371 1832 1828 1787 +4 1501 2422 2360 2208 +4 1542 1933 2205 2228 +4 259 2014 2034 312 +4 312 2528 2014 2034 +4 1501 2303 2422 2208 +4 249 2099 1566 2001 +4 526 2532 2057 1646 +4 2246 1251 1897 1896 +4 2246 2257 1897 1251 +4 504 1612 446 1578 +4 504 1578 493 1612 +4 508 438 2259 1642 +4 2530 2233 2226 2235 +4 504 1612 510 446 +4 2233 1868 2256 2235 +4 512 2217 456 466 +4 2514 2209 1493 2571 +4 2027 2359 2108 1809 +4 1975 2020 849 758 +4 1975 849 2020 1778 +4 1569 1503 2329 1833 +4 1569 2361 2329 1503 +4 1999 1514 1612 573 +4 57 95 1605 2362 +4 2362 1605 1478 1521 +4 2425 1388 1358 1333 +4 2224 1224 2495 2428 +4 1593 1596 2086 2198 +4 1593 1992 2086 1596 +4 2411 1725 1982 956 +4 2411 2150 1982 1725 +4 2224 2268 2428 2495 +4 489 1639 582 508 +4 2336 2425 1388 1358 +4 504 1612 573 510 +4 2336 2425 2295 1388 +4 1479 1496 2072 1763 +4 812 925 2373 2059 +4 504 570 573 1612 +4 1112 1118 2464 2287 +4 1463 1497 1481 1789 +4 2287 2133 1118 2512 +4 582 2279 508 1639 +4 2118 1835 2308 1580 +4 514 1999 2120 573 +4 291 367 1910 2008 +4 367 2365 461 1910 +4 2004 2376 13 8 +4 7 1734 18 13 +4 513 540 521 2525 +4 2118 1835 1961 2308 +4 521 540 542 2525 +4 222 264 2008 2131 +4 1665 1978 1510 1712 +4 824 1805 895 2006 +4 824 2006 1745 1805 +4 1665 1712 1672 1978 +4 2361 1493 2051 1797 +4 2394 1507 245 225 +4 521 542 526 2057 +4 2394 1540 2289 1515 +4 1899 2370 2243 1567 +4 1899 2243 2370 1933 +4 2001 1563 1566 1946 +4 497 1654 636 2356 +4 2001 1566 1563 2099 +4 271 2243 1933 284 +4 1929 1681 2237 1833 +4 1929 1681 1371 2237 +4 2136 288 2090 362 +4 2224 1262 2428 2268 +4 540 2523 564 542 +4 1796 2453 2209 2220 +4 1484 1614 1615 1659 +4 2354 2514 1796 2209 +4 2514 1796 2209 2220 +4 1480 597 692 2488 +4 1609 1654 2146 2356 +4 437 2356 1609 2146 +4 647 1680 2576 1526 +4 2207 647 543 2576 +4 584 2028 669 1729 +4 1729 1739 2028 669 +4 577 514 573 1999 +4 1487 1881 1851 1154 +4 1798 1851 1487 1881 +4 510 573 2120 1612 +4 1501 1696 2211 1068 +4 1045 1092 1696 1068 +4 1023 1501 1068 1696 +4 1023 1696 1068 1045 +4 164 1996 184 1777 +4 583 2468 634 1657 +4 602 2374 1646 2458 +4 24 2206 31 73 +4 284 298 1933 2234 +4 2234 298 1933 2263 +4 603 2374 1646 602 +4 270 282 303 1524 +4 1918 2264 2210 2417 +4 1918 2264 2417 1414 +4 1560 1600 2001 277 +4 1971 2048 1590 2169 +4 1971 2048 2169 2049 +4 637 626 648 2578 +4 577 762 633 1702 +4 577 633 1999 1702 +4 1702 763 762 633 +4 2228 2205 2450 2218 +4 1524 343 2416 303 +4 1728 632 1610 1654 +4 2228 1542 1933 2263 +4 1026 1839 2089 1848 +4 637 648 676 2578 +4 1793 2237 2230 2265 +4 2265 2237 2392 1794 +4 2244 2265 1794 2237 +4 2375 1637 1657 2488 +4 637 2578 676 651 +4 565 601 2473 2057 +4 2265 2237 2230 2392 +4 2244 2052 2265 2237 +4 1896 2246 2227 2530 +4 526 565 2473 2057 +4 2532 2478 1646 1645 +4 2260 2246 2226 2530 +4 2486 2246 2226 2260 +4 1682 1661 2216 1981 +4 1682 1981 2216 2319 +4 1561 2216 2319 1682 +4 1617 2216 1561 1682 +4 1617 1682 1661 2216 +4 1573 2217 1869 1647 +4 1506 1829 2163 2112 +4 2534 1506 2238 1829 +4 2534 1829 2163 1506 +4 1389 2175 1498 1649 +4 466 2435 2418 2217 +4 466 1608 2217 2418 +4 812 2013 2059 1756 +4 2013 1763 1756 1951 +4 812 2013 925 2059 +4 2013 1496 1763 1813 +4 248 259 2014 2351 +4 310 1941 2015 2014 +4 247 248 2014 2429 +4 247 2015 2014 310 +4 259 2351 2034 2014 +4 2033 2375 1637 1740 +4 796 2215 2212 2493 +4 2173 1699 1658 2132 +4 878 2212 848 2453 +4 796 2215 848 2212 +4 664 1695 684 679 +4 260 2429 2015 286 +4 2076 1738 2074 2556 +4 2015 2214 2170 1578 +4 664 638 1695 679 +4 2212 1797 2453 878 +4 2212 2453 1797 2493 +4 64 2126 1718 1520 +4 1942 1673 2318 1993 +4 1942 1673 1672 2318 +4 2248 1287 1338 1918 +4 2015 1941 1494 2443 +4 247 2429 2015 260 +4 2015 1941 2443 2014 +4 247 2429 2014 2015 +4 1512 2133 2444 1464 +4 1512 2444 1973 1464 +4 1464 166 2444 1973 +4 1464 166 2133 2444 +4 1499 1548 1544 1725 +4 1725 1583 1548 1544 +4 1160 2226 1182 2256 +4 2226 2256 2495 1182 +4 2555 1929 2244 1743 +4 2555 1929 1743 1744 +4 1509 2146 2286 1575 +4 1509 2146 1614 1615 +4 2303 2570 2530 2569 +4 826 2437 1495 894 +4 1921 1525 142 125 +4 1921 1525 141 142 +4 2197 1601 1946 1656 +4 1566 2197 1946 1656 +4 2208 1871 1108 1101 +4 1215 1818 1565 1858 +4 1215 1913 1651 1858 +4 805 1699 2148 756 +4 1759 1606 1751 2201 +4 1215 1565 1913 1858 +4 2342 1818 1215 1858 +4 1702 759 762 812 +4 2342 1215 1651 1858 +4 13 1734 28 2376 +4 1734 28 2376 1511 +4 2004 2376 1734 13 +4 2073 1847 2050 2539 +4 2073 2022 2050 1847 +4 805 816 1699 764 +4 1847 2551 2022 2050 +4 437 2308 1961 1509 +4 1837 2019 2035 1006 +4 783 1758 1972 784 +4 783 1758 786 1972 +4 1835 1509 1961 2308 +4 2303 2530 1870 1871 +4 2240 2439 2274 2490 +4 2234 250 298 2263 +4 2554 2252 2414 2333 +4 2554 2252 2333 2381 +4 1693 2554 2252 2414 +4 2554 2252 2381 1693 +4 2240 2439 1795 2460 +4 1972 784 1703 736 +4 1972 786 1703 1758 +4 1975 1755 2020 758 +4 2240 1795 2439 2490 +4 349 2517 398 373 +4 349 1573 398 2517 +4 1071 1470 1472 2070 +4 349 1573 2517 2416 +4 349 2517 373 2416 +4 736 784 1703 787 +4 250 2263 2350 298 +4 586 2491 1648 2500 +4 2439 1796 2481 2209 +4 1627 1590 2167 1631 +4 558 1648 2500 586 +4 1514 1572 1661 2550 +4 556 1648 586 585 +4 556 1648 558 586 +4 2167 1627 1631 1632 +4 586 585 1648 2491 +4 2439 2354 1796 2209 +4 2262 1796 2481 2439 +4 2460 2262 2439 1796 +4 2505 1796 2439 2354 +4 2460 2439 2505 1796 +4 2530 2251 2226 2233 +4 2256 1898 2251 2495 +4 584 1997 674 2028 +4 1997 1697 674 2028 +4 2246 2251 2226 2530 +4 2251 2495 1897 2257 +4 2233 2251 2256 1898 +4 2391 2252 1746 2414 +4 2252 765 2381 705 +4 349 392 398 1573 +4 705 715 2252 765 +4 2416 2506 349 1573 +4 2506 1573 392 349 +4 1494 2120 1578 1577 +4 2023 2261 1583 1483 +4 2 3 2272 2332 +4 3 2272 2332 2299 +4 7 2004 2272 1734 +4 2004 2272 1734 2299 +4 2 2004 2272 7 +4 2024 1469 1950 1818 +4 2408 2414 770 1747 +4 878 2281 848 2212 +4 1191 2155 1243 1248 +4 2367 2026 2352 2275 +4 2367 509 2026 2275 +4 804 806 2025 1751 +4 1734 2275 413 1502 +4 806 814 2025 1751 +4 2275 2376 2352 2367 +4 2025 1759 1704 1705 +4 1191 2155 1248 2349 +4 2281 1797 2212 878 +4 2215 2502 2453 2481 +4 2215 2481 2453 2493 +4 2215 2481 2493 2510 +4 2489 2249 1937 2408 +4 1191 2155 2349 2325 +4 2215 2502 2481 2510 +4 2380 2408 2489 1937 +4 2392 1493 2479 2484 +4 2354 1493 2392 2484 +4 2325 2268 2495 2155 +4 2325 2349 2268 2155 +4 2295 1918 2210 2417 +4 798 2219 2240 2460 +4 846 882 848 2213 +4 2295 1918 2417 1414 +4 2460 2219 2439 2262 +4 292 2181 2243 309 +4 882 2453 878 848 +4 2498 2516 1937 2282 +4 2516 2282 2498 685 +4 309 2243 292 271 +4 2127 1902 1512 2287 +4 64 102 1718 2126 +4 904 2117 969 851 +4 883 1795 892 854 +4 2215 2453 2212 2493 +4 811 2490 2274 781 +4 857 2130 1758 904 +4 1746 2274 839 2490 +4 811 2240 2274 2490 +4 2490 2274 839 2439 +4 1160 1171 1182 2226 +4 1171 2226 2495 1182 +4 1160 2235 2226 2256 +4 2233 2256 2226 2235 +4 2226 2256 2251 2495 +4 2233 2251 2226 2256 +4 2215 2453 848 2212 +4 2006 2231 2238 2534 +4 1251 2257 2291 2155 +4 2267 2155 2291 2257 +4 2495 2155 2267 2257 +4 2006 2231 1791 2238 +4 2251 2226 2495 2325 +4 1699 1752 1706 1700 +4 1699 1752 1761 1706 +4 2217 1653 1533 1608 +4 1700 1753 1752 1706 +4 2108 1808 1809 1851 +4 1706 1761 1753 1752 +4 758 1755 2020 761 +4 761 2119 1755 2020 +4 2020 1779 2039 1720 +4 512 1608 2217 466 +4 512 2217 1608 575 +4 575 1653 2217 1608 +4 878 1797 896 881 +4 1284 2225 1329 1918 +4 1973 1872 1860 1842 +4 1973 1872 1842 1238 +4 2248 2225 1284 1918 +4 877 1795 908 883 +4 584 1997 2028 1729 +4 1997 1697 2028 1687 +4 882 2453 902 878 +4 2233 1898 2256 1868 +4 2248 1918 2425 2225 +4 885 2213 906 882 +4 2481 2209 1796 2453 +4 2502 1796 2481 2262 +4 882 2453 906 902 +4 2502 1796 2453 2481 +4 883 1795 919 892 +4 1572 573 696 1514 +4 883 908 919 1795 +4 573 1999 1514 1572 +4 522 1552 2488 527 +4 343 2016 380 340 +4 2227 2260 1870 2530 +4 2227 2246 2260 2530 +4 2486 2246 2260 2227 +4 2267 2248 2291 2155 +4 2425 2155 2291 2248 +4 2562 1623 1690 2261 +4 2562 1623 2261 2242 +4 1607 1653 1862 2217 +4 1246 2248 2425 1288 +4 1256 2248 1293 2433 +4 904 2117 971 969 +4 902 2453 2571 926 +4 1643 1640 2065 1692 +4 2250 1262 2224 2268 +4 833 923 2030 2534 +4 833 2534 2030 1497 +4 923 2030 2534 2163 +4 1497 1789 2030 1481 +4 1481 2163 1789 2030 +4 1607 1862 1869 2217 +4 1803 1017 972 912 +4 1670 1720 1676 1721 +4 855 1751 2017 920 +4 12 2026 2004 2352 +4 952 928 2354 953 +4 1473 1984 2019 1855 +4 924 880 876 2236 +4 2004 509 2026 1772 +4 1606 2236 1751 2201 +4 814 2201 859 876 +4 2349 2250 2268 1262 +4 4 2026 2004 12 +4 2571 954 960 930 +4 434 1740 439 482 +4 4 1772 2004 2026 +4 933 2571 960 930 +4 886 909 1796 2514 +4 886 1796 2505 2354 +4 884 2505 886 1796 +4 1092 1151 1868 2235 +4 976 953 952 2484 +4 345 2093 1945 2475 +4 2095 1508 2094 2288 +4 976 2484 958 953 +4 2354 886 1796 2514 +4 1266 1226 1893 2032 +4 2095 2094 2427 2288 +4 2033 476 472 519 +4 316 363 1961 2090 +4 316 1961 2118 2096 +4 1961 1835 1541 1509 +4 2300 1790 2066 2259 +4 983 2385 979 2571 +4 2259 1790 2066 2279 +4 947 926 954 2121 +4 984 1838 966 963 +4 984 1838 987 966 +4 2262 817 842 1796 +4 791 817 2262 790 +4 1488 1682 1494 1561 +4 1729 1739 1687 2028 +4 790 817 2262 2219 +4 1488 1556 1682 1561 +4 2034 2182 2443 1549 +4 715 717 703 2252 +4 1003 984 980 1838 +4 2219 798 847 2460 +4 1007 986 987 1838 +4 2219 2460 847 845 +4 2248 1288 1284 2225 +4 1007 1838 1005 986 +4 2248 1284 1287 1918 +4 1796 2514 910 2220 +4 2421 1893 2344 2241 +4 2036 1914 2241 2575 +4 1792 2036 2477 2241 +4 1806 2241 1792 2477 +4 2476 2421 2451 2241 +4 2220 2453 2209 2571 +4 2514 2220 2209 2571 +4 2453 906 2571 2220 +4 1032 996 1021 2338 +4 906 910 2571 2220 +4 1293 1287 1338 2248 +4 1003 1007 1838 1031 +4 1794 2422 2392 1493 +4 1794 2392 2422 2237 +4 1007 1838 1031 1005 +4 2248 1918 2401 2433 +4 303 343 2416 318 +4 1283 2098 2036 1320 +4 1272 2405 1307 1285 +4 1320 2098 1334 1339 +4 1323 1334 2036 2098 +4 1334 1320 2036 2098 +4 1283 2032 2383 2431 +4 1307 2092 2447 2405 +4 318 2416 354 343 +4 1536 1903 2036 2116 +4 2309 2557 1621 1622 +4 2309 2048 2305 1621 +4 1172 1201 2091 1898 +4 1201 1241 2091 1898 +4 1241 2091 1898 1903 +4 1172 1898 2091 1841 +4 1841 2091 1903 1898 +4 2309 1622 1621 2305 +4 1190 1181 2037 1226 +4 1226 2032 2037 1893 +4 1803 2017 1017 912 +4 2032 2383 2461 1893 +4 1251 1897 2291 2257 +4 1251 2155 2291 2425 +4 1803 1017 2027 1054 +4 1803 2027 1844 1054 +4 2433 1918 2210 2248 +4 2425 2248 2210 1918 +4 1036 1807 1849 1019 +4 2428 2257 2291 1897 +4 1872 1842 1238 1865 +4 1872 1865 2040 1969 +4 1872 1865 1969 1842 +4 2328 2521 2157 2271 +4 1021 2338 1062 1032 +4 1534 2542 1808 1809 +4 2542 1606 1808 1809 +4 1606 2117 2542 1808 +4 2165 2542 1808 1534 +4 2165 1808 2542 2117 +4 1032 2338 1062 1049 +4 1843 1371 1681 1828 +4 1849 1074 1057 1036 +4 1847 1787 1781 2551 +4 2551 1944 1787 1781 +4 1251 2293 2431 2116 +4 2248 2401 1293 2433 +4 2293 1897 2116 1251 +4 1536 2293 1897 2116 +4 2431 2293 1536 2116 +4 2038 1789 1735 1630 +4 1679 1630 2038 2540 +4 2038 1789 1782 1735 +4 1527 1733 1843 1847 +4 44 2521 2157 2328 +4 1676 627 2039 2119 +4 2313 2444 2037 1893 +4 1849 1848 1103 1019 +4 1893 2461 2037 2313 +4 1806 1893 2313 2461 +4 239 250 2263 1542 +4 1849 1057 1074 1104 +4 239 2263 1933 1542 +4 1057 1104 1849 1076 +4 2240 2219 2439 2460 +4 2219 2439 1747 2274 +4 1057 1849 1807 1076 +4 2442 2417 2210 2264 +4 2433 2442 2210 2264 +4 2240 2274 2439 2219 +4 2433 2264 1384 2442 +4 2041 1911 1947 2175 +4 1650 2175 1958 2041 +4 1060 2331 1819 1061 +4 845 798 847 2219 +4 2236 2298 1606 1802 +4 1852 2135 1234 1888 +4 2135 1234 1888 2223 +4 2135 2223 1888 1564 +4 2454 2298 1606 2236 +4 2135 1564 1888 1979 +4 2454 1808 2298 967 +4 1849 1019 1103 1074 +4 2427 2288 2299 509 +4 2246 2251 1897 2257 +4 1764 1951 2178 1814 +4 1951 1813 1818 1565 +4 1951 2149 1814 1565 +4 2251 2226 2325 2486 +4 3 2272 2299 2094 +4 2299 2272 1734 2094 +4 2288 413 2299 509 +4 1734 2299 2094 413 +4 1660 2179 1707 1783 +4 2427 3 2299 2094 +4 1991 1723 1679 1953 +4 2254 1991 1953 1723 +4 2509 2255 1529 2271 +4 2395 1530 2255 2271 +4 1533 1663 1658 2043 +4 1130 1076 1849 1104 +4 1663 1658 2043 1709 +4 1663 2043 2545 1709 +4 1580 2283 1920 1647 +4 1920 2560 1533 1619 +4 2283 1619 1920 2007 +4 2007 1533 1619 1920 +4 1614 1580 1920 2308 +4 63 2386 2255 2509 +4 63 2255 1529 2509 +4 2386 1530 2255 2395 +4 2303 1833 1569 2570 +4 2044 1581 1587 2557 +4 2307 2265 2392 1794 +4 2307 2392 1795 839 +4 2016 2033 2537 1869 +4 2307 839 1794 2392 +4 2307 2230 1795 2392 +4 2307 2265 2230 2392 +4 2147 1087 1858 1159 +4 2147 1159 1116 1087 +4 2184 1890 2045 1974 +4 2045 1887 1890 1873 +4 1472 1860 1537 2232 +4 1883 2343 2232 1857 +4 1883 1860 1472 2232 +4 271 2243 292 1899 +4 1135 1106 1144 1851 +4 1087 1858 1159 1117 +4 718 2266 711 720 +4 2445 2266 2578 718 +4 2578 2266 2445 2249 +4 767 1746 781 2391 +4 1238 2444 2037 2313 +4 250 256 2263 1542 +4 1135 1851 1154 1120 +4 1950 1818 2111 1823 +4 251 1542 2263 256 +4 2391 2274 1746 781 +4 1768 2100 2046 2239 +4 251 279 2263 1542 +4 279 1542 2228 2263 +4 2079 2047 1991 2254 +4 1667 2191 2254 1990 +4 2047 1713 2553 1543 +4 2047 1723 1990 2553 +4 1135 1881 1851 1144 +4 1135 1851 1881 1154 +4 2287 1512 2444 1238 +4 1173 1881 1154 1135 +4 1238 2444 2287 2037 +4 802 2409 2421 1662 +4 885 2220 906 2213 +4 1888 2409 802 1662 +4 1888 1890 2409 1662 +4 2518 197 2316 2407 +4 2554 2189 2381 2258 +4 983 986 1005 1838 +4 983 1838 1005 1002 +4 983 1838 2571 986 +4 2381 2189 1741 2258 +4 2189 1741 2258 2185 +4 2102 2451 802 1564 +4 2385 983 1002 1838 +4 2147 1159 1858 2419 +4 983 1838 2385 2571 +4 298 2277 1933 2228 +4 298 2228 1933 2263 +4 2102 2451 1564 2000 +4 1892 2147 2419 1200 +4 2311 1921 142 2317 +4 2311 1921 141 142 +4 1190 1226 2037 1977 +4 870 1796 885 2213 +4 1628 1627 1621 2048 +4 1501 1871 1101 1090 +4 2213 2220 906 2453 +4 2277 1570 2218 2228 +4 845 1796 2262 2460 +4 1584 2547 1553 2049 +4 866 2460 884 1796 +4 2049 1551 2158 2169 +4 2049 2547 2169 1557 +4 1718 1584 2049 1557 +4 1718 2049 1551 2158 +4 2508 2507 1192 2436 +4 2460 2505 884 1796 +4 2460 1796 866 845 +4 1658 1705 1709 1710 +4 828 1742 1793 2387 +4 2387 2230 1793 893 +4 828 2387 1793 893 +4 910 2514 2571 2220 +4 2425 1918 2210 2295 +4 1501 1068 2211 1090 +4 910 938 2571 2514 +4 1860 1973 1891 2232 +4 2433 2264 2210 1918 +4 360 2312 2197 2474 +4 2474 2312 1948 2301 +4 360 408 2312 2474 +4 1243 1185 1246 2155 +4 2474 408 2312 2301 +4 2197 2312 1948 2474 +4 1090 2211 1122 1068 +4 318 2399 354 2416 +4 2487 770 2391 768 +4 2441 1348 1374 2442 +4 2487 2414 2391 770 +4 1388 2295 1373 2425 +4 1929 1569 2237 1794 +4 1734 2275 2004 2299 +4 2299 2275 2004 509 +4 1206 1896 1221 1251 +4 832 1796 870 2213 +4 2361 1569 2051 1493 +4 1262 2267 2428 2268 +4 1744 2051 1929 1743 +4 2428 2267 2291 2257 +4 1738 1737 1371 1733 +4 1243 1288 1284 2248 +4 1495 2185 2052 1793 +4 166 1973 802 2313 +4 1243 2248 1287 1248 +4 1973 2313 1806 802 +4 1243 1284 1287 2248 +4 2495 2267 2428 2257 +4 2428 2433 2291 2267 +4 1675 2053 1782 1949 +4 2444 1973 166 2313 +4 1262 2433 2428 2267 +4 2502 832 2213 1796 +4 1198 1210 2495 2268 +4 360 330 2474 300 +4 1210 2268 2224 2495 +4 1198 2268 2495 2325 +4 330 2474 2353 2457 +4 2038 1490 1735 1782 +4 2082 1839 1917 1784 +4 1221 1896 1218 1251 +4 1490 1782 1843 1735 +4 2268 2155 2267 2495 +4 1221 1251 1309 1279 +4 2540 2038 1490 1735 +4 2546 1843 1735 1490 +4 2540 1735 1490 2546 +4 2281 807 848 2212 +4 1697 2292 1886 2374 +4 1253 1893 2519 1266 +4 796 2212 848 807 +4 2232 1564 802 1891 +4 2268 2267 2428 2495 +4 885 1796 910 2220 +4 1915 2000 1564 1891 +4 2232 1915 1564 1891 +4 885 1796 2220 2213 +4 765 767 2252 1746 +4 2213 1796 2220 2453 +4 51 1529 2060 2446 +4 2531 1559 2001 224 +4 224 1560 1559 2001 +4 2446 2370 1529 2060 +4 1930 1465 1634 1579 +4 33 2126 64 1520 +4 1945 1602 1994 1655 +4 33 1520 1717 2126 +4 1899 2370 2060 1933 +4 2157 2060 1933 1899 +4 2502 846 2215 2213 +4 781 2490 2274 1746 +4 2502 2453 2213 2215 +4 373 354 2517 396 +4 2489 2324 2249 2497 +4 373 354 2416 2517 +4 1967 2107 1757 1676 +4 2433 1369 1384 2264 +4 1967 1676 2119 2107 +4 768 2274 2391 781 +4 2225 2425 2295 1918 +4 2502 2453 1796 2213 +4 2033 2375 476 519 +4 2033 2375 1740 476 +4 476 1740 482 2375 +4 1218 2293 2431 1251 +4 1218 2431 2293 2032 +4 842 2502 2262 1796 +4 345 346 2314 1604 +4 1660 1707 1928 1783 +4 345 1604 369 346 +4 2431 1536 2293 2032 +4 345 1604 2314 1945 +4 850 898 2387 893 +4 345 1604 1945 2093 +4 1784 1855 1471 1473 +4 1473 1959 1855 1471 +4 1706 1767 2543 1711 +4 1711 1712 1706 1767 +4 9 11 17 2094 +4 11 2094 25 17 +4 1711 1767 1995 1712 +4 148 2429 247 80 +4 345 1604 2093 369 +4 148 2429 248 247 +4 792 2502 2510 791 +4 1997 1729 1641 1687 +4 1198 2349 2268 2325 +4 1729 1997 2028 1687 +4 1256 2155 2267 2268 +4 1841 1894 1903 2091 +4 1841 1903 1894 1969 +4 791 2510 1747 2502 +4 192 1555 195 160 +4 192 236 195 1555 +4 1674 1785 1953 2077 +4 1953 1785 1675 2077 +4 1674 1785 2077 1680 +4 378 362 315 1576 +4 441 436 362 1576 +4 2091 1894 2535 1841 +4 2535 1894 1969 1841 +4 2181 2304 1874 1945 +4 2181 2304 365 1874 +4 350 329 377 1577 +4 1570 2304 2181 1945 +4 377 329 359 1577 +4 2155 1248 1256 2248 +4 2155 2248 1256 2267 +4 1897 2291 2116 1251 +4 2428 2116 1897 2291 +4 817 1796 2262 845 +4 779 811 798 2274 +4 336 2537 352 393 +4 336 2537 393 412 +4 2225 2425 1356 2295 +4 768 770 2274 779 +4 350 1577 377 457 +4 2414 2274 1747 839 +4 2184 1888 2409 802 +4 2012 324 317 267 +4 350 457 378 1577 +4 770 2414 2274 1747 +4 1151 2256 1175 1898 +4 2012 1597 2011 317 +4 2012 1597 1522 2011 +4 573 1999 1572 577 +4 2256 2495 1182 1202 +4 1151 1868 2235 2256 +4 1151 1868 2256 1898 +4 2059 1702 2550 1763 +4 2433 2210 2291 2248 +4 2425 2248 2291 2210 +4 1480 1625 2280 1669 +4 1802 1808 1809 2108 +4 1480 1625 1552 2280 +4 425 2259 508 438 +4 2280 1669 1663 1480 +4 2184 1888 1890 2409 +4 1351 1357 1498 1389 +4 425 489 508 1639 +4 1351 1498 1427 1389 +4 2027 2108 1115 1079 +4 2027 1079 1802 2108 +4 2416 1524 1869 2016 +4 1552 522 2033 468 +4 2010 2096 297 252 +4 466 1608 467 512 +4 2010 252 1511 2096 +4 2010 288 297 2090 +4 512 467 579 1608 +4 2243 1570 2218 2277 +4 2277 2181 323 309 +4 563 504 493 1612 +4 563 1612 570 504 +4 796 832 846 2502 +4 542 2057 565 526 +4 542 2523 566 565 +4 796 846 848 2215 +4 1922 2516 1937 1901 +4 2303 2570 1569 2422 +4 2498 1901 1937 2516 +4 583 600 634 2468 +4 796 846 2215 2502 +4 2427 2094 2299 2288 +4 2094 413 2299 2288 +4 2094 413 2288 1508 +4 2518 2316 2271 1530 +4 2018 1676 627 1721 +4 2491 2516 1922 1901 +4 637 602 626 2578 +4 2518 2407 2316 1530 +4 2388 2406 2518 1530 +4 2388 1530 2518 2271 +4 2406 1530 2407 2518 +4 756 698 764 1699 +4 756 1699 764 805 +4 2281 878 881 1797 +4 2155 1243 2248 1246 +4 2509 2395 2255 2271 +4 2155 2248 2425 1246 +4 734 1972 786 1703 +4 833 740 830 1497 +4 2386 2395 2255 2509 +4 2282 1937 2489 2404 +4 702 2489 2404 2282 +4 2282 2380 2489 1937 +4 731 2282 2489 702 +4 731 2380 2489 2282 +4 1710 1766 2009 2166 +4 2166 1774 1766 1773 +4 857 904 851 2130 +4 2166 1926 1773 1766 +4 2316 2509 2271 2395 +4 2166 1926 1766 2009 +4 825 2483 837 889 +4 837 2483 880 889 +4 883 1795 854 838 +4 2381 813 1742 757 +4 2381 1742 1741 757 +4 877 883 838 1795 +4 2252 1746 2381 765 +4 261 267 1562 2012 +4 765 715 2252 767 +4 870 882 846 2213 +4 261 2012 1562 1522 +4 267 2031 1562 2012 +4 1562 2012 1598 1522 +4 2225 2295 1382 1918 +4 1562 2031 1598 2012 +4 870 2213 885 882 +4 760 785 1504 1748 +4 2570 2530 1870 2303 +4 1363 1382 1383 2225 +4 785 1748 1797 1504 +4 1362 2225 1383 1918 +4 2154 1874 1994 1945 +4 1075 2035 2420 925 +4 1362 1363 1383 2225 +4 2181 1874 2154 1945 +4 2225 1382 1383 1918 +4 1075 925 1052 2035 +4 1508 413 509 1499 +4 2288 413 509 1508 +4 2288 1508 509 1750 +4 1750 1508 509 1499 +4 2350 2263 306 298 +4 1284 1336 1329 2225 +4 984 1838 963 958 +4 980 984 958 1838 +4 1007 984 1838 987 +4 1003 1007 984 1838 +4 1032 2338 1024 998 +4 1329 2225 1362 1918 +4 1131 1006 1075 2035 +4 1131 2494 1139 1006 +4 2496 2328 2157 2271 +4 210 2518 1542 2157 +4 1821 1974 2330 2345 +4 1954 1935 1974 1857 +4 1810 1900 1798 1853 +4 1202 2495 1224 1898 +4 1798 1853 1844 1936 +4 2495 1224 1898 2428 +4 2225 1376 1382 2295 +4 1356 2295 1376 2225 +4 1849 1074 1036 1019 +4 1518 1499 1605 2327 +4 1032 2338 1049 1024 +4 1750 1499 1605 1518 +4 0 2004 2332 2 +4 2 2332 2272 2004 +4 1780 1826 1963 2063 +4 1104 1849 1142 1103 +4 1780 1821 2063 2551 +4 2332 2272 2004 2299 +4 0 2427 2332 2004 +4 2427 2332 2004 2299 +4 1767 2177 2552 1774 +4 2180 1636 921 1956 +4 1130 1088 1849 1076 +4 1821 2345 2177 2552 +4 1633 1956 1636 2180 +4 1130 1088 1148 1849 +4 2541 1954 2177 1817 +4 2541 1817 2290 1954 +4 2180 1636 2081 921 +4 1732 2052 2273 1736 +4 1135 1099 1106 1851 +4 1736 1495 2052 2273 +4 1363 2225 1365 1382 +4 1120 1135 1851 1099 +4 1329 1336 1362 2225 +4 2530 1870 2143 2570 +4 2530 2570 2143 1867 +4 1362 1363 2225 1336 +4 1686 2065 1640 2076 +4 2065 2554 2029 1692 +4 2567 1563 1714 1525 +4 1606 2017 1802 1809 +4 2554 2414 1743 2333 +4 2252 1746 2414 2333 +4 2099 1525 1563 2567 +4 1678 2018 1850 1727 +4 1253 1977 1893 1226 +4 1692 1694 2414 2554 +4 1692 2554 2414 1743 +4 190 2407 2316 197 +4 1964 1943 2066 1636 +4 1191 2155 1185 1243 +4 1964 1943 1636 2193 +4 1266 2032 1250 1226 +4 1266 1893 1226 1253 +4 2350 279 306 2263 +4 1167 2467 1881 1140 +4 1167 2359 1881 2467 +4 1508 73 24 25 +4 1726 73 25 80 +4 1979 2135 1984 2019 +4 1979 1852 2135 2019 +4 1885 2549 1013 1909 +4 1879 1909 2564 2549 +4 1879 2549 1885 1909 +4 2323 1967 1669 1755 +4 955 952 2230 997 +4 1972 1703 734 736 +4 952 1795 2392 2354 +4 2452 1150 1227 2097 +4 1508 1499 1750 2206 +4 2452 1890 2097 1227 +4 1604 1994 2297 2183 +4 259 2034 2398 325 +4 779 798 1747 2274 +4 2034 325 353 2398 +4 798 2219 1747 2274 +4 300 2197 258 2353 +4 2487 768 719 770 +4 258 2197 1566 2353 +4 175 133 208 1528 +4 2408 2414 2487 770 +4 1528 133 208 1899 +4 1957 2322 1553 1584 +4 729 770 771 2408 +4 823 784 1758 903 +4 1249 1977 1893 1253 +4 2436 2507 1192 2444 +4 738 1703 2055 795 +4 2201 795 2055 1703 +4 700 1830 1700 1654 +4 2181 323 344 2304 +4 2181 1570 2243 2277 +4 1018 1814 1081 1027 +4 1018 1081 1814 2149 +4 1027 1081 1093 1814 +4 1081 1093 1814 2472 +4 1081 1814 2149 2472 +4 1146 2287 1190 1181 +4 1181 2037 2287 1190 +4 2287 1112 1146 2464 +4 1190 2444 2287 2512 +4 2277 1570 323 2181 +4 2554 2258 2381 2333 +4 2252 1746 2333 2381 +4 1932 1598 2195 1594 +4 1932 2084 2195 1598 +4 2258 1743 2333 2554 +4 2236 2337 931 1802 +4 1878 1906 2105 1684 +4 1684 1650 1906 2105 +4 981 2027 1043 985 +4 2236 2337 924 931 +4 2017 2337 1802 2027 +4 2337 1802 2236 2017 +4 342 2312 408 1600 +4 342 2312 1600 2197 +4 1986 2339 1892 2068 +4 1987 1892 2068 1986 +4 1021 2296 2360 2338 +4 1493 2338 2360 2296 +4 2021 1987 2426 2068 +4 2426 1987 1892 2068 +4 2492 2338 1493 2296 +4 2338 996 1021 2296 +4 2338 2296 2492 996 +4 344 2304 365 2181 +4 1050 1988 1861 2069 +4 1470 2069 1861 1987 +4 2069 1987 1986 1861 +4 2069 1986 1988 1861 +4 1470 1861 2069 1050 +4 2070 1470 2069 1050 +4 1122 1153 2235 1871 +4 1153 2235 1871 2226 +4 765 1746 813 788 +4 788 2490 1746 813 +4 813 1746 1742 2490 +4 2381 1746 1742 813 +4 765 1746 2381 813 +4 215 1933 271 1899 +4 1899 2243 1933 271 +4 1062 2208 2360 1108 +4 1062 1108 2360 1067 +4 1111 1067 2360 1108 +4 2238 1829 1466 2002 +4 1659 1711 1706 2543 +4 1510 1711 1706 1659 +4 2053 1950 1769 2070 +4 1769 2111 2070 1950 +4 166 2424 2434 2503 +4 300 330 2474 2353 +4 300 2353 2474 2197 +4 2542 1816 1798 1856 +4 1810 2542 1816 1798 +4 1756 2071 2200 1951 +4 1707 1763 2072 917 +4 917 1985 1763 2072 +4 1479 1763 2072 1707 +4 2317 125 109 1921 +4 1687 2074 1739 2556 +4 166 2313 2344 1893 +4 2241 1893 2344 1806 +4 2313 1893 1806 2344 +4 1479 2082 1496 1917 +4 1351 1498 1662 1840 +4 2128 2082 1939 1479 +4 1351 1662 1498 1321 +4 1917 2082 2128 1479 +4 1953 1724 1675 1785 +4 1990 1675 1724 1677 +4 1953 1990 1675 1724 +4 1662 1498 1564 1840 +4 1662 1498 2102 1564 +4 1673 2075 1723 1713 +4 1713 1776 2075 1723 +4 1702 1763 1980 2550 +4 1689 2576 1467 1638 +4 2077 1630 2576 1680 +4 1929 1569 1833 2237 +4 1956 1679 2078 921 +4 1956 1673 2078 1679 +4 1623 1465 2079 1991 +4 1623 1465 1667 2079 +4 2079 2191 2047 2254 +4 1601 2145 2285 1603 +4 1603 1886 2145 2285 +4 2080 1641 1688 1687 +4 1599 2194 2081 2301 +4 2081 1688 2080 1638 +4 33 1717 20 2126 +4 1717 2352 20 2126 +4 1815 1677 1675 1949 +4 1949 1677 2053 1823 +4 1675 1677 2053 1949 +4 1815 1677 1949 1823 +4 1583 2261 2242 1588 +4 1588 2562 2261 2242 +4 2083 1660 2125 1617 +4 1585 1682 1488 1556 +4 1563 1468 2084 1946 +4 1468 2084 1599 2180 +4 1563 1946 2084 1656 +4 1163 1166 2260 2486 +4 1145 2260 2486 1163 +4 2486 2227 2260 1145 +4 2098 2441 1397 1916 +4 1397 2441 2529 1916 +4 2314 346 1570 1604 +4 2323 1730 1669 1967 +4 1559 1560 2085 1613 +4 2314 1604 1570 1945 +4 1559 2548 2085 1560 +4 1592 2085 1596 1955 +4 2323 1967 1755 650 +4 545 2323 1625 1669 +4 2314 1945 1570 2475 +4 646 2323 1669 1755 +4 2323 1625 1669 1730 +4 2151 334 2475 2093 +4 2151 2475 1945 2093 +4 1555 2198 2548 1560 +4 1560 1596 2198 2548 +4 177 139 2316 190 +4 162 2395 2316 177 +4 259 262 2034 2351 +4 353 2034 262 2182 +4 2316 2395 2271 1530 +4 162 2509 2316 2395 +4 452 549 1757 2365 +4 1524 343 2016 2416 +4 853 856 1803 2114 +4 853 1803 1751 2114 +4 1300 1394 1650 1291 +4 1394 1650 1355 2432 +4 2228 304 306 1570 +4 1300 1650 2105 1291 +4 304 2228 2450 1570 +4 1694 1693 2487 2414 +4 2006 1739 1745 1864 +4 2487 1693 2252 2414 +4 2138 2002 1045 1063 +4 2138 1045 2002 1503 +4 1694 2554 1693 2414 +4 297 2096 2090 316 +4 2090 1961 1541 1575 +4 2090 1575 1541 1982 +4 316 2090 1961 2096 +4 1740 2468 1607 561 +4 1346 2425 1356 2225 +4 1288 2225 2425 1346 +4 2425 1373 1356 2295 +4 2032 1536 1896 2037 +4 1272 2092 2405 2144 +4 2092 2116 2036 1903 +4 1323 2092 1342 2098 +4 1323 2098 2036 2092 +4 512 2217 1607 456 +4 456 2435 2217 1607 +4 839 2439 1493 2392 +4 839 2310 1794 1493 +4 1026 925 1496 1839 +4 2089 2013 1756 1951 +4 2089 1807 1951 1756 +4 2089 1496 2013 1813 +4 839 2439 2310 1493 +4 839 1493 1794 2392 +4 2091 2535 1205 1169 +4 1841 1169 1866 2535 +4 2010 2090 1541 1982 +4 2010 2090 297 2096 +4 990 1045 1063 2138 +4 2138 2002 2238 1503 +4 1599 2301 1948 1600 +4 1946 1948 1600 1599 +4 1946 1600 1948 2197 +4 2089 1839 1496 1813 +4 1278 2348 1322 2021 +4 1278 1313 1322 2348 +4 2068 1278 2021 2348 +4 2312 1600 1948 2301 +4 1323 1342 1352 2098 +4 2441 2098 2116 1916 +4 948 2121 993 2156 +4 915 2156 1797 2121 +4 1293 2401 1353 2433 +4 1524 340 303 301 +4 2433 1353 1369 2264 +4 202 211 2001 2141 +4 202 2001 238 224 +4 211 2099 249 2001 +4 102 128 1718 2126 +4 2060 2370 1529 2205 +4 2060 2205 1529 2271 +4 2271 2205 1529 1542 +4 2433 2442 2291 2210 +4 678 2055 2043 1653 +4 678 1657 2043 2055 +4 1929 1864 1791 2329 +4 1569 2329 1929 1833 +4 2101 2134 733 686 +4 2101 686 1500 2134 +4 2347 775 773 2497 +4 2481 1493 2209 2453 +4 11 24 25 2094 +4 2439 2209 2481 1493 +4 24 2094 1508 25 +4 2206 2095 1508 24 +4 952 2392 997 2484 +4 997 2392 1505 2484 +4 2096 2010 2269 1511 +4 509 1750 1717 1772 +4 1750 1717 1478 509 +4 2362 1750 1717 1478 +4 2430 1750 1717 2362 +4 2430 1772 1717 1750 +4 1524 1869 1966 1647 +4 1507 1647 2334 1524 +4 1507 1966 1647 1524 +4 2440 1524 2334 1647 +4 2440 1524 1647 1869 +4 1986 2372 1891 1842 +4 2096 2118 316 307 +4 720 2266 711 2324 +4 2324 2578 2249 2266 +4 2324 1937 2578 2404 +4 2404 2324 711 2578 +4 2324 2249 2578 1937 +4 2027 1084 2359 1844 +4 2364 2307 1795 839 +4 2364 1795 2230 908 +4 1895 1811 2499 1804 +4 1804 1845 1811 2499 +4 2490 2364 1795 839 +4 877 1795 2364 908 +4 2097 1150 1227 1887 +4 2092 2098 2036 2116 +4 2364 2230 1795 2307 +4 1489 2150 1502 413 +4 1489 1734 413 1502 +4 2349 1262 2268 1256 +4 42 2352 82 1777 +4 387 2366 1604 394 +4 2258 2185 1742 2244 +4 2096 1835 1540 1541 +4 125 1525 109 1921 +4 1283 2431 2098 1308 +4 387 2466 1604 2366 +4 2009 1720 2020 1755 +4 2437 2185 1741 1736 +4 2437 2185 1736 1495 +4 1836 2237 2465 2570 +4 429 2403 2366 2377 +4 2403 2366 2377 1645 +4 2403 2466 2366 1645 +4 394 429 2366 2377 +4 646 1755 1532 758 +4 1755 1975 1532 758 +4 417 2403 2366 429 +4 414 2466 2366 2403 +4 1166 2486 1191 2325 +4 1166 2325 2226 2486 +4 2440 1647 2397 1573 +4 2257 2325 2495 2155 +4 282 2440 326 2326 +4 2326 326 349 2506 +4 2440 2506 326 2326 +4 2264 1403 1415 1410 +4 1958 2000 1498 1564 +4 1283 2431 2036 2098 +4 2264 2417 1415 1418 +4 1283 2383 2036 2431 +4 2027 2359 1100 1091 +4 2383 1536 2036 2431 +4 2229 1865 1536 2110 +4 1897 2229 1536 2110 +4 2431 2116 2036 2098 +4 2431 1536 2036 2116 +4 2264 2417 1418 2442 +4 4 1717 15 2400 +4 2400 15 16 1717 +4 16 2400 1717 2430 +4 4 1772 1717 2400 +4 2400 1717 2430 1772 +4 596 1693 1644 2278 +4 2315 1693 1644 594 +4 594 1693 1644 596 +4 1644 2029 2278 1693 +4 1644 2315 2029 1693 +4 2568 1848 1485 2549 +4 1470 1215 1834 1651 +4 2102 1337 2000 1357 +4 2005 1823 1825 2341 +4 1263 1252 2409 2456 +4 1175 2256 1202 1898 +4 1303 2102 2421 1662 +4 2096 1961 1835 1541 +4 2096 2090 1961 1541 +4 2256 1898 2495 1202 +4 2518 2316 1542 2271 +4 1501 2303 2208 1871 +4 1806 2461 1238 1792 +4 1973 1806 2313 1238 +4 1806 2461 1792 2241 +4 2316 2509 1542 2271 +4 2292 2578 2445 2249 +4 2445 2578 2292 2374 +4 2101 2122 733 2134 +4 2101 2134 1500 2550 +4 2374 704 2445 2578 +4 1504 2249 1748 2310 +4 2249 2445 1697 1504 +4 1504 841 1805 1797 +4 1805 1504 1797 2051 +4 2156 2361 1805 1797 +4 1805 2361 2051 1797 +4 396 383 2016 1740 +4 2016 2033 1869 1740 +4 1638 1467 1688 1491 +4 1491 1687 2556 1688 +4 841 891 1805 1797 +4 1638 2576 1491 2207 +4 891 1805 1797 2156 +4 1147 2368 1166 2226 +4 2368 1871 1870 2260 +4 2368 1166 2226 2260 +4 367 1589 2365 1910 +4 1166 2226 2260 2486 +4 733 2101 803 2122 +4 2101 803 2122 1764 +4 1884 1987 1889 1911 +4 1006 1139 2019 2494 +4 1139 2019 2494 1878 +4 1884 1911 1958 1915 +4 1884 2041 1958 1911 +4 578 2132 698 2106 +4 578 2106 1608 2132 +4 2106 635 1653 2173 +4 1884 1915 1987 1911 +4 2526 2341 2112 1863 +4 2341 1949 1825 2112 +4 2027 1084 1100 2359 +4 2526 2341 1825 2112 +4 1321 1662 1498 2102 +4 2033 1869 1637 455 +4 1321 2102 1498 1357 +4 2338 1062 1501 2360 +4 1986 1894 2339 2068 +4 2008 1589 2131 264 +4 2008 1589 2199 2131 +4 2535 1894 2339 1986 +4 1726 413 1508 1499 +4 823 2454 1758 2236 +4 2496 2328 2271 1530 +4 2328 61 2521 2388 +4 2027 1091 1115 2359 +4 2027 2359 1115 2108 +4 2201 2483 1758 2236 +4 823 2236 1758 2483 +4 1675 1481 1789 1463 +4 1675 1630 1463 1789 +4 490 503 1970 1629 +4 490 1970 2320 1629 +4 770 1747 2274 779 +4 1986 2372 2471 1894 +4 1994 2285 2300 1643 +4 1994 2561 2300 2285 +4 591 1901 618 2491 +4 1966 2283 2007 1619 +4 591 2491 2500 1901 +4 1351 1498 1840 1427 +4 1146 1902 2287 1181 +4 1181 2037 1902 2287 +4 1902 1112 1146 2287 +4 2440 2416 2506 2326 +4 1686 1733 1850 1732 +4 2526 1866 1863 2112 +4 1650 1924 1649 2175 +4 2158 2011 1522 1551 +4 261 2011 1522 2158 +4 1872 1969 2040 1988 +4 1872 1842 1969 1988 +4 1656 1655 2561 2054 +4 1071 1472 1471 1769 +4 1471 1472 1492 1769 +4 1071 1472 1769 2070 +4 1582 1656 2054 1655 +4 1723 1675 1677 2053 +4 276 1574 351 2334 +4 276 2334 1507 1574 +4 2440 326 2506 2397 +4 1071 1470 2070 2111 +4 1191 2325 2486 2155 +4 155 2289 1515 2394 +4 2486 2325 2257 2155 +4 269 2394 2118 276 +4 276 1507 2394 2118 +4 1039 1519 1118 2127 +4 1039 1519 2127 1824 +4 448 431 1531 524 +4 3 2094 11 9 +4 445 2517 1573 1607 +4 447 2517 445 1607 +4 2089 1839 1813 2568 +4 2203 1279 1251 2425 +4 1251 2425 2291 2203 +4 2010 2090 2096 1541 +4 345 1945 2314 2475 +4 2344 2503 2421 2409 +4 802 2344 2421 2409 +4 2344 2503 1893 2421 +4 239 2234 1933 2263 +4 2260 2226 1871 2530 +4 2368 2226 1871 2260 +4 1147 2368 2226 1871 +4 2532 2057 1646 2478 +4 2478 1927 2057 1646 +4 1793 2265 2230 2387 +4 2493 2310 2497 2510 +4 850 877 2364 898 +4 2493 2481 2310 2510 +4 2387 2230 2364 2307 +4 2387 2265 2230 2307 +4 2183 1643 2029 1645 +4 2183 2284 1645 2466 +4 2366 2183 2377 1645 +4 2366 2466 2183 1645 +4 1944 1787 1828 1827 +4 2551 1827 1787 1944 +4 2551 1550 1827 1944 +4 2033 1637 2375 2488 +4 1915 1979 1564 1958 +4 1587 2242 2557 2562 +4 2242 2562 1623 2557 +4 1583 1587 2242 2557 +4 1585 1682 1494 1488 +4 1598 2066 1571 2054 +4 300 2197 285 258 +4 1598 2066 1964 1635 +4 2328 37 40 2402 +4 38 52 2060 2157 +4 1579 1930 991 1634 +4 1955 1579 991 1634 +4 23 1750 14 2430 +4 952 2354 2484 953 +4 952 2354 2392 2484 +4 2354 2514 1493 1838 +4 2114 2152 2148 805 +4 2032 2383 1536 2461 +4 2148 1760 1759 1705 +4 2060 2496 1529 39 +4 39 2060 51 1529 +4 696 2550 1572 1514 +4 2492 2571 2385 1838 +4 1502 216 233 1489 +4 214 288 2010 289 +4 752 756 2025 2173 +4 756 2148 804 2025 +4 2025 2114 2148 804 +4 2025 2148 1759 1705 +4 218 2316 1542 227 +4 215 2234 1933 239 +4 205 2316 1542 218 +4 1966 2537 1880 455 +4 382 1880 2537 455 +4 1975 1778 851 849 +4 205 2509 1542 2316 +4 2509 2271 1529 1542 +4 1049 1062 1101 1501 +4 1062 2208 1108 1101 +4 2275 509 2026 2004 +4 2004 2275 1734 2376 +4 1734 2275 2299 413 +4 413 2275 2299 509 +4 2004 2376 2352 2275 +4 1517 2005 2024 1815 +4 1740 2468 552 546 +4 2440 1869 1647 1573 +4 2119 1731 755 653 +4 1962 2446 2162 2393 +4 2393 2446 2162 1567 +4 209 2396 2446 2393 +4 2393 2396 2446 1567 +4 1999 1611 1617 1660 +4 2033 471 518 472 +4 1552 522 2488 2033 +4 2121 926 1797 915 +4 1493 2296 2360 1838 +4 697 1783 763 1701 +4 2360 1493 1838 2479 +4 1584 1557 2547 2049 +4 2565 1557 2547 1584 +4 2336 2210 2529 2417 +4 2529 2442 2417 2210 +4 761 2119 1754 755 +4 1517 1815 1825 2005 +4 2156 1503 1805 2361 +4 703 675 2487 712 +4 2431 1916 2116 2098 +4 1805 2361 2329 2051 +4 2361 1805 2329 1503 +4 1564 2451 1891 2000 +4 2394 1507 1540 2118 +4 2033 1740 1637 1869 +4 1862 1637 1869 1533 +4 1999 1928 1660 1661 +4 383 2033 2016 1740 +4 778 807 1748 2493 +4 2024 1469 1952 1950 +4 2024 1950 1952 1677 +4 2370 1570 2243 1567 +4 1488 2443 2023 1494 +4 2243 1570 2370 2218 +4 2243 2277 1933 284 +4 2416 2517 1869 1573 +4 1573 1869 1607 2517 +4 778 2493 1748 2497 +4 2134 733 746 2122 +4 1500 2134 1514 2550 +4 1693 2252 2381 705 +4 2487 1693 1694 1901 +4 703 1901 1693 2487 +4 2487 675 703 1901 +4 2487 1901 1694 2498 +4 386 461 1476 1910 +4 461 1476 2365 1757 +4 705 715 1693 2252 +4 386 1597 1910 1476 +4 715 2252 703 1693 +4 2487 2498 675 1901 +4 2275 2367 1511 2376 +4 798 2274 2240 2219 +4 790 2219 1747 793 +4 1520 1516 1718 1584 +4 2151 273 2031 1582 +4 2219 1747 2439 2262 +4 790 2262 1747 2219 +4 2446 1528 2162 1567 +4 793 2219 1747 798 +4 2127 1902 1112 1085 +4 2127 1085 1826 1902 +4 1519 2133 1134 1118 +4 1118 1134 2512 2133 +4 1134 2133 1204 1197 +4 773 2347 731 771 +4 2489 2347 773 2497 +4 2489 2347 2249 2408 +4 1473 1984 2129 1878 +4 1485 1848 2129 2549 +4 1834 1884 2129 1473 +4 1848 2549 1879 2129 +4 1878 2564 1984 2129 +4 2489 2249 2347 2497 +4 2408 2347 771 731 +4 1781 1872 1828 1940 +4 1783 1928 1660 1999 +4 2130 2545 2188 1975 +4 2492 1838 1493 2571 +4 1724 2142 1481 1463 +4 1724 2142 1815 1481 +4 2450 2370 1529 2396 +4 2446 1567 2370 1528 +4 2475 2370 1567 1570 +4 429 474 2403 1644 +4 429 2377 1644 2403 +4 2403 2315 1645 1644 +4 2348 1891 2372 2451 +4 1986 2348 1891 2372 +4 2348 2372 1894 2449 +4 1986 2348 2372 1894 +4 2403 2377 1644 1645 +4 516 2315 2403 1644 +4 2130 2117 851 2164 +4 2164 1819 1765 2165 +4 2117 1765 2165 2164 +4 474 2403 1644 516 +4 1660 1707 2191 1928 +4 1928 1980 1707 2191 +4 1928 1707 1980 1702 +4 404 394 1604 2377 +4 394 1604 2377 2366 +4 2349 1248 1256 2155 +4 2132 1608 1609 2294 +4 2132 1484 2294 1609 +4 2132 2173 698 2106 +4 2427 2288 1772 2095 +4 2427 509 1772 2288 +4 222 264 278 2008 +4 203 235 258 1566 +4 1999 1514 1572 1661 +4 235 258 1566 2353 +4 2187 2178 2024 1771 +4 404 1644 2377 418 +4 404 429 2377 1644 +4 2297 1644 2183 2029 +4 1249 1252 2515 2503 +4 696 754 2550 2134 +4 418 1644 2377 2297 +4 2444 2512 1192 2133 +4 2275 1511 1734 2376 +4 2512 2444 2287 2133 +4 2040 1829 2112 1866 +4 2526 1866 2112 1829 +4 1746 839 1742 2490 +4 2333 1746 1742 2381 +4 2134 746 754 2122 +4 2333 1746 839 1742 +4 811 2240 798 2274 +4 2274 1747 839 2439 +4 1778 851 959 2164 +4 1778 1975 2164 1765 +4 1975 1778 2009 1765 +4 2315 2029 1693 1694 +4 270 1524 1507 282 +4 282 2334 2440 1524 +4 282 2334 1524 1507 +4 1155 1896 1867 1902 +4 1902 1867 2229 1896 +4 2255 2496 1529 2271 +4 2255 1530 2496 2271 +4 63 2386 2496 2255 +4 63 2496 1529 2255 +4 2249 1747 2497 2310 +4 2408 2249 2414 1747 +4 2347 1747 2249 2408 +4 2249 1747 2310 2414 +4 2347 2249 1747 2497 +4 2532 2525 2057 2478 +4 1988 1969 1986 1842 +4 2403 2532 2478 2525 +4 1650 2175 1649 1958 +4 2135 1958 1979 1984 +4 2036 2241 2383 2575 +4 1283 2036 2383 2575 +4 1792 2036 2241 2383 +4 2383 2036 1536 1792 +4 1667 2191 1990 1980 +4 2047 1990 1980 917 +4 1862 1533 1869 2217 +4 1647 1920 2217 1869 +4 1579 1634 1992 1465 +4 1869 1533 1920 2217 +4 1971 2159 2048 1547 +4 1971 1586 2048 2159 +4 366 1604 2466 1874 +4 131 97 1962 130 +4 1604 387 366 2466 +4 2206 57 93 1518 +4 2059 1763 1479 1702 +4 2059 1496 1479 1763 +4 2059 2013 1763 1756 +4 2059 2013 1496 1763 +4 502 2137 1783 633 +4 2206 1518 1750 57 +4 712 703 717 2487 +4 2252 717 2391 767 +4 767 1746 2391 2252 +4 2108 2359 1115 1129 +4 703 2252 2487 1693 +4 2127 1902 1826 1512 +4 750 1504 1745 1697 +4 707 689 2282 1695 +4 2484 1493 2479 1838 +4 2354 1493 2484 1838 +4 1635 2174 2107 1850 +4 2018 2107 1850 627 +4 1605 1499 1478 2327 +4 1472 1470 1537 2069 +4 1478 1499 1548 2327 +4 1472 2070 1470 2069 +4 2175 1924 1431 1454 +4 2175 1454 2432 1924 +4 2138 911 2006 2534 +4 2138 2534 2238 1829 +4 801 785 1797 1504 +4 1504 1748 1797 2310 +4 1751 2017 2236 1606 +4 93 2139 2346 1518 +4 2139 2351 195 259 +4 785 1797 1748 820 +4 807 820 1748 2493 +4 2281 2212 1797 2493 +4 2493 1797 1748 2310 +4 754 2122 810 2550 +4 2122 810 2550 1756 +4 818 2420 1719 2128 +4 2420 1719 2128 1895 +4 180 2099 211 2141 +4 2141 211 2001 2099 +4 2404 2489 714 2324 +4 2408 2249 1937 1694 +4 2498 1694 2408 1937 +4 2487 2498 1694 2408 +4 1342 2092 1385 2098 +4 2098 1385 1397 2441 +4 1422 1397 2529 1387 +4 1589 1708 2306 1626 +4 1708 2306 1626 1627 +4 1708 1627 1626 1631 +4 726 2142 852 2245 +4 2304 347 366 1604 +4 724 2142 2371 1463 +4 852 1517 2245 2142 +4 2024 1724 2142 1815 +4 1724 1481 1815 1675 +4 2304 1604 366 1874 +4 425 438 371 2259 +4 2347 774 775 1747 +4 1625 1626 2280 1730 +4 2497 2510 1747 775 +4 2355 614 641 2382 +4 589 2511 2520 613 +4 2355 1695 641 611 +4 2355 611 613 1695 +4 2491 2382 614 2355 +4 2355 1695 2520 2491 +4 751 814 2055 2025 +4 751 806 2025 752 +4 691 2055 1653 2025 +4 54 46 2496 63 +4 2478 1927 1922 2057 +4 1922 1927 1799 2057 +4 828 1742 2387 850 +4 898 2387 2230 2364 +4 828 850 2387 893 +4 1272 1298 2092 2144 +4 1298 2441 1367 2092 +4 1514 2134 696 2550 +4 2134 754 2550 2122 +4 2096 2394 269 230 +4 2096 2118 307 269 +4 2173 756 2025 2148 +4 1282 1317 1812 1873 +4 1812 1662 1873 2223 +4 1282 1662 1873 1812 +4 2144 2092 1903 2116 +4 592 1901 618 591 +4 592 591 2500 1901 +4 2328 35 41 2390 +4 2145 2469 1603 451 +4 2328 41 2402 1530 +4 1575 2286 1616 2146 +4 2328 2496 35 2390 +4 219 270 1524 1507 +4 219 1545 1524 275 +4 2101 2550 2122 2134 +4 1547 1546 2159 1989 +4 2006 2238 1791 1864 +4 1864 2329 2238 1791 +4 529 1740 539 2375 +4 1740 2468 546 539 +4 2357 1570 327 304 +4 1512 1973 2444 1238 +4 1973 2444 1238 2313 +4 2444 2313 166 1893 +4 2357 320 327 2314 +4 304 1570 2450 2357 +4 1242 2426 1892 2068 +4 2357 2314 2475 320 +4 2357 1570 2450 2475 +4 1278 1235 2068 1242 +4 2173 756 2148 1699 +4 635 2106 698 2173 +4 1747 2310 2414 839 +4 913 938 910 2514 +4 966 2571 2514 1838 +4 1568 2154 2181 2457 +4 2114 1760 1759 2148 +4 2025 2114 1759 2148 +4 1760 1766 1767 2541 +4 1760 1766 2541 1810 +4 2130 2117 1758 904 +4 2130 904 851 2117 +4 1778 851 2164 1975 +4 2543 1760 1766 1767 +4 720 2497 2266 2324 +4 2324 2266 2249 2497 +4 40 2388 61 2328 +4 219 1507 1524 1545 +4 2489 1937 2324 2404 +4 1695 1937 2282 2404 +4 2449 1304 2513 1914 +4 543 2576 647 1680 +4 543 2576 1919 2207 +4 2184 2409 166 802 +4 2184 1973 2232 802 +4 805 2152 856 2114 +4 2114 856 1803 2152 +4 2184 2409 1890 166 +4 1291 1394 1650 1355 +4 1355 1650 2105 1906 +4 103 1777 128 2126 +4 2126 128 1718 1777 +4 1018 1055 2149 2140 +4 1018 2149 1814 2140 +4 2149 1858 1565 1818 +4 679 684 2282 1695 +4 684 1695 707 2282 +4 415 454 2532 2403 +4 2096 2394 2118 269 +4 679 2282 2404 1695 +4 2403 454 2532 2525 +4 2150 1502 413 2411 +4 1489 2150 413 1726 +4 1726 2150 413 1499 +4 718 2266 2578 711 +4 711 2266 2578 2324 +4 244 2393 2151 268 +4 2151 1945 1567 1655 +4 244 2393 1582 2151 +4 2393 2162 1582 2151 +4 2114 2152 1803 1760 +4 826 1495 2273 900 +4 2273 1495 1698 900 +4 16 2430 1717 2362 +4 1747 2262 2481 2439 +4 775 792 2510 791 +4 2502 2262 2481 1747 +4 239 250 2234 2263 +4 775 791 1747 790 +4 398 1573 445 2517 +4 95 1521 1605 2362 +4 49 95 2362 87 +4 1211 1229 1875 1255 +4 608 699 1668 2253 +4 608 2253 1668 2320 +4 1655 1601 2154 2353 +4 1566 2197 1656 2353 +4 330 2474 2457 1603 +4 326 351 2397 2334 +4 406 1574 466 2397 +4 406 1574 2397 351 +4 466 2397 1574 2418 +4 2334 1647 1574 2397 +4 2334 351 2397 1574 +4 246 279 1542 274 +4 1033 1825 2163 2526 +4 2408 2380 731 732 +4 2408 1747 771 2347 +4 2408 731 771 732 +4 2118 1580 2308 1574 +4 1574 2308 1647 1580 +4 750 1745 1504 827 +4 1567 2243 1945 1570 +4 1570 2181 2243 1945 +4 1210 2250 2224 2268 +4 2349 1210 2268 2250 +4 1124 1143 2368 1123 +4 1108 1123 2368 1870 +4 1143 2384 1163 2368 +4 993 2156 1044 1004 +4 2156 2121 1493 1797 +4 2156 1493 2361 1797 +4 2156 1501 2361 1493 +4 2001 1600 1613 1946 +4 1560 1600 1613 2001 +4 926 2571 954 2121 +4 46 2386 2496 63 +4 2492 2571 979 2385 +4 2121 2492 1493 2571 +4 2492 979 996 2385 +4 2314 1570 346 327 +4 2357 2314 327 1570 +4 2357 1570 2475 2314 +4 905 886 2505 2354 +4 49 2362 1801 87 +4 1 10 2095 2410 +4 10 14 2095 2410 +4 2498 1901 1694 1937 +4 2403 2478 1645 2315 +4 1502 2136 2010 1982 +4 1982 1538 1502 2136 +4 791 817 842 2262 +4 1353 2401 1386 2264 +4 2518 197 229 2316 +4 197 227 229 2316 +4 198 200 229 2518 +4 2405 2092 2036 1903 +4 2091 2405 1894 1903 +4 227 2316 1542 229 +4 2405 1903 2471 1894 +4 2518 229 1542 2316 +4 1303 1337 2102 1357 +4 2522 1303 1337 2102 +4 2433 1353 2264 2401 +4 2416 2016 354 343 +4 73 93 1998 2206 +4 1524 340 2016 343 +4 93 1518 2346 1998 +4 2346 1518 2351 1998 +4 1569 1833 1696 1503 +4 1696 1833 1569 2303 +4 145 190 2407 139 +4 190 139 2316 2407 +4 38 32 2060 53 +4 791 2502 1747 2262 +4 791 2262 1747 790 +4 2440 1573 2506 2416 +4 2487 770 719 729 +4 2487 770 729 2408 +4 1 2410 2095 1772 +4 2410 14 2095 1772 +4 2498 716 2380 732 +4 2498 2408 2380 1937 +4 2287 1512 2133 2444 +4 2282 2498 2380 1937 +4 731 708 2380 2282 +4 1922 1799 2520 2057 +4 2408 2498 2380 732 +4 2523 2057 2520 1799 +4 1727 1847 2073 2539 +4 731 716 2380 708 +4 2539 1787 1847 2050 +4 31 1750 14 57 +4 309 2243 271 284 +4 309 2181 2243 2277 +4 309 2277 2243 284 +4 79 2388 2406 90 +4 90 2406 2518 2388 +4 903 907 1758 2454 +4 2117 2454 1758 914 +4 907 916 1758 2454 +4 1758 2454 1606 2236 +4 823 903 1758 2454 +4 1758 2117 1606 2454 +4 1263 1662 2409 1890 +4 1263 2409 1662 2456 +4 2409 2421 1662 1303 +4 2095 1508 2288 1750 +4 2095 1750 14 31 +4 2206 1750 2095 31 +4 612 2355 614 641 +4 24 2206 2095 31 +4 34 2328 47 44 +4 44 47 59 2328 +4 2355 2382 641 1695 +4 2491 1695 2382 2355 +4 44 59 2521 2328 +4 2518 200 229 197 +4 2491 2516 2382 1695 +4 149 197 2518 2407 +4 1143 1145 2384 1870 +4 2384 2368 1870 2260 +4 1145 1870 2260 2384 +4 1143 1870 2384 2368 +4 282 2440 2326 318 +4 2440 2416 2326 318 +4 2404 714 711 2324 +4 679 702 2404 2282 +4 2275 1502 1511 2367 +4 1002 1838 1030 2385 +4 1558 1563 1595 1932 +4 1002 2385 1030 1021 +4 2296 1838 2492 2385 +4 2476 2241 2451 1914 +4 2413 1327 2476 2522 +4 2284 1645 1646 1886 +4 2333 1746 2414 839 +4 46 2390 2386 58 +4 2386 1530 2496 2255 +4 46 2390 2496 2386 +4 1141 1169 1841 2091 +4 2091 1169 1841 2535 +4 2277 306 323 1570 +4 2277 1570 2228 306 +4 512 1607 2217 575 +4 575 1653 1607 2217 +4 2349 1256 2268 2155 +4 109 1528 2415 131 +4 141 2415 1528 2321 +4 131 1528 2415 1962 +4 1962 2162 1528 2415 +4 1921 2415 109 1528 +4 2415 2321 2162 1528 +4 1528 2415 141 1921 +4 349 2416 373 2399 +4 1986 2471 1969 1894 +4 1969 2471 1792 1903 +4 1574 2418 1647 2308 +4 2418 1608 1647 2308 +4 817 793 845 2219 +4 1761 1938 1811 2541 +4 2541 2290 1938 1811 +4 290 2353 330 300 +4 1782 1788 1781 1843 +4 1490 1781 1843 1782 +4 1386 2401 1410 2264 +4 2094 413 1508 1726 +4 2094 36 413 98 +4 2094 98 413 1726 +4 1744 1864 2051 1504 +4 2051 1864 1805 1504 +4 707 708 2282 689 +4 2282 2516 1937 1695 +4 685 1695 2282 689 +4 2516 1695 2282 685 +4 2372 1806 1792 2477 +4 1891 1806 2372 2451 +4 2372 1792 2471 2449 +4 2 3 9 2272 +4 3 9 2272 2094 +4 1544 1483 2023 1583 +4 7 2272 9 1734 +4 2272 9 1734 2094 +4 2 2272 9 7 +4 1551 1971 1590 2169 +4 2161 1540 1507 1580 +4 2161 1507 1966 1580 +4 1540 2161 1546 2159 +4 2161 1546 2159 1925 +4 2161 1580 1966 1925 +4 1023 1501 1696 1503 +4 1023 1503 1696 1045 +4 718 1748 2266 769 +4 769 1748 2266 2497 +4 1519 2063 1859 2133 +4 1519 1859 1134 2133 +4 55 79 2388 2402 +4 79 71 2406 2388 +4 1528 2321 1568 208 +4 1528 208 1568 1899 +4 2321 208 1528 175 +4 2389 710 729 2498 +4 40 55 2388 2402 +4 2328 2388 2271 1530 +4 40 2402 2388 2328 +4 2487 2498 2408 729 +4 2422 2237 2570 1569 +4 2461 1792 1536 1238 +4 1842 1806 1238 1792 +4 2313 2461 2037 1238 +4 1973 1842 1806 1238 +4 34 2328 44 2496 +4 1935 2045 1234 1882 +4 1853 2172 1935 1854 +4 1853 1882 1936 1935 +4 1854 1852 2172 1935 +4 963 966 2514 1838 +4 1935 1234 1852 1882 +4 958 963 2514 1838 +4 2336 2295 2417 1416 +4 1416 2295 2417 1425 +4 69 2060 133 1528 +4 1528 133 1899 2060 +4 2390 1530 48 41 +4 2328 2390 41 1530 +4 2328 2496 2390 1530 +4 2392 1505 2422 2237 +4 1505 2237 2570 2422 +4 1505 1836 2570 2237 +4 2230 2237 1836 1505 +4 2230 2392 2237 1505 +4 717 768 2487 2391 +4 770 2274 2391 768 +4 2487 2252 2391 2414 +4 1788 1949 2040 1506 +4 2252 717 2487 2391 +4 2163 1825 1949 2112 +4 1949 1825 2163 1481 +4 923 2030 2163 1825 +4 1481 1825 2163 2030 +4 1742 2265 2307 1794 +4 703 717 2487 2252 +4 770 2414 2391 2274 +4 2244 1742 1794 2265 +4 1843 1787 1781 1847 +4 1847 1781 1843 1490 +4 1731 2539 2039 1786 +4 1705 1760 1759 2544 +4 2544 1766 1760 1759 +4 166 1890 2424 2409 +4 1204 1890 2088 2424 +4 1263 2409 2424 1890 +4 166 1890 2434 2424 +4 1658 1705 2173 1704 +4 1691 2381 2554 2189 +4 2333 2258 2381 1742 +4 1351 1812 1840 1662 +4 1282 1662 1812 1351 +4 323 1570 347 2304 +4 2181 323 2304 1570 +4 2390 1530 70 48 +4 2390 1530 2386 70 +4 2390 1530 2496 2386 +4 2167 2174 1632 1631 +4 177 2395 2316 139 +4 139 1530 2316 2407 +4 2065 2554 2278 2029 +4 360 300 2474 2197 +4 2457 2353 2154 1601 +4 2388 2271 2518 2521 +4 2328 2388 2521 2271 +4 776 779 798 1747 +4 776 793 1747 798 +4 1643 1692 2029 1645 +4 1645 1692 2029 1694 +4 1645 2292 1692 1694 +4 1643 1692 1645 1886 +4 1886 1645 2292 1692 +4 153 193 2157 2521 +4 2035 2129 2494 1473 +4 2035 1131 2494 2129 +4 2035 2494 2019 1473 +4 2395 1530 2316 139 +4 1551 1590 1522 2169 +4 2169 1594 1590 1522 +4 2169 2048 1590 1594 +4 2571 938 966 2514 +4 2170 1494 1578 1577 +4 2015 1494 1578 2170 +4 286 2214 2015 1578 +4 2312 408 1600 2301 +4 2571 1838 966 965 +4 2427 2095 1772 1 +4 2295 1918 1399 1382 +4 1290 2021 1345 1911 +4 2021 1345 1911 2000 +4 708 2498 2380 2282 +4 708 716 2380 2498 +4 1947 2041 1906 1909 +4 2171 1908 2270 1905 +4 1846 1845 2172 1876 +4 1846 1877 1876 2172 +4 1853 2172 1876 1882 +4 2172 2270 1877 1876 +4 1338 1918 1360 2401 +4 1360 1918 1379 2401 +4 2401 1398 1410 1918 +4 2401 1379 1398 1918 +4 1761 1811 1895 1804 +4 2248 1338 2401 1918 +4 1700 1753 816 1752 +4 2401 1918 1410 2264 +4 2433 2401 2264 1918 +4 773 2347 2489 731 +4 2408 2347 731 2489 +4 2025 2114 1751 1759 +4 2025 2201 1759 1751 +4 1557 1475 1562 1558 +4 2221 1562 1558 1557 +4 2173 2025 1704 1705 +4 1632 1964 2193 1678 +4 2174 1678 1850 1943 +4 1632 2174 1964 1678 +4 2174 1678 2018 1850 +4 37 41 2402 2328 +4 2402 1530 2388 2328 +4 1723 1782 2038 1675 +4 1723 1675 2053 1782 +4 1723 1782 1776 1490 +4 2118 2308 397 1574 +4 1389 1431 2175 1649 +4 58 2390 2386 70 +4 894 978 1793 1831 +4 1495 1793 2052 1831 +4 978 1793 1831 2465 +4 70 2386 114 2395 +4 894 1831 1793 1495 +4 1778 1819 2176 1926 +4 1768 2177 1775 2239 +4 2177 1775 2064 2153 +4 2177 1954 2345 2330 +4 2177 2345 1954 2541 +4 2386 2395 2509 114 +4 1742 2307 2364 839 +4 1763 1813 1985 1469 +4 1469 1985 1950 1813 +4 1763 1813 2072 1985 +4 1071 1800 1813 1215 +4 850 1742 2387 2364 +4 1800 1950 1215 2111 +4 1399 1918 2295 1414 +4 1766 2541 1810 1816 +4 2541 2335 1811 1810 +4 1534 1851 1099 1086 +4 1742 839 1794 2307 +4 1534 1856 1851 1086 +4 2117 971 2454 914 +4 1035 1808 2165 2117 +4 2024 2178 2140 1771 +4 2178 1469 1818 1951 +4 2024 2178 1469 1818 +4 2178 1951 2149 1814 +4 1938 2566 1474 1513 +4 1768 2046 1938 1817 +4 1938 1817 2046 1474 +4 70 1530 2395 94 +4 2179 1666 2047 1713 +4 2179 1707 1535 1543 +4 94 1530 2395 115 +4 1955 1468 2180 1633 +4 1955 1634 1633 2180 +4 1468 2195 2180 1633 +4 2195 2180 1633 1636 +4 70 2386 2395 1530 +4 1567 1568 2154 2243 +4 1558 1559 2547 1595 +4 2085 991 1592 1591 +4 1554 1592 2548 1555 +4 1556 2061 1561 2182 +4 2034 353 1556 2182 +4 313 262 2182 353 +4 2326 2506 349 2416 +4 1864 1739 1745 2074 +4 318 2326 349 2416 +4 318 349 2399 2416 +4 1750 1499 1478 1605 +4 2432 1924 1650 2175 +4 1394 1650 2432 2115 +4 141 171 1525 2321 +4 2321 171 1525 1566 +4 2133 166 2436 2444 +4 104 2406 2407 149 +4 2406 149 152 2518 +4 235 1568 290 2353 +4 1138 1195 2160 1858 +4 2184 2045 1890 1888 +4 1935 2045 1887 2003 +4 2184 1464 166 1974 +4 2097 2045 1887 1890 +4 641 2382 670 1695 +4 2382 667 670 689 +4 1857 1888 2232 1852 +4 1852 1979 1888 2232 +4 1852 1888 1979 2135 +4 2382 685 689 1695 +4 2389 729 716 2498 +4 1833 2570 2303 2569 +4 1390 2295 1411 1399 +4 1652 2570 2530 1867 +4 1390 1406 1411 2295 +4 1131 2035 2494 1006 +4 1006 2494 2019 2035 +4 1756 1807 1951 2200 +4 2013 1763 1951 1813 +4 2089 2013 1951 1813 +4 2408 2380 2489 731 +4 1843 1681 1791 1788 +4 152 149 200 2518 +4 1262 1280 2428 2433 +4 1262 2433 2267 1256 +4 1280 1311 2428 2433 +4 2116 2441 1916 2291 +4 2437 1742 1741 2185 +4 2437 1793 2185 1495 +4 1727 2022 1847 1722 +4 1727 2022 2073 1847 +4 1721 2022 1749 1727 +4 1727 2073 2022 1749 +4 1504 2310 1797 2051 +4 1778 2009 1765 1926 +4 1744 2249 1504 2310 +4 2186 1952 1469 1763 +4 2550 2071 1763 2186 +4 2490 1742 2364 839 +4 2186 1469 2071 1763 +4 1980 1763 2186 2550 +4 1980 1763 917 1952 +4 850 2490 1742 2364 +4 813 2490 850 838 +4 2187 1764 2071 2178 +4 2122 1764 2071 2187 +4 1704 1759 2201 2188 +4 2188 2117 1606 1758 +4 1713 1543 2042 2100 +4 1713 1543 2100 1776 +4 714 2489 728 720 +4 728 2489 772 720 +4 720 2497 2324 2489 +4 714 2324 2489 720 +4 772 2489 2497 720 +4 1694 2414 2487 2408 +4 1694 2249 2414 2408 +4 1664 1710 1709 2190 +4 1660 1928 2191 1661 +4 1660 1707 2047 2191 +4 1661 1980 1928 2191 +4 2191 1707 2047 1980 +4 41 56 2402 1530 +4 2402 50 79 71 +4 1981 1715 2123 1980 +4 2402 79 2388 71 +4 1661 2123 1980 1981 +4 1510 1712 2042 1706 +4 977 998 2338 2492 +4 996 2492 2338 998 +4 71 1530 2406 2388 +4 977 2492 2338 2121 +4 2492 2296 1493 1838 +4 2402 50 71 56 +4 2402 71 2388 1530 +4 1689 1680 2077 2576 +4 1688 1683 2459 921 +4 1634 1679 1467 1689 +4 1689 2077 1679 1467 +4 1634 1679 921 1467 +4 2459 2546 1679 921 +4 115 2395 139 1530 +4 2351 1549 1544 1998 +4 1615 1510 1659 1665 +4 104 108 2407 1530 +4 108 139 2407 1530 +4 152 2518 200 154 +4 1197 1204 2485 2434 +4 1197 2434 2133 1204 +4 2133 2434 1890 1204 +4 2434 2424 1204 2485 +4 2434 1890 1204 2424 +4 2197 1600 1948 2312 +4 2197 2353 2474 1601 +4 1595 1633 2195 1468 +4 2195 1964 1633 1632 +4 2195 1633 1964 1636 +4 71 76 2406 1530 +4 76 104 2406 1530 +4 1586 1620 1931 2196 +4 1586 2196 2558 1620 +4 1272 1254 1241 2405 +4 2196 1621 1620 1931 +4 2091 1254 1894 2405 +4 104 1530 2407 2406 +4 72 101 123 2521 +4 59 72 91 2521 +4 275 1880 1545 1524 +4 275 293 1545 1880 +4 2567 1558 2221 1562 +4 2567 2141 1558 1563 +4 456 1607 450 2435 +4 2435 1573 2397 1647 +4 2435 1573 1647 2217 +4 2435 1573 2217 1607 +4 1376 2295 1390 1399 +4 2434 1197 1192 2508 +4 2133 2436 1192 2444 +4 2133 2434 1197 1192 +4 1376 2295 1399 1382 +4 567 1729 1641 584 +4 567 1729 2207 1641 +4 491 1641 584 567 +4 1983 1589 1625 2365 +4 355 1983 2365 1589 +4 889 2236 823 2483 +4 285 2001 2197 1600 +4 1373 1406 1390 2295 +4 337 323 344 2181 +4 1372 1398 1386 2401 +4 2548 1596 2086 1592 +4 1372 1379 1398 2401 +4 2547 1594 1591 2048 +4 2199 1925 2579 1586 +4 2321 2353 1655 1568 +4 1525 1656 2321 1566 +4 1656 1601 1655 2353 +4 2451 2348 1891 2000 +4 2451 1914 2348 2482 +4 68 2446 130 1529 +4 68 97 130 2446 +4 1854 2172 1852 2019 +4 1852 2019 1877 2135 +4 51 2060 1528 2446 +4 2019 1878 1877 1984 +4 2019 2135 1984 1877 +4 1844 1936 1876 1875 +4 1834 2549 1884 1651 +4 976 2484 999 2504 +4 2484 2479 1505 999 +4 2484 2392 1505 2479 +4 1507 1647 1966 1580 +4 1507 1647 1574 2334 +4 1134 2133 1859 2452 +4 1859 2452 2133 2097 +4 2102 2421 802 2451 +4 2421 2575 2241 2413 +4 2421 2241 2344 2451 +4 1795 2439 2392 2354 +4 839 1795 2439 2392 +4 1795 2505 2439 2354 +4 2353 2321 1655 1656 +4 1776 1492 1769 2046 +4 920 975 981 2017 +4 2017 981 2337 2027 +4 981 1042 2027 975 +4 2337 1802 2027 985 +4 1760 1761 1804 1811 +4 2418 2435 2397 1647 +4 2418 2435 1647 2217 +4 2418 1608 2217 1647 +4 2418 2397 1574 1647 +4 1710 2543 2544 1766 +4 814 1751 2201 2025 +4 805 2148 1699 2152 +4 805 1752 2152 1699 +4 2148 1705 1699 1760 +4 2366 1604 2377 2183 +4 2055 1703 1704 2201 +4 2428 2144 2116 2441 +4 2144 2092 2116 2441 +4 2366 2466 1604 2183 +4 2403 2532 1645 2478 +4 2563 2280 1619 455 +4 2439 2354 2209 1493 +4 618 1901 645 2516 +4 1901 2498 675 2516 +4 1509 1580 1614 2308 +4 1524 2537 1966 1869 +4 1524 2537 1869 2016 +4 2372 1842 2471 1792 +4 1842 1969 2471 1792 +4 2291 2442 1916 2210 +4 2093 1604 1994 2297 +4 1945 1604 1994 2093 +4 1874 1604 1994 1945 +4 1322 2482 2000 2348 +4 2451 2482 2348 2000 +4 1322 1337 2000 2482 +4 2102 2482 2451 2000 +4 2102 2482 2000 1337 +4 1524 2537 2016 340 +4 1524 2537 340 314 +4 2095 1750 1772 14 +4 14 1750 1772 2430 +4 182 2221 1562 2567 +4 1622 2222 1665 1666 +4 1989 2159 1541 1540 +4 1234 1873 2223 1907 +4 1812 1407 1840 1907 +4 2270 1234 2223 1907 +4 2270 1908 1907 2223 +4 2392 2422 1505 2479 +4 2422 2479 1111 1505 +4 1868 1898 1841 2110 +4 1152 1867 1896 2227 +4 811 2240 1795 2460 +4 2507 1977 1192 2444 +4 1977 2444 1893 2037 +4 2444 166 2436 1893 +4 2037 1536 1896 2229 +4 2433 1331 1359 1384 +4 1860 1891 1973 1842 +4 2433 1384 1359 2442 +4 57 1605 121 1518 +4 1605 1518 160 121 +4 2303 1696 2235 1871 +4 1696 1871 2303 1501 +4 2206 1499 1750 1518 +4 1998 1499 2206 1518 +4 1987 2348 2021 2000 +4 2237 2570 1833 1832 +4 2231 1506 1791 2238 +4 2052 1832 1787 1968 +4 1775 2239 2064 1822 +4 2239 2343 1883 1817 +4 1768 2239 2046 1817 +4 1252 1249 2436 2503 +4 1249 1893 2507 2436 +4 1249 1977 2507 1893 +4 1815 1950 1677 1823 +4 1950 2111 2070 1823 +4 760 1748 1504 2445 +4 704 713 760 2445 +4 2266 1748 2445 2249 +4 2249 1748 2445 1504 +4 704 2445 2578 713 +4 1023 1044 1068 1501 +4 2156 1501 1023 1503 +4 1743 2310 2051 1794 +4 1743 1794 2244 1742 +4 2181 2154 1874 1603 +4 2304 1604 1874 1945 +4 2396 2370 1529 2446 +4 1743 1929 2244 1794 +4 2396 1567 2370 2446 +4 2447 2471 2449 1894 +4 2447 1323 2036 2092 +4 2447 2092 2036 2405 +4 2447 2405 2471 1894 +4 1737 2244 2052 2185 +4 1735 1788 1843 1791 +4 1733 1371 1843 1787 +4 2448 1302 1347 1916 +4 2431 1916 1302 2448 +4 1251 2431 2448 1916 +4 782 852 1771 2245 +4 782 1716 2245 1771 +4 852 1517 1771 2245 +4 1517 1771 2245 2024 +4 876 880 2201 2236 +4 859 2236 2201 1751 +4 392 2506 406 2435 +4 406 2397 2435 2506 +4 45 2060 1528 51 +4 2446 2370 2060 1528 +4 760 1504 750 1697 +4 1697 1504 1745 1744 +4 1692 1694 2249 2414 +4 1692 1744 1743 2249 +4 97 51 1528 2446 +4 51 1529 2446 68 +4 1692 1743 2555 2554 +4 2370 1899 2060 1528 +4 2333 839 1743 1742 +4 1792 2449 2477 2036 +4 2348 2372 2449 1914 +4 1686 2189 2555 1737 +4 2189 2555 1737 2185 +4 2372 1792 2449 2477 +4 2513 2348 2449 1914 +4 281 294 2450 2475 +4 304 2357 2450 294 +4 304 279 2450 2228 +4 1570 2370 2450 2475 +4 1570 2218 2450 2370 +4 2315 1922 1694 1901 +4 2348 2451 2372 1914 +4 699 1668 2253 1716 +4 1668 1716 1981 2253 +4 2253 2245 1716 1715 +4 2442 1916 2529 2441 +4 1672 1722 1713 1712 +4 753 1532 2545 1975 +4 1532 1975 1709 2545 +4 753 2545 1532 692 +4 2545 1709 1532 1663 +4 2254 1723 2047 1991 +4 2079 2254 1991 1465 +4 2254 1990 1723 1953 +4 2254 2047 1723 1990 +4 2001 1946 1566 2197 +4 2001 1946 2197 1600 +4 2092 2098 2116 2441 +4 2197 1601 1656 2353 +4 193 210 2157 2521 +4 210 2521 2518 2157 +4 2259 1571 1639 2066 +4 2259 2279 2066 1639 +4 358 1602 2259 371 +4 425 1639 2259 1571 +4 1742 2387 2364 2307 +4 1590 2048 1931 1627 +4 1931 1627 1621 1620 +4 2310 1493 2481 1797 +4 807 2212 2281 2493 +4 878 1797 2453 896 +4 820 2493 2281 1797 +4 2261 2125 1617 2083 +4 2557 2222 2083 1616 +4 2557 1622 2222 1616 +4 2557 1622 1616 1615 +4 2286 1581 2557 1615 +4 2286 1616 1615 2557 +4 2102 2000 1498 1357 +4 1351 1321 1498 1357 +4 1792 2471 2449 2036 +4 2405 1903 2036 2471 +4 2447 2036 2449 2471 +4 2447 2405 2036 2471 +4 1792 2471 2036 1903 +4 1192 2434 2508 2436 +4 1192 2436 2133 2434 +4 2454 967 2298 957 +4 2454 2236 945 2298 +4 757 813 1742 828 +4 757 1742 1741 828 +4 2456 1351 1321 1662 +4 2456 1662 1321 1303 +4 2181 361 2457 1603 +4 330 1603 2457 361 +4 2457 1601 2154 1603 +4 2353 2474 1601 2457 +4 2457 2154 2181 1603 +4 1190 2444 1977 2037 +4 1190 2037 2287 2444 +4 626 602 2473 2458 +4 2374 2578 2292 2458 +4 1799 2292 2578 2458 +4 601 602 2473 626 +4 602 2374 2458 2578 +4 1241 2405 2091 1903 +4 1241 2405 1903 2144 +4 2405 2092 1903 2144 +4 2523 2520 2511 1799 +4 595 616 621 2511 +4 595 1799 2523 2511 +4 1695 1937 2404 1799 +4 945 2236 1802 2298 +4 945 2454 2298 957 +4 2096 1541 1540 2269 +4 1882 1907 1234 2270 +4 1573 1607 1869 2217 +4 1779 1780 1820 1824 +4 2523 1648 2520 2057 +4 2304 366 365 1874 +4 2552 2345 2541 1816 +4 2552 1820 2345 1816 +4 2292 1937 2578 2249 +4 1922 1695 1937 2516 +4 1922 1937 1694 1901 +4 2292 1694 1937 2249 +4 835 1786 2273 1731 +4 835 2273 1786 1698 +4 2273 900 1698 835 +4 1720 1774 2166 1773 +4 654 2276 1731 2378 +4 2276 1850 1731 1732 +4 2276 2273 1732 1731 +4 654 1731 2276 2107 +4 2107 2276 1850 1731 +4 649 2381 1693 2278 +4 1642 1691 2278 2065 +4 2279 2189 1686 1685 +4 2461 2383 2241 1893 +4 2037 2461 1536 1238 +4 1806 2313 1238 2461 +4 1806 1893 2461 2241 +4 1893 2461 2032 2037 +4 1619 1664 1663 2280 +4 2280 2190 1664 1663 +4 1614 2577 2559 2560 +4 1614 1659 2294 2560 +4 1619 2559 2560 1664 +4 369 376 2462 2093 +4 369 1604 2462 404 +4 1610 1654 1616 1728 +4 376 2093 2297 2462 +4 404 2377 1604 2462 +4 2462 2377 1604 2297 +4 2283 1966 2573 1619 +4 2283 2558 1620 2573 +4 2573 2558 1620 1586 +4 2283 1920 2577 1614 +4 1750 2095 1508 2206 +4 662 2404 2578 1799 +4 2489 2249 2324 1937 +4 605 617 652 2468 +4 2403 2500 516 515 +4 2375 2468 1657 1637 +4 2468 1657 1637 2043 +4 1740 2468 561 552 +4 2403 2500 2315 516 +4 1603 1886 2285 2284 +4 1601 2080 2561 2285 +4 1655 1567 2154 1945 +4 2033 455 1637 1552 +4 1567 2154 1945 2243 +4 2243 2181 2154 1945 +4 1591 1587 2305 1993 +4 1578 1960 486 1612 +4 1575 1610 2146 1616 +4 1581 2286 1509 1615 +4 1599 2080 2081 1636 +4 2561 1640 2080 1636 +4 242 1568 1899 292 +4 292 2243 1568 1899 +4 2464 1118 2512 2287 +4 2287 2464 1146 1190 +4 128 2470 1718 1996 +4 164 184 2289 226 +4 1996 1546 2289 2363 +4 1742 2265 2387 2307 +4 1882 2062 1873 1907 +4 1811 1853 2290 2499 +4 2499 1854 1853 2290 +4 2290 1853 1954 1857 +4 2290 1857 1854 1853 +4 1811 2335 2290 1853 +4 2335 2290 1853 1954 +4 2530 1870 2227 2143 +4 2530 2143 2227 1867 +4 2206 93 1998 1518 +4 1692 1694 2292 2249 +4 1930 1465 1991 1679 +4 1633 1930 2318 1956 +4 1930 1673 1956 1679 +4 1608 2106 1533 2294 +4 2132 1608 2294 2106 +4 2132 1659 1658 2294 +4 1993 1991 1930 1623 +4 1993 1623 1666 1991 +4 1623 1930 1465 1991 +4 241 1529 2450 257 +4 241 2450 1529 2396 +4 2098 1397 1387 1916 +4 1387 1397 2529 1916 +4 415 2403 2532 2466 +4 2466 415 388 2532 +4 1602 2297 2300 1642 +4 388 2466 2532 1874 +4 2297 1994 2300 1643 +4 2466 2284 1645 2532 +4 2403 2532 2466 1645 +4 1874 2284 2466 2532 +4 414 415 2466 2403 +4 423 2474 2145 1641 +4 1601 2474 2080 2145 +4 2301 1638 2080 1641 +4 2301 2080 1638 2081 +4 0 1772 4 1 +4 0 2004 6 4 +4 1593 1629 1992 1531 +4 4 6 12 2004 +4 4 1717 2026 12 +4 4 1772 2026 1717 +4 0 1 2427 1772 +4 2302 1628 1632 2318 +4 1993 2302 2318 1628 +4 1591 2305 2302 1993 +4 2032 1536 2383 2431 +4 427 1624 1556 490 +4 2048 2305 1621 1628 +4 1586 2579 2306 2573 +4 1586 1620 2573 2306 +4 1589 2306 2563 1626 +4 421 467 1574 2308 +4 2308 1920 1608 1647 +4 2308 1920 1609 1608 +4 0 2427 3 2332 +4 2427 3 2332 2299 +4 0 2004 4 1772 +4 0 2427 2004 1772 +4 1969 1894 2471 1903 +4 2372 2471 1894 2449 +4 1986 1842 2471 2372 +4 205 2509 246 1542 +4 2509 1542 1529 246 +4 1251 2203 1916 2448 +4 2448 1347 1380 2480 +4 2448 2480 1380 2336 +4 1493 2422 2479 2360 +4 458 2284 2532 1646 +4 458 433 2284 1646 +4 1246 2425 1294 1288 +4 2248 2225 2425 1288 +4 2456 1252 2409 2501 +4 2456 2409 1662 1303 +4 454 420 2532 2525 +4 1648 453 454 481 +4 2181 319 1568 2457 +4 330 2457 290 319 +4 553 2473 602 1646 +4 2473 602 1646 2458 +4 2473 1646 2057 2458 +4 2088 2424 1263 1252 +4 2088 1890 1263 2424 +4 547 1644 594 2315 +4 2413 2421 2102 2476 +4 2522 1327 2476 1337 +4 2102 2421 2451 2476 +4 2102 2476 2451 2482 +4 2102 2476 2482 1337 +4 1628 1942 1672 2318 +4 2318 1965 1673 1672 +4 2319 1667 1465 1674 +4 2319 1674 1981 1667 +4 2216 1981 1667 2319 +4 1561 1667 2319 2216 +4 2192 1465 2319 1667 +4 1624 1668 1682 2320 +4 1682 1668 1981 2320 +4 1622 1942 1665 1628 +4 1622 1942 1628 1993 +4 2477 2036 1914 2241 +4 242 292 1899 271 +4 1899 2243 1568 1567 +4 1806 2241 2477 2451 +4 2372 1806 2477 2451 +4 2477 2449 1914 2036 +4 2372 2477 2449 1914 +4 1521 1554 2322 2565 +4 1957 1548 2322 1478 +4 1478 2322 1521 2327 +4 1957 1548 1553 2322 +4 2478 2057 1922 1648 +4 2525 1648 2057 2478 +4 1915 2000 1987 1911 +4 2500 1648 2478 1922 +4 2021 1911 1987 2000 +4 2403 2525 2478 1648 +4 1311 2433 1359 2442 +4 2403 1648 2478 2500 +4 1977 1190 1192 2444 +4 44 62 2157 2521 +4 2334 326 2440 2397 +4 1874 405 1603 2284 +4 1051 2504 2479 1041 +4 1041 1111 2479 1505 +4 1051 999 2479 2504 +4 2484 2504 2479 999 +4 2155 1251 1196 1222 +4 62 91 2157 2521 +4 91 2521 153 2157 +4 594 1693 649 625 +4 625 649 655 1693 +4 2327 1554 1549 1548 +4 2327 1549 1554 1555 +4 1516 1957 1547 1584 +4 1584 1957 1547 1553 +4 369 2093 2462 1604 +4 2093 1604 2297 2462 +4 1347 1916 1375 2480 +4 2336 1916 2529 2210 +4 2448 1347 2480 1916 +4 2448 1916 2480 2336 +4 1290 1911 2426 2021 +4 2021 1911 2426 1987 +4 2330 2343 1857 2232 +4 1817 1857 1954 2330 +4 1817 2330 2343 1857 +4 2330 1974 1857 1954 +4 1816 2003 1856 2331 +4 38 44 2157 2496 +4 2512 2133 1197 1192 +4 2512 1134 1197 2133 +4 1797 1493 2481 2453 +4 1747 2481 2310 2439 +4 2439 2481 2310 1493 +4 796 2215 2493 2510 +4 1228 1894 1265 2339 +4 1228 2339 2535 1894 +4 2339 1265 2068 1894 +4 1066 1030 1838 2360 +4 1066 1067 1030 2360 +4 825 823 2483 889 +4 2485 2424 2088 1252 +4 1197 2485 2508 2434 +4 2434 2424 2485 1252 +4 962 1004 1023 2156 +4 962 2156 1805 951 +4 1501 2156 2361 1503 +4 1810 1853 2335 1811 +4 2335 1853 1798 1936 +4 2335 1954 1853 1935 +4 1810 1853 1798 2335 +4 1088 2463 1849 2574 +4 1807 1565 2574 1849 +4 1849 1885 1913 2463 +4 1076 1849 2574 1088 +4 1076 1807 2574 1849 +4 1811 1900 1810 1853 +4 1266 2383 2032 1893 +4 1266 2383 1893 2575 +4 249 258 285 1566 +4 249 285 2001 1566 +4 285 2001 1566 2197 +4 521 542 2057 2525 +4 542 2523 565 2057 +4 2532 521 2057 2525 +4 1063 1078 2002 1121 +4 1078 1121 1866 2002 +4 2569 1868 2002 1466 +4 823 2236 945 2454 +4 787 1758 2483 823 +4 2569 1696 1833 2238 +4 1832 2340 1902 1867 +4 1827 1902 1832 2340 +4 2340 1832 1652 1867 +4 1832 2570 1652 1867 +4 1056 2147 2341 1116 +4 1056 2005 2341 2147 +4 1116 1863 2455 2147 +4 1823 1861 1050 2341 +4 2341 1863 1861 1050 +4 2005 2147 1858 2342 +4 1822 1860 1872 1332 +4 2070 1988 2069 1860 +4 1822 1860 1332 2070 +4 2343 1860 1973 1550 +4 2343 1860 1550 1822 +4 788 838 2490 813 +4 811 1795 2240 2490 +4 2490 2439 839 1795 +4 2005 1818 2342 1858 +4 2147 2419 1858 2342 +4 2342 1858 1651 2419 +4 1817 1883 1857 2343 +4 2345 1974 1954 2003 +4 2345 1859 1974 2003 +4 2114 1760 2148 2152 +4 1384 2264 1405 2442 +4 2152 2148 1699 1760 +4 858 884 2460 879 +4 2460 2439 1795 2505 +4 2346 2351 259 148 +4 2346 2139 259 2351 +4 285 2197 1566 258 +4 365 388 1874 366 +4 388 366 2466 1874 +4 1975 2130 2164 1765 +4 2491 1901 618 2516 +4 155 164 1515 2289 +4 2491 2520 1648 1922 +4 1777 164 1996 1515 +4 454 1648 487 2525 +4 2403 1648 454 2525 +4 431 1629 1531 524 +4 2510 2310 2497 1747 +4 1489 194 233 1538 +4 2493 2481 1797 2310 +4 2493 2481 2453 1797 +4 2510 2481 2310 1747 +4 2033 518 522 2488 +4 2033 2375 519 2488 +4 175 2321 235 203 +4 203 235 1566 2321 +4 208 1568 235 2321 +4 2321 235 2353 1568 +4 175 208 235 2321 +4 2321 235 1566 2353 +4 2147 1863 2341 1116 +4 2147 2005 2341 2342 +4 1308 2431 2098 1335 +4 1335 2098 1387 2431 +4 148 2351 248 2429 +4 2351 1549 1998 1518 +4 2351 2443 1544 1549 +4 248 2351 2014 2429 +4 2351 1544 2443 2014 +4 1388 2295 1416 1406 +4 2253 726 1716 2245 +4 1388 2425 1373 1333 +4 665 675 2498 2516 +4 2352 2269 1515 1989 +4 2396 2370 1567 2475 +4 281 2475 2450 2396 +4 2475 2370 2450 2396 +4 2464 2512 1190 2287 +4 1181 2032 2037 1226 +4 2429 1539 1544 2170 +4 2132 1658 2173 2106 +4 787 2483 825 823 +4 787 1758 1703 2483 +4 1703 1758 2201 2483 +4 1726 2429 181 1539 +4 2150 1539 1538 2109 +4 2427 2095 11 2094 +4 3 2427 11 2094 +4 2298 1808 1059 1014 +4 2454 916 1758 914 +4 2454 970 971 1808 +4 1094 2108 1129 2467 +4 2108 2467 2359 1129 +4 313 1593 385 2182 +4 313 2182 385 353 +4 2057 1927 1799 2458 +4 1927 2292 1799 2458 +4 2473 2458 1799 626 +4 1252 1249 2508 2436 +4 29 2328 34 2496 +4 2393 2162 2151 1567 +4 2334 1647 2397 2440 +4 459 2356 578 1609 +4 223 229 1542 2518 +4 1058 1859 1134 1519 +4 1058 1519 1824 1859 +4 2534 1497 2438 1789 +4 740 1739 2438 1526 +4 2403 484 453 1648 +4 620 2371 726 2253 +4 620 2253 608 2320 +4 11 2095 24 2094 +4 2095 2094 1508 24 +4 743 2130 857 2358 +4 2358 857 851 2130 +4 2358 2130 2545 743 +4 796 2493 778 2510 +4 2141 2099 2001 1563 +4 2249 2497 1748 2310 +4 2493 2310 1748 2497 +4 1901 2516 675 645 +4 729 2498 2408 732 +4 792 796 2510 2502 +4 1241 1271 1301 2144 +4 2428 2144 1898 1897 +4 1298 1301 1340 2441 +4 1801 27 92 1520 +4 1801 2362 1717 1520 +4 2362 1521 1520 87 +4 2362 1520 1478 1717 +4 2362 1478 1520 1521 +4 2375 2468 539 583 +4 2375 1740 539 2468 +4 2337 1802 989 931 +4 713 766 760 2445 +4 2289 1546 1545 2363 +4 2445 718 766 1748 +4 1546 2363 1551 2199 +4 1044 2156 1501 1023 +4 358 2031 1571 1602 +4 962 951 1004 2156 +4 31 57 93 2206 +4 31 2206 1750 57 +4 1696 2002 1503 2238 +4 1582 273 2031 1562 +4 588 2491 586 2500 +4 2500 2491 1648 1922 +4 2501 2421 1303 1295 +4 2501 2421 2409 1303 +4 2456 2501 2409 1303 +4 2336 2295 1416 1388 +4 2460 1795 879 2505 +4 2502 832 846 2213 +4 2215 846 848 2213 +4 2215 2453 2213 848 +4 740 830 2438 1739 +4 740 1497 2438 830 +4 29 2496 35 2328 +4 2096 1540 2118 2394 +4 2496 54 1529 39 +4 2494 2129 1878 1473 +4 2035 2129 1473 1485 +4 620 628 2371 1970 +4 628 2371 1970 1680 +4 1024 993 2156 1044 +4 915 946 2121 947 +4 57 1750 14 23 +4 57 2362 1750 23 +4 2430 1750 2362 23 +4 763 2373 815 1479 +4 2373 1479 925 815 +4 2097 1890 1887 1227 +4 928 2505 1795 2354 +4 905 928 2354 2505 +4 905 928 932 2354 +4 537 2374 2536 1646 +4 537 1997 2536 2374 +4 2375 2488 571 519 +4 2503 2424 1252 2409 +4 2503 2501 2421 2409 +4 2436 2434 1252 2503 +4 2503 2424 2434 1252 +4 208 1568 266 235 +4 208 242 266 1568 +4 2126 1777 1718 1516 +4 242 208 1899 1568 +4 526 1646 2473 553 +4 526 2473 1646 2057 +4 21 2376 78 65 +4 2376 1511 2269 2367 +4 2413 1914 1325 1296 +4 2413 1296 2575 1914 +4 2413 1914 1327 1325 +4 2413 2575 2241 1914 +4 2404 2489 702 714 +4 1367 2441 1385 2092 +4 2092 2441 1385 2098 +4 663 2516 2498 685 +4 161 2518 210 2521 +4 724 2371 2142 726 +4 726 2142 2245 2371 +4 2245 2024 1724 2142 +4 2378 2273 1731 749 +4 2378 1685 2276 1736 +4 2378 2276 1731 2273 +4 2379 1905 1650 1908 +4 2379 1924 1923 1650 +4 2375 576 523 571 +4 576 580 1657 2375 +4 428 2033 2016 383 +4 428 2033 2537 2016 +4 414 2366 387 394 +4 2504 1838 1041 980 +4 2035 1485 1839 1102 +4 1052 1102 2035 1839 +4 2504 1838 2479 1041 +4 884 2505 905 886 +4 928 897 2505 905 +4 1312 1323 1334 2036 +4 1312 1326 1914 2036 +4 2449 1312 1914 2036 +4 2447 2036 1323 1312 +4 2447 1312 2449 2036 +4 340 2016 380 2537 +4 2362 1521 87 95 +4 1520 1521 92 87 +4 49 57 2362 95 +4 2503 1249 2436 1893 +4 2515 2503 2421 1893 +4 2413 2421 2476 2241 +4 2451 2241 2477 1914 +4 2411 413 2150 1499 +4 2372 2451 2477 1914 +4 1998 1499 1508 2206 +4 851 2164 2117 964 +4 964 1819 2164 2165 +4 2117 2164 2165 964 +4 1375 1916 2529 2480 +4 289 288 2136 362 +4 2480 2529 2336 1916 +4 1242 2426 1889 1892 +4 2440 2506 1573 2397 +4 2136 299 315 1538 +4 2269 2394 1515 1540 +4 730 836 1463 1497 +4 1463 836 1481 1497 +4 730 836 724 1463 +4 724 836 2142 1463 +4 2142 836 1481 1463 +4 2508 1249 2507 2436 +4 1893 2507 2436 2444 +4 290 2457 2353 1568 +4 290 2457 1568 319 +4 2508 2434 1252 2436 +4 2508 2485 1252 2434 +4 838 2364 877 1795 +4 655 1901 1693 703 +4 2107 1850 627 1731 +4 2553 917 1543 1769 +4 2553 1952 917 1769 +4 2553 1990 917 1952 +4 2047 2553 917 1543 +4 2047 2553 1990 917 +4 1322 2000 1357 1345 +4 777 2510 2497 775 +4 775 2510 1747 791 +4 2510 2502 2481 1747 +4 366 387 388 2466 +4 1592 1579 2562 991 +4 991 1930 1579 1993 +4 2562 1579 1993 991 +4 2511 638 1799 1695 +4 16 5 2400 2430 +4 2236 931 940 1802 +4 2236 940 945 1802 +4 2468 652 605 600 +4 742 1736 2273 826 +4 826 1495 1736 2273 +4 137 1529 201 2509 +4 54 2496 1529 63 +4 63 2509 1529 106 +4 2043 2025 2055 1704 +4 65 78 1515 2376 +4 932 935 2514 958 +4 2354 932 2514 958 +4 935 938 2514 963 +4 82 1515 155 164 +4 1777 82 164 1515 +4 392 2435 456 450 +4 2253 1724 1674 2371 +4 620 1970 2371 2253 +4 392 2506 2435 1573 +4 2435 2397 1573 2506 +4 165 2470 240 191 +4 752 691 1653 2025 +4 752 1653 2173 2025 +4 812 918 1026 2013 +4 976 2504 980 1838 +4 976 2484 2504 1838 +4 2484 1838 2479 2504 +4 2369 1526 1463 1680 +4 647 2369 1680 1526 +4 628 2369 2371 1680 +4 593 2523 2524 2511 +4 694 1657 2055 1703 +4 450 1607 1573 2435 +4 392 2435 450 1573 +4 626 602 2458 2578 +4 626 2458 1799 2578 +4 891 901 951 2156 +4 891 1805 2156 951 +4 891 901 2156 1797 +4 2503 1252 2501 2409 +4 2421 2515 1292 1295 +4 1727 2018 1850 627 +4 1853 1935 1936 2335 +4 373 410 407 2517 +4 2515 2501 1295 2421 +4 1922 1937 1799 1927 +4 1 2410 1772 5 +4 2410 14 1772 5 +4 294 2357 2475 320 +4 294 2357 2450 2475 +4 643 2516 663 667 +4 4 1772 2400 5 +4 1543 917 2072 1769 +4 5 2400 2430 1772 +4 63 2386 2509 88 +4 88 2386 2509 114 +4 921 2193 2078 1956 +4 2016 1740 1869 2517 +4 2193 921 2078 1683 +4 2517 1869 1607 1740 +4 447 1740 2517 1607 +4 407 422 1740 2517 +4 422 447 1740 2517 +4 2500 1922 2315 1901 +4 2500 1922 2478 2315 +4 2403 2478 2315 2500 +4 2081 1467 921 1688 +4 1634 2081 1467 921 +4 1980 1990 1952 917 +4 1980 2186 1763 1952 +4 2491 2516 618 615 +4 991 1633 1930 2318 +4 991 1930 1993 2318 +4 2302 991 2318 1633 +4 1993 2302 991 2318 +4 509 1478 1499 956 +4 509 1516 1957 2367 +4 2367 1982 2067 956 +4 2367 956 2067 1957 +4 770 1747 771 2408 +4 729 2408 771 732 +4 1493 2338 1501 2360 +4 1024 2121 2338 2156 +4 2156 2338 1501 1493 +4 2336 2417 1440 1430 +4 2336 1401 1419 2529 +4 1478 1499 956 1548 +4 1592 1579 991 1955 +4 1592 2085 1955 991 +4 10 31 24 2095 +4 1499 1548 1725 956 +4 952 1795 2354 928 +4 2070 1988 1050 2069 +4 1823 2341 1050 1949 +4 2413 1914 2476 1327 +4 2476 1914 2482 1327 +4 1726 2094 43 25 +4 1508 2094 1726 25 +4 2259 438 1602 1642 +4 558 586 2500 588 +4 2494 1131 1878 2129 +4 2035 1131 2129 1485 +4 2035 1131 1485 1102 +4 2490 1795 821 811 +4 2467 1105 1808 1110 +4 2467 1851 1808 2108 +4 2108 1851 2359 2467 +4 2150 1502 2411 1982 +4 114 2395 2509 138 +4 2412 2565 1554 1521 +4 2082 1471 2072 1496 +4 2365 1589 1625 1626 +4 2429 2351 2014 1544 +4 2515 1292 2575 2421 +4 1893 1249 2515 2503 +4 2515 2421 2575 1893 +4 2511 616 644 638 +4 621 2511 644 1799 +4 2352 2376 1515 2269 +4 362 1575 2090 2136 +4 1295 1303 2522 2413 +4 2522 1303 2102 2413 +4 284 298 323 2277 +4 284 2277 1933 298 +4 1815 1675 1481 1949 +4 1815 1481 1825 1949 +4 284 2277 323 309 +4 2519 2575 1296 1266 +4 2519 1292 1296 2575 +4 974 996 2492 979 +4 1032 2338 998 996 +4 1433 2417 1446 1435 +4 1892 2419 1889 1200 +4 1305 1914 1325 2482 +4 755 2119 2039 1731 +4 1305 2482 2348 1914 +4 2482 1325 1327 1914 +4 1394 2115 1451 1409 +4 1394 1409 1650 2115 +4 1409 1451 1455 2115 +4 1409 1455 2379 2115 +4 1409 2115 2379 1650 +4 2413 2476 2102 2522 +4 663 665 2498 2516 +4 1418 2442 2417 1433 +4 953 958 2354 2484 +4 958 935 2514 963 +4 2354 958 2514 1838 +4 1489 194 1538 2150 +4 2150 194 1538 1539 +4 2121 2338 1493 2492 +4 2140 1055 2149 2005 +4 2140 2005 1818 2024 +4 2127 2063 1826 1824 +4 703 675 655 1901 +4 2352 65 82 1515 +4 2352 1515 82 1777 +4 2352 1989 1515 1777 +4 1009 2574 1807 1814 +4 2024 1815 1950 1677 +4 2519 1292 2575 2515 +4 1769 1071 2070 2111 +4 1071 2423 1855 1472 +4 1071 2423 1472 1470 +4 1071 1470 1834 2423 +4 2491 1695 1922 2516 +4 2500 2491 1922 1901 +4 138 2395 2509 162 +4 162 2509 205 2316 +4 2296 996 1021 2385 +4 2296 2385 2492 996 +4 1488 2182 1561 1483 +4 976 1838 958 2484 +4 2484 958 2354 1838 +4 1238 1792 1536 1865 +4 1536 1865 1792 1903 +4 2110 1865 1536 1903 +4 2340 2229 1865 1238 +4 2490 1795 838 821 +4 2551 1550 1944 1781 +4 33 20 42 2126 +4 2403 1648 507 484 +4 2403 2500 515 507 +4 2173 2148 2025 1705 +4 589 611 613 2355 +4 589 2511 2524 2520 +4 2511 1695 639 638 +4 585 2491 2520 1648 +4 585 587 2520 2355 +4 587 589 2520 2355 +4 1922 1799 1695 2520 +4 267 1562 2031 273 +4 2491 1695 2520 1922 +4 2511 1799 2520 1695 +4 2355 613 2520 1695 +4 882 2213 2453 848 +4 882 2213 906 2453 +4 1304 1312 1326 1914 +4 1312 2036 1334 1326 +4 2449 1914 1312 1304 +4 268 2393 2151 283 +4 295 2151 334 2475 +4 2151 334 2093 1602 +4 44 2328 2157 2496 +4 720 769 2266 2497 +4 711 2324 714 720 +4 2525 487 513 1648 +4 564 2524 593 2523 +4 61 90 2521 2388 +4 1488 2182 1483 2443 +4 59 61 2521 2328 +4 101 2518 161 2521 +4 2034 2182 1488 2443 +4 2491 615 614 2516 +4 2491 2355 614 585 +4 585 2355 2520 2491 +4 101 90 2518 2521 +4 355 1589 2365 367 +4 355 442 2365 1983 +4 90 2388 2518 2521 +4 2008 367 1910 1589 +4 532 1648 2500 558 +4 1370 1377 1947 1909 +4 1377 1421 1947 1366 +4 533 531 2524 1648 +4 560 589 2524 557 +4 557 587 2524 1648 +4 2524 2523 2520 2511 +4 533 560 564 2524 +4 1242 1889 2426 1276 +4 90 116 2518 2406 +4 200 198 154 2518 +4 1377 1366 1947 1909 +4 513 540 2525 1648 +4 2525 540 542 2523 +4 2525 542 2057 2523 +4 533 1648 2524 2523 +4 2525 540 2523 1648 +4 2525 2523 2057 1648 +4 2201 819 2055 795 +4 354 373 2416 2399 +4 2522 2413 1327 1325 +4 507 2500 532 1648 +4 2403 1648 2500 507 +4 638 1695 2404 1799 +4 644 638 662 1799 +4 679 2404 638 1695 +4 679 2404 662 638 +4 184 2289 2131 1996 +4 184 2289 243 2131 +4 240 1551 2008 2011 +4 642 2516 667 2382 +4 2491 2516 614 2382 +4 1517 1815 2142 1825 +4 1815 1481 2142 1825 +4 1024 2338 1049 2156 +4 2219 845 2262 2460 +4 660 647 2207 1526 +4 1216 1896 2032 1218 +4 520 1644 1642 2278 +4 508 1691 590 2278 +4 1116 1159 2147 2455 +4 2147 1159 2419 1200 +4 1394 2432 1451 2115 +4 157 2141 2099 180 +4 1647 2007 1920 1869 +4 1966 1647 1869 2007 +4 1215 2549 1651 1913 +4 1215 2549 1834 1651 +4 2111 1818 1215 2342 +4 2111 1215 1470 2342 +4 1215 2568 2549 1913 +4 1215 1565 2568 1913 +4 1215 2568 1834 2549 +4 1345 1364 1911 2000 +4 1364 2175 2000 1389 +4 2437 828 1741 1742 +4 1176 1013 1858 2419 +4 1176 1195 1858 1013 +4 1550 1872 1973 1238 +4 1234 2045 1888 1873 +4 2184 1234 2045 1888 +4 1630 1735 2438 1789 +4 1463 1497 1789 2438 +4 740 1497 1526 2438 +4 1497 2438 1463 1526 +4 1683 2546 2556 2459 +4 2540 2572 1467 1630 +4 1688 2556 2459 1683 +4 1491 2572 1467 1688 +4 1852 1234 2270 1882 +4 1852 2270 1234 2135 +4 1552 462 2537 455 +4 424 2033 1552 2537 +4 2244 1371 2052 2237 +4 563 1514 1612 550 +4 2289 1545 1507 219 +4 155 2289 225 219 +4 226 184 2289 243 +4 155 164 2289 219 +4 2289 219 226 1545 +4 155 2394 225 2289 +4 2035 1839 1473 1784 +4 1784 2035 2019 1473 +4 2494 1878 2019 1473 +4 1129 2467 1167 1140 +4 1129 2359 1167 2467 +4 900 1831 1008 978 +4 1298 2144 1301 2441 +4 1298 2144 2441 2092 +4 1181 1896 2032 1216 +4 1181 1896 2037 2032 +4 2374 704 1697 2445 +4 1449 2529 1436 1443 +4 1435 1433 2417 2442 +4 1436 1449 2417 2529 +4 1488 1556 1561 2182 +4 2034 1556 1488 2182 +4 2396 2475 295 272 +4 2393 295 2396 2475 +4 2393 283 295 2151 +4 678 694 1657 2055 +4 1488 2443 1483 2023 +4 1417 1412 2442 1435 +4 1435 2442 2417 2529 +4 1727 1722 1847 1527 +4 1727 1527 1847 1733 +4 1637 1663 1552 455 +4 1552 2280 1625 455 +4 2067 1583 2044 1587 +4 1840 1564 1662 2223 +4 1888 2223 1662 1564 +4 2300 1571 2066 2054 +4 1550 1973 1512 1238 +4 2285 2561 2300 1640 +4 1637 1533 2043 1663 +4 1862 2043 1533 1653 +4 1862 2043 1637 1533 +4 1541 1575 2044 1982 +4 1541 2044 2067 1982 +4 2078 1490 1673 1527 +4 2078 2546 1527 1683 +4 1884 1987 1915 1537 +4 1579 1992 1690 1465 +4 1593 1992 1596 1531 +4 1958 1498 1908 1564 +4 1915 2000 1958 1564 +4 1617 2261 1561 2125 +4 1596 1992 2194 1531 +4 1630 1463 2438 1526 +4 2576 1526 2572 1491 +4 2064 1550 1464 2551 +4 2393 2475 2151 295 +4 2379 1423 1452 1393 +4 2379 1393 2171 1423 +4 2537 1869 2033 455 +4 1563 2084 1468 1595 +4 1595 2195 2084 1468 +4 1679 2540 2459 1467 +4 2459 1735 2556 2572 +4 1688 2572 1467 2459 +4 1613 1468 1599 2194 +4 1463 1630 2438 1789 +4 1638 2576 1467 1491 +4 1467 1630 2572 2576 +4 2077 1630 1467 2576 +4 2071 1469 2178 1951 +4 2024 2187 1469 2178 +4 2187 2071 1469 2178 +4 1471 1769 1813 1071 +4 1952 1985 1469 1763 +4 1952 1469 1985 1950 +4 1537 1987 2069 1470 +4 2342 1651 1470 1861 +4 1380 1401 2336 2480 +4 2463 2472 1565 2574 +4 1039 1058 1519 1824 +4 1861 2147 2342 2419 +4 1861 2147 2419 1892 +4 1420 1419 1434 2336 +4 2336 1434 2417 2529 +4 597 630 692 2488 +4 656 630 1657 2545 +4 656 692 630 2545 +4 2465 1902 1832 1831 +4 1896 1897 2293 1251 +4 1270 1251 2448 1309 +4 2140 1771 1517 2024 +4 2140 2005 2024 1517 +4 1205 2091 1236 2535 +4 2091 1894 1254 1236 +4 1060 959 1061 1819 +4 2072 1813 1496 1471 +4 2072 1813 1471 1769 +4 2450 2205 1529 2370 +4 2393 2475 2396 1567 +4 20 26 42 2352 +4 20 2352 42 2126 +4 803 1764 867 2200 +4 803 2200 2122 1764 +4 1812 1662 2223 1840 +4 1105 2467 1140 1110 +4 2467 1144 1881 1140 +4 2467 2359 1881 1851 +4 1179 1230 1892 2339 +4 2469 478 2536 1646 +4 2469 2284 1886 1603 +4 2470 1551 2363 204 +4 10 2095 24 11 +4 10 14 31 2095 +4 646 1755 1669 1532 +4 1755 2190 1669 1532 +4 447 1607 495 1740 +4 447 2517 410 445 +4 2472 2463 1156 1095 +4 808 860 2200 929 +4 860 1756 2200 922 +4 2426 1290 1315 1911 +4 1065 1867 1902 1119 +4 360 372 2474 330 +4 372 2474 330 1603 +4 2474 1601 1603 2145 +4 2151 2475 1567 1945 +4 545 2323 650 549 +4 442 545 549 2323 +4 549 1967 2323 650 +4 442 1625 2323 1730 +4 554 2119 653 2107 +4 554 2107 1757 1967 +4 2376 1515 113 78 +4 1778 2020 2009 1926 +4 1254 1285 1894 2405 +4 340 2537 380 352 +4 352 380 384 2537 +4 380 384 2537 428 +4 428 2537 2033 426 +4 1892 1863 1861 2147 +4 2147 1861 2341 1863 +4 2321 203 171 1566 +4 1083 1157 1485 1848 +4 1485 1848 1157 2129 +4 1848 2129 1879 1157 +4 2207 1729 1491 1641 +4 372 1603 451 2474 +4 2474 2145 1603 451 +4 2149 1818 2005 1858 +4 2140 2149 1818 2005 +4 2062 1277 1354 1350 +4 946 977 2121 947 +4 977 2338 1024 2121 +4 2121 2156 1493 2338 +4 2472 1095 2574 2463 +4 508 2259 1639 2279 +4 425 1639 508 2259 +4 1001 2138 1078 1829 +4 2138 1078 1829 2002 +4 2469 2536 478 451 +4 1216 2032 1237 1218 +4 893 894 968 1793 +4 2437 1793 1495 894 +4 2437 1793 894 893 +4 1092 1868 2002 1696 +4 2243 2181 1568 2154 +4 1570 1604 2304 1945 +4 2062 1350 1354 1907 +4 619 1657 622 571 +4 2488 630 2545 1657 +4 1908 1840 1498 1649 +4 1740 492 552 495 +4 1582 187 221 1562 +4 2013 1026 1496 2089 +4 678 2055 739 694 +4 738 694 2055 1703 +4 572 2488 622 581 +4 1139 1213 1217 1878 +4 1139 1217 1877 1878 +4 1139 1878 1877 2019 +4 620 2320 608 525 +4 490 2320 1624 1556 +4 525 1668 1624 2320 +4 1328 1391 2171 1905 +4 1328 2171 1904 1905 +4 1391 2171 1905 2379 +4 2379 2171 1905 1908 +4 18 85 1734 89 +4 1240 1889 1276 1909 +4 1 2095 11 2427 +4 1 10 11 2095 +4 3 1 11 2427 +4 1575 1576 2044 1982 +4 1378 1427 1840 1923 +4 1378 1351 1840 1427 +4 1427 1923 1649 1840 +4 1822 1860 1472 1883 +4 1822 2070 1472 1860 +4 1769 1472 1492 2070 +4 1071 2111 1215 1470 +4 1071 1470 1215 1834 +4 1472 1470 2423 1537 +4 1470 1834 2423 1651 +4 2423 1470 1651 1987 +4 1472 1537 2423 1855 +4 1470 1987 2423 1537 +4 968 2230 893 1793 +4 911 2138 1001 2534 +4 1523 151 2141 2567 +4 140 151 1523 2567 +4 151 2567 157 2141 +4 2351 1549 1518 195 +4 2139 1518 195 2351 +4 2346 1998 2351 148 +4 2346 2139 2351 1518 +4 2420 2035 1006 1837 +4 1359 1384 1405 2442 +4 1171 2325 1198 2495 +4 1060 2533 1819 2331 +4 2175 1454 1431 1421 +4 2175 1421 2432 1454 +4 968 1793 1836 2230 +4 968 894 978 1793 +4 2495 2428 1898 1897 +4 2495 2257 2428 1897 +4 974 977 2121 2492 +4 1715 2024 1724 2245 +4 2005 1815 1818 2024 +4 2024 1815 1818 1950 +4 1895 1513 2499 1938 +4 1839 1485 1473 1959 +4 1959 1834 1485 1473 +4 1762 2046 1471 1474 +4 2046 1471 1474 1883 +4 1817 1883 1474 2566 +4 1883 2566 1855 1474 +4 1938 1817 1474 2566 +4 1513 1855 2566 1474 +4 1582 221 273 1562 +4 43 36 2094 98 +4 423 2145 491 1641 +4 2145 1641 517 491 +4 2145 517 1641 2536 +4 1378 1407 1923 1840 +4 544 610 2538 1618 +4 2538 550 1618 1514 +4 1500 2538 1618 1514 +4 1822 1550 1781 1872 +4 1822 1872 1781 1332 +4 1842 1806 1792 2372 +4 157 2567 1525 2099 +4 157 2567 2099 2141 +4 2534 1506 2163 1789 +4 2534 2030 1789 2163 +4 2536 2374 1886 1646 +4 2536 1997 1886 2374 +4 1171 2325 2495 2226 +4 2251 2226 2486 2246 +4 1265 1894 2513 2068 +4 1255 1259 2062 1875 +4 2251 1898 1897 2495 +4 2325 2495 2251 2257 +4 2467 1110 1808 1851 +4 1110 2467 1140 1144 +4 624 2538 690 1514 +4 1514 563 690 624 +4 43 98 2094 1726 +4 1808 1073 1035 1534 +4 1035 1856 1534 1086 +4 1073 1086 1035 1534 +4 1106 1851 1099 1534 +4 2379 1923 1457 1423 +4 2379 1423 2171 1923 +4 2260 2227 1870 1145 +4 480 1639 1635 2107 +4 2107 1685 1639 1635 +4 1545 1966 1507 1524 +4 261 2012 1522 2011 +4 1851 2359 1881 1798 +4 1798 1881 1487 1936 +4 2535 1841 1969 1866 +4 2222 1660 1623 2083 +4 1853 1876 1936 1882 +4 1855 2232 1537 1979 +4 2232 1915 1537 1979 +4 1617 1667 1561 2216 +4 1464 1974 2133 166 +4 1974 2045 1935 2003 +4 1958 2175 1649 1498 +4 1958 2041 2175 1911 +4 1915 1911 1958 2000 +4 2135 1908 1564 1958 +4 2135 1958 1564 1979 +4 1666 1713 1991 2047 +4 2047 1723 1713 1991 +4 1984 1958 2564 1684 +4 1884 2564 1958 2041 +4 1958 1650 2041 1684 +4 1958 2564 1684 2041 +4 2151 1602 1945 1655 +4 2151 2054 1655 1582 +4 2135 1984 1684 1958 +4 2135 1958 1684 1908 +4 1952 2553 1677 1769 +4 1990 2553 1677 1952 +4 1667 1990 1953 1674 +4 1674 1990 1953 1724 +4 1816 2541 2335 2345 +4 1592 2562 1591 991 +4 1587 1993 2562 1622 +4 407 422 2517 410 +4 1051 1505 1098 1041 +4 2296 2385 1030 1838 +4 1111 1067 1066 2360 +4 1505 1107 1111 1870 +4 1066 2479 1111 2360 +4 2419 1200 1232 1889 +4 1997 1697 1886 2374 +4 2374 673 1697 704 +4 2089 1026 1496 1839 +4 1488 2443 1494 1941 +4 2014 2443 1488 1941 +4 2014 1488 2443 2034 +4 1218 2293 1896 2032 +4 1494 2443 2023 2170 +4 2015 2443 1494 2170 +4 2143 1097 1152 1867 +4 2143 1867 2465 1097 +4 2526 1109 1863 1866 +4 2526 1109 1116 1863 +4 42 2352 1777 2126 +4 2533 1819 1820 2176 +4 2533 1859 1824 1820 +4 441 1912 1576 1577 +4 502 441 2103 1611 +4 844 1779 1778 950 +4 950 2176 1779 1778 +4 1778 2176 1779 1926 +4 1391 2379 1905 1300 +4 1300 1905 2105 1650 +4 1300 1905 1650 2379 +4 437 497 2356 2146 +4 1509 2146 1609 1614 +4 1168 2227 1196 2486 +4 1485 1834 2129 1473 +4 923 941 836 1825 +4 923 836 2030 1825 +4 1502 233 289 1538 +4 1502 1489 233 1538 +4 2393 1567 2151 2475 +4 2119 2039 1754 755 +4 83 1511 170 2376 +4 2376 2269 1511 170 +4 2165 1047 1819 1856 +4 1819 1816 2542 1856 +4 837 2201 880 2483 +4 1412 2441 2529 1397 +4 1413 1422 2529 1387 +4 386 1597 1476 470 +4 170 1515 2394 199 +4 170 2394 1515 2269 +4 844 2020 1778 1779 +4 1778 2020 1926 1779 +4 2475 1567 1945 1570 +4 2423 1834 1473 1884 +4 1071 1959 2423 1834 +4 2423 1959 1473 1834 +4 509 1516 1478 1957 +4 1717 1516 1478 509 +4 1516 1957 1520 1478 +4 2367 509 956 1957 +4 1717 1520 1478 1516 +4 1857 2330 2232 2184 +4 2232 1979 1564 1915 +4 2318 1673 1930 1993 +4 2151 1655 2162 1582 +4 1499 2150 1725 1544 +4 2194 1689 1638 1531 +4 2194 1689 1531 1992 +4 2342 1215 1470 1651 +4 1395 2441 2442 1412 +4 2529 2442 2210 1916 +4 2531 2412 192 1521 +4 1411 2295 1416 1425 +4 2515 2503 2501 2421 +4 609 2538 1618 2527 +4 1452 2379 1457 1423 +4 2379 1923 1461 1457 +4 2379 1461 1923 1924 +4 2431 1916 1368 1344 +4 2431 1916 1387 1368 +4 2431 2098 1387 1916 +4 1996 2470 2363 204 +4 927 900 1698 1831 +4 1495 2052 1698 1831 +4 1221 1251 1270 1309 +4 1412 2442 1435 2529 +4 2352 1516 1777 2126 +4 1717 2352 2126 1516 +4 2534 1789 2030 1497 +4 159 1557 2202 96 +4 1425 2295 2417 1414 +4 202 2531 2001 224 +4 2531 2001 1559 2141 +4 1350 1907 2171 1354 +4 1350 1907 1904 2171 +4 1354 2171 1424 1907 +4 2171 1424 1907 1840 +4 1726 194 2150 1539 +4 409 431 503 1593 +4 503 1629 1593 431 +4 431 1629 524 503 +4 431 1593 1531 1629 +4 163 192 1521 2531 +4 192 2531 224 2412 +4 2412 1560 1559 224 +4 867 2200 1764 939 +4 2534 2163 1001 923 +4 2534 2138 1001 1829 +4 902 906 2571 2453 +4 2465 1065 1097 1867 +4 2465 1902 1831 1065 +4 2358 2130 851 1975 +4 2358 1975 2545 2130 +4 1265 1268 2513 1894 +4 609 2527 682 2538 +4 2432 1924 1458 1451 +4 2432 1924 1460 1458 +4 2567 1563 2099 2141 +4 1358 2448 1380 2336 +4 332 370 2247 390 +4 2143 1870 1127 1098 +4 1836 2570 2465 2143 +4 2143 2227 1127 1870 +4 2470 204 222 1551 +4 2470 222 240 1551 +4 2470 2158 240 191 +4 1137 1846 1077 1006 +4 2469 2536 1886 1646 +4 576 529 580 2375 +4 634 2468 652 1657 +4 2375 1657 583 580 +4 451 2536 2145 2469 +4 66 2317 109 1921 +4 1247 1264 1317 1873 +4 1247 1873 1887 1264 +4 1264 1873 1341 1317 +4 1264 1887 2062 1873 +4 2378 1736 741 666 +4 2378 666 1685 1736 +4 2378 1736 742 741 +4 2497 2266 2249 1748 +4 1996 2363 2289 2131 +4 2131 243 264 1545 +4 1546 1545 2363 2199 +4 2008 355 367 1589 +4 2008 1589 264 355 +4 179 188 242 1899 +4 179 242 208 1899 +4 188 1899 271 242 +4 1480 2545 2488 692 +4 14 23 2430 16 +4 14 2430 5 16 +4 2527 2538 1618 1500 +4 2463 1565 1849 2574 +4 2470 1551 1546 2363 +4 1996 2470 1546 2363 +4 950 1824 936 1779 +4 1059 1808 1094 1064 +4 1059 1808 1802 1094 +4 1064 1094 1105 1808 +4 1094 1105 1808 2467 +4 1094 2108 1808 1802 +4 1094 2467 1808 2108 +4 537 603 2374 1646 +4 637 2578 2374 602 +4 1895 1846 2499 1513 +4 994 1846 1837 1006 +4 994 1846 2499 1895 +4 2467 1851 1881 1144 +4 1131 1199 1878 2129 +4 1878 1906 2129 1199 +4 1199 1906 1260 2105 +4 1199 2105 1878 1906 +4 2105 1260 1355 1906 +4 1286 1349 1289 1906 +4 812 762 1702 2373 +4 1975 1778 2020 2009 +4 2535 1894 1231 1228 +4 1119 1867 1902 1155 +4 1675 1789 1481 1949 +4 1497 2030 836 1481 +4 1481 2142 1825 836 +4 1879 1245 1286 1909 +4 2426 1315 1343 1911 +4 1255 1229 2062 1274 +4 1736 2189 1691 1685 +4 1736 1691 2189 1741 +4 1375 1396 2529 1368 +4 1375 2480 2529 1401 +4 1401 2529 2336 2480 +4 2528 2014 1488 1941 +4 2528 1941 1488 1585 +4 2528 1488 2014 2034 +4 2169 1594 1475 2104 +4 1598 2167 1594 1522 +4 277 332 1560 1600 +4 311 2247 1560 332 +4 332 1600 2247 1560 +4 1560 1600 1596 1613 +4 1541 2159 2067 1581 +4 2159 1580 1925 1586 +4 1540 2161 2159 1580 +4 2161 2159 1580 1925 +4 936 1786 1824 1826 +4 1786 1780 1824 1826 +4 1779 1824 1786 1780 +4 2039 2539 1780 1786 +4 2540 1735 2546 2459 +4 1688 2459 2556 2572 +4 2540 1630 2038 1735 +4 2540 1735 2459 2572 +4 2119 2107 627 1731 +4 2119 627 2039 1731 +4 653 2107 2119 1731 +4 2118 1961 397 2308 +4 1539 2170 1577 1576 +4 1576 2023 2170 1577 +4 2140 2149 1814 2178 +4 1553 1587 2048 1591 +4 1546 2159 1971 1547 +4 1546 1971 2199 1551 +4 1551 1971 2199 1590 +4 2199 1586 2579 1590 +4 1547 1971 1546 2049 +4 1138 2472 2160 1156 +4 1468 2084 2180 2195 +4 2084 2180 2195 1636 +4 2550 2071 2186 2187 +4 2187 1469 2071 2186 +4 797 2101 2187 1764 +4 797 1771 1764 2187 +4 2187 1764 2178 1771 +4 2101 2122 2187 1764 +4 2042 1762 1768 2046 +4 2544 2543 1760 1766 +4 1704 1759 2544 1705 +4 1704 1759 2188 2544 +4 2544 1765 1759 2188 +4 831 1758 2130 1703 +4 1703 2188 1758 2130 +4 1703 2201 2188 1704 +4 1661 1980 2191 1667 +4 1704 1658 2043 2173 +4 1510 2042 1712 1978 +4 1510 2179 2042 1978 +4 1545 2199 1925 1589 +4 2131 1589 1545 264 +4 341 1545 1983 1589 +4 1545 1925 2563 1589 +4 1563 1946 1656 1566 +4 1596 1992 1955 2194 +4 1955 1634 2180 2194 +4 2194 1467 2081 1638 +4 2438 1739 1735 2572 +4 660 2207 1729 1739 +4 660 1526 2207 1739 +4 1526 1739 2572 1491 +4 2546 1733 1843 1527 +4 2078 1490 1527 2546 +4 1555 2198 2086 2548 +4 2548 1596 2198 2086 +4 2167 1964 2195 1632 +4 2167 2174 1964 1632 +4 2547 1591 1594 1595 +4 2547 2085 1591 1595 +4 2548 1592 1591 2085 +4 2548 1592 2085 1596 +4 2547 2048 2169 1594 +4 2049 2048 2169 2547 +4 2174 2018 2107 1850 +4 1689 2576 2077 1467 +4 2171 1840 1907 1908 +4 2379 1908 1650 1923 +4 2379 2171 1908 1923 +4 2172 1877 2270 1852 +4 1846 1877 2172 2019 +4 2172 1877 1852 2019 +4 1844 1853 1876 1936 +4 1483 2261 1690 1561 +4 2550 1756 1763 2071 +4 2059 1756 1763 2550 +4 2122 1756 2071 2200 +4 1699 816 1752 1700 +4 1661 1928 1980 1702 +4 1661 1980 2550 1702 +4 751 2025 2055 691 +4 2043 1653 2025 2173 +4 1549 2182 1483 2086 +4 1473 1878 2019 1984 +4 1768 2177 2239 1817 +4 2177 2064 1817 2330 +4 2064 2239 1817 2343 +4 2552 1816 1819 1820 +4 1720 1926 1773 2166 +4 1778 1819 1926 1765 +4 1767 2177 2541 2552 +4 2552 2345 2177 2541 +4 1153 1160 2226 1171 +4 1160 1151 2235 2256 +4 2246 1897 2251 2530 +4 1687 1744 2074 2076 +4 1687 2028 1745 1697 +4 1687 1745 1739 2074 +4 1903 1536 1897 2116 +4 1470 1987 1861 1651 +4 2342 1651 1861 2419 +4 1861 2419 1651 1892 +4 1743 839 1794 1742 +4 1738 1791 1929 2074 +4 2244 1929 1371 2237 +4 2265 2052 1793 2237 +4 2244 2185 1742 2265 +4 1721 2022 1727 1722 +4 2553 1677 1769 2053 +4 1686 2065 2555 2189 +4 2249 1504 1697 1744 +4 1692 2414 2249 1743 +4 2065 2555 2554 1692 +4 2539 2052 1698 2273 +4 2273 1495 2052 1698 +4 2555 1738 1737 2244 +4 2556 2074 1739 1735 +4 2572 1739 1735 2556 +4 1686 1733 1732 1737 +4 628 724 2371 2369 +4 2369 1463 2371 1680 +4 2371 1674 1680 1785 +4 1669 1755 1676 1670 +4 1665 1978 1672 1666 +4 1665 1712 1711 1672 +4 1663 1709 2190 1664 +4 1663 1709 1532 2190 +4 2190 1975 1709 1532 +4 2567 1523 2221 1558 +4 2567 2141 1523 1558 +4 1583 2261 2083 2242 +4 2242 1623 2261 2083 +4 1509 2196 1615 1614 +4 1580 1614 2283 2558 +4 2283 1614 2577 2558 +4 2558 2196 2559 1620 +4 2557 1615 2196 1621 +4 2079 2179 1660 2222 +4 1617 2216 1661 1667 +4 2125 1617 1660 1667 +4 1617 1667 1661 1660 +4 1617 2125 1561 1667 +4 2079 1623 1660 1667 +4 1615 1659 2559 1665 +4 1614 1659 2559 1615 +4 2560 1663 1658 1533 +4 2560 1658 1663 1664 +4 1920 2560 1614 2294 +4 1920 2560 2294 1533 +4 1614 2560 2559 1659 +4 2560 1659 1658 1664 +4 1665 2222 1510 1978 +4 2308 1609 1920 1614 +4 1509 2308 1614 1609 +4 1654 1510 1616 1728 +4 2023 2083 1583 2261 +4 1611 1999 1617 2120 +4 1533 2560 2294 1658 +4 1608 2294 1533 1920 +4 2132 2106 2294 1658 +4 1513 2499 2566 1854 +4 164 1996 1515 2289 +4 1378 1407 1840 1812 +4 2135 1908 2223 1564 +4 2223 1908 1840 1564 +4 2127 2287 1512 2133 +4 2127 1519 2063 1824 +4 2284 1603 1994 2285 +4 1874 1994 1604 2183 +4 2474 408 2301 423 +4 1601 2145 2080 2285 +4 2285 1886 2145 2080 +4 405 433 2284 458 +4 405 2284 1874 2532 +4 433 1646 2469 2284 +4 2469 1646 1886 2284 +4 2300 1571 2259 2066 +4 2300 1642 1790 2259 +4 2301 2080 2081 1599 +4 2048 2302 1594 1591 +4 1591 2048 2302 2305 +4 1594 2302 1627 1632 +4 2562 1623 1579 1690 +4 1586 1620 2306 1931 +4 2306 1931 1620 1627 +4 1966 455 2563 1619 +4 1925 2563 2579 2573 +4 2579 2563 2306 2573 +4 2563 2306 1619 1626 +4 2573 1966 2563 1619 +4 418 1644 2297 443 +4 418 2377 2462 2297 +4 443 2297 1642 1644 +4 1983 1625 1589 2563 +4 2010 1541 2367 1982 +4 2010 1541 2269 2367 +4 2096 1541 2269 2010 +4 1876 1882 2270 1904 +4 1882 2270 1904 1907 +4 1286 1906 1289 1879 +4 1878 1906 1684 2564 +4 1878 1906 2564 2129 +4 2129 1906 2564 1879 +4 1645 1927 2478 1646 +4 1645 1694 2315 1922 +4 2279 2065 1686 2189 +4 582 2279 1685 1691 +4 582 1691 508 2279 +4 508 1691 1642 2279 +4 2318 1930 1673 1956 +4 1619 1664 1626 1620 +4 1619 1664 2280 1626 +4 1626 1670 1664 2280 +4 2280 1664 2190 1670 +4 1620 1626 1671 1664 +4 1626 1671 1664 1670 +4 2320 1674 1981 2319 +4 1682 1981 2319 2320 +4 455 1663 2280 1619 +4 1552 1663 2280 455 +4 1957 2322 1584 1520 +4 1478 2322 2327 1548 +4 2412 1559 1554 2565 +4 2531 1521 2565 2412 +4 2531 2565 1558 1559 +4 160 195 2327 1555 +4 160 2327 1521 2412 +4 195 1555 1549 2327 +4 1891 1806 1842 2372 +4 2476 1914 2451 2482 +4 1242 2426 2068 2021 +4 2149 1814 1565 2472 +4 2149 1858 2472 1565 +4 1938 2499 2290 2566 +4 1513 2499 1938 2566 +4 2566 1857 1854 2290 +4 1811 2541 2290 2335 +4 2541 2290 2335 1954 +4 2370 1567 1899 1528 +4 1520 2322 2565 1521 +4 2322 1553 1584 2565 +4 2565 2547 1553 1584 +4 2565 2547 1557 1558 +4 1839 1485 2568 1848 +4 1807 2089 1565 1849 +4 2089 2568 1565 1849 +4 2089 1839 2568 1848 +4 2345 1974 2330 1954 +4 2569 1865 2229 2110 +4 2340 1865 2229 2569 +4 1501 2303 1569 2422 +4 2143 1098 1505 1870 +4 2143 1082 1836 1505 +4 1816 2003 2331 2345 +4 2345 1859 2003 2331 +4 1061 1856 2331 1819 +4 1819 1856 2331 1816 +4 1817 2330 2064 2343 +4 2330 2064 2343 1464 +4 356 370 1531 1596 +4 356 1596 1593 2198 +4 2531 1559 224 2412 +4 2531 2412 2565 1559 +4 176 1529 2396 207 +4 228 1529 2396 241 +4 554 650 2119 1967 +4 554 1967 2119 2107 +4 1072 1808 1106 1534 +4 2441 1374 1395 2442 +4 1368 1387 2529 1916 +4 2535 1894 1236 1231 +4 2535 2091 1236 1894 +4 1267 2431 1270 1237 +4 2431 1916 1344 1302 +4 1906 1947 1404 2432 +4 1577 457 2120 1578 +4 1578 1612 457 2120 +4 159 1557 212 2221 +4 159 2221 2202 1557 +4 2221 1562 1557 212 +4 697 1783 2137 763 +4 1102 1177 1485 1157 +4 1131 1177 2129 1485 +4 1485 1157 1177 2129 +4 1131 1177 1485 1102 +4 1839 1485 1959 2568 +4 2568 1834 1485 1959 +4 27 33 64 1520 +4 27 1520 1717 33 +4 1784 1473 2019 1855 +4 1474 1855 1471 1784 +4 1474 1784 1513 1855 +4 1784 2019 1513 1855 +4 1355 2432 1906 1404 +4 1355 1650 1906 2432 +4 1291 1355 1650 2105 +4 2381 765 757 705 +4 1505 1053 1082 1836 +4 1505 1870 2570 2143 +4 2476 1327 2482 1337 +4 1280 2433 1359 1311 +4 2527 1500 1668 2101 +4 660 669 744 1739 +4 660 1739 1729 669 +4 660 1739 744 740 +4 740 1739 1526 660 +4 1075 2035 1006 2420 +4 2034 2398 353 262 +4 1048 1836 2465 1082 +4 1082 2143 1836 2465 +4 910 913 2514 1796 +4 2571 1838 965 986 +4 947 977 2121 974 +4 979 2571 954 983 +4 1551 1971 2169 2049 +4 1546 1586 1971 2159 +4 1835 2159 1509 1580 +4 2159 1580 2196 1509 +4 1554 1588 1591 1592 +4 1554 1592 1591 2548 +4 1553 1591 2547 1554 +4 1553 1591 2048 2547 +4 2049 2048 2547 1553 +4 2151 2093 1945 1602 +4 869 994 1804 1895 +4 1752 1719 869 1895 +4 869 1752 1895 1804 +4 362 1576 1575 2136 +4 2437 1793 1742 2185 +4 286 328 1539 2214 +4 328 329 1539 2214 +4 329 2214 1577 1539 +4 2214 2170 2429 2015 +4 1539 2214 1577 2170 +4 350 315 1539 1576 +4 350 1577 1576 1539 +4 1154 1194 1487 1881 +4 1946 1613 1468 1599 +4 1946 1468 2084 1599 +4 1946 1599 2084 1656 +4 1656 2561 1655 1601 +4 2176 1819 2552 1926 +4 2176 2552 1819 1820 +4 2177 1768 2541 1817 +4 1548 1583 2067 1587 +4 1548 1583 1587 1588 +4 1548 1587 2067 1553 +4 2184 2045 1234 1935 +4 2009 2544 1765 1766 +4 2381 2258 1741 1742 +4 1755 1670 2190 1720 +4 1755 1720 2190 2009 +4 1755 1720 1676 1670 +4 335 313 2198 1593 +4 313 2182 1555 2198 +4 2182 2198 2086 1555 +4 280 1555 2198 313 +4 1659 1706 1699 2543 +4 1853 1882 1935 2172 +4 2172 1852 1882 1935 +4 1549 1483 1588 2086 +4 2023 1583 2109 1544 +4 1559 2085 1595 1613 +4 2547 1559 2085 1595 +4 1560 1596 2085 1613 +4 1560 2548 2085 1596 +4 1557 1558 2547 2104 +4 1558 2547 2104 1595 +4 1557 2104 1475 1558 +4 1558 1932 1595 2104 +4 1910 2008 1589 1590 +4 2131 1589 2199 1545 +4 2131 2363 2199 1551 +4 1949 1823 2053 1050 +4 1677 1950 2053 1823 +4 2053 1823 1950 2070 +4 1903 1898 1897 2110 +4 2233 1897 2251 1898 +4 2432 2041 1947 2175 +4 2432 2175 1650 2041 +4 1929 2051 1794 1743 +4 2571 954 2492 979 +4 2052 2237 1371 1832 +4 2237 1681 1832 1833 +4 2024 2178 1818 2140 +4 796 2502 2215 2510 +4 1723 2553 1776 2053 +4 1723 2075 1490 1776 +4 1843 1371 1828 1787 +4 2076 1738 2556 1683 +4 1687 2076 2074 2556 +4 1675 2038 1789 1782 +4 2038 1675 1789 1630 +4 2201 1606 1758 2188 +4 1703 1758 2188 2201 +4 2535 1986 1969 1894 +4 1179 2535 2339 1863 +4 1232 1889 1276 1240 +4 2191 2047 2254 1990 +4 2191 2047 1990 1980 +4 1467 2572 1491 2576 +4 1630 2438 2572 1526 +4 1688 2572 2556 1491 +4 2438 1739 2572 1526 +4 1491 1739 2572 2556 +4 1679 1723 1490 2038 +4 1679 1490 1673 2078 +4 1679 1723 1673 1490 +4 1679 2038 1490 2540 +4 1679 2540 1490 2546 +4 1679 1490 2078 2546 +4 1975 1709 2188 2009 +4 2130 1975 2188 1765 +4 2391 2414 1746 2274 +4 1766 2552 2541 1816 +4 1981 1716 1715 2253 +4 466 2435 2217 456 +4 2160 1885 1013 1208 +4 2258 1743 1742 2333 +4 1580 1614 2558 2196 +4 1128 1844 1876 1875 +4 2003 2097 1859 1974 +4 2174 1632 2018 1678 +4 1731 2539 2273 1732 +4 1732 2052 2539 2273 +4 1710 2543 1766 1767 +4 1711 2543 1710 1767 +4 1727 2073 2039 2539 +4 1774 1720 1749 1773 +4 1670 1671 2087 1721 +4 1659 1699 1658 2543 +4 2132 1699 1658 1659 +4 1699 1752 1760 1761 +4 1699 1705 2543 1760 +4 2543 1699 1760 1761 +4 1705 1760 2544 2543 +4 1599 1636 2081 2180 +4 1599 2194 2180 2081 +4 2084 1636 2561 1599 +4 2084 1599 2180 1636 +4 1599 2080 1636 2561 +4 2044 2083 1616 2557 +4 2044 2083 2557 1583 +4 2561 2080 1640 2285 +4 1587 1588 2242 2562 +4 2557 1623 1622 2562 +4 1587 1622 2562 2557 +4 2284 2285 1994 1643 +4 1811 2499 2290 1938 +4 2566 1854 2499 2290 +4 2305 1628 2302 1993 +4 2048 1627 1594 2302 +4 2305 2048 2302 1628 +4 2269 1515 1989 1540 +4 2474 2301 2080 1641 +4 2474 1641 2080 2145 +4 2301 1600 2194 1638 +4 2301 2194 2081 1638 +4 2044 1581 2557 2286 +4 2044 1616 2286 2557 +4 1622 1666 1993 1623 +4 1622 1623 2222 1666 +4 1623 1666 2079 2222 +4 1623 1991 2079 1666 +4 2023 1561 2261 1483 +4 2023 2083 2261 1617 +4 2135 1234 2223 2270 +4 2135 1908 2270 2223 +4 1594 2195 2302 1632 +4 2195 2302 1632 1633 +4 1594 1632 2167 2195 +4 2573 2283 1619 1620 +4 2283 1925 2573 1966 +4 2283 1925 2558 2573 +4 2573 1620 1619 2306 +4 1925 2563 2573 1966 +4 2573 2563 2306 1619 +4 1964 2193 1678 1943 +4 1632 2193 2318 1678 +4 2193 1956 2318 2078 +4 2046 1492 1769 1471 +4 1589 1590 2306 1708 +4 1590 2306 1708 1627 +4 1590 1627 1708 1631 +4 2308 1580 1920 1647 +4 467 1608 2418 2308 +4 459 1609 1608 2308 +4 2106 1658 1533 2294 +4 2294 2560 1659 1658 +4 1817 2566 1857 1883 +4 1520 2322 1584 2565 +4 2322 1554 1553 2565 +4 2322 1521 2327 1554 +4 1268 2449 1894 1275 +4 1275 2449 1894 1285 +4 1285 2405 2447 1894 +4 2513 2348 1894 2449 +4 1268 2513 1894 2449 +4 1903 1897 2144 2116 +4 2144 1903 1898 1897 +4 2428 2116 2144 1897 +4 2428 1271 2144 2441 +4 1257 1258 1885 1909 +4 1258 1245 1885 1909 +4 2533 1820 2331 1859 +4 1060 1859 2533 2331 +4 1536 1896 1897 2293 +4 1897 2110 1536 1903 +4 2293 1536 1896 2032 +4 2465 1867 1832 1902 +4 2465 1867 1902 1065 +4 160 1555 2412 192 +4 2412 2327 1554 1555 +4 160 2327 2412 1555 +4 2526 1116 2341 1863 +4 2341 1949 2112 1050 +4 1050 1863 2112 2341 +4 1019 2089 1849 1848 +4 2089 2568 1849 1848 +4 1820 1821 2345 1859 +4 1821 1859 1974 2345 +4 972 1803 1804 1900 +4 1488 1561 2023 1483 +4 1488 1561 1494 2023 +4 2528 1556 1488 2034 +4 819 814 876 2201 +4 1350 1393 2171 1904 +4 2437 1793 893 828 +4 813 1742 850 2490 +4 2437 828 1742 1793 +4 2247 390 1531 1600 +4 518 519 2488 2033 +4 2488 571 622 1657 +4 2375 1657 571 2488 +4 1009 1016 2574 1814 +4 2472 1095 1093 2574 +4 1029 1093 2574 1814 +4 28 83 2376 1511 +4 1340 1348 1374 2441 +4 2144 1301 2441 1271 +4 813 828 850 1742 +4 277 1600 2001 285 +4 1412 2442 2529 2441 +4 422 447 2517 410 +4 2163 1001 1015 1829 +4 2526 2112 2163 1829 +4 2534 1829 1001 2163 +4 2431 2448 1302 1270 +4 1251 2431 1270 2448 +4 835 1786 927 1698 +4 1556 1593 2182 385 +4 1271 1311 1348 2428 +4 1239 2144 1898 2428 +4 2575 2036 1914 1320 +4 1292 2575 2421 2413 +4 2519 1893 2575 1266 +4 1253 2519 1893 2515 +4 1271 2428 1348 2441 +4 22 1734 413 1489 +4 18 89 1734 22 +4 1734 1489 89 85 +4 1255 1229 1875 2062 +4 2145 1886 1603 2469 +4 2469 2536 2145 1886 +4 1893 1249 1253 2515 +4 2421 2575 1893 2241 +4 2519 2515 2575 1893 +4 2264 1410 1414 1918 +4 2264 2417 1414 1426 +4 1649 1427 1450 1924 +4 1649 1924 1450 1431 +4 1649 1431 2175 1924 +4 414 2466 387 2366 +4 1598 1597 2167 1522 +4 2167 1635 2174 1631 +4 1558 1595 1563 1559 +4 1559 1613 1595 1563 +4 1559 1613 1563 2001 +4 2141 2001 1559 1563 +4 2531 2141 1559 1558 +4 921 2546 1683 2459 +4 1679 2540 2546 2459 +4 921 2546 2078 1683 +4 1467 1688 2459 921 +4 921 2546 1679 2078 +4 1634 2180 921 1956 +4 1633 1956 2180 1634 +4 1634 2180 2081 921 +4 2194 1634 2180 2081 +4 1613 2194 2085 1468 +4 1613 2194 1599 1600 +4 2194 2085 1468 1955 +4 2544 1765 1766 1759 +4 2541 1817 1938 2290 +4 2558 2196 1614 2559 +4 2196 1620 1621 2559 +4 1580 2558 1586 2196 +4 1586 2196 2048 2159 +4 1586 2159 1580 2196 +4 1989 1546 2159 1540 +4 1533 2043 1658 2106 +4 2043 1658 2106 2173 +4 2376 1515 2269 170 +4 2499 1853 1854 2172 +4 1845 1853 2172 1876 +4 1904 2171 1907 2270 +4 2171 1908 1907 2270 +4 2039 1786 1780 1779 +4 2201 1759 1704 2025 +4 2172 1882 2270 1876 +4 2172 2270 1882 1852 +4 2179 2042 1713 1543 +4 2179 1666 2079 2047 +4 2222 1978 2179 1510 +4 2079 1666 2179 2222 +4 1583 1587 1588 2242 +4 2044 2557 1587 1583 +4 2188 1765 2117 2130 +4 1785 1630 1463 1675 +4 2077 1630 1785 1675 +4 1680 1630 1785 2077 +4 1680 1785 1630 1463 +4 1491 1739 2556 1687 +4 1729 1491 1687 1739 +4 1527 1843 1490 1847 +4 2546 1843 1490 1527 +4 1723 1490 2038 1782 +4 1673 1723 2075 1490 +4 1615 1665 1621 1622 +4 2557 1621 1622 1615 +4 2488 1663 1552 1637 +4 1981 1715 1716 2187 +4 1527 1847 1490 1722 +4 1673 1490 1722 1527 +4 1673 2075 1722 1490 +4 2576 1526 1630 2572 +4 647 2576 2207 1526 +4 2577 1619 1620 2559 +4 1920 1619 2577 2560 +4 2577 1619 2559 2560 +4 2283 1920 1619 2577 +4 2283 2577 1619 1620 +4 2558 2577 1620 2559 +4 1720 1926 2166 2009 +4 1765 1816 2542 1819 +4 2190 2009 1720 1710 +4 1984 2564 1958 1884 +4 1473 1884 2129 1984 +4 1984 2564 1884 2129 +4 1728 1510 2222 2179 +4 1761 1760 1767 2541 +4 1761 1760 2541 1811 +4 2543 1761 1760 1767 +4 950 1824 2176 1058 +4 1058 2176 2533 1824 +4 2533 2176 1820 1824 +4 2259 1642 1790 2279 +4 508 2259 2279 1642 +4 978 1836 2465 1048 +4 978 1793 2465 1836 +4 1793 1836 2237 2465 +4 1736 2185 1741 2189 +4 2258 1741 1742 2185 +4 2563 1625 2280 455 +4 2541 1816 2335 1810 +4 1816 2331 1819 1820 +4 2280 1669 2190 1663 +4 1730 1669 1670 2280 +4 2280 2190 1669 1670 +4 2177 2330 2345 1821 +4 2177 2064 2330 1821 +4 166 2436 1893 2503 +4 2335 1936 1798 2003 +4 2335 1954 1935 2003 +4 1737 1736 2052 1732 +4 2394 2289 1540 1507 +4 2289 1540 2161 1546 +4 1507 1540 2161 2289 +4 1882 1887 1873 2062 +4 1935 1887 1882 1936 +4 1935 1882 1887 2045 +4 1882 1887 2045 1873 +4 1936 1887 1882 2062 +4 1705 2544 1710 2543 +4 2055 2201 1704 2025 +4 2089 1813 1565 2568 +4 2089 1813 1951 1565 +4 2146 1615 1616 1654 +4 2286 2146 1615 1616 +4 1483 1561 1690 2182 +4 1483 1690 2086 2182 +4 2182 2061 1561 1690 +4 2182 1593 2061 2086 +4 1183 1245 1879 1885 +4 1509 2146 1615 2286 +4 1575 1509 1581 2286 +4 1575 2286 1581 2044 +4 1565 2463 1913 2472 +4 2129 1884 2549 2564 +4 1483 2086 1690 1588 +4 2023 2120 1494 1577 +4 2170 2023 1494 1577 +4 2173 1699 1705 1658 +4 2173 2148 1705 1699 +4 2152 1760 1752 1804 +4 1752 1760 1761 1804 +4 2152 1752 1760 1699 +4 1803 1900 1810 1804 +4 1804 1811 1900 1810 +4 1656 2561 1599 2084 +4 1656 1599 2561 1601 +4 2249 2414 2310 1743 +4 1554 2548 1559 2412 +4 2412 1559 1560 2548 +4 2239 1883 1822 2046 +4 2239 1822 1883 2343 +4 2064 2239 2343 1822 +4 420 2525 479 2532 +4 483 2532 526 1646 +4 2532 479 432 483 +4 2532 521 526 2057 +4 1828 1832 2340 1827 +4 1828 2340 1832 2569 +4 1655 1994 2561 2054 +4 2185 1793 1742 2265 +4 2185 2244 2052 2265 +4 1957 1548 2067 1553 +4 2322 1548 1553 1554 +4 2322 2327 1548 1554 +4 2555 1737 2185 2244 +4 1591 1993 2302 991 +4 2085 1595 991 1591 +4 2340 1902 1867 2229 +4 1652 2229 1867 2530 +4 2340 2229 1867 1652 +4 1516 1957 1584 1520 +4 2126 1520 1516 1718 +4 1717 1520 1516 2126 +4 1553 2547 2565 1554 +4 1554 2565 1559 2547 +4 2565 2547 1558 1559 +4 356 1531 1593 1596 +4 1543 2046 1776 1769 +4 2553 1543 1776 1769 +4 2553 1769 1776 2053 +4 997 1505 1836 1053 +4 1501 1493 2360 2422 +4 2253 1724 2245 1715 +4 2253 726 2245 2371 +4 516 2500 2315 551 +4 551 2500 2315 592 +4 626 648 2578 1799 +4 648 662 2578 1799 +4 662 2404 711 2578 +4 638 1799 2404 662 +4 1735 1791 1738 2074 +4 1735 1791 1843 1738 +4 2556 1738 2546 1683 +4 2556 1738 2074 1735 +4 1683 1738 2546 1733 +4 1587 2562 1591 1588 +4 1588 1591 1592 2562 +4 1587 1591 2562 1993 +4 2074 1864 1744 1745 +4 1687 1745 1744 1697 +4 1687 1744 1745 2074 +4 2321 1567 1568 1655 +4 319 361 2181 337 +4 405 1874 395 2532 +4 2181 1603 364 361 +4 2302 2318 1632 1633 +4 2320 2253 1981 1674 +4 620 2253 2320 1970 +4 1883 1860 2232 2343 +4 1620 1626 1627 1671 +4 2306 1626 1620 1619 +4 2306 1620 1626 1627 +4 1711 2166 1721 1995 +4 1710 1767 1766 2166 +4 1664 2087 1670 1671 +4 1766 2552 1773 1774 +4 2579 1589 1590 2306 +4 1925 1589 2579 2563 +4 2199 1925 1589 2579 +4 2579 1589 2306 2563 +4 2008 2199 1589 1590 +4 2199 2579 1589 1590 +4 2276 1736 1732 2273 +4 2378 1736 2273 742 +4 2378 2276 2273 1736 +4 1773 1820 1780 1774 +4 1773 1779 1780 1820 +4 1720 1773 1779 1749 +4 1821 1824 2063 1859 +4 1820 1859 1824 1821 +4 2531 202 2001 2141 +4 224 1560 2001 238 +4 936 950 1039 1824 +4 950 1824 1058 1039 +4 1271 1348 1301 2441 +4 131 1962 206 130 +4 2354 905 886 2514 +4 932 935 909 2514 +4 909 1796 2514 913 +4 2432 1454 1460 1924 +4 1421 2432 1947 2175 +4 1121 1868 2002 1092 +4 436 1610 2124 497 +4 497 2124 632 1610 +4 929 2200 934 1807 +4 2200 934 1807 1814 +4 1972 1758 1703 784 +4 784 1758 1703 787 +4 1106 1110 1144 1851 +4 1110 2467 1144 1851 +4 795 2201 837 2483 +4 1703 2483 2201 795 +4 1156 2463 2472 1885 +4 2198 1596 1560 356 +4 567 660 2207 1729 +4 2538 1500 686 690 + +CELL_TYPES 10415 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 diff --git a/data/paper_roll.vtk b/data/paper_roll.vtk new file mode 100644 index 000000000..75a9d6bd2 --- /dev/null +++ b/data/paper_roll.vtk @@ -0,0 +1,5057 @@ +# vtk DataFile Version 2.0 +paper_roll_, Created by Gmsh +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 600 double +-0.7820900079999999 0.827568293 0.00924713165 +-0.777751207 -0.116710462 -0.292424589 +-0.760061324 0.612008035 0.469892025 +-0.758299351 0.0285010096 -0.508030534 +-0.757440627 -0.281620979 -0.11854291 +-0.755117834 0.545724452 -0.420966506 +-0.753011942 0.355996579 0.552646041 +-0.752702415 0.839826524 -0.311538458 +-0.752169073 -0.0221501123 0.171718746 +-0.751354992 0.429423869 -0.664133906 +-0.7427160739999999 0.279877931 -0.466493368 +-0.7423388359999999 -0.276159674 0.0325088315 +-0.735330284 0.0552638285 0.440456748 +-0.7309169170000001 0.6727296109999999 -0.123499498 +-0.727841139 0.664434493 0.154362813 +-0.7120038869999999 0.0857423618 -0.248685122 +-0.704680979 -0.0259495564 -0.0562133938 +-0.692267537 0.808981061 0.323690504 +-0.688575387 0.521184921 0.687356412 +-0.684659839 -0.235523224 0.375390887 +-0.6599670050000001 0.429824173 0.228702262 +-0.641646385 0.762646198 0.55748409 +-0.637655854 0.214568764 -0.713702679 +-0.611218035 1.00772202 0.150314391 +-0.591715336 -0.133775547 0.524025679 +-0.5797129733124321 -0.4580813380658779 -0.06126051562511654 +-0.563363671 0.22195138 0.213813603 +-0.558436751 0.7173757549999999 -0.644143164 +-0.555462956 0.0557920933 0.704378963 +-0.540820003 0.32432577 0.752981007 +-0.536605656 0.529989123 0.0492394082 +-0.528958917 0.107748583 0.0936217904 +-0.514113069 1.00604153 0.390880138 +-0.511549294 0.409274012 -0.196746707 +-0.5044604539999999 -0.0423647687 -0.714398742 +-0.470181137 0.191926137 -0.190280318 +-0.461713195 -0.474114776 0.142999947 +-0.452569008 0.426997244 0.174725875 +-0.451511621 0.466333836 -0.780845582 +-0.450170666 0.61155045 0.752854705 +-0.44810605 0.118423574 -0.0389554799 +-0.445279419 -0.457892597 -0.307217538 +-0.431424201 -0.248849958 -0.5798019170000001 +-0.402966708 0.956615388 -0.516652882 +-0.40294072 -0.150119454 0.654799342 +-0.39707762 1.11489272 -0.191939786 +-0.372760028 -0.339257717 0.450148106 +-0.365174264 0.176143721 -0.803318202 +-0.360029668 1.14899528 0.128510192 +-0.338620335 -0.508157253 -0.0993897244 +-0.303045332 -0.0917355567 -0.708141744 +-0.297312021 0.721218288 -0.697373211 +-0.284920633 0.243149951 0.193386912 +-0.282121956 0.0691090077 0.777621329 +-0.277643472 1.08766937 0.359720021 +-0.273138851 0.897254705 0.599794269 +-0.270049244 0.382808089 0.823784888 +-0.261656851 0.49722743 -0.0640060529 +-0.233890429 0.489648372 0.0943357274 +-0.224296093 -0.358356118 -0.41699627 +-0.22386612 0.348200947 -0.191356912 +-0.219943941 1.07609093 -0.360988408 +-0.21773608 -0.498598963 0.157047302 +-0.2087989190844438 0.4318002537120776 -0.7945872557455335 +-0.2074801119017711 0.1289235505236849 0.07511904111340301 +-0.176491395 0.400617927 0.187972382 +-0.173133805 1.15574384 -0.10363923 +-0.163750947 0.119577698 -0.0614402033 +-0.149812683 -0.218826205 0.646565735 +-0.1480777665008541 0.5843266473142498 0.7937703783491504 +-0.123148434 0.0849537402 -0.781158447 +-0.1118294755314862 0.893787158690768 -0.5859152796278914 +-0.113120742 1.12658715 0.231646299 +-0.0999215022 0.192852184 -0.1694711 +-0.0984651372 0.990201354 0.506852448 +-0.06605836750000001 -0.502095044 -0.143843308 +-0.0605958179 -0.412635803 0.424389124 +-0.0506579615 0.290637374 0.838822722 +-0.0394688249 0.491579235 -0.0294632278 +-0.0333795249 0.328329116 0.205668539 +-0.0237065684 0.476464748 0.115677327 +-0.0231782347 -0.200002059 -0.633648872 +-0.0208175201 0.625109375 -0.761601388 +-0.01635247803672384 0.1815307466550659 0.1562609697772235 +-0.00634849397 0.463727981 -0.151865005 +0.0254614782 0.373255402 -0.815463066 +0.0305427089 0.12843658 0.0349309221 +0.03955574045351479 0.2626254634539036 -0.1839469927591317 +0.0415809192 -0.00357565447 0.773635745 +0.0560093448 0.134973124 -0.0884106085 +0.071758613 1.06635392 -0.361566156 +0.0853891 -0.400400728 -0.426258266 +0.0881352276 0.826709509 0.678089857 +0.088500604 -0.51136601 0.122946389 +0.106995657 1.15039468 0.0268787704 +0.116223842 0.510438979 0.0658026114 +0.124930114 0.528206468 0.812987149 +0.134407356 -0.261956215 0.614182234 +0.134416729 0.443234473 0.157149315 +0.14921774 1.01572132 0.441060394 +0.156304911 0.498166531 -0.0910604671 +0.1665059077476068 0.2640134955301657 0.2073675250144031 +0.182221517 0.0693684369 -0.789641678 +0.183541641 0.800524116 -0.664221287 +0.191553205 -0.43845576 0.36290881 +0.20760563 0.132553548 0.107585885 +0.210804701 0.390742004 -0.20469436 +0.214177504 0.236100793 0.830788791 +0.2202802 -0.228184164 -0.6354748609999999 +0.232006446 0.479744285 -0.797239363 +0.269812733 0.258523583 -0.182527706 +0.286229223 -0.0676486343 0.744530559 +0.288329214 -0.489812881 -0.177450582 +0.300046235 0.113015406 -0.0393598527 +0.324255496 1.13464522 -0.138143376 +0.338882893 0.448639512 0.829264998 +0.346093744 -0.354025573 -0.494020849 +0.348575711 -0.473726839 0.168014571 +0.36269334 0.710747719 0.737573147 +0.378205031 0.914241076 0.595089436 +0.38050583 1.09386134 0.233951658 +0.406433314 0.6552896499999999 -0.727028072 +0.409949958 -0.28618294 0.554079056 +0.418190897 0.958052397 -0.516825616 +0.430716038 -0.100692198 -0.708976388 +0.457791954 0.240161762 -0.813592374 +0.473669708 0.242004395 0.197489277 +0.484736621 0.5018922689999999 0.0997527614 +0.505268872 0.199926615 0.792335868 +0.518808067 0.0964314267 0.0487414226 +0.536203325 0.390831411 -0.23384504 +0.53704989 0.545846164 -0.118342184 +0.552657723 -0.128089428 0.598260939 +0.557037592 0.113979928 -0.140113711 +0.559492886 1.10838175 0.021280339 +0.568943083 -0.40190661 -0.245474771 +0.574575126 0.586955249 0.754173756 +0.576400638 -0.425468564 -0.0327172652 +0.60234195 -0.34045127 0.354068577 +0.612495005 0.714707077 0.574165106 +0.70434922 0.671015799 0.100994535 +0.721601844 -0.0504203029 -0.0239661094 +0.727235615 0.541150868 -0.325555116 +0.729470134 0.403400838 0.354186803 +0.729528248 0.258957416 -0.344238997 +0.731559396 0.405687749 -0.588601708 +0.739753604 -0.189714774 -0.456155211 +0.7420095799999999 -0.120032072 0.442290694 +0.742529213 0.059047956 0.263216376 +0.7445417050000001 0.047858879 -0.592498541 +0.7481378319999999 0.109689914 0.610141814 +0.752550483 0.464530468 0.615466416 +0.756147742 0.959810555 -0.234599814 +0.75674957 0.000453827321 -0.2848019 +0.757090628 -0.259135753 -0.154094577 +0.7622035740000001 0.8827526570000001 0.302715659 +0.776359677 -0.207132444 0.13785924 +0.781452656 0.939227521 0.0645362735 +0.786792457 0.658583522 0.344229817 +0.788562059 0.761680961 -0.169412613 +0.789607704 0.737834454 -0.434313715 +0.2639742543549618 -0.12188533779187 -0.4693067392602531 +0.3997416065971071 0.7760820916540657 0.4137597367854066 +0.2156923504549144 -0.01183942340975848 0.0002449532492955829 +0.5890650810668157 -0.1763976012702824 0.1453836655215379 +0.3546419117372926 -0.192622320880546 -0.2560179798604978 +-0.5160213274196126 -0.09275195554426584 -0.1736439244553409 +0.1248375138934383 1.086697469113976 0.2240067064879445 +-0.2830921812342539 0.9135672290577925 0.3059126020350168 +0.1326899190097699 0.9185620295864479 -0.5299639577792437 +0.01241554778201077 0.1402768063635599 -0.4120816856949395 +0.215342174099125 -0.2025180029412313 0.04426375335562415 +-0.4547449687806509 0.5567785951245051 -0.333148999165962 +0.5442191006351726 0.4031606936474492 0.4725765589651983 +0.397616162714051 0.6316242241049695 0.24219097077094 +0.5805256730485973 0.6192103476233654 0.436163380671397 +-0.655569583 0.7786011395 -0.477840811 +-0.3708041639821506 -0.1605421389171156 0.4840459032806712 +-0.6064486055 0.235902034 -0.328386843 +-0.557646672812028 0.07591375072253272 -0.5274504896472157 +0.5884844467723939 -0.3825931418158329 0.1643140882603351 +-0.5332133072572869 0.7275018926076025 0.1777539626701911 +0.5609208556405583 0.6885699113587034 -0.60901203910222 +-0.5098987702870925 -0.1101128602554956 0.1379088635059278 +-0.03928875927492152 0.6907015749623512 0.5740507527944501 +-0.5394141731099225 0.05610201904806805 0.3048805575972297 +-0.5131965358044932 0.03782730778663345 0.521539754600943 +-0.5863138729978957 0.2823531291480914 -0.5319481645805786 +-0.3345609676030371 0.7125334014131369 -0.4727623793720038 +0.2464812193948978 0.4407009988907476 -0.47697628465166 +-0.5592706585148439 0.5379244553141946 0.3063552485213277 +-0.5558310659127391 0.7354638865906747 -0.3428410410159482 +-0.5360995847012263 0.7281385421056884 0.4210684518670839 +-0.5147223545501228 0.7963319122377728 -0.06597605494761165 +-0.06273955155504127 -0.3444113017235448 0.136286879605596 +0.4325193261065495 -0.2791456175623793 0.2107984492169988 +-0.632168535468532 0.3657499159500963 -0.3322192484193015 +-0.3685202419509329 -0.0524467305788773 -0.04207042666807665 +-0.4296271378100891 0.2076552899350621 0.5726314329055343 +-0.3616547585 0.7544025775000001 0.676324487 +-0.2846284003660516 -0.4397691972949996 -0.2445975413152526 +-0.3536699542020597 0.06254967995460783 0.6304177766068466 +0.4123121055 0.8066710235 -0.621926844 +-0.4052556089385801 0.6353293532339694 -0.04684871340491523 +-0.4084870825737062 0.5656952826263154 0.4131343281546925 +-0.2862868249334498 -0.4169907742322871 0.3120817084936982 +0.5988499496888546 0.03406638417504917 0.4451411962311665 +0.2340635827248111 0.5226874872683532 0.6642717488090042 +-0.3854723987076846 0.7463689121074932 -0.2536422222913952 +-0.3278769391319354 0.717956784487031 0.4752342949906083 +0.3904574134104982 -0.3262093592946221 -0.112600642375939 +-0.358910551124857 0.9672749515480802 -0.05546435118541547 +0.1777842219292163 -0.5015115306850915 -0.01559122658785206 +0.3080747370485818 0.2762134259510752 -0.6493980193937912 +0.596148947364803 -0.02242153033838366 0.2003985935595925 +0.005868031171049204 0.5742771191362569 -0.6128641683686463 +-0.5031988367527793 0.1700838668722822 -0.3892349805527489 +0.7380505505 0.226773314 -0.5905501245 +0.444253996 0.069734782 -0.761284381 +-0.04072401750205674 0.6998532920180478 0.7385113850298272 +-0.2241826522349804 -0.108914385402135 -0.5028546491818637 +-0.5583658887627073 -0.09849887189225132 0.3337795369800887 +-0.2465329413090951 0.05096673974517221 -0.465247201752063 +-0.2270609815369053 0.009990034517554319 -0.008762866427291557 +0.4528914132678232 -0.1923465406284653 0.4430929491970397 +-0.2493943105206236 0.1909248483991208 -0.5756605527763113 +0.018048499 1.071154235 0.3363533465 +-0.2980310927227215 0.3604984817780851 0.6226086829270667 +0.3150650911482455 -0.4824214813441841 -0.01264437812642028 +-0.2279790858320304 0.5261974025744819 0.4250055412484496 +0.210372147779073 0.6608162260661162 -0.7222276304945168 +-0.626018324034779 0.5467487517192777 -0.1585253101852808 +-0.2806855309943436 0.7806043052563052 0.05994497375613275 +-0.01357773823181021 -0.4731951475207171 0.2387339677843767 +-0.7134993375000001 -0.255841449 0.20394985925 +-0.2213004561694942 1.016076831276243 0.006032288960241026 +-0.1277886358363003 -0.4354334392840132 -0.2744684586560308 +-0.6999756186074673 0.3980788703843943 0.3679956174735358 +0.6543483434999999 -0.295810692 -0.350814991 +0.2076354266068133 1.102265342894897 -0.2432516760325281 +-0.1469344129527683 -0.3173338262546361 -0.1295262300060529 +0.1038414976 0.22131191945 -0.802552372 +0.4754588305 -0.4070890545 0.261041574 +0.6594138579162944 -0.3312662587513039 0.06099542201255562 +-0.07706951970182109 0.1797760696316847 -0.5948617691516774 +0.04600382857782633 0.3569839829281879 0.3597159290887764 +-0.01181728646638883 0.9928903554608727 -0.4573499082475507 +-0.6105877787137619 0.09200974441510709 -0.1576557626923875 +-0.1730089337956447 0.3252173558240206 0.4000279981195682 +-0.1036114158038377 0.3018841403883422 0.6614205742608137 +-0.1285717258954858 0.4865128212146718 0.2905938145380103 +-0.1528626461022948 0.4267144943059667 0.5819750657824302 +-0.03365704925193866 0.7178635176183265 0.01211938618229452 +-0.1624946727401371 0.7181792834373332 0.4125307110767419 +-0.1249991825118702 0.9075602937622239 -0.2164446605902048 +-0.5670634012884104 0.4789351932515074 0.5255013308795011 +-0.07118606173847287 0.1844770945889653 0.4946725961308542 +-0.04722631186391081 -0.1728291609905124 0.01824033679594382 +0.106202462407417 -0.2898826765668148 0.2717942219962696 +-0.009148278200741098 -0.05742475941143399 -0.5359551569344423 +-0.02920576835441901 -0.06808276749825923 -0.3828850601310922 +0.08127315488953187 -0.1128767144106133 0.1978798193189848 +0.5992671422672019 0.6006069594217325 0.2710841932552703 +-0.05737979956552589 -0.1205232996242379 0.5482998130876485 +-0.08983735168674543 0.04996638881584602 -0.2248910198709924 +0.1731204124089802 0.09628826877295726 -0.2780335800090111 +0.06362899826815994 0.4855284830619491 -0.4700154898768044 +-0.01636859275625989 0.4718572715027586 0.4630132256450378 +0.03878628879476876 0.618439676186409 0.15687011234707 +0.2133727677139987 -0.1069391342852011 -0.6985762996220262 +0.4575184135 -0.3779660915 -0.36974781 +-0.006131419210343462 0.7358301639853686 -0.4326023513860816 +-0.05405613560952399 0.8167418980636915 0.3631079754940496 +0.4992180918960951 -0.08007328660623374 0.3362418013826005 +0.128181407825433 -0.3602170530780842 0.06885550113089853 +0.3278043500818183 0.9023828334435329 0.2384666184541569 +0.107343543142228 0.2118798749791732 -0.5893938363361989 +0.09606458749858425 -0.1197754755194738 0.4762534131608184 +0.1729916137376935 0.3651884325785796 0.7052197431571986 +0.1547998084961187 0.7385108277511383 -0.5168673099275507 +0.07066198514495449 0.2822654114242402 0.6049380422569561 +0.129861721183466 -0.1256623437282304 -0.241130487451232 +0.3639693677911176 0.7717403394724629 -0.4018177888141752 +0.246413231786097 -0.3315841400964608 -0.2517687551136596 +-0.4370713685 1.077518405 0.259695165 +0.2346005345129934 -0.279173134176122 -0.3869864648871733 +-0.1296004889740936 -0.2509615982759544 -0.5565715621434977 +0.2732712397218225 -0.1733270374861026 0.4375114500707871 +-0.6313799025 -0.006931879550000001 -0.611214638 +0.2792130649864308 0.01744737166256686 -0.1880436785953508 +-0.3707201958776298 -0.000216713485035196 -0.6013388931617913 +0.4134445065665123 0.02638936999070854 0.5061630681338118 +0.2027777202471357 0.07941561829215574 0.5925815173645189 +-0.1202705184 0.032766676615 0.775628537 +0.6080994605 0.1505261755 0.2303528265 +-0.08104726365334487 0.927338699024686 0.1452611453838045 +-0.2569888293593879 0.2129234949381172 0.6709087517551079 +0.2264201905809853 0.4917999420371671 0.2975324824559517 +0.2480908205035909 0.4342407372369588 0.4873351832035028 +0.3003209367273754 0.6476315854444429 0.004455023233879768 +0.3213903626823207 0.5880765763551442 0.4303490309974519 +0.1858373319376397 0.7761706129426137 -0.1267362841452064 +0.1990112113919275 0.7295675863734614 0.2102311144792054 +0.294800961478138 0.7704202596361805 0.544314603576825 +0.0514764450260705 -0.3231609275200833 -0.1081403707428057 +0.7370349765 0.1534081475 -0.468368769 +-0.175600380415933 0.1841289068684208 0.8076456418626176 +-0.0488434779 0.2291045711 -0.7983107565000001 +0.3163975304863207 0.1526275959205735 -0.8013041953537731 +0.3803168305509414 -0.09940455895869463 -0.03382278105602927 +-0.378553644 1.131944 -0.031714797 +0.440420042331257 0.02044447373923311 -0.1122559147595921 +0.3879825995646426 -0.02608570317351572 0.1634865096812157 +0.2616000885627874 0.1038836544398141 0.7916400589399095 +0.4209134807381419 0.2396514183654148 -0.3879747460404239 +-0.1526173310693432 -0.4620882467757088 0.2698580443870818 +-0.2327208584919928 -0.3721756681649825 0.4385924364839587 +0.3829218349293956 0.487693441171232 -0.5990486957268655 +0.594214158088059 0.591647198825381 -0.4695533690619706 +-0.7439512315000001 0.638221264 0.312127419 +0.06666664441787797 0.8381888790183591 -0.6323344890603951 +-0.577879727 0.8843438640000001 0.474182114 +0.2562687008632893 1.05440533053123 0.3375618477583878 +0.4106350787122626 0.571554037042148 0.598086437895837 +0.3632068485 0.11449248735 0.07816365380000001 +0.300866269 0.8792882565 -0.5905234515 +0.7578809359662353 -0.1631478692850403 0.2950023559297956 +0.3560388567706489 0.9759014826915028 -0.1202215576675565 +-0.2760856 0.22595854835 0.8007031085 +0.626703352 0.1548082645 0.701238841 +0.352803060115629 -0.1915903028440435 0.6370512920675127 +0.5181595860766487 -0.2763245929925319 -0.03062964633423859 +-0.0541158819 -0.111200929735 0.71010074 +-0.1067065089939684 0.4388939757661122 0.8160309749685285 +0.2264431220332744 0.8684453483955979 0.6385145088216334 +0.5380336807323466 -0.04146455301365152 -0.2574046505294451 +0.5017758683329372 0.1530108938712742 -0.574395890350818 +0.1621666317507848 -0.3497608989650544 0.4892470675567965 +-0.1143330663853956 0.3174254588405397 -0.3256534123835161 +0.7510036300061766 0.0253245444041582 -0.419134670006914 +0.5304039390535441 0.457566624385319 -0.411303679362402 +0.03690576905 -0.337296009 0.519285679 +0.5740492055597302 0.6187150513010521 -0.2946706383133586 +-0.2930533924722016 -0.04047045542017398 -0.2469726424381117 +0.6348771105532396 0.7494081132582944 0.00391819742569142 +0.748422116 -0.2244252635 -0.305124894 +0.4213031458952744 -0.09568224645599024 0.6717566170772428 +-0.002934350521053876 -0.04418438016667272 -0.08057327415571866 +-0.374411821 0.593776062 -0.7391093965 +-0.16311178335 -0.14586880785 -0.670895308 +-0.02236705343928478 1.152756715277995 -0.03386905076856864 +-0.237174821681813 0.2819244792917927 -0.6701647301123524 +-0.1774650709332056 0.6104078042007642 -0.5437197815867819 +-0.2096801247284537 0.5525081045364506 -0.2936476594726115 +0.1056444988053929 0.6544936573457479 0.4475095882977211 +-0.07708137163715441 -0.5044385925564089 0.1389455443683938 +0.03244532286180241 -0.2926494648593701 -0.5385066157759721 +0.6893508134999999 -0.273791857 0.2459639085 +-0.7181870845439935 0.5379493163336553 0.3643699069276878 +0.4624881745 -0.4495977015 0.06764865289999999 +-0.2308542756954482 0.7013823204028391 0.2467760591111332 +-0.3883523538334695 0.4053145177404067 -0.5027448419991272 +0.2374445322138322 0.07847100568432935 -0.5489138099566739 +0.02041092563810991 0.4969868894965609 0.6155012636908862 +-0.6449713751282236 0.04365925384400418 0.5650751325977057 +-0.6791723541968456 0.1294484258935303 0.5568513423835166 +0.2091086543781634 -0.3402428984005577 -0.1169159914501656 +0.0295365415 0.07716108855000001 -0.7854000624999999 +0.4166311687679766 0.42795068698587 0.2901806273380771 +-0.4854255144936192 -0.2276737119933137 0.495238219425664 +-0.2998393325 0.5987428125000001 0.7731704715 +0.6700254167705061 0.1912766492047019 -0.2680683499520117 +0.2254142838 0.768728614 0.707831502 +-0.4083429425 0.3212387785 -0.792081892 +0.6118602151782522 0.6017027239833412 -0.01342289659309948 +-0.6979776025 0.1215348868 -0.6108666064999999 +-0.7099950615 -0.09012969775 0.4079238175 +-0.3973772896349685 0.2245316630768252 0.7724108775192793 +-0.3935901855911365 0.9499260473633004 0.4969392382762782 +0.4220758825000001 0.3242830635 0.810800433 +-0.01244477667285913 0.9185012492295468 0.5813586958400904 +0.768800199 0.949519038 -0.08503177025 +0.1385825733849104 0.1362859793817315 0.8069262943141158 +-0.2652665560174546 0.2507643820503184 -0.1843543023829021 +-0.4332451549345435 -0.2761449123848795 -0.04712433587873845 +-0.5828644471445453 0.009303370465401853 -0.2969097005890317 +0.05507887495148227 0.3522234706372749 -0.674906726931316 +-0.2611405077274244 -0.264224358878034 0.5650751325977057 +-0.1286908298637121 -0.4998733743123825 0.01167982799999992 +-0.1347135962171717 0.8702247094690542 0.6297938935489598 +-0.3730398917315206 0.5898990131524667 0.189494390632109 +0.06878579266499295 -0.2809468953432176 -0.3270657292879972 +0.1303593362507234 0.9659721458376256 -0.02772486463057064 +-0.304823728762865 0.2468383721950917 -0.3469948664951402 +0.4875941725 0.712727398 0.6558691265000001 +-0.1902355174180589 1.147935964547409 0.01167982799999992 +-0.1286908298637121 1.14627186697646 0.01167982799999992 +-0.6297990473636167 0.5983988150415105 -0.03133294467443288 +0.759696474531203 -0.08099381576573061 0.1929931685717061 +0.3742443188820755 0.2173989581868927 0.8097221023646461 +0.3658807952177907 0.04080746129839851 -0.381184345888455 +-0.5677257385427414 0.05111431288201838 -0.04700141912586819 +-0.367707707 0.3787374795 -0.1940518095 +0.10559446295 0.5524268299999999 -0.7794203755 +0.7850073575000001 0.850454241 -0.05243816974999999 +-0.7273599804999999 0.1828101464 -0.357589245 +-0.02350171457629825 0.1454349968107266 0.8059114619551944 +0.675142036720216 1.021009727397936 -0.1291981337035111 +-0.074092664 1.071222425 -0.361277282 +-0.3349032765887264 0.2988206399604422 -0.1914464767284626 +0.134412095442962 0.8764531974718023 0.3743818650409987 +-0.7472539545 -0.14915489315 0.10211378875 +0.1277016158024905 -0.4347890970278095 -0.3306188903662953 +0.1939458131166668 -0.4348433774415986 -0.3253266604193746 +0.05392177045979735 0.6467995316493583 0.7607830232119621 +0.1284336424293361 0.7114145106723391 0.7309026286963567 +-0.007702663499999998 -0.24039121 0.6303739845 +-0.4841817327430866 1.07916972584929 0.1392871095708649 +0.08905301360320472 1.117676833807724 -0.1266689981494265 +0.08136206045 0.7128167455 -0.7129113375 +0.575378546709734 0.2639724693471707 -0.4717588144807696 +-0.3059284985 0.119000636 -0.0501978416 +0.3975749886070091 -0.3435149522074285 0.4333758592338917 +-0.1882160181362105 0.6599782088525731 -0.09599001310879446 +0.4567290095000001 0.5177973805 0.7917193769999999 +-0.418792456 0.0624505505 0.741000146 +0.670472771 1.0238046355 0.04290830625 +0.3137078711101374 -0.4165711695685994 -0.3491717349974371 +0.7457397860248199 0.8149968660444264 0.08142305857752383 +0.6458092539306622 0.5511980640810215 -0.2287686273657668 +-0.009325448433570832 0.556447443504914 0.8034472722472692 +0.5161660622432566 0.9962948304034485 -0.3376019318099303 +-0.1297925807265876 0.2075579905385145 0.1719425411786639 +-0.7437496785 0.0165568581 0.306087747 +0.5439079575816403 -0.2348704073119916 0.5013064156866869 +-0.342531338 -0.04050522315000001 0.7162103355 +0.3445899328653428 0.5808466133927399 0.783345051143958 +0.5595232522070114 0.8699171393474577 -0.4883350445872095 +-0.1006862141921001 0.3755842035731846 -0.536187609637698 +0.5278413567190053 0.04265679563791372 0.6993488146981004 +0.3053535989335354 0.6135285042462623 -0.2809982702231557 +0.6239301484294514 0.3244157806518154 0.7074025971085623 +0.6088822455753933 -0.1748060687254698 0.5054058628876268 +-0.3880680653644658 0.9461092478870653 0.1476264948214181 +-0.7294348242194837 0.6687325297732887 0.01039109004331744 +0.5945429205 0.586454034 0.1003736482 +0.7578988369999999 0.6514159145 -0.2474838645 +0.5783495731945012 -0.1427023481668301 -0.5885024723964152 +-0.5261336061998214 1.018513067889989 -0.1266689981494265 +-0.20233935125 -0.5051261485 -0.1216165162 +0.672175765 -0.230241671 0.3981796355 +-0.1998277033118015 0.8028813138705528 -0.644896314003633 +-0.6002334693423355 0.908832979121474 0.362489674719866 +0.7421476545000001 -0.0709279475 -0.5243268759999999 +-0.434817359 0.06688947615 -0.758858472 +0.6573614565831066 -0.3509406915052969 -0.08710216234203301 +-0.196538873 1.115917385 -0.232313819 +0.2949874775 0.7279068829999999 -0.6956246795000001 +-0.5481414794999999 0.19005893165 0.7286799850000001 +-0.134002672485 0.4804777055 -0.10793552895 +-0.6984051713199357 0.2387840137900556 0.3367051814571075 +0.1353764299648782 -0.4780710586391412 0.2325118614544099 +-0.6090674907364764 0.8877911993239954 -0.3957780542634616 +-0.62610461455476 0.140835279571756 0.1998252794721451 +-0.6825470918285934 0.5321272967492519 -0.6570038338370034 +-0.6108233443477076 0.4467229623900011 -0.7188347455544635 +-0.6477921355590651 0.1401147153780417 0.3250859738478666 +0.08163657554990444 0.2599539149754445 0.8340295638254563 +-0.6046449656223021 -0.3211530073407549 0.2919864844729801 +-0.5260398634548487 -0.2882785068265378 0.4134094680680197 +-0.6405639949999999 0.04279923535 0.1326702682 +-0.6487042040033901 0.6385958047872833 -0.5417154765977057 +-0.735151619 0.0571216857 -0.378357828 +-0.6022093702194187 0.1268300850569397 0.6684740962317406 +-0.7565366330000001 0.484002307 0.511269033 +-0.2394641001034601 0.1148261485624934 0.5083312902155539 +0.3796661355634049 1.028307531787924 0.3657516905238768 +-0.2381319755461765 1.137959559845314 0.1790739141507273 +-0.7310608030000001 -0.1537852677 -0.08737815190000001 +-0.3523414057774087 0.1193819162242842 0.08345654940137237 +-0.1670513556942967 0.1476639866433246 0.6853975129888606 +0.491527211775953 0.8767230099064776 -0.3576787895052269 +-0.611110507627907 0.04707784208931466 0.03590316184270162 +0.224823909918745 -0.4916598621391116 0.1455174697268168 +0.7890848815 0.7497577075 -0.301863164 +-0.15915007895 0.2857395335 0.1995277255 +0.5879051830173755 -0.1312328181629561 -0.03091650124172288 +-0.4714705453377269 0.8286552115834435 0.5734798976752782 +0.1362085258637122 -0.4950849931870408 -0.1630246768211957 +-0.03354185635108828 1.101203243006822 -0.2620317974150549 +0.03200980229991217 -0.4362439894145285 -0.3267180599675696 +0.2238955145203569 0.3862128453084461 0.1689297420916538 +0.2908262033375297 0.4694237795386023 0.1315231231040461 +0.2686582037274242 0.5069036544252195 0.07984600349034679 +0.3631746113983145 -0.4028950213783935 0.3200490954073999 +0.3911909622643115 -0.2325573810956805 -0.5947209428078721 +0.3804885590027836 0.3221889149999998 -0.8079935059418835 +0.4083943120090749 0.1887834915072822 -0.1620636054355603 +0.4011078815911363 0.07268525434576245 0.7696027767310227 +-0.08033734196299368 1.125044123347636 -0.1874421679119592 +0.3175834201831442 -0.3510320614893416 0.4721979755680141 +-0.5732049810233725 -0.03698288637924527 0.6161135173168364 +0.4360377611558628 0.4150470839575156 -0.7771446956288611 +0.5934586505613839 0.3221889149999998 -0.7020972298353929 +0.5929569495533226 0.3149045639322232 0.2698984488086043 +-0.3210225909479638 -0.03016997607227345 0.4609838855735307 +0.668201941553165 0.6583941036709069 -0.1449730685559288 +-0.7376666775511308 -0.06195993575102453 -0.1697783258309644 +0.4477720190683279 -0.4533468822016663 -0.1044058000961708 +0.6714198478507514 0.7808493122735425 0.4673234194269466 +-0.226003479515528 -0.02596641339387037 -0.7345521078168125 +0.7195024689836664 0.5095871130936205 0.2537232724075318 +0.7428491880458155 0.1324569173680413 -0.3151530471833702 +0.7656443631359708 0.6007185761559954 -0.4980064546313765 +0.5481569544035449 -0.2696858398356596 -0.4745846474572304 +0.7581312955 0.53099218 0.34920831 +-0.001187757123279426 0.4790826521424858 -0.792560053050398 +0.7341587184228582 0.2797682634125023 0.3215258070007447 +-0.4861455826593302 -0.03778932783356562 0.6818463199633092 +0.06547869354999999 -0.4255457815 0.393648967 +0.7828813564764288 0.864139289232903 0.1393702043623115 +-0.626557275662794 -0.3555283688941081 -0.1976506498218573 +0.6317194699999999 0.4659911395 -0.279700078 +-0.6120321164741807 -0.0956055767339937 -0.5401461650276367 +-0.5672965194668056 1.006961918115629 0.2591246056456138 +-0.5923262667509051 0.9638731530546771 -0.2576030333031172 +-0.422417234725205 -0.4145403076368929 0.2786857495587826 +-0.1689984953242323 0.2800651042107679 -0.7888626259987992 +0.6328657865 0.3248944135 -0.2890420185 +0.2068697489114221 0.2725431582060267 -0.7934032481303889 +0.2917061549090935 0.4997025262900997 -0.01239465102149138 +0.3650663955845319 1.057923218602443 -0.3026645544541764 +0.377839852016985 0.2366977478299788 0.6331284685323818 +0.5971030551512994 0.4813489702530399 -0.6538028063370844 +0.5280234911595738 1.046204977256199 -0.199018524776329 +0.605611352146886 -0.01185900625938162 -0.6461764025625136 +0.6081906709061105 0.1392999242488457 -0.6976298363409739 +0.5936224884778267 0.8965765424109324 0.4310721061880765 +0.6247001748070808 0.9591267233355141 -0.3443709153131588 +0.03191817785028314 1.003635378203311 0.4722187010027843 +0.5867117438337976 0.9756406571490535 0.2794402884811847 +0.7394071964043885 0.2470546307365991 0.4904350386969196 +0.7504430274887314 0.2950607589409968 0.612923418189792 +0.7707912755113853 0.5679030566893855 0.4709779433479037 +0.6744152268160057 0.9793918895075621 0.1831520552318593 +-0.2611405077274244 0.1924489632263062 -0.1785318809127656 +-0.2793442594376665 0.1494816108349954 -0.1140298617366095 +0.325498119 -0.164438181 -0.6722256245 +-0.6322233975 0.597211808 0.1018011106 +0.02516927586536039 0.912088341316739 -0.5493319854885629 +-0.693904072 0.547129333 0.1915325375 +-0.7505077124999999 0.1541894703 -0.487261951 +-0.2174244839372807 0.5515983141699703 0.640387887018809 +0.1639050711 -0.035612144385 0.759083152 +0.7428056516336679 -0.03804572692362167 0.3539912629317745 +0.6630168555 -0.3305211815 -0.199784674 +-0.31883657 1.118332325 0.2441151065 +0.2609379706443655 -0.4557204260350181 0.2703587782118858 +-0.662696388019261 -0.03281296550057797 0.4877764474112855 +0.3762930989968171 0.2136085095269253 0.3742264161778107 +-0.10871340236182 0.01778830518081138 0.3995337227586074 +0.4724137007256082 -0.3580689682694919 0.3699704850108812 +0.739346236 -0.15477802795 -0.0890303432 +0.6200146871847843 1.041017373494854 0.10530635978592 +0.6473336515 -0.12406075 0.5202758165 +-0.2851057125 1.13531828 -0.147789508 +0.5287545611966908 -0.1392067845309163 -0.4213354536326884 +-0.6582368983483218 0.7908947914350368 0.4534526806746441 +-0.1430167092176138 0.07490458264061339 -0.6492234686236587 +0.08388244265199932 1.091940286898562 -0.2438784263051275 +-0.767595917 -0.1991657205 -0.2054837495 +-0.16035360275 0.3367227315 0.831303805 +-0.2097786215 0.484371632 0.8086355629999999 +0.5125469269854189 0.6869473599200009 -0.09853734746837725 +-0.2286408078583423 -0.2405279232592276 0.3134059449210754 +0.5044111904391458 0.8526092385213425 0.03781456432454199 +-0.4403551171131159 -0.08802006176784058 -0.4098924838927542 +-0.4658940375121693 0.2490644699980772 0.3876957519798871 +-0.08849663263755718 -0.1738489593599477 -0.2674985592654301 +0.1624682949916841 0.03112968241853449 0.2643152189029817 +0.2909587483869299 -0.2463697785247968 0.2807953124675155 +0.612582424565331 0.8027046362601925 -0.1871508222031324 +-0.08611139305 0.128835335 0.05488930645 +-0.5046578916801988 0.3281994213382713 0.1934801096734574 +0.09674139590000001 0.1567863675 0.1317693185 +0.5806163479922719 0.8131306167241257 0.2374712039043944 +0.5871564384955728 -0.264816246192471 0.4388716008459512 +0.1121718767318561 0.894341730658045 0.5934988779994386 +-0.05064102015207904 -0.1047663836930181 -0.683276641908932 +0.1870898647858736 -0.4631822034085463 -0.2516167829132483 +0.5508634939863065 0.4545417939578261 0.7672300951380143 +0.06452843101832736 -0.03713383443257134 -0.7259526274063929 +-0.6891368437773799 0.05934258363587798 0.1857720127360726 +0.1878269303637121 1.133562631782395 0.08845371227471319 +0.4933907725962033 -0.3097192297119729 0.4673340874488308 +-0.4350025181705176 0.175810975815872 -0.5877709394329067 +-0.171080354158048 -0.04172120227562189 0.1865800253740316 +0.4749035614910188 0.8945857219931469 -0.2057236583594797 +0.6645889484636944 0.4295118545506725 0.2867339149282234 +0.1689495705649597 0.2712275976427702 -0.3743393491188874 + +CELLS 2224 11120 +4 38 187 373 361 +4 208 43 191 525 +4 84 353 254 271 +4 220 578 286 260 +4 222 259 568 244 +4 260 362 281 161 +4 420 145 533 340 +4 166 385 35 343 +4 127 368 598 262 +4 271 279 246 90 +4 476 119 322 162 +4 483 557 195 580 +4 250 268 58 360 +4 368 173 300 298 +4 343 223 197 257 +4 95 100 78 252 +4 161 400 566 124 +4 590 175 323 136 +4 107 292 278 532 +4 230 266 189 279 +4 189 457 279 440 +4 104 287 580 258 +4 171 281 163 309 +4 354 184 410 272 +4 209 378 487 55 +4 400 335 336 314 +4 167 392 275 410 +4 432 256 560 83 +4 341 337 277 97 +4 384 596 194 240 +4 288 179 523 34 +4 472 179 385 523 +4 207 415 354 184 +4 267 363 354 184 +4 305 336 339 420 +4 254 499 392 489 +4 16 482 470 183 +4 173 532 590 323 +4 221 24 186 558 +4 232 254 193 211 +4 63 516 82 215 +4 558 376 185 221 +4 356 108 285 91 +4 312 129 214 486 +4 73 170 87 264 +4 282 342 484 581 +4 357 326 164 273 +4 273 450 206 442 +4 221 369 177 24 +4 3 551 288 375 +4 532 346 291 439 +4 170 244 545 338 +4 165 335 309 210 +4 72 226 539 168 +4 422 195 580 224 +4 414 363 207 278 +4 347 304 257 240 +4 52 65 250 485 +4 445 575 262 344 +4 497 130 133 314 +4 371 133 528 335 +4 211 254 456 235 +4 102 276 241 367 +4 505 387 574 68 +4 445 127 575 374 +4 111 292 330 277 +4 112 210 270 427 +4 450 586 195 138 +4 491 126 368 559 +4 12 558 185 186 +4 22 454 595 34 +4 185 596 183 479 +4 448 211 525 45 +4 70 47 568 351 +4 67 347 223 264 +4 161 591 362 269 +4 270 238 566 135 +4 7 13 525 0 +4 273 206 559 291 +4 213 314 336 420 +4 110 265 599 400 +4 180 331 195 164 +4 14 550 548 181 +4 15 16 507 385 +4 271 90 254 282 +4 15 385 507 1 +4 16 183 401 482 +4 16 401 183 166 +4 352 266 438 215 +4 183 469 36 574 +4 581 152 597 407 +4 430 363 184 414 +4 19 221 469 183 +4 540 585 575 544 +4 44 387 177 505 +4 221 505 177 574 +4 25 4 11 384 +4 12 185 466 365 +4 575 573 597 581 +4 518 425 201 28 +4 265 110 599 87 +4 289 309 113 163 +4 29 198 255 227 +4 30 37 58 390 +4 31 197 401 40 +4 258 171 261 580 +4 104 461 258 557 +4 33 57 172 231 +4 557 494 580 104 +4 22 373 187 595 +4 368 126 504 559 +4 40 197 546 421 +4 40 401 166 197 +4 275 392 120 575 +4 427 165 270 285 +4 48 556 443 477 +4 48 235 443 211 +4 51 352 188 348 +4 37 52 250 248 +4 52 256 432 248 +4 52 37 577 248 +4 52 248 432 485 +4 435 44 201 68 +4 328 306 53 296 +4 306 53 296 480 +4 57 58 78 423 +4 57 423 203 58 +4 57 459 353 423 +4 57 353 203 423 +4 58 250 37 65 +4 58 80 250 65 +4 80 58 250 268 +4 260 281 170 264 +4 260 362 259 170 +4 264 281 170 265 +4 260 161 259 362 +4 167 410 322 99 +4 409 35 402 393 +4 173 175 300 323 +4 62 49 36 384 +4 64 67 582 223 +4 582 347 223 67 +4 64 596 582 83 +4 64 432 596 83 +4 64 479 223 596 +4 65 79 80 250 +4 37 52 65 250 +4 66 456 235 565 +4 66 235 254 396 +4 596 185 505 577 +4 66 254 350 396 +4 343 264 546 223 +4 69 333 552 430 +4 70 527 351 244 +4 101 559 298 280 +4 73 87 89 264 +4 73 89 67 264 +4 74 380 389 272 +4 74 72 168 54 +4 75 490 304 589 +4 325 103 279 169 +4 403 82 215 419 +4 77 249 333 280 +4 79 80 250 98 +4 80 95 78 268 +4 81 161 391 356 +4 566 535 335 339 +4 81 259 588 286 +4 81 161 259 391 +4 245 298 280 101 +4 84 266 338 353 +4 84 338 266 106 +4 90 489 254 569 +4 356 285 161 391 +4 95 100 301 299 +4 252 301 100 84 +4 414 363 184 207 +4 195 309 312 164 +4 102 362 276 591 +4 103 279 230 457 +4 207 323 532 298 +4 302 162 174 275 +4 108 269 81 161 +4 110 113 289 497 +4 110 130 599 106 +4 115 424 207 436 +4 148 214 398 554 +4 118 372 303 323 +4 118 323 207 372 +4 118 119 394 303 +4 566 153 345 146 +4 220 286 59 50 +4 74 539 380 272 +4 393 338 438 361 +4 129 311 309 113 +4 131 130 440 342 +4 131 440 573 342 +4 136 175 394 139 +4 36 11 411 384 +4 123 325 282 90 +4 359 242 195 117 +4 587 119 303 410 +4 140 428 344 585 +4 141 156 486 562 +4 141 164 486 156 +4 309 164 486 312 +4 144 145 420 528 +4 133 335 486 311 +4 148 206 214 554 +4 453 153 566 146 +4 305 420 371 144 +4 135 335 210 331 +4 447 124 566 535 +4 157 426 575 544 +4 157 428 544 575 +4 158 262 175 520 +4 13 397 193 444 +4 159 581 484 506 +4 302 300 174 162 +4 74 389 55 272 +4 297 174 302 300 +4 353 438 352 266 +4 33 5 172 196 +4 171 228 366 210 +4 209 199 487 39 +4 201 44 505 68 +4 397 13 193 231 +4 96 207 372 118 +4 120 275 593 392 +4 210 112 366 283 +4 210 366 165 283 +4 212 112 366 228 +4 212 488 366 112 +4 496 213 529 308 +4 93 461 274 194 +4 483 117 195 557 +4 214 126 312 273 +4 218 125 308 336 +4 270 165 161 285 +4 116 161 285 270 +4 287 580 273 224 +4 422 494 195 561 +4 293 560 256 88 +4 293 88 263 560 +4 19 469 221 24 +4 209 55 253 168 +4 561 138 195 586 +4 442 434 224 586 +4 206 291 273 132 +4 442 132 224 434 +4 410 167 226 99 +4 226 99 539 410 +4 109 230 317 121 +4 468 19 183 234 +4 6 198 577 255 +4 217 336 420 503 +4 164 326 398 214 +4 309 486 129 312 +4 96 430 414 278 +4 201 458 28 425 +4 218 535 536 336 +4 238 566 345 146 +4 566 238 514 146 +4 4 384 478 11 +4 4 384 521 570 +4 11 411 384 16 +4 332 293 263 68 +4 3 551 472 288 +4 242 138 180 195 +4 138 195 242 561 +4 156 486 154 455 +4 5 13 231 191 +4 471 191 172 27 +4 271 82 352 71 +4 13 231 191 193 +4 119 410 587 99 +4 79 245 250 248 +4 248 280 245 267 +4 219 184 414 430 +4 542 441 151 173 +4 141 164 214 486 +4 469 369 574 221 +4 221 177 369 574 +4 44 24 505 177 +4 384 197 166 183 +4 559 173 329 206 +4 44 369 24 177 +4 1 576 385 166 +4 583 190 577 37 +4 187 216 595 361 +4 361 188 353 352 +4 27 172 188 191 +4 231 172 208 203 +4 261 580 171 579 +4 231 203 208 193 +4 30 390 203 181 +4 192 209 181 168 +4 192 181 204 190 +4 23 452 181 443 +4 190 255 577 204 +4 190 204 577 37 +4 595 222 225 361 +4 576 343 216 385 +4 576 222 290 595 +4 255 227 204 552 +4 276 189 386 266 +4 313 107 399 532 +4 576 385 166 343 +4 40 166 35 546 +4 197 546 223 343 +4 216 393 402 35 +4 595 225 222 290 +4 201 53 480 296 +4 577 475 248 198 +4 188 191 172 208 +4 204 229 227 577 +4 204 227 229 552 +4 203 58 232 390 +4 390 360 232 181 +4 190 204 390 181 +4 190 37 390 204 +4 208 525 193 254 +4 181 209 204 360 +4 335 339 420 371 +4 232 235 211 443 +4 99 322 119 410 +4 449 388 240 384 +4 80 250 98 268 +4 170 276 599 362 +4 244 276 241 386 +4 276 362 213 189 +4 213 336 314 362 +4 222 545 343 264 +4 343 347 264 223 +4 223 596 347 582 +4 505 577 475 560 +4 201 480 53 293 +4 393 338 244 438 +4 475 480 296 201 +4 475 201 293 480 +4 475 248 198 256 +4 225 438 361 393 +4 225 351 361 438 +4 251 249 248 267 +4 227 229 552 251 +4 83 579 584 101 +4 58 250 360 390 +4 41 384 59 166 +4 67 264 546 73 +4 333 430 363 552 +4 229 552 267 184 +4 265 281 161 289 +4 281 289 165 161 +4 171 312 309 163 +4 187 595 216 179 +4 179 595 216 576 +4 576 222 595 216 +4 194 461 274 258 +4 257 258 274 171 +4 363 430 280 278 +4 220 343 578 260 +4 220 260 259 222 +4 257 223 596 347 +4 271 282 440 279 +4 568 591 259 588 +4 222 170 260 259 +4 222 260 170 264 +4 568 259 222 588 +4 251 363 552 333 +4 251 333 249 363 +4 333 363 280 249 +4 333 280 363 430 +4 385 576 1 523 +4 472 385 1 523 +4 48 443 556 284 +4 356 81 286 391 +4 229 354 250 253 +4 194 461 233 93 +4 574 519 76 233 +4 252 254 295 392 +4 451 82 352 51 +4 287 291 273 579 +4 35 216 393 343 +4 536 336 217 503 +4 148 294 214 206 +4 490 391 240 304 +4 519 104 461 258 +4 240 578 304 391 +4 257 194 258 596 +4 140 262 585 344 +4 362 170 281 265 +4 260 578 264 343 +4 260 578 281 264 +4 258 596 277 261 +4 170 259 591 362 +4 264 347 281 265 +4 347 86 163 89 +4 560 292 256 88 +4 81 286 391 259 +4 388 194 240 384 +4 304 257 274 171 +4 352 215 271 266 +4 576 290 222 220 +4 84 271 254 301 +4 200 384 240 59 +4 200 49 449 384 +4 78 252 100 84 +4 184 92 354 587 +4 254 301 392 252 +4 84 301 100 440 +4 391 161 260 281 +4 272 410 302 295 +4 140 511 158 262 +4 391 281 304 366 +4 557 104 580 258 +4 149 535 339 305 +4 149 305 217 536 +4 258 287 261 277 +4 281 289 309 165 +4 307 527 386 85 +4 85 241 386 307 +4 262 173 598 143 +4 511 262 598 143 +4 270 566 165 135 +4 277 579 287 261 +4 476 275 540 537 +4 476 162 275 537 +4 174 302 299 493 +4 174 299 302 575 +4 125 213 496 308 +4 48 211 417 310 +4 41 384 200 59 +4 386 317 109 403 +4 599 276 266 189 +4 267 363 280 298 +4 267 280 245 298 +4 363 298 278 280 +4 448 23 193 211 +4 43 45 525 254 +4 574 205 36 62 +4 92 354 587 372 +4 233 76 574 315 +4 316 315 574 76 +4 316 574 68 76 +4 160 318 182 513 +4 318 282 160 182 +4 160 282 342 484 +4 365 12 6 460 +4 320 279 103 169 +4 378 32 168 452 +4 133 141 335 153 +4 133 486 335 141 +4 298 323 532 173 +4 172 196 471 361 +4 56 571 227 333 +4 182 317 533 318 +4 113 311 309 289 +4 303 323 162 394 +4 118 394 323 303 +4 107 278 399 532 +4 420 213 314 317 +4 567 321 192 452 +4 193 254 423 208 +4 193 423 254 232 +4 122 132 224 330 +4 230 189 317 457 +4 276 386 189 213 +4 266 189 386 403 +4 85 109 386 529 +4 297 493 302 174 +4 278 292 280 532 +4 516 386 63 85 +4 516 109 386 85 +4 189 440 130 340 +4 189 130 440 106 +4 386 403 516 266 +4 309 113 163 324 +4 334 587 119 303 +4 301 302 299 575 +4 372 118 303 119 +4 301 299 440 575 +4 272 539 380 410 +4 91 356 59 391 +4 129 148 294 214 +4 338 170 599 87 +4 117 195 494 242 +4 197 223 596 257 +4 504 143 598 173 +4 440 597 282 301 +4 282 440 340 342 +4 237 577 583 190 +4 299 440 575 573 +4 440 575 597 301 +4 531 327 239 301 +4 575 134 327 392 +4 575 374 573 344 +4 486 141 562 335 +4 323 175 300 162 +4 555 335 154 345 +4 569 301 392 254 +4 239 569 301 392 +4 346 224 291 132 +4 439 291 132 346 +4 237 460 26 577 +4 583 237 26 577 +4 253 272 354 250 +4 250 268 354 98 +4 579 559 273 312 +4 229 267 250 354 +4 249 267 280 248 +4 106 599 266 189 +4 314 317 340 420 +4 40 166 247 35 +4 166 384 343 197 +4 251 229 552 267 +4 229 184 267 354 +4 271 301 440 282 +4 305 217 536 336 +4 172 208 203 353 +4 476 119 162 537 +4 349 588 286 81 +4 350 392 418 94 +4 312 273 126 559 +4 246 61 71 254 +4 455 555 486 154 +4 303 162 119 394 +4 351 438 244 386 +4 41 166 59 576 +4 221 574 183 505 +4 27 172 361 188 +4 188 208 172 353 +4 585 520 175 262 +4 12 376 185 558 +4 364 365 186 12 +4 18 6 255 29 +4 222 393 361 216 +4 352 63 215 438 +4 63 438 386 516 +4 24 186 364 501 +4 25 384 11 36 +4 25 41 521 384 +4 29 56 377 227 +4 33 402 172 57 +4 93 233 194 355 +4 39 192 21 487 +4 39 56 29 552 +4 356 108 161 285 +4 68 76 574 341 +4 156 243 357 164 +4 295 226 168 272 +4 137 210 359 331 +4 210 359 508 137 +4 49 449 384 62 +4 400 535 336 335 +4 91 116 285 413 +4 232 295 360 252 +4 92 587 334 372 +4 113 129 311 133 +4 122 434 224 132 +4 308 213 529 102 +4 132 442 206 564 +4 132 206 439 150 +4 256 249 280 248 +4 363 251 552 267 +4 140 428 585 520 +4 251 363 249 267 +4 363 267 280 249 +4 75 304 490 240 +4 578 347 281 264 +4 155 509 585 175 +4 112 589 366 283 +4 391 283 281 366 +4 206 148 294 541 +4 175 543 158 139 +4 236 490 59 240 +4 236 200 240 59 +4 537 275 540 585 +4 58 203 57 30 +4 207 298 354 372 +4 574 519 233 194 +4 194 233 574 315 +4 315 194 62 574 +4 415 354 92 372 +4 306 480 296 249 +4 492 127 174 368 +4 94 392 593 167 +4 179 595 576 290 +4 219 370 552 69 +4 371 512 305 144 +4 95 301 252 268 +4 239 531 301 282 +4 57 78 459 423 +4 140 374 445 344 +4 205 36 526 574 +4 433 376 185 12 +4 376 19 221 24 +4 135 165 270 210 +4 135 210 270 112 +4 380 92 184 587 +4 157 381 404 575 +4 157 381 575 426 +4 187 22 595 179 +4 595 290 454 47 +4 79 250 245 98 +4 27 43 188 51 +4 239 282 301 569 +4 505 68 574 263 +4 293 68 505 263 +4 505 560 293 263 +4 485 250 248 79 +4 281 161 165 285 +4 207 298 532 278 +4 207 323 424 532 +4 504 559 294 206 +4 135 335 165 210 +4 273 326 164 214 +4 398 326 554 214 +4 273 554 214 206 +4 390 204 360 181 +4 560 596 574 505 +4 93 274 304 194 +4 194 304 257 274 +4 191 525 193 208 +4 400 497 314 110 +4 110 497 289 400 +4 392 499 350 418 +4 189 314 317 340 +4 189 314 362 213 +4 409 383 393 60 +4 396 66 235 395 +4 565 235 66 48 +4 471 5 172 191 +4 6 473 365 198 +4 444 548 181 14 +4 77 96 278 430 +4 192 39 255 204 +4 402 60 353 57 +4 164 156 326 357 +4 142 528 145 144 +4 513 142 318 145 +4 399 128 532 379 +4 128 498 399 532 +4 199 219 552 55 +4 13 191 525 193 +4 247 401 166 40 +4 439 329 291 532 +4 55 199 487 209 +4 495 161 116 566 +4 495 161 566 124 +4 124 362 400 535 +4 124 362 535 218 +4 402 361 353 60 +4 109 230 403 317 +4 103 279 320 419 +4 230 419 215 279 +4 230 103 419 279 +4 75 240 388 93 +4 388 93 240 194 +4 327 597 534 575 +4 70 527 47 351 +4 178 216 187 196 +4 90 408 254 489 +4 155 585 520 175 +4 158 155 520 175 +4 402 409 393 60 +4 325 169 282 90 +4 519 461 194 258 +4 454 290 50 510 +4 545 338 73 170 +4 151 175 173 590 +4 590 441 173 151 +4 153 335 562 141 +4 304 366 274 212 +4 108 547 269 161 +4 81 161 591 259 +4 259 591 362 161 +4 543 139 175 151 +4 492 493 297 174 +4 471 5 9 196 +4 417 284 443 48 +4 48 417 211 443 +4 371 512 339 305 +4 371 512 153 339 +4 87 89 265 110 +4 466 185 26 577 +4 460 466 577 365 +4 305 217 336 420 +4 503 420 213 336 +4 90 282 569 254 +4 569 282 301 254 +4 503 125 336 213 +4 536 125 336 503 +4 130 522 528 340 +4 130 133 314 528 +4 287 224 273 291 +4 346 287 291 224 +4 330 224 287 346 +4 76 341 519 574 +4 231 33 5 172 +4 328 377 227 296 +4 25 4 384 521 +4 120 563 575 134 +4 542 173 329 441 +4 541 542 329 150 +4 173 175 323 590 +4 379 128 532 590 +4 93 304 274 212 +4 366 304 391 589 +4 421 223 546 67 +4 421 64 223 67 +4 594 434 224 122 +4 135 335 566 165 +4 238 135 335 566 +4 244 338 170 438 +4 211 48 565 310 +4 211 235 565 48 +4 527 386 85 63 +4 527 351 244 386 +4 84 423 254 353 +4 216 576 385 179 +4 203 423 208 193 +4 203 193 232 423 +4 435 53 201 425 +4 44 435 201 518 +4 422 287 500 122 +4 228 508 210 359 +4 16 411 384 183 +4 210 228 359 195 +4 272 302 268 252 +4 184 587 410 380 +4 274 483 171 258 +4 93 274 461 483 +4 274 483 258 461 +4 366 228 274 212 +4 93 212 274 483 +4 428 157 544 520 +4 79 101 245 256 +4 256 280 101 245 +4 248 256 245 280 +4 506 344 374 140 +4 244 259 591 170 +4 510 568 222 588 +4 222 259 244 170 +4 431 534 597 538 +4 445 262 511 140 +4 433 12 185 592 +4 86 163 113 105 +4 307 527 244 386 +4 243 331 455 137 +4 70 568 47 510 +4 454 290 510 47 +4 354 587 410 184 +4 97 287 277 330 +4 553 97 277 111 +4 97 330 277 111 +4 53 435 201 293 +4 436 207 96 118 +4 361 60 338 353 +4 232 295 443 168 +4 353 271 266 352 +4 596 579 277 261 +4 410 162 119 303 +4 181 193 23 443 +4 264 545 546 73 +4 232 211 193 443 +4 44 68 387 505 +4 484 160 437 538 +4 444 181 193 0 +4 215 230 279 266 +4 90 408 246 254 +4 329 206 150 439 +4 439 206 291 329 +4 140 445 262 344 +4 318 317 340 282 +4 533 318 317 340 +4 256 280 292 101 +4 185 221 183 505 +4 577 365 198 6 +4 390 250 360 229 +4 390 229 37 250 +4 181 209 360 168 +4 360 253 250 272 +4 272 354 268 302 +4 250 272 354 268 +4 410 322 162 275 +4 410 119 162 322 +4 174 585 262 575 +4 438 266 353 338 +4 257 261 596 258 +4 304 171 274 366 +4 281 165 366 283 +4 171 281 309 165 +4 183 574 221 469 +4 468 36 183 469 +4 255 227 577 204 +4 566 153 335 345 +4 510 222 225 290 +4 382 107 313 292 +4 449 75 240 388 +4 449 236 240 75 +4 456 499 254 489 +4 220 286 50 349 +4 349 588 220 286 +4 147 450 206 554 +4 450 147 206 442 +4 147 450 554 326 +4 352 215 63 82 +4 30 33 231 57 +4 243 180 164 331 +4 365 198 186 577 +4 164 273 214 312 +4 71 82 352 451 +4 160 318 142 342 +4 149 339 535 453 +4 43 188 254 208 +4 43 27 191 176 +4 379 424 590 532 +4 66 254 235 456 +4 457 282 317 121 +4 457 202 282 121 +4 7 191 5 471 +4 289 165 400 335 +4 289 400 497 335 +4 216 179 385 472 +4 532 424 590 323 +4 40 479 223 64 +4 40 64 223 421 +4 503 502 317 533 +4 320 271 71 82 +4 82 271 352 215 +4 467 107 382 278 +4 96 467 278 107 +4 15 35 385 216 +4 385 35 15 247 +4 539 587 380 410 +4 84 60 338 87 +4 84 60 353 338 +4 96 278 115 107 +4 529 213 386 241 +4 216 405 472 15 +4 474 6 255 18 +4 382 406 467 280 +4 366 171 274 228 +4 192 190 2 319 +4 378 192 452 168 +4 589 490 304 391 +4 293 256 480 406 +4 538 123 437 481 +4 86 171 163 579 +4 247 166 385 35 +4 374 506 573 344 +4 297 492 174 368 +4 504 173 598 368 +4 348 27 188 51 +4 219 55 389 184 +4 65 250 485 79 +4 293 256 475 480 +4 427 210 165 283 +4 112 210 427 283 +4 486 164 331 243 +4 367 241 307 244 +4 198 201 475 296 +4 426 134 575 563 +4 113 324 309 129 +4 519 337 104 258 +4 445 374 575 344 +4 197 596 384 240 +4 194 596 257 240 +4 574 596 560 277 +4 588 259 222 220 +4 286 588 220 259 +4 320 279 271 419 +4 419 279 271 215 +4 343 222 393 545 +4 297 174 300 368 +4 280 292 559 532 +4 37 58 390 250 +4 204 390 229 37 +4 391 161 281 285 +4 107 399 278 115 +4 115 278 207 379 +4 300 372 298 323 +4 207 323 298 372 +4 389 55 272 184 +4 531 597 282 481 +4 501 186 364 28 +4 28 186 518 501 +4 316 205 574 315 +4 86 163 171 347 +4 505 475 201 293 +4 505 475 293 560 +4 507 478 166 16 +4 590 441 532 173 +4 77 278 280 430 +4 352 361 188 348 +4 463 592 470 185 +4 306 293 480 406 +4 543 158 515 175 +4 158 175 262 515 +4 511 158 262 515 +4 319 190 2 358 +4 206 450 273 554 +4 398 156 326 164 +4 450 273 554 326 +4 356 286 59 391 +4 129 133 141 486 +4 250 245 267 248 +4 250 267 245 98 +4 152 534 538 597 +4 86 579 163 105 +4 59 286 578 391 +4 524 32 452 168 +4 524 32 168 284 +4 197 546 343 166 +4 257 258 171 261 +4 109 496 502 213 +4 502 109 213 317 +4 144 371 528 420 +4 195 309 331 210 +4 559 329 173 532 +4 384 197 183 596 +4 207 363 354 298 +4 355 194 388 62 +4 443 23 417 211 +4 359 180 195 242 +4 97 263 416 332 +4 216 179 472 551 +4 207 118 424 323 +4 325 282 279 457 +4 325 202 282 457 +4 547 161 495 124 +4 136 151 175 139 +4 136 590 175 151 +4 341 416 97 263 +4 574 341 277 263 +4 549 279 320 169 +4 549 246 279 169 +4 240 304 257 194 +4 399 498 313 532 +4 535 336 305 536 +4 168 272 55 253 +4 550 20 190 358 +4 282 202 182 121 +4 317 282 182 121 +4 187 10 551 405 +4 68 341 574 263 +4 4 384 570 478 +4 384 16 166 478 +4 210 228 195 171 +4 18 29 255 39 +4 29 552 255 39 +4 2 567 192 17 +4 319 2 192 17 +4 155 540 544 585 +4 368 174 300 173 +4 555 335 486 154 +4 117 195 557 494 +4 524 443 452 23 +4 524 168 452 443 +4 593 114 392 94 +4 189 213 317 314 +4 189 386 317 213 +4 362 189 599 314 +4 362 599 400 314 +4 296 227 256 198 +4 523 576 1 42 +4 556 168 54 32 +4 396 392 254 350 +4 403 189 317 230 +4 186 365 185 12 +4 575 381 581 407 +4 42 220 576 59 +4 541 173 542 151 +4 500 122 287 337 +4 196 35 402 33 +4 179 290 523 34 +4 555 135 331 335 +4 555 135 335 238 +4 174 262 175 173 +4 174 175 300 173 +4 293 560 475 256 +4 471 7 191 176 +4 566 453 535 339 +4 304 281 171 366 +4 314 528 420 340 +4 113 289 163 89 +4 113 163 86 89 +4 110 113 89 289 +4 179 187 551 216 +4 216 187 551 405 +4 187 216 178 405 +4 182 318 533 513 +4 52 250 248 485 +4 81 588 259 591 +4 459 353 84 60 +4 385 179 576 523 +4 581 152 538 597 +4 19 376 221 433 +4 546 264 343 545 +4 140 404 344 428 +4 561 195 242 494 +4 224 422 195 561 +4 287 422 500 580 +4 562 156 486 154 +4 335 562 154 153 +4 486 562 154 335 +4 404 575 581 344 +4 174 575 262 127 +4 573 575 299 127 +4 187 22 179 375 +4 9 465 187 22 +4 22 10 187 9 +4 450 357 273 326 +4 442 586 224 273 +4 408 61 246 254 +4 366 304 589 488 +4 45 254 61 456 +4 45 61 254 43 +4 579 101 559 105 +4 216 393 361 402 +4 347 163 281 289 +4 295 226 72 168 +4 268 252 360 272 +4 88 97 263 277 +4 155 537 540 585 +4 63 351 361 373 +4 24 505 186 44 +4 186 44 505 201 +4 518 201 44 186 +4 518 186 44 501 +4 501 186 44 24 +4 572 552 56 370 +4 435 68 201 293 +4 201 68 505 293 +4 240 93 304 194 +4 230 189 457 279 +4 323 394 118 136 +4 295 72 396 235 +4 94 396 392 295 +4 564 442 206 147 +4 564 147 206 150 +4 599 265 362 400 +4 30 58 203 390 +4 504 368 598 127 +4 45 565 211 456 +4 163 113 105 324 +4 353 172 188 361 +4 360 272 168 253 +4 280 382 292 278 +4 88 382 553 292 +4 553 382 313 292 +4 355 93 388 194 +4 573 506 342 581 +4 540 544 575 563 +4 288 179 34 375 +4 495 566 447 124 +4 27 471 191 176 +4 185 365 186 577 +4 558 24 186 364 +4 558 376 221 24 +4 400 566 535 335 +4 400 165 566 335 +4 567 21 2 192 +4 57 353 459 60 +4 221 177 505 24 +4 568 244 351 225 +4 140 520 585 262 +4 253 55 184 272 +4 531 123 282 90 +4 531 481 282 123 +4 531 431 481 123 +4 174 162 175 585 +4 270 165 566 161 +4 116 566 161 270 +4 399 379 278 115 +4 22 595 454 47 +4 0 23 193 448 +4 227 571 296 249 +4 145 340 420 528 +4 460 6 577 237 +4 237 6 577 255 +4 166 384 59 343 +4 166 343 59 576 +4 41 521 166 576 +4 41 521 384 166 +4 504 294 541 206 +4 541 173 206 329 +4 532 111 292 346 +4 291 292 532 559 +4 346 532 291 292 +4 329 559 206 291 +4 472 288 179 523 +4 270 238 514 566 +4 394 323 162 175 +4 394 136 323 175 +4 20 190 37 30 +4 492 368 297 491 +4 492 368 491 126 +4 559 491 101 297 +4 77 467 278 96 +4 234 411 19 183 +4 96 115 278 207 +4 8 183 470 221 +4 221 592 470 8 +4 426 134 407 575 +4 317 282 318 182 +4 571 77 249 333 +4 571 77 306 249 +4 200 384 449 240 +4 244 591 367 276 +4 572 333 552 69 +4 552 370 572 69 +4 43 188 51 451 +4 449 388 384 62 +4 122 224 287 330 +4 196 178 216 35 +4 393 402 60 361 +4 108 161 285 116 +4 87 106 110 599 +4 415 96 207 372 +4 195 309 164 331 +4 195 171 309 210 +4 309 331 486 164 +4 497 335 400 314 +4 37 229 248 250 +4 353 188 254 352 +4 58 252 423 232 +4 209 229 360 253 +4 84 78 252 423 +4 58 268 78 252 +4 58 360 252 232 +4 203 390 232 181 +4 574 596 277 258 +4 438 386 276 244 +4 213 420 503 317 +4 481 581 597 282 +4 481 484 581 282 +4 237 474 6 255 +4 298 559 173 532 +4 297 559 368 298 +4 204 229 360 209 +4 204 360 229 390 +4 568 222 225 510 +4 254 271 353 352 +4 234 11 411 36 +4 466 592 185 12 +4 365 460 466 12 +4 59 240 391 578 +4 59 220 578 286 +4 343 347 240 578 +4 596 347 261 257 +4 347 261 171 86 +4 10 187 178 405 +4 266 440 279 271 +4 268 252 302 301 +4 20 358 237 190 +4 573 440 581 342 +4 426 563 575 544 +4 576 59 220 343 +4 40 197 166 546 +4 21 321 192 567 +4 443 295 232 235 +4 192 168 181 452 +4 10 178 187 196 +4 595 225 351 361 +4 290 225 47 595 +4 187 465 361 38 +4 384 240 59 343 +4 479 197 31 40 +4 574 194 62 384 +4 250 268 360 272 +4 84 271 301 440 +4 208 254 423 353 +4 203 423 353 208 +4 194 388 62 384 +4 369 469 574 46 +4 438 266 599 276 +4 591 170 362 276 +4 244 367 241 276 +4 451 352 188 51 +4 49 200 41 384 +4 262 515 173 143 +4 151 143 173 515 +4 46 205 574 316 +4 63 38 361 348 +4 254 66 350 499 +4 577 52 475 560 +4 456 66 254 499 +4 338 545 73 383 +4 552 39 56 370 +4 510 70 568 588 +4 588 70 568 591 +4 295 302 272 252 +4 560 263 277 88 +4 579 287 291 292 +4 171 165 309 210 +4 347 171 281 163 +4 16 183 384 166 +4 212 75 304 488 +4 443 181 193 232 +4 50 510 220 349 +4 577 229 227 248 +4 596 574 194 258 +4 170 599 276 438 +4 529 85 241 386 +4 167 410 295 392 +4 94 167 295 392 +4 98 297 302 354 +4 354 302 300 297 +4 550 190 548 181 +4 550 190 181 319 +4 490 391 412 91 +4 101 292 559 280 +4 188 254 352 71 +4 71 271 254 352 +4 343 257 240 347 +4 578 347 304 281 +4 257 304 347 171 +4 493 299 100 95 +4 98 491 297 101 +4 98 101 297 245 +4 98 492 297 491 +4 70 244 591 367 +4 70 367 307 244 +4 269 102 591 362 +4 252 254 301 84 +4 391 285 281 283 +4 317 440 340 282 +4 300 298 173 323 +4 335 535 336 339 +4 133 153 335 371 +4 153 335 371 339 +4 580 500 494 422 +4 130 314 497 110 +4 283 112 589 413 +4 283 112 413 427 +4 362 281 161 265 +4 103 325 279 457 +4 207 532 379 278 +4 213 308 362 102 +4 336 125 308 213 +4 470 183 31 185 +4 506 131 342 429 +4 573 131 342 506 +4 224 195 586 561 +4 450 195 273 357 +4 537 139 119 162 +4 158 139 509 175 +4 127 262 598 445 +4 145 318 533 340 +4 447 146 566 514 +4 453 146 566 447 +4 506 342 581 484 +4 105 579 312 559 +4 17 452 181 23 +4 335 339 336 420 +4 318 342 340 142 +4 159 446 506 484 +4 157 404 428 575 +4 596 183 505 185 +4 98 297 493 302 +4 582 596 86 83 +4 224 594 561 586 +4 586 594 561 138 +4 196 5 9 10 +4 544 428 585 575 +4 428 344 585 575 +4 428 404 344 575 +4 350 396 392 94 +4 199 219 370 552 +4 255 474 2 358 +4 255 2 190 358 +4 255 237 474 358 +4 471 9 187 196 +4 132 442 224 273 +4 442 206 273 132 +4 224 195 580 273 +4 209 192 39 487 +4 431 538 481 123 +4 99 539 410 587 +4 57 203 172 231 +4 57 353 172 203 +4 194 519 233 461 +4 61 71 254 43 +4 191 188 43 208 +4 462 43 191 176 +4 448 525 193 0 +4 7 191 525 13 +4 462 7 191 525 +4 42 59 576 41 +4 241 244 386 307 +4 335 339 153 566 +4 72 395 235 477 +4 72 396 235 395 +4 55 184 219 552 +4 401 183 166 197 +4 142 160 342 484 +4 513 160 318 142 +4 77 280 278 467 +4 564 150 206 132 +4 70 527 244 307 +4 47 568 351 225 +4 122 330 287 97 +4 220 42 290 50 +4 537 139 162 509 +4 305 420 339 371 +4 477 235 443 48 +4 349 510 220 588 +4 72 226 295 94 +4 132 439 206 291 +4 532 291 559 329 +4 589 391 412 490 +4 440 100 106 131 +4 414 92 415 184 +4 207 96 415 414 +4 517 504 294 541 +4 31 52 185 479 +4 479 596 64 52 +4 479 596 52 185 +4 575 381 404 581 +4 132 273 224 291 +4 386 109 317 213 +4 97 263 332 88 +4 550 20 548 190 +4 133 314 335 497 +4 524 284 443 417 +4 524 168 443 284 +4 213 102 276 241 +4 529 102 213 241 +4 171 228 195 483 +4 124 161 362 269 +4 201 458 425 53 +4 201 377 458 53 +4 213 386 241 276 +4 557 494 195 580 +4 372 303 354 587 +4 372 587 334 303 +4 518 435 201 425 +4 516 403 215 266 +4 63 215 438 516 +4 368 127 504 126 +4 64 223 582 596 +4 582 347 86 596 +4 8 221 592 433 +4 8 19 221 433 +4 19 221 183 8 +4 105 579 101 584 +4 83 579 596 86 +4 156 486 455 243 +4 334 372 303 119 +4 577 505 475 198 +4 198 475 201 505 +4 120 275 540 476 +4 13 193 525 0 +4 586 450 273 442 +4 138 195 450 357 +4 174 175 162 300 +4 165 566 161 400 +4 124 362 161 400 +4 336 314 362 400 +4 431 481 597 531 +4 82 403 215 516 +4 531 327 301 597 +4 411 8 183 16 +4 120 575 392 134 +4 549 71 320 271 +4 127 131 573 374 +4 356 81 161 108 +4 294 504 126 559 +4 282 160 182 202 +4 149 535 305 536 +4 243 180 357 164 +4 145 305 144 420 +4 106 266 84 440 +4 106 100 440 84 +4 590 323 424 136 +4 585 509 537 162 +4 585 175 509 162 +4 119 162 139 394 +4 495 108 116 161 +4 418 569 392 489 +4 399 532 278 379 +4 433 376 221 185 +4 394 175 162 139 +4 363 184 207 354 +4 104 258 337 287 +4 500 337 287 104 +4 226 410 295 167 +4 94 226 295 167 +4 299 100 530 493 +4 32 168 54 378 +4 380 389 184 92 +4 219 184 389 92 +4 343 216 393 222 +4 74 55 168 272 +4 74 539 272 168 +4 253 272 184 354 +4 417 211 23 310 +4 393 545 338 383 +4 309 324 163 312 +4 324 312 309 129 +4 158 520 140 262 +4 17 181 319 14 +4 599 106 266 338 +4 45 211 254 456 +4 310 211 23 45 +4 211 310 565 45 +4 448 23 211 45 +4 265 289 161 400 +4 403 419 215 230 +4 392 254 350 499 +4 507 16 166 385 +4 74 72 539 168 +4 444 181 0 14 +4 238 335 555 345 +4 176 7 191 462 +4 484 160 538 152 +4 196 9 187 10 +4 333 77 280 430 +4 19 411 8 183 +4 12 558 186 364 +4 385 247 15 16 +4 357 180 195 164 +4 456 254 408 489 +4 456 254 61 408 +4 320 419 271 82 +4 82 419 271 215 +4 155 537 585 509 +4 417 23 443 524 +4 171 228 483 274 +4 41 25 49 384 +4 465 464 471 27 +4 214 294 273 206 +4 142 340 145 528 +4 473 458 198 6 +4 28 364 473 186 +4 28 201 518 186 +4 63 361 351 438 +4 21 321 487 192 +4 187 216 361 196 +4 22 465 187 38 +4 237 20 583 26 +4 26 460 237 20 +4 348 38 361 27 +4 46 574 369 177 +4 316 46 387 574 +4 397 548 181 444 +4 385 16 166 247 +4 271 246 254 90 +4 168 226 539 272 +4 179 595 290 34 +4 46 369 44 177 +4 22 38 187 373 +4 361 373 351 595 +4 174 585 175 262 +4 298 559 368 173 +4 297 368 300 298 +4 302 410 162 275 +4 162 585 174 275 +4 281 289 163 309 +4 377 198 227 296 +4 377 198 296 201 +4 198 377 458 201 +4 227 29 198 377 +4 106 338 599 87 +4 84 338 106 87 +4 477 168 295 72 +4 556 168 443 477 +4 94 396 295 72 +4 192 168 378 209 +4 424 207 436 118 +4 179 595 34 22 +4 36 183 384 411 +4 21 18 255 39 +4 133 528 335 314 +4 279 549 271 246 +4 279 549 320 271 +4 431 538 597 481 +4 69 219 430 552 +4 93 75 304 212 +4 304 75 589 488 +4 30 548 190 181 +4 53 293 480 306 +4 467 77 280 406 +4 545 393 343 35 +4 325 123 282 202 +4 446 429 342 142 +4 446 506 342 429 +4 446 142 342 484 +4 484 506 342 446 +4 433 221 592 185 +4 71 246 271 549 +4 413 91 412 391 +4 277 553 292 88 +4 277 560 88 292 +4 88 382 292 280 +4 484 437 481 538 +4 428 520 544 585 +4 191 43 188 27 +4 566 447 514 495 +4 122 97 287 337 +4 159 506 344 581 +4 159 404 581 344 +4 140 159 344 404 +4 140 159 506 344 +4 413 589 391 412 +4 500 104 580 494 +4 495 161 547 108 +4 262 175 173 515 +4 151 515 173 175 +4 543 515 151 175 +4 30 181 397 548 +4 181 444 193 397 +4 330 346 287 292 +4 482 183 401 31 +4 31 197 183 401 +4 366 488 589 112 +4 133 497 311 113 +4 106 189 266 440 +4 594 224 422 122 +4 106 130 599 189 +4 476 275 322 120 +4 547 161 124 269 +4 551 10 187 375 +4 422 224 287 122 +4 124 102 362 308 +4 438 276 170 244 +4 502 125 213 496 +4 248 250 229 267 +4 439 329 532 128 +4 374 131 573 506 +4 256 88 292 280 +4 260 170 281 362 +4 238 335 345 566 +4 50 290 220 510 +4 511 515 262 143 +4 40 479 197 223 +4 479 596 197 223 +4 424 323 118 136 +4 71 254 271 246 +4 150 206 554 147 +4 305 535 339 336 +4 381 152 159 581 +4 381 152 581 407 +4 520 157 544 155 +4 544 520 155 585 +4 285 165 281 283 +4 576 343 220 222 +4 457 282 440 317 +4 19 183 469 468 +4 486 311 309 129 +4 26 466 577 460 +4 129 486 311 133 +4 466 185 592 463 +4 466 26 185 463 +4 473 198 186 365 +4 473 364 365 186 +4 185 577 466 365 +4 527 351 63 47 +4 63 351 373 47 +4 187 464 9 471 +4 187 464 465 9 +4 187 471 361 465 +4 187 471 465 464 +4 326 554 214 273 +4 331 555 486 455 +4 555 335 331 486 +4 523 290 576 42 +4 210 359 331 195 +4 273 294 559 206 +4 193 254 525 211 +4 453 153 339 566 +4 453 447 566 535 +4 451 43 188 71 +4 451 352 71 188 +4 341 277 258 574 +4 97 341 263 277 +4 163 324 105 312 +4 131 440 130 106 +4 198 458 377 29 +4 582 67 86 347 +4 492 127 493 174 +4 493 127 299 174 +4 530 493 127 299 +4 6 29 198 255 +4 361 393 338 60 +4 199 370 39 552 +4 496 109 529 213 +4 361 353 338 438 +4 7 191 13 5 +4 101 126 559 105 +4 129 214 126 312 +4 126 129 312 324 +4 126 324 312 105 +4 105 559 312 126 +4 168 55 54 378 +4 330 132 224 346 +4 96 278 414 207 +4 360 295 168 272 +4 510 225 47 290 +4 210 165 270 427 +4 165 427 283 285 +4 185 577 186 505 +4 160 437 282 484 +4 160 437 202 282 +4 437 481 282 484 +4 437 123 282 481 +4 63 361 352 348 +4 234 36 411 183 +4 415 92 354 184 +4 207 415 184 414 +4 218 125 336 536 +4 42 59 50 220 +4 102 124 362 269 +4 299 530 100 131 +4 440 100 131 299 +4 294 126 273 559 +4 129 294 126 214 +4 550 190 319 358 +4 265 289 110 89 +4 89 87 265 264 +4 20 190 583 37 +4 114 593 392 120 +4 135 331 210 137 +4 135 455 331 137 +4 135 137 210 508 +4 458 29 198 6 +4 148 129 141 214 +4 224 422 561 594 +4 193 231 191 208 +4 459 423 84 353 +4 566 514 116 495 +4 541 329 206 150 +4 541 150 206 148 +4 313 292 532 111 +4 532 111 498 313 +4 532 439 128 498 +4 216 402 361 196 +4 196 361 172 402 +4 203 193 231 397 +4 203 193 397 181 +4 532 590 128 441 +4 570 478 166 507 +4 98 101 245 79 +4 541 173 329 542 +4 121 317 533 182 +4 413 116 285 427 +4 237 190 583 20 +4 471 196 187 361 +4 68 416 341 263 +4 416 263 68 332 +4 484 481 581 538 +4 283 413 285 427 +4 534 134 114 327 +4 413 391 283 285 +4 477 295 443 235 +4 477 72 295 235 +4 120 134 392 114 +4 304 488 366 212 +4 212 228 274 483 +4 130 429 342 131 +4 130 522 342 429 +4 492 127 368 126 +4 440 131 573 299 +4 111 553 292 277 +4 330 346 292 111 +4 346 287 292 291 +4 111 313 292 553 +4 517 294 148 541 +4 35 383 393 409 +4 545 383 393 35 +4 202 282 437 123 +4 522 142 342 429 +4 78 84 459 423 +4 175 158 155 509 +4 371 335 528 420 +4 377 201 296 53 +4 328 377 296 53 +4 318 282 340 342 +4 360 232 168 295 +4 503 317 420 533 +4 570 384 521 166 +4 570 384 166 478 +4 5 231 172 191 +4 171 258 483 580 +4 78 95 252 268 +4 95 100 252 301 +4 576 222 216 343 +4 391 304 281 578 +4 479 183 31 197 +4 183 574 596 505 +4 384 574 596 183 +4 312 171 579 163 +4 193 0 181 23 +4 13 193 0 444 +4 130 528 314 340 +4 589 391 366 283 +4 283 589 391 413 +4 200 449 236 240 +4 156 164 398 141 +4 112 508 210 228 +4 228 112 366 210 +4 443 168 556 284 +4 205 574 526 46 +4 540 563 575 120 +4 128 441 329 532 +4 31 26 185 52 +4 403 230 215 266 +4 351 438 386 63 +4 527 351 386 63 +4 81 161 269 591 +4 598 262 511 445 +4 124 400 566 535 +4 391 285 413 91 +4 484 152 538 581 +4 195 357 164 273 +4 486 164 243 156 +4 51 352 63 82 +4 194 233 315 355 +4 355 194 62 315 +4 293 263 88 332 +4 101 297 298 559 +4 245 298 101 297 +4 126 491 101 559 +4 297 491 368 559 +4 282 254 271 301 +4 325 279 282 169 +4 197 223 546 421 +4 197 40 223 421 +4 143 517 541 504 +4 541 173 151 143 +4 541 143 504 173 +4 237 255 577 190 +4 244 170 591 276 +4 29 56 227 552 +4 34 454 290 50 +4 160 318 342 282 +4 567 452 192 17 +4 17 452 192 181 +4 296 480 475 256 +4 29 552 227 255 +4 353 438 361 352 +4 63 438 352 361 +4 225 351 438 244 +4 95 493 268 98 +4 492 98 297 493 +4 415 207 354 372 +4 404 381 159 581 +4 498 346 532 439 +4 498 111 532 346 +4 121 502 317 109 +4 330 292 287 277 +4 531 597 301 282 +4 531 282 239 90 +4 576 220 42 290 +4 477 395 235 48 +4 362 161 400 265 +4 169 90 279 282 +4 169 90 246 279 +4 531 327 534 114 +4 531 534 597 431 +4 525 254 45 211 +4 52 596 64 432 +4 566 270 116 514 +4 239 569 392 418 +4 94 239 392 418 +4 470 31 463 185 +4 463 31 26 185 +4 2 474 255 18 +4 88 97 277 553 +4 368 504 173 559 +4 271 279 90 282 +4 80 268 98 95 +4 327 114 531 239 +4 193 443 211 23 +4 559 504 173 206 +4 185 505 186 221 +4 574 263 277 560 +4 596 277 579 560 +4 368 262 174 173 +4 540 585 275 575 +4 275 120 540 575 +4 595 222 361 216 +4 400 161 165 289 +4 462 43 525 191 +4 382 107 292 278 +4 127 575 262 445 +4 335 420 336 314 +4 505 263 574 560 +4 560 596 505 577 +4 360 229 250 253 +4 210 335 309 331 +4 58 252 360 268 +4 552 184 209 55 +4 174 575 275 585 +4 267 98 250 354 +4 214 294 126 273 +4 254 43 208 525 +4 532 441 329 173 +4 302 174 575 275 +4 208 353 188 254 +4 391 281 260 578 +4 276 189 599 362 +4 83 86 584 579 +4 150 206 148 554 +4 522 142 340 342 +4 522 340 142 528 +4 181 168 232 443 +4 181 360 232 168 +4 521 1 166 576 +4 42 1 521 576 +4 541 504 206 173 +4 406 382 88 280 +4 293 406 88 256 +4 436 207 115 96 +4 141 214 129 486 +4 148 214 141 398 +4 164 398 141 214 +4 287 422 580 224 +4 494 195 580 422 +4 430 552 184 363 +4 430 363 414 278 +4 341 337 519 258 +4 205 62 574 315 +4 236 490 240 75 +4 438 266 338 599 +4 519 341 258 574 +4 457 282 279 440 +4 213 109 529 386 +4 239 282 569 90 +4 56 328 227 571 +4 328 306 296 571 +4 306 249 296 571 +4 227 328 296 571 +4 469 369 221 24 +4 574 68 387 316 +4 171 483 195 580 +4 258 483 557 461 +4 443 168 295 477 +4 49 36 384 25 +4 152 534 597 407 +4 402 353 172 57 +4 361 402 353 172 +4 195 171 312 309 +4 580 195 171 312 +4 348 27 361 188 +4 178 216 15 405 +4 38 373 63 361 +4 373 187 595 361 +4 73 338 60 87 +4 73 60 338 383 +4 172 191 231 208 +4 296 256 475 198 +4 312 486 214 164 +4 393 222 244 545 +4 545 222 244 170 +4 92 184 414 219 +4 36 468 183 234 +4 121 230 317 457 +4 21 192 255 2 +4 21 39 255 192 +4 134 534 575 327 +4 430 219 184 552 +4 166 401 247 16 +4 368 127 174 262 +4 368 173 598 262 +4 196 35 216 402 +4 178 216 35 15 +4 551 405 472 216 +4 551 179 288 375 +4 551 179 472 288 +4 187 375 179 551 +4 472 15 1 385 +4 426 381 575 407 +4 137 180 331 359 +4 359 180 331 195 +4 243 180 331 137 +4 226 410 272 295 +4 226 539 272 410 +4 130 189 314 599 +4 142 318 145 340 +4 89 67 347 86 +4 483 557 580 258 +4 239 392 327 114 +4 94 114 392 239 +4 114 134 392 327 +4 378 168 55 209 +4 145 503 217 420 +4 503 420 145 533 +4 321 32 378 452 +4 487 321 378 192 +4 321 452 378 192 +4 190 192 181 319 +4 14 181 319 550 +4 587 303 354 410 +4 552 204 255 39 +4 209 552 39 204 +4 192 209 39 204 +4 186 505 24 221 +4 185 221 186 558 +4 302 162 354 300 +4 552 229 209 184 +4 254 295 392 396 +4 254 235 295 396 +4 84 252 254 423 +4 360 252 295 272 +4 199 552 209 55 +4 192 378 487 209 +4 579 287 580 273 +4 261 579 287 580 +4 534 134 575 407 +4 354 300 303 372 +4 300 162 354 303 +4 300 303 323 162 +4 372 300 303 323 +4 174 127 299 575 +4 203 232 193 181 +4 211 456 565 235 +4 52 256 248 475 +4 577 248 475 52 +4 70 351 568 244 +4 595 351 225 47 +4 84 353 271 266 +4 282 342 581 440 +4 440 581 597 573 +4 410 303 354 162 +4 59 220 343 578 +4 286 260 391 259 +4 343 260 222 264 +4 220 260 222 343 +4 577 227 255 198 +4 343 347 578 264 +4 261 86 579 171 +4 257 171 347 261 +4 261 86 596 579 +4 272 302 410 354 +4 389 184 272 380 +4 184 380 410 272 +4 337 277 287 258 +4 560 579 256 292 +4 579 292 101 256 +4 579 291 273 559 +4 189 314 340 130 +4 510 47 225 568 +4 579 291 559 292 +4 486 335 331 309 +4 295 410 302 392 +4 599 314 110 400 +4 335 528 420 314 +4 198 248 227 256 +4 298 280 559 532 +4 574 596 194 384 +4 59 490 391 240 +4 91 59 490 391 +4 347 265 89 289 +4 438 516 215 266 +4 227 552 56 333 +4 207 424 379 532 +4 227 251 552 333 +4 391 161 259 260 +4 286 220 260 259 +4 252 301 392 302 +4 295 392 302 252 +4 87 599 265 170 +4 264 265 170 87 +4 266 189 279 440 +4 302 392 275 575 +4 189 340 317 440 +4 130 522 340 342 +4 581 481 597 538 +4 221 183 470 185 +4 221 185 470 592 +4 2 192 255 190 +4 190 204 192 255 +4 186 198 505 577 +4 194 257 258 274 +4 210 171 165 366 +4 281 165 171 366 +4 289 311 309 335 +4 289 335 497 311 +4 133 311 497 335 +4 301 597 327 575 +4 406 280 88 256 +4 71 43 188 254 +4 183 574 36 384 +4 471 361 27 172 +4 31 479 185 183 +4 577 52 185 26 +4 52 560 596 432 +4 596 560 52 577 +4 452 181 443 168 +4 20 30 548 190 +4 154 153 345 335 +4 130 314 110 599 +4 131 127 573 299 +4 131 127 299 530 +4 196 402 172 33 +4 139 509 175 162 +4 317 533 502 121 +4 286 578 391 260 +4 410 162 354 302 +4 267 363 184 552 +4 2 255 21 18 +4 333 571 227 249 +4 75 304 240 93 +4 362 124 308 218 +4 362 218 308 336 +4 243 331 486 455 +4 470 482 31 183 +4 484 581 159 152 +4 166 570 1 521 +4 256 79 248 245 +4 516 403 386 109 +4 480 256 249 406 +4 406 77 249 306 +4 406 306 249 480 +4 406 280 249 77 +4 406 280 256 249 +4 83 256 579 101 +4 83 79 256 101 +4 362 400 535 336 +4 218 362 535 336 +4 472 1 3 523 +4 523 3 472 288 +4 577 365 6 460 +4 507 166 570 1 +4 255 190 237 358 +4 30 203 397 181 +4 359 228 117 195 +4 195 228 117 483 +4 55 184 209 253 +4 253 354 184 229 +4 46 177 387 574 +4 505 177 574 387 +4 46 177 44 387 +4 503 502 213 317 +4 125 213 503 502 +4 476 162 322 275 +4 537 275 585 162 +4 361 38 465 27 +4 187 10 22 375 +4 373 47 595 22 +4 373 47 351 595 +4 508 112 210 135 +4 533 513 318 145 +4 80 58 268 78 +4 336 308 362 213 +4 145 217 305 420 +4 420 533 317 340 +4 545 73 264 170 +4 120 322 593 275 +4 167 593 322 275 +4 392 593 167 275 +4 167 275 322 410 +4 432 256 83 79 +4 248 256 432 79 +4 485 248 432 79 +4 552 209 39 199 +4 30 57 231 203 +4 170 599 438 338 +4 73 338 87 170 +4 270 427 285 116 +4 531 327 597 534 +4 440 581 282 597 +4 486 335 309 311 +4 289 335 309 165 +4 440 573 597 575 +4 575 581 597 407 +4 130 342 340 440 +4 227 249 251 333 +4 343 197 240 257 +4 510 222 220 588 +4 510 290 220 222 +4 304 347 171 281 +4 59 240 578 343 +4 266 440 271 84 +4 392 301 239 327 +4 390 58 232 360 +4 204 229 209 552 +4 583 577 52 37 +4 26 52 583 577 +4 301 575 392 302 +4 302 275 392 410 +4 403 189 230 266 +4 545 170 264 222 +4 52 256 560 432 +4 83 596 579 560 +4 574 519 194 258 +4 232 252 254 295 +4 235 232 254 295 +4 225 222 568 244 +4 70 591 244 568 +4 347 281 265 289 +4 256 83 579 560 +4 577 596 185 52 +4 578 304 347 240 +4 467 382 280 278 +4 201 198 505 186 +4 277 292 579 560 +4 277 287 579 292 +4 438 276 386 266 +4 36 62 384 574 +4 448 193 525 211 +4 471 27 361 465 +4 267 297 98 354 +4 579 292 559 101 +4 102 276 362 213 +4 102 591 276 367 +4 235 66 48 395 +4 54 74 55 168 +4 209 253 360 168 +4 42 521 41 576 +4 597 407 534 575 +4 52 256 475 560 +4 248 37 577 229 +4 192 181 209 204 +4 298 280 532 278 +4 432 560 596 83 +4 227 229 251 248 +4 227 249 248 251 +4 227 248 249 256 +4 347 264 67 89 +4 67 264 223 546 +4 343 223 257 347 +4 232 235 254 211 +4 232 423 254 252 +4 58 78 423 252 +4 384 343 197 240 +4 229 248 267 251 +4 209 184 229 253 +4 347 596 261 86 +4 386 266 516 438 +4 577 37 204 229 +4 258 287 580 261 +4 500 287 580 104 +4 267 354 298 297 +4 245 297 98 267 +4 267 245 297 298 +4 197 596 240 257 +4 343 546 545 35 +4 385 343 216 35 +4 166 35 546 343 +4 392 575 301 327 +4 203 423 232 58 +4 183 197 479 596 +4 599 362 265 170 +4 110 400 289 265 +4 573 581 575 344 +4 506 344 581 573 +4 225 244 438 393 +4 225 393 222 244 +4 244 393 545 338 +4 296 249 480 256 +4 296 249 256 227 +4 259 591 568 244 +4 577 198 248 227 +4 300 354 298 372 +4 100 299 440 301 +4 189 317 457 440 +4 95 301 268 299 +4 95 493 299 268 +4 301 299 302 268 +4 268 493 299 302 +4 363 267 354 298 +4 297 354 298 300 +4 89 265 347 264 +4 347 163 289 89 +4 222 393 225 361 +4 278 363 207 298 +4 579 580 312 273 +4 580 171 579 312 +4 105 579 163 312 +4 271 279 266 215 +4 268 354 98 302 +4 268 98 493 302 +4 584 86 105 579 +4 15 216 385 472 +4 262 575 585 344 +4 575 127 573 374 +4 60 393 338 383 +4 477 54 168 72 +4 556 54 168 477 +4 28 186 198 201 +4 458 28 198 201 +4 473 198 458 28 +4 28 473 198 186 +4 352 51 63 348 +4 384 16 478 11 +4 489 569 392 254 +4 392 499 418 489 +4 135 555 331 455 +4 586 434 224 594 +4 523 179 576 290 +4 179 22 34 375 +4 595 454 290 34 +4 8 470 183 16 +4 526 574 36 469 +4 46 469 574 526 +4 0 181 23 17 +4 319 192 181 17 +4 0 14 181 17 +4 30 203 231 397 +4 91 285 116 108 +4 356 285 391 91 +4 497 113 289 311 +4 56 572 333 552 +4 97 277 287 337 +4 341 337 258 277 +4 424 207 379 115 +4 34 42 50 290 +4 34 42 290 523 +4 313 292 107 532 +4 190 37 30 390 +4 190 30 181 390 +4 507 166 1 385 +4 386 189 317 403 +4 196 471 5 172 +4 284 168 556 32 +4 56 377 227 328 +4 224 195 273 586 +4 138 180 195 357 +4 450 586 273 195 +4 195 273 164 312 +4 580 312 273 195 + +CELL_TYPES 2224 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 diff --git a/data/torus.vtk b/data/torus.vtk new file mode 100644 index 000000000..a06ef2061 --- /dev/null +++ b/data/torus.vtk @@ -0,0 +1,9917 @@ +# vtk DataFile Version 2.0 +torus_, Created by Gmsh +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 1036 double +-0.75 -2.18556941e-08 1.13246855e-07 +-0.71031338 -0.135160238 1.07254337e-07 +-0.710313141 0.135160565 1.07254301e-07 +-0.692909718 -2.18556941e-08 -0.287012398 +-0.692909598 -2.18556941e-08 0.287012607 +-0.65624404 -0.135160238 -0.271825016 +-0.6562439799999999 -0.135160238 0.271825194 +-0.656243861 0.135160565 -0.271824926 +-0.656243742 0.135160565 0.271825105 +-0.603853762 -0.227407992 9.11793805e-08 +-0.603853405 0.227408156 9.11793308e-08 +-0.558141589621361 -0.2272469457790709 -0.2307452454467901 +-0.557888091 -0.227407992 0.231084868 +-0.557887852 0.227408156 -0.23108457 +-0.557887793 0.227408156 0.231084719 +-0.530330241 -2.18556941e-08 -0.530329943 +-0.50226754 -0.135160238 -0.5022673010000001 +-0.50226742 -0.135160238 0.50226742 +-0.50226742 0.135160565 -0.502267122 +-0.502267241 0.135160565 0.502267241 +-0.464421362 -0.247455373 7.01256795e-08 +-0.464420974 0.247455314 7.01256155e-08 +-0.42906943 -0.247455373 -0.177726254 +-0.4296712671318722 -0.247455373 0.1747004492923097 +-0.429069072 0.247455314 -0.17772612 +-0.429069012 0.247455314 0.177726239 +-0.426989228 -0.227407992 -0.426988989 +-0.426989079 -0.227407992 0.426989079 +-0.426988959 0.227408156 -0.426988721 +-0.42698884 0.227408156 0.42698884 +-0.336284906 -0.18893747 5.07776079e-08 +-0.336284608 0.188937217 5.07775653e-08 +-0.328395605 -0.247455373 -0.328395396 +-0.328395486 -0.247455373 0.328395486 +-0.328395337 0.247455314 -0.328395128 +-0.328395218 0.247455314 0.328395218 +-0.310686767 -0.18893747 -0.128690585 +-0.310686737 -0.18893747 0.128690675 +-0.310686499 0.188937217 -0.128690481 +-0.310686469 0.188937217 0.128690571 +-0.287012696 -2.18556941e-08 -0.692909598 +-0.287012637 -2.18556941e-08 0.692909598 +-0.271825254 -0.135160238 -0.6562439799999999 +-0.271825224 -0.135160238 0.6562439799999999 +-0.271825165 0.135160565 -0.656243742 +-0.271825135 0.135160565 0.656243742 +-0.260126799 -0.07043330370000001 3.92780564e-08 +-0.26012671 0.07043293120000001 3.92780422e-08 +-0.240325853 -0.07043330370000001 -0.09954615679999999 +-0.240325823 -0.07043330370000001 0.0995462313 +-0.240325764 0.07043293120000001 -0.099546127 +-0.240325734 0.07043293120000001 0.0995461941 +-0.237789407 -0.18893747 -0.237789273 +-0.237789333 -0.18893747 0.237789333 +-0.237789199 0.188937217 -0.237789065 +-0.237789124 0.188937217 0.237789124 +-0.231084913 -0.227407992 -0.557888091 +-0.231084883 -0.227407992 0.557888091 +-0.231084779 0.227408156 -0.557887793 +-0.231084749 0.227408156 0.557887793 +-0.18393749 -0.07043330370000001 -0.183937371 +-0.183937415 -0.07043330370000001 0.183937415 +-0.183937415 0.07043293120000001 -0.183937311 +-0.1826027894390168 0.07043797995747503 0.1848329123509294 +-0.177726433 -0.247455373 -0.42906937 +-0.177726403 -0.247455373 0.42906937 +-0.177726284 0.247455314 -0.429069012 +-0.177726254 0.247455314 0.429069012 +-0.128690705 -0.18893747 -0.310686737 +-0.12869069 -0.18893747 0.310686737 +-0.1286906 0.188937217 -0.310686469 +-0.128690571 0.188937217 0.310686469 +-0.0995462537 -0.07043330370000001 -0.240325823 +-0.09954623880000001 -0.07043330370000001 0.240325823 +-0.0995462164 0.07043293120000001 -0.240325734 +-0.0995462015 0.07043293120000001 0.240325734 +-3.27835394e-08 -2.18556941e-08 0.75 +-3.10487849e-08 -0.135160238 0.71031338 +-0.002247339125087955 0.135160565 0.7098661234313948 +-2.6395286e-08 -0.227407992 0.603853762 +-2.639527e-08 0.227408156 0.603853405 +0.005294134150853763 -0.247455373 0.4633682886880875 +-2.03004848e-08 0.247455314 0.464420974 +-1.46994799e-08 -0.18893747 0.336284906 +-1.46994674e-08 0.188937217 0.336284608 +-1.13705036e-08 -0.07043330370000001 0.260126799 +-1.13704992e-08 0.07043293120000001 0.26012671 +3.10198112e-09 -0.07043330370000001 -0.260126799 +3.10198001e-09 0.07043293120000001 -0.26012671 +4.01015754e-09 -0.18893747 -0.336284906 +4.01015399e-09 0.188937217 -0.336284608 +5.53816948e-09 -0.247455373 -0.464421362 +5.53816459e-09 0.247455314 -0.464420974 +7.20088389e-09 -0.227407992 -0.603853762 +7.20087989e-09 0.227408156 -0.603853405 +8.470402160000001e-09 -0.135160238 -0.71031338 +8.470399489999999e-09 0.135160565 -0.710313141 +8.943660029999999e-09 -2.18556941e-08 -0.75 +0.0995461792 0.07043293120000001 0.240325734 +0.0995462164 -0.07043330370000001 0.240325823 +0.09954622389999999 0.07043293120000001 -0.240325719 +0.09954626110000001 -0.07043330370000001 -0.240325809 +0.128690541 0.188937217 0.310686469 +0.1286906 0.188937217 -0.310686439 +0.12869066 -0.18893747 0.310686737 +0.12869072 -0.18893747 -0.310686707 +0.177726209 0.247455314 0.429069012 +0.177726299 0.247455314 -0.429068983 +0.177726358 -0.247455373 0.42906937 +0.177726448 -0.247455373 -0.42906934 +0.183937356 0.07043293120000001 0.183937356 +0.183937415 -0.07043330370000001 0.183937415 +0.183937415 0.07043293120000001 -0.183937296 +0.18393749 -0.07043330370000001 -0.183937356 +0.231084689 0.227408156 0.557887793 +0.231084794 0.227408156 -0.5578877330000001 +0.231084824 -0.227407992 0.557888091 +0.231084928 -0.227407992 -0.557888091 +0.237789124 0.188937217 0.237789124 +0.237789199 0.188937217 -0.237789035 +0.237789333 -0.18893747 0.237789333 +0.237789407 -0.18893747 -0.237789258 +0.240325734 0.07043293120000001 0.0995461866 +0.240325794 0.07043293120000001 -0.09954606739999999 +0.2405965857521089 -0.07043330370000001 0.09818501000602463 +0.240325883 -0.07043330370000001 -0.0995460972 +0.26012671 0.07043293120000001 1.69520092e-07 +0.260126799 -0.07043330370000001 1.69520149e-07 +0.271825075 0.135160565 0.656243742 +0.271825165 -0.135160238 0.6562439799999999 +0.271825194 0.135160565 -0.6562436820000001 +0.271825284 -0.135160238 -0.65624392 +0.287012577 -2.18556941e-08 0.692909598 +0.287012696 -2.18556941e-08 -0.692909598 +0.310686469 0.188937217 0.128690556 +0.310686529 0.188937217 -0.128690392 +0.310686737 -0.18893747 0.128690675 +0.310686827 -0.18893747 -0.128690511 +0.328395218 0.247455314 0.328395218 +0.328395337 0.247455314 -0.328395098 +0.328395486 -0.247455373 0.328395486 +0.328395605 -0.247455373 -0.328395367 +0.336284608 0.188937217 2.19150877e-07 +0.336284906 -0.18893747 2.19151062e-07 +0.42698884 0.227408156 0.42698884 +0.426988959 0.227408156 -0.426988691 +0.426989079 -0.227407992 0.426989079 +0.426989228 -0.227407992 -0.42698893 +0.429069012 0.247455314 0.177726224 +0.429069132 0.247455314 -0.177726001 +0.4285832038493428 -0.2473905309719522 0.1782033175787506 +0.429069489 -0.247455373 -0.17772615 +0.464420974 0.247455314 3.02655138e-07 +0.464421362 -0.247455373 3.02655394e-07 +0.502267241 0.135160565 0.502267241 +0.50226742 -0.135160238 0.50226742 +0.50226742 0.135160565 -0.502267063 +0.50226754 -0.135160238 -0.502267241 +0.530330062 -2.18556941e-08 0.530330062 +0.530330241 -2.18556941e-08 -0.5303298829999999 +0.557887793 0.227408156 0.231084704 +0.557887912 0.227408156 -0.231084421 +0.557888091 -0.227407992 0.231084839 +0.557888269 -0.227407992 -0.231084555 +0.603853405 0.227408156 3.9352085e-07 +0.603853762 -0.227407992 3.93521077e-07 +0.656243742 0.135160565 0.271825075 +0.65624392 0.135160565 -0.271824747 +0.6562439799999999 -0.135160238 0.271825165 +0.656244159 -0.135160238 -0.271824837 +0.692909598 -2.18556941e-08 0.287012577 +0.692909837 -2.18556941e-08 -0.287012219 +0.710313141 0.135160565 4.62898811e-07 +0.71031338 -0.135160238 4.62898981e-07 +0.75 -2.18556941e-08 4.88762055e-07 +0.2148047599579061 0.05862636186789426 0.502491616306411 +0.08708371449759361 -0.07904678396405236 0.4544761890310727 +-0.146602316861926 -0.009632696391538147 -0.315119087525655 +0.1692244930490057 0.1812843605 0.623422415988969 +0.2079651687174781 0.1331645320914401 -0.5836410988931576 +0.1536632925775345 0.1239510807482383 0.4572738201945878 +-0.5671834958762344 -0.01939125278810325 -0.1175294783630399 +0.5569435355 0.06758027157215296 0.45546928025 +0.45546936975 -0.06758012992784704 0.5569436249999999 +-0.6446421632553362 -0.05976163801653798 -0.1092778761071423 +-0.6214703736046712 -0.0666511357727524 0.1250423258651282 +0.300758051598111 0.07172693423651585 0.4583027905022347 +-0.654305795925001 0.03357102801595683 0.001848341005699126 +-0.6258175216303261 0.05432506588159775 0.1162604558790866 +-0.442057131510203 0.03095741689814975 -0.2765487156973705 +0.30043105825 -0.181284115 0.5743412825 +0.6159713774510746 0.1837769934522046 -0.1922216808197105 +0.5322994338378045 0.008502274921264123 -0.3744977122371063 +0.04265738067802943 -0.1046145807176613 -0.4450745330079127 +0.1246996850352893 0.06574632593164867 -0.7058907283422399 +0.414704820039705 0.05850602124603817 -0.5873244043967869 +-0.5997874394191635 -0.06652994583433987 -0.3918934603056267 +0.4105207575547945 -0.02280618123261142 -0.4112567807811419 +0.1154383286484265 -0.0670131696695989 0.3444306649723132 +-0.5457887659485642 -0.1555429921777584 -0.2112258584708629 +-0.556036820477818 -0.1322847934326201 -0.08914487821102607 +-0.5287910658346734 -0.145964002948216 0.09942815883918801 +-0.5488808869220985 -0.1230845936541704 0.1994070919703603 +-0.5514166647614607 -0.06021660203561584 0.006754432547757371 +-0.5410083912396699 -0.04992438886868006 0.1097211985421525 +-0.5282477366216665 -0.0457190959344033 0.2285741534938628 +-0.5471074779992053 -0.03863338164943837 0.3383833878444414 +-0.5379197870483288 0.04712173579130802 -0.311524103556143 +-0.5444049150912931 0.04459180613937631 0.004718340344478199 +-0.5221095018638044 0.0369594492107734 0.119071275868263 +-0.5308799781628447 0.04747798722078263 0.3117821923412912 +0.4475426814502823 0.1489278561181345 -0.2688886257995359 +0.2996792148585254 0.1654024873724193 -0.4496521940991762 +0.0006848522370035207 -0.1023848032902419 0.5037054741521728 +-0.5278138632473582 0.1468044649733942 0.09245296480095991 +-0.5412677375001846 0.1432254272463678 0.2064531176041771 +-0.4231612307707837 -0.1037401749254241 -0.1337060640227804 +0.3305945547851408 0.01949853570690828 0.5514300148461841 +-0.4037618125828935 -0.1605445022397436 -0.336392455313646 +-0.4247760234915319 -0.1530323475734049 0.2024351829109144 +-0.4495954867690495 -0.1502396951148145 0.3301820862519624 +-0.4408269404029921 -0.07227179543752946 -0.0169300934674944 +-0.4374801290473587 -0.07174959795745348 0.1003803329881969 +-0.4416965121862891 -0.04176342978079188 0.3173556488626441 +-0.4210349730051253 -0.04504186570420775 0.4288698757126937 +-0.4469474911194326 0.05062181151367538 -0.4380625839577525 +-0.4208545034966771 0.02789523773719308 -0.124023188409767 +-0.4426622831200132 0.05234302201265242 -0.01514508992852398 +-0.4508707370426806 0.07401740893526983 0.235274710670023 +-0.4193989654820721 0.05283121747753344 0.3293365305174706 +-0.429259712191232 0.04147422157022783 0.4546009980040832 +-0.4365211327554736 0.1347201315161209 -0.3271173605683869 +-0.4285450353537538 0.1540513903482495 0.1047628151789162 +-0.4403871896259152 0.1709419521191819 0.210772629951794 +-0.4174665753576615 0.1439620252099086 0.3300534389646202 +0.2079223709471942 -0.1155629893027928 -0.3256443507170392 +0.4773776328763831 0.08791904828105823 -0.3315091410248636 +0.6109661671423812 -0.1312233317339073 -0.04826091956918894 +-0.3210912808149326 0.09886036457796581 -0.3443362945660071 +-0.5107203347875002 -0.0511037324690895 -0.2162246520966066 +-0.4274951252036663 -0.03507233851382638 -0.1978104046406515 +-0.3221922211749222 -0.1445975170440534 -0.4425145553301829 +-0.3286954227264652 -0.1434492302514711 0.2222906885168947 +-0.3285017090814557 -0.1265089069691785 0.308151421041821 +-0.3395649970840241 -0.1554064149526791 0.4225686128741589 +-0.3290190794293953 -0.05254108065203134 -0.5467141964176405 +-0.3159309151850979 -0.04120775039923903 -0.3224716358271946 +-0.3258398369406388 -0.03510117790117903 -0.1134249561622734 +-0.3376001506561476 -0.05717751503157612 0.102342810283574 +-0.3114520801316878 -0.03409065073118795 0.2177680683076604 +-0.328474165477487 -0.02648855206584399 0.3310258350020063 +-0.3225401600591715 0.05796838860563992 -0.5319520165267214 +0.2015107240799966 -0.0348512362201389 -0.4020904760206556 +-0.3346454802644096 0.05207433096846966 -0.01301303916511887 +-0.324625531231217 0.04835716156963638 0.1075824478319873 +-0.3479391062280647 -0.126665390258168 -0.2287931817071033 +-0.3339391802062537 0.08638104506876045 0.4153871716356871 +-0.3437931748730649 0.06799499691212332 0.5252200011202918 +0.2457413693967162 0.1472628478350848 0.429295858344446 +0.5295492770417918 0.1093862086104987 0.2733651267765829 +-0.3160302043757477 0.1364302962912125 -0.2386521499676249 +-0.3325980279608176 0.1444494011689514 0.2364387692234707 +-0.2930387724981217 0.1411993925395293 0.34719695896367 +-0.3437518688936977 0.1722947186730353 0.4268002410906342 +-0.3002781246773413 -0.05656847936871779 0.5773421353060838 +0.6116200389999999 -2.18556941e-08 -0.408671051 +0.4086714685 -2.18556941e-08 -0.6116197404999999 +-0.6116199795 -2.18556941e-08 -0.4086711705 +0.4086713195 -2.18556941e-08 0.61161983 +0.61161983 -2.18556941e-08 0.4086713195 +-0.3961672556480173 -6.155555294249769e-05 0.6199534874067836 +0.2898606410459698 0.09953935377376469 -0.5721343919035593 +0.1274258562189954 0.1820950256176694 -0.6308011075224357 +-0.2983307807445332 0.1419806263712661 -0.4269982341363224 +-0.01753325163574215 -0.1046126048589783 0.5737683073312927 +-0.1065471808270385 0.08839229482936621 -0.6047472533910651 +-0.5078357084441076 -0.1134888177294395 -0.3438187367651265 +0.07138585320850009 -0.05840339156309945 0.6482034465556364 +0.1875194341956316 -0.06385973718928681 0.6174557333286409 +-0.1940775370390703 0.1189988285552581 -0.5653164243045676 +0.210606074927093 -0.07955350966472875 -0.5157443637988349 +-0.2329323291013624 -0.1248761065775685 -0.5354600680477379 +0.4529133510639263 0.1027731533397032 0.4209756521472898 +-0.4260979781625683 -0.08344441861394807 -0.4140970192187416 +-0.2169229250232756 -0.139728824653224 0.3022348443465113 +-0.2198768006712144 -0.149968159355379 0.4321842579547452 +-0.2214114204232291 -0.1225220799957973 0.5409621791502991 +-0.1929736857355174 -0.03818610480938463 -0.5031431915557217 +0.2447988857322374 0.00381362611841892 0.5899237674964953 +-0.2253454435756435 -0.0510535612519891 0.3044597114244738 +-0.2040544704023095 -0.03176029619634726 0.427052550607548 +-0.2092215002784332 -0.02565337133532111 0.5411861284909295 +0.480989766979571 -0.08319996631774527 -0.4210647206063204 +0.6832787695 -0.135160238 -0.1359121870505095 +-0.1359126227647989 -0.135160238 -0.6832786799999999 +-0.2289056667134217 0.04663271431507766 -0.4255814967903377 +0.1359126012351997 0.135160565 -0.6832784115 +-0.2066628191114914 0.05480046826812753 0.3198049648384878 +-0.2243058615160185 0.07964437541474738 0.4247297184543852 +-0.208113090690223 0.06445928225980971 0.5231662485997532 +0.1359125669756076 -0.135160238 0.6832786799999999 +-0.1359126275243924 -0.135160238 0.6832786799999999 +0.387046307 0.135160565 -0.5792553725 +0.3870462925 -0.135160238 0.5792557 +-0.6832786799999999 -0.135160238 0.1359126506271685 +0.6832786799999999 -0.135160238 0.1359128139494905 +-0.2194004785644676 0.1475847545349244 -0.3469514787709857 +-0.5956393160156814 0.09490531950004515 -0.2042934565935917 +-0.2178745302422234 0.1453261132084583 0.3328986335035305 +-0.2418619683830102 0.1723327817400896 0.4269176136807822 +-0.1831818339704835 0.1484536604414157 0.5221446291367574 +0.03663870813279047 0.05005509956049407 -0.6414864284917617 +0.1942350135205994 0.05851852115451094 -0.6161295752759666 +-0.5420417635302861 0.1012002134691774 -0.1193827443122811 +-0.5756313767461709 0.1636057234662092 -0.06013303154197015 +-0.08651201916266667 -0.06865067701275893 -0.3321620682941319 +0.1027626229516373 -0.1314567021304453 0.3834698204860338 +-0.362428029410273 -0.1070244315800844 0.4886937738212236 +-0.1011488098433493 -0.1488108851409737 -0.5298702748774109 +0.1020647599765114 -0.07371707566437634 -0.366754583133816 +0.3903368429134106 0.101699745956457 -0.433818578133064 +-0.1074126412370914 -0.1526189193003277 0.4088007775076468 +-0.1151641662391919 -0.1438442203091108 0.5312796308049904 +0.2921648111109675 -0.07492673849593907 -0.2773684319721069 +-0.1285905486543048 -0.05647037586924304 -0.6133127505128496 +-0.1216163521409942 -0.03813129009229205 -0.4360208940675083 +-0.09905003496170785 -0.06196894632151512 0.3368756483460959 +-0.0990668004357604 -0.05903067457631835 0.4461241622524353 +-0.4776363609860341 0.1465133577617411 -0.2274197198236627 +-0.08773698924304667 -0.05184598555492647 0.6268363586823165 +-0.2267429148408685 0.1249132199309427 -0.4913909097447509 +-0.1121832809510704 0.04646092772441284 -0.5238551018576121 +0.2073757465014909 -0.0005490189447118193 -0.2818296401738018 +0.3574044012045842 0.1547702511617189 -0.2277470630249493 +-0.2354812082527474 -0.150851567101606 -0.3768350049973243 +-0.08743158532283671 0.05697845190875393 0.3357206925042919 +-0.1277896175209473 0.0578934535227305 0.440598521116173 +-0.1033125957436848 0.03928284369367165 0.5233789300229542 +-0.09304793425364484 0.05084289554029058 0.6380521403377361 +0.2386457396262456 0.1715816661461778 -0.3828757503815334 +0.423909910978836 0.1317032982272586 0.06356530576229823 +0.4097262710096638 0.1454523582378435 0.1438076249432514 +-0.0911470481544097 0.1452334358097956 -0.4158156824845399 +-0.1016133527545378 0.136860667934726 0.4330388861157719 +-0.4292389925744527 -0.1654781027874459 -0.07721888439167002 +0.2059596359472754 -0.0381533441888445 0.2457693811615254 +0.2680266045401745 -0.0409369721715605 -0.1942463155450726 +-0.5684009439817774 -0.181284115 0.3093214345483903 +0.156376008505201 -0.03237108451866057 0.2901862018655822 +0.4036041502130215 0.07115527728618469 0.4897612657744972 +0.4145351070767421 0.04784708682520229 -0.4968945110667345 +0.5250185200556235 0.04036754828805152 0.3708378603636437 +-0.3939857586234845 -0.0354399188984108 0.5159839140024425 +-0.5136737465592929 -0.02096928334744927 -0.3939635237507689 +-0.6094018716296354 0.002003007624447968 -0.202297769504363 +-0.3663963947652291 0.008372259341285189 -0.228274073560665 +0.3184424023319196 -0.02249886458617977 0.3579632423854461 +0.006561687502009625 0.05724662934245741 -0.5358999954437873 +-0.02114722495813348 0.04872463253946129 -0.3390579201943842 +0.3048686051070211 0.1840817211670154 -0.5675677732621035 +-0.01038008191495194 0.05798805100217008 0.4357427118599579 +0.0008467820919496345 0.03331469483369875 0.5521021583643705 +0.407017633 0.1812843605 -0.50312203175 +0.05776611603134262 0.1376535741227746 -0.2918362873837625 +0.0497730822502663 0.1296850741 0.288305171 +0.2457107185925527 0.135139000195845 0.1648979522399937 +0.1686676516 0.1296850741 0.239057429 +-0.5000568779581299 -0.1795990531282913 0.4150386052352156 +0.5014528792180527 -0.1816753454552545 -0.408719237110252 +-0.5029512339302212 0.1812843605 -0.4072733907773048 +0.5029512152035382 0.1812843605 -0.4072733664139633 +-0.3764123707272886 0.09879670488745546 -0.4095454500084148 +-0.4725332676819864 0.005642352703116546 0.2020216355148748 +-0.1496650072925399 -0.235647257655321 0.5167782537253931 +-0.5302451570783469 0.2365965943548609 -0.04876828145860426 +-0.002591613671415457 -0.1026208303124244 0.3928908007681053 +-0.0523451173707068 0.1302623922386563 0.4927621326423263 +0.05860755375353332 0.1257279774771141 0.4794596148821863 +0.08802430931468684 -0.1225325715056166 0.5603036431373815 +0.1032241182142573 -0.0340591879952308 -0.5533129910255919 +0.00745278544232821 -0.06582211103224113 0.630052478596229 +-0.01082466888663697 -0.03801533319731521 -0.6156480556982972 +0.4726120106138331 0.12484313881195 0.3448375643845454 +0.4814544006975456 -0.05513774069059533 -0.2986534077813469 +0.4732694108739305 -0.05522915948677016 -0.1778180843447857 +0.4909415760273616 -0.03837679976116375 -0.06661192117720928 +0.100095691090951 0.05093218150821434 -0.4304550833388545 +0.1239385805155771 0.044544506316063 -0.3352807243241612 +-0.2802087049206544 -0.08144478342526922 0.4785192195300021 +0.09580812999656925 0.05650133103318054 0.5018653908681395 +0.1112308163202565 0.150059329766388 -0.5249317956161899 +0.6459383261078916 0.06758027157215296 0.3222791452973603 +-0.1565518800075456 0.04876135164867082 -0.3722630768346345 +0.5560387821509727 -0.04441632956197366 -0.1490117451147615 +0.581792943649261 -0.04102538424861867 -0.06392366822802879 +-0.2582127270014075 0.02913406223927319 0.2684441064386298 +0.2927387924644004 -0.0149633208788464 -0.4491729904496716 +0.2013878265835575 -0.1266401577586878 0.3266978710424491 +0.443141937 -0.2374316825 -0.279739961 +0.5157281007889414 -0.2374270833779515 -0.09271138174935373 +0.2090559597555721 -0.04395774488034123 0.4278392112683149 +-0.4944336897194478 -0.09005668250886321 0.3978113830106517 +-0.432532593947051 -0.2375984594420146 -0.2935702535581112 +0.2277292536980891 0.0428303539450235 -0.5320631122757074 +0.2865164264133694 -0.2374651039703354 0.4383398348635704 +0.2056064164492523 0.04985412590180793 0.3127630284553709 +-0.2820232971018125 0.2372968610762593 -0.4427223751947126 +0.4395616904484677 -0.2384988760845237 0.2719947621906035 +-0.5081604390019669 -0.2378210470469928 0.1169813244873835 +0.4327316470501742 0.2384381322497851 -0.2829623286064294 +0.2877680748853014 0.2378403864535273 -0.4344245922410273 +0.2797399535 0.237431735 0.4431415055 +-0.4340564080289104 0.2378165773830367 0.2886114810717543 +-0.1828011762689302 0.05364457025045295 -0.6355453293052928 +0.6375438199914241 -0.02935637925234931 -0.152892417653076 +0.2602975085172395 -0.09745952344616611 0.5477608240078249 +0.2775263424353848 -0.1228377492099226 0.384791984454249 +0.3596151937197254 -0.141597768176489 -0.4231164447026335 +0.3208415581685442 -0.1349795480412619 -0.2171832530745286 +0.3109056466661628 -0.1388776022384641 0.1987929501681949 +0.3335612390022412 -0.04552068754656854 -0.5281548867660718 +-0.4531333533695962 0.07692855650042288 -0.555266519638251 +-0.4585715218401867 -0.07760329815977847 -0.5513992488579733 +0.3396141930387401 -0.05279514643595638 -0.0921131507041876 +0.3204727004155962 -0.06529806721664831 0.1046288254150648 +0.31306525603795 -0.06567965594681423 0.2046364937964013 +0.3159038841314221 0.02599107147295122 -0.3415755577703607 +0.3351976816345975 0.06128680549085182 -0.1479704239571715 +0.3388606878224936 0.0394365795661426 -0.03384902201879005 +0.3437417281098993 0.05703090942030965 0.107072764716187 +0.3220169919082694 0.05095046011482658 0.2177406215607413 +0.0689665525288998 -0.01163147790780546 -0.665821750833281 +0.4247853193968322 0.138055140745489 0.2498450206885172 +0.5666235297019543 -0.1721782523580675 -0.1155446617485881 +0.2372398230317664 -0.03167176195468971 -0.6080155472507058 +0.3357930029995391 0.1567136729231967 0.4253357575546892 +0.3540986515356748 -0.1424058629083627 0.3969252358031086 +-0.3414012713464936 -0.0621048952609243 0.002901790927666791 +-0.006352275712959725 -0.06508036243897163 -0.3374551632923645 +0.4077025720526192 0.04826923006195883 -0.2421012815042307 +0.1654412905940297 0.04562478981903653 0.4212167249231981 +0.4197084439871971 0.05192469954844516 0.1814469788058192 +-0.2208049830591295 0.06251985565641553 -0.6877215877450071 +0.426338398304634 -0.1434752602320325 -0.3367315691514332 +0.4326170457437952 -0.1411491565218985 -0.2188400560397645 +0.4237305177426459 -0.141661095432702 -0.08709124284118519 +0.404215024391447 -0.1399533434716075 0.2156067827615666 +0.4328630722823912 -0.1328013499737094 0.3308716072960298 +0.2248175293217677 -0.06758012992784704 0.6854376795667962 +0.4161155946855566 -0.05584439860466436 -0.002441013836284896 +0.4313140076389336 -0.05978578617486206 0.1088070022131595 +0.450918256819464 -0.03847381900589373 0.2359583877933817 +0.4457060890403761 -0.02620527055913056 0.413482502816888 +0.09835692228621801 0.06442805687023616 0.3643175222483206 +0.4369762376240091 0.04583458804269828 -0.1157588923316206 +0.4259958964602643 0.06108205071788198 -0.01539096574106599 +0.4162805245750874 0.04502838616233909 0.3078736604558807 +-0.2079118128565157 -0.04963516806072479 -0.3889561128873697 +-0.4299064880738119 0.135160565 0.5506171529961174 +0.5281180042296583 -0.1378503329927562 -0.2334815132298401 +0.5223484067072454 -0.1458065956801332 -0.02071680486975328 +0.5425252574054265 -0.1373263383845702 0.1072054410899196 +0.5350977120239054 -0.05103806950915329 0.3245688546285393 +0.5333863472702021 0.05046379975240864 -0.1975902518114613 +0.532455096746828 0.04560488532328932 -0.005699071116475381 +0.5419193981501835 0.0486765864019862 0.1239391687217768 +0.5355481056583311 0.1414417937687622 -0.09261594688985184 +-0.4967510892678877 0.04316175247488441 -0.1928494949928883 +-0.02348498660855512 -0.05726929540916417 -0.4929404584818559 +0.3389491987958484 0.1263167279134933 0.5054477140885989 +0.6274560120419712 -0.05198890175872962 0.1099921569861211 +0.4878419111093683 0.05875103888030383 0.2200223268103224 +0.6240885685723052 0.04492717659879997 -0.1054570120072385 +-0.6018963927443802 0.05107175258897927 0.2237810152843244 +0.641493437015596 0.04698768983416271 0.1038913003334417 +-0.2638401636369636 -0.05493290412767491 -0.4459854414188743 +-0.4048759839159633 -0.06931554420171929 0.2011181734596874 +-0.6013782642278841 -0.008670811585460226 0.05953811030783254 +0.236902116816932 0.07230934141622231 -0.4053013921960443 +0.1152841078827855 0.0709724499571117 -0.6207345739323095 +-0.2104418741655573 -0.06950722531256681 -0.2601247953068311 +-0.2245041950568541 -0.1051655974782383 -0.3165675198391922 +0.2110263114297359 0.1100623185224954 -0.31596710503771 +-0.3303083506116173 -0.02760598174876897 0.4317847611411088 +-0.3969790557273846 0.08278970153870198 -0.223719143864455 +0.3181074745640283 0.001246966633677706 -0.2511003853726549 +-0.001060707671683717 -0.1065111122750068 -0.5541061858275393 +0.650853451752721 0.009920080387569559 0.011665510543036 +-0.3574599974014963 0.09734137741098607 -0.09965203923949038 +-0.1436064464398353 0.08831529589285453 -0.3151052839264627 +-0.007506786969251721 -0.004105502730003744 -0.4243101107139098 +0.1065931068429387 -0.0001085366789827557 0.4135578084754778 +-0.3329912408681484 0.06421172716095264 0.3029882505886588 +-0.3375421951262143 0.006229202633078193 -0.4349069127969654 +-0.6985554476013591 -0.1024719621527603 0.1073642970980115 +0.5452928391102743 0.01608060722268402 0.2319397301056004 +0.1155424676004419 -0.227407992 -0.5808709265000001 +0.4924387485 -0.227407992 -0.3290367425 +0.5805699011497513 -0.227407992 -0.1170558901122047 +0.3290369515 -0.227407992 0.492438585 +0.492438585 -0.227407992 0.329036959 +0.11554240060044 0.227408156 -0.580870569 +0.4924384355 0.227408156 -0.329036556 +0.5808706585 0.227408156 -0.115542013739575 +-0.329036869 0.227408156 -0.492438257 +-0.5770880277546183 -0.227407992 -0.1345605514496855 +-0.492438585 -0.227407992 0.3290369735 +0.3290368765 0.227408156 -0.492438212 +0.3290367645 0.227408156 0.4924383165 +-0.4846991967808343 0.2275824300242007 0.3384793634329527 +-0.4924384055 0.227408156 -0.3290366455 +-0.5808706285 0.227408156 -0.1155422394103346 +0.5263242134816848 0.1427634180929979 0.04084918483631195 +-0.1523500837504407 0.1543677763815984 -0.5036055611948859 +0.502190705004582 0.1453440444158882 0.1545363581935308 +0.1381249001229966 -0.1411164872603262 -0.4731299872355259 +-0.6070921062993293 0.07694558145276738 0.3755620352998136 +0.1406031141985266 0.1429805795156574 -0.4029942841166447 +-0.5103359034007181 0.2364667903916487 0.1533976511473124 +0.1425452530490057 0.237431735 0.5057831616462883 +-0.3731252291502142 0.1294891353399314 -0.4883120817928434 +0.3723381797994571 -0.04828163511992769 -0.2021711263110909 +0.3764661100207322 -0.04326195962319036 -0.3110841143459703 +-0.5149001436269404 0.1817831010578217 0.3883744154118514 +-0.4075790725065548 -0.07011207976826006 -0.5880659568874272 +-0.5303300891969429 -5.833858670062555e-08 0.5303300379042957 +0.3692070733341348 0.05887650239374177 0.3977133352200331 +-0.4079152010050289 -0.1850652088177073 -0.4973754617889673 +0.3329196737418877 0.1396696471672832 -0.5128027077454528 +-0.06310352592163579 -0.05063790301029709 0.5320612101990535 +-0.4016297809554171 0.07665157112216678 -0.5897760485424426 +-0.3792981735569309 0.2069810069713509 0.4866624706549424 +0.3021500544248019 -0.07243349234632183 -0.3680829388445839 +-0.3032017640904151 0.0466666413092313 -0.2590452631690672 +-0.2390805197549287 0.05934859095666144 -0.3203443511140383 +-0.3843687658895464 0.0597781261690172 -0.320510805268692 +-0.297150850631037 0.04789404968614406 -0.1751198455174624 +-0.491150875371558 -0.02431634563507673 -0.1034359022115692 +-0.3426425664506795 0.06567166007506782 -0.6329930304230099 +0.622054807140332 -0.06919338799472372 0.2517012930533061 +-0.1703098257617832 -0.1826550824458945 -0.6216246471829776 +-0.2174347219811193 0.01272135947138664 -0.245695297556412 +0.4439378877973604 0.06758027157215296 0.5646485581078916 +0.04763992432268208 -0.01224661208412182 0.5024657892071374 +-0.1708675632617437 -0.1854258582415338 0.6183160665788725 +-0.1716332338339093 -0.07729741666714569 0.6931634498852716 +0.4859623908309793 -0.1751256506962191 -0.1293025462109802 +-0.1895947160490057 0.135160565 0.6726003965825593 +0.5863066585133995 -0.05325755980125289 -0.2416842667002071 +-0.6726003999896268 0.135160565 0.1895947010490057 +0.1895946860490058 0.135160565 0.6726003904889689 +-0.6705388748474567 0.135160565 -0.1999589308460862 +0.6726004757712991 0.135160565 -0.1895945220490057 +-0.5959268895394246 -0.08763387546571111 -0.193621137504829 +0.2024962576489122 0.1321155658524761 -0.4660263074064109 +0.4354731070692088 0.1354985673547656 -0.1637449946554581 +-0.1637739673863473 0.08397379746190908 0.6927663054735529 +0.3265732257357251 -0.1509614322112238 0.2884515197475907 +0.2732793647740832 0.1546584917298763 0.3314554491719456 +0.3352013350452636 0.1560501476469682 0.2713065059666275 +0.1855214459446696 0.1402342518748386 0.377939225620567 +0.5952374280764472 0.05149610372169009 0.2848800021155177 +0.309976557537971 0.02941156572264442 -0.5861860739822928 +-0.5819583326726456 -0.05848943025699382 -0.2922827175629795 +0.4478022466495745 0.1487306241748066 -0.05278736440785489 +-0.06061965019220951 -0.1546782628110873 -0.4451638315554993 +-0.4739719375085265 0.1595241468053785 -0.07235625997418475 +-0.4389376217620313 -0.1571890255726863 0.05923078313502133 +0.03523894539594524 0.1322226216130693 -0.4287150964234601 +0.4406472348063602 -0.1457053958490441 0.05768599293734747 +-0.6888037686428277 -0.07036105566768017 -0.2037901556721537 +-0.06229448528435831 0.03133867538934622 -0.6561603563492422 +0.6623351609753214 -0.05696093651650429 -0.04555963134792926 +0.7142163401685105 -0.06509681597650166 -0.08380314178483944 +0.08210689966282012 0.05937132490740349 0.7162348457707524 +0.08333145252853005 -0.06595830440988804 -0.7140572377641591 +0.06608137356851983 0.1491054590402661 0.4009851807085034 +-0.3611274408840614 -0.1077702581600939 -0.06242896573356903 +0.3796094865805174 0.1486590723480749 0.3447589131660058 +0.04712138799494611 -0.09589795714366683 -0.6301910061738919 +0.0659446078747277 0.09224666523738477 0.621360874667907 +0.181154043491014 -0.08994650355324102 -0.6200918491966262 +0.5771762656224043 0.09484020020585483 0.1912421960319913 +0.0226914655921382 0.02659887758775728 0.6516329293572531 +0.3075185328989046 0.07299906362394958 -0.4985846099332604 +0.07577543452462263 -0.1433929495342712 -0.5746623127656189 +0.1596925585545952 -0.1348942439547208 -0.561311843514139 +0.4452187262509794 0.04287656012943429 0.1108911178589169 +-0.646405235051362 0.1812843605 -0.0536821029593403 +-0.2904552754354776 -0.04991148299524247 -0.2135005964108463 +-0.2027902505473725 0.04060653507155906 -0.5494798040191847 +0.312554733939242 -0.1507221313137781 -0.3192189438369041 +0.532405183857342 0.02947761865663639 -0.102715572874153 +0.5275086031262067 -0.1055867242650335 -0.1088883244036733 +-0.4264568237336529 0.03087572834513268 0.1118487827067294 +0.5386311781670815 -0.1739261713797737 0.3688656825855084 +0.318987690826632 0.08094470550083935 0.3082873048685877 +-0.5247960083693182 0.05760442579045268 0.2134851504654077 +0.6158593372512614 -0.1874400435104712 0.1715324352895766 +0.4315624334526753 -0.02798427575426788 -0.5103779956811643 +-0.4123433473060267 -0.04764382775535243 -0.5032775626162018 +0.7173603882156612 0.07561188915947202 -0.05247448317129177 +-0.2713328395803039 0.1161625451622493 0.5697169244581305 +-0.1741215833851504 -0.1867567049684828 0.4804577250082678 +0.6976598577362255 -0.06827042213568386 0.1623536943023283 +-0.04610012519939551 0.1448809950000666 0.5674450728739088 +-0.06820624315971494 0.1391422404993094 -0.5422448272563861 +0.04976206459513634 0.1459319893446545 0.5648956198046813 +-0.4405659160829608 -0.05935747034583092 -0.2987452142975358 +0.7101340715369242 0.06931532101520638 0.09809893503159287 +-0.5233272589156744 0.1371867973524671 -0.006070351955850449 +0.003411548988928413 0.1576623979034729 0.5143549750367112 +-0.007709896184820183 0.1617475887412644 -0.4979439886996553 +-0.5015913141449097 -0.148026251126252 -0.0007504796998853022 +0.3156046534344432 -0.02657801295699586 0.456855152278661 +-0.7146314176639721 -2.18556941e-08 -0.1778099321739148 +-0.714631391435433 -2.18556941e-08 0.1778099059453759 +-0.6889572874750536 -0.135160238 -0.1073642970980114 +-0.0800325114130878 -0.2144714877278948 -0.376277204125747 +-0.2045620552658866 -0.2184651849984501 -0.3362589268787387 +-0.6889570651027241 0.135160565 -0.1073642970980114 +-0.6889570579792537 0.135160565 0.1073642970980115 +0.07462547832493387 -0.2197393122455355 0.3888876602281924 +0.3226232787263165 -0.2162282417004459 0.2163220611664897 +-0.382677138 -0.2181964215 0.08886321938880395 +0.3260948967187077 0.2168535096272338 -0.2135434742241258 +-0.08047208479996108 0.2175162374763322 -0.3828568457923386 +-0.5709528055146412 -0.1788981212378028 -0.3103633892284121 +0.2294042978034777 0.2168584666811915 -0.3155098213988843 +-0.5989670613063136 -0.135160238 -0.3575461347945523 +0.38267687 0.2181962655 -0.0888628909245615 +0.091470285862678 0.217038063599734 -0.379622106314556 +-0.07140032689038553 0.2154323042171401 0.3800981761532723 +0.221030943918663 0.2171582416863385 0.3218790327721636 +-0.3857783053634699 0.2178326861474558 -0.06926851353584285 +-0.2269041027428502 0.2188124539906703 0.322227403264663 +-0.3317374084906508 0.2173518025519454 0.207025087688183 +-0.5835519514615468 -0.2268300252085159 0.105417351210259 +-0.3827407025570413 0.217881574844037 0.08507772784439768 +-0.5824973265862685 0.227408156 0.1073642970980115 +0.3812711629175531 -0.2165997755367423 0.0783551961348893 +-0.1521653160164021 -0.1287108372045364 -0.4187192410115158 +-0.4859042057485281 -0.227407992 -0.3388164423898491 +-0.4257266172768689 0.1457644899011558 -0.1483052091300335 +0.02270542428141074 -0.01774936420632196 0.3414903994776349 +-0.3716315400264734 0.1944972016295138 -0.508779491398935 +-0.3048382051472016 -0.1745592467809746 0.5805511771905953 +-0.3135551595490744 -0.1851134063945669 -0.5603592340360726 +-0.4356442171131527 -2.18556941e-08 -0.5935971483996163 +-0.07717212950074337 -0.1785652289067969 -0.6448708338027288 +-0.06507398806140052 -0.1761046441822036 0.6501169839026913 +0.6453716043734744 -0.1791687299460072 0.07115349393080496 +0.3897301333485112 0.1893134174198639 0.5037431591401457 +-0.6887090665053673 -0.07379341498840072 0.1991994430700723 +-0.5935971383366712 -2.18556941e-08 0.4356441969872622 +-0.6117749063923518 0.01644354433148199 -0.2978603801681667 +-0.387558001269515 -0.135160238 -0.5789137973090235 +-0.5789137969635547 -0.135160238 0.3875580010967806 +-0.3875580048364737 -0.135160238 0.5789138044429412 +-0.5789135088604425 0.135160565 -0.3875580605546097 +-0.3875580495343058 0.135160565 -0.5789134868198349 +0.5644643984827786 -0.06495018187921164 -0.4455770106383233 +-0.578913471633707 0.135160565 0.3875580419412419 +0.23709719603894 0.1014150416760966 0.2680955908015779 +0.04018451750921416 -0.1349437665400113 0.6245923834942313 +-0.6051502767477215 -0.1339196929326989 0.04824931533981232 +0.06106294228067399 0.1185684120684981 -0.6226282579399706 +-0.6062220019205854 0.1293499032270441 0.03599799757209045 +-0.6078126614727571 0.08914747057635643 -0.04573977024164903 +0.5754370663803664 0.1269034291391263 -0.2020234705263327 +-0.3709021398994805 -0.00134424386124089 -0.6363908604690129 +-0.1778099073798559 -2.18556941e-08 -0.7146313928699131 +-0.1778099039496093 -2.18556941e-08 0.7146313894396665 +0.4347152300153192 -0.03845077592829239 0.3242724391810436 +-0.3575457461164083 0.135160565 -0.598967070476627 +0.5212411926782172 -0.05775566056478709 0.01756777546771002 +0.5259509822148767 -0.03592485772890536 0.09957469724955148 +-0.1073642970980114 0.135160565 -0.6889570487660757 +-0.3575457351476239 0.135160565 0.5989670649922347 +-0.1073642970980114 0.135160565 0.6889570511651186 +-0.3462750200225362 -0.227407992 -0.4809205082873176 +-0.1073642970980114 -0.227407992 -0.5824976636260482 +-0.33153474006408 -0.227407992 0.4907696355829997 +-0.1073642970980114 -0.227407992 0.5824976644313991 +-0.1073642970980114 0.227408156 -0.5824973216541982 +-0.3318778745421381 0.227663389878087 0.4884459660073816 +-0.1073642970980114 0.227408156 0.5824973224595431 +-0.09142014233927777 -0.04957767833824132 -0.5334365820416362 +-0.1411060818092554 -0.05316603507842676 0.5382820154556561 +0.07839309595428723 -0.03606997118258356 0.5627924560811802 +0.2228311347285496 -0.04566485180113804 0.3316338944249109 +0.1778098936435355 -2.18556941e-08 0.7146313791335925 +0.1119377679059749 0.135160565 0.688047318674596 +0.1073642970980115 -0.227407992 0.5824976533568385 +0.1107310237709541 0.2263410543301188 0.5830591323502694 +0.1073642970980115 -0.135160238 -0.6889572750606456 +0.1778099085090079 -2.18556941e-08 -0.7146313939990649 +-0.2867197080342601 0.06935592017993335 0.2082907636499682 +-0.1040286901134598 0.04955933054357604 -0.428733056122008 +0.1087667398617572 0.05680384432486649 -0.5469337818933063 +0.3462749938603848 -0.227407992 -0.4809204952062419 +0.3575457135947208 0.135160565 0.5989670542157832 +0.3575461221925426 -0.135160238 -0.5989670550053088 +0.1812223911135857 -0.1736821308172768 -0.6298093261526846 +-0.6193708249721932 -0.181284115 0.1895947455490057 +0.1905191600437536 -0.1743820496510929 0.62715234095378 +-0.1895947310490057 0.1812843605 -0.6193705318270991 +-0.6237485270845429 0.1807169479230611 0.1708771116222541 +0.6193705496990755 0.1812843605 0.1895946860490058 +-0.6285656566370914 0.1761324746024394 -0.1732584543457864 +0.394701284275205 -0.1042605866668516 -0.4997370861425395 +0.4699929441616674 0.227408156 0.3626286470636558 +-0.5084742133742602 0.06489101169978406 0.3985956981616894 +0.5085238562446177 -0.09862272073648808 0.3981796479379747 +-0.252784993881451 0.08889640338330405 -0.2133526125177653 +-0.053682158699257 -0.2374316825 0.5234595132156995 +0.5789137897334826 -0.135160238 0.3875579974817446 +0.5789134714070765 0.135160565 -0.3875580418279266 +-0.5234595159721932 -0.2374316825 0.05368218361184548 +0.5789137748970357 -0.135160238 -0.387557990063521 +0.4119679658371732 0.171320395173378 -0.3619113785125 +0.5824973573981509 0.227408156 0.1073642970980115 +0.5824976994624926 -0.227407992 0.1073642970980115 +0.5989670542157832 0.135160565 0.3575457135947208 +-0.1851208683566414 0.124208603344928 -0.4239884656902839 +0.6889570984230848 0.135160565 0.1073642970980115 +0.173734377190098 -0.1592113573896186 0.4569211512536634 +-0.28606352997408 0.1545826835379782 -0.5211144100507749 +0.6889570315425984 0.135160565 -0.1073642970980114 +0.5456779809973004 -0.1215914160305011 0.2584213678038438 +-0.558393685464368 -0.1146177080545493 0.2834043871933823 +0.6190017582884673 -0.07274211245430767 -0.3599170327319804 +0.0411829889215951 -0.01367151147718778 0.4358118977414294 +-0.426429427626163 0.143843426080977 0.002542584081843323 +0.7146314120566302 -2.18556941e-08 0.1778099265665732 +0.7143730345430807 -0.00140176429054186 -0.1770398293756113 +0.3739725842088806 0.1215769468470212 -0.08292337630397037 +-0.05485930368709809 -0.1053031201782086 -0.3871347894732904 +-0.3714078393416314 -0.1180642596737125 0.05878671147875928 +0.3598360547299361 -0.1098711723824991 0.05711255573169563 +-0.2229579979104957 -0.01042827856541734 -0.3327072361197876 +-0.6422801729477911 -0.03894346107858589 -0.3425982442479343 +0.6608410879144642 -0.08766114178271175 0.05095820244838246 +0.1426328224684481 -0.01999499921288682 -0.6425278445708872 +0.1451338818735528 0.04608510717745574 0.6124456115996282 +0.01809742601197574 -0.1721964576789065 -0.4967334593128879 +-0.246127712574023 0.04135798095259782 0.5983282486609528 +-0.3138521513056136 -0.1556622707844267 -0.3161040462964457 +0.323493049226149 0.1290001483902456 -0.3253386948631966 +0.2728508941316176 0.07549347174791185 -0.2372820664953083 +0.5562842649028102 -0.0485295044900356 0.1953580131414835 +-0.3673911643395928 -0.09103973029133546 0.3705530982467184 +0.4355860589542803 -0.06553550803975287 -0.5709373490885763 +0.5632559126388801 -0.06387772482078147 0.4479415235371896 +-0.5623988653662189 -0.05767263513801224 0.4524406607131942 +-0.5561151775794455 0.06810076880820351 -0.4564393132378073 +0.5660902677743312 0.06010819246444307 -0.4456534833601336 +-0.2548913804596937 0.06258836563347484 -0.609930088042597 +0.6241570345002212 0.002226028570825955 0.2002465762605789 +-0.649776531707054 -0.0725164334290863 0.001715429544915426 +-0.004389374735116239 0.1180139820763546 0.6205176565062831 +-0.02316628772584089 0.1114646632479806 -0.6235726113015037 +-0.1543271382898399 -0.09275660230181169 -0.3310827964762754 +-0.6484132865773928 0.03340105755634293 -0.112249268939819 +0.08134865638375682 -0.0668181207163879 0.7141991738988013 +-0.08165379287038785 -0.05609759458137611 -0.7172863175211743 +-0.08318554957996099 -0.0696514590344952 0.7130018514806905 +-0.0739077083046028 0.05868607434484126 0.7180669935902767 +0.05266965457730004 -0.1751399486361745 0.6536976595518434 +0.05368213302461863 0.1812843605 0.6464052261462883 +-0.05328394604293371 0.1784463116146165 -0.6497597270761811 +-0.0536821640733928 0.1812843605 0.6464052317297715 +-0.6464055249721932 -0.181284115 0.05368220217617423 +0.6467232799244399 0.1809402739390439 0.05407987922160953 +0.234169056917011 0.05670640816227374 0.4156758517070452 +-0.5089134388924373 -0.1923102973818645 0.05068212359475061 +0.1676413756067232 -0.06781041643326767 0.531558722267077 +0.5865201611484786 0.1316140442522556 0.1131982866086703 +-0.04196278628353433 0.08189709568967014 -0.4641796369398359 +-0.2423508878776404 0.001876770083158745 0.1933769569910977 +0.2800534084650199 -0.001419473771088816 0.1515067266544594 +-0.1560211292574079 -0.0006481472840781907 0.2851380005602722 +0.7123616063516282 -0.08049241694007397 0.07040161526726069 +-0.6278805340950337 0.105766568169776 0.1909343800546901 +0.6415084338809066 0.0798150248930703 0.1822983339745222 +-0.193204923899704 -0.05572412844052755 0.6224482061031797 +-0.6304617438564843 -0.1035122462338923 0.198036709796241 +0.6156512441366255 -0.1032623802693025 0.1753596888902071 +0.6334392450885363 0.06696755323160408 -0.1838983985512123 +0.3782062441392018 -0.12204988584297 0.133183390216391 +-0.3828751918786762 -0.1285998340989022 0.1330862319117084 +0.5072024770378601 0.02634700497318234 0.4506209427980654 +-0.7191544659780258 -0.06197279360122413 -0.06358919318901379 +0.5728575186449349 0.07727439263062541 -0.2980850278327078 +-0.7044764983498082 0.06248231541307675 0.1366278139779501 +0.2566443629179671 -0.1170930898586065 -0.57977294954992 +-0.2765169719865896 0.01562580963005574 0.4859752387090623 +-0.1753814023370256 -0.124284950943586 0.367624994491605 +0.4898723741986995 -0.09038045200736297 0.1732492806675991 +0.3766615163973158 -0.123978037291708 -0.1575263032116939 +0.4881935107812874 -0.0085710500253026 0.1662459875931393 +-0.56444933379114 -0.002316203731541758 0.1710273760706686 +-0.5614368059721748 0.0973977351253799 0.1566922547789323 +-0.3759252044357331 0.0156099603600098 0.3811072818299944 +0.05383705383083659 0.2145299440226167 0.3816158270208281 +-0.1619732726120931 0.1330765460643622 0.3981378604129159 +0.3740296575279978 0.2111397287358895 0.05465499176783607 +0.382604670169172 0.2201042797991723 0.1102298907106016 +-0.05959478828599387 0.005930859013459864 -0.5663805162004295 +-0.01717673474360292 -0.03153853481555432 0.4675011682325878 +0.1364068407452007 -0.007277509535040018 0.4931110900239976 +0.385242784587982 0.00493529360549544 0.0469820988995634 +-0.6153711266794439 -0.1812035918895354 -0.2101699509978979 +-0.4726629202983678 -0.003327897542008701 0.3806000630414419 +-0.2761035454032154 0.007953612206295075 -0.3797424360944924 +-0.3888636207135883 -0.007938706908226399 0.04178998606509782 +-0.383278176165127 0.002973667381423688 -0.3690494541521624 +-0.3951191553982251 -0.008625205350272521 0.167258353233485 +-0.3778274958314471 0.097823632437333 0.06631071941621698 +-0.3790763659663187 0.1397429760054126 0.166309023532448 +-0.07173407266451474 -0.01249665451441885 -0.3804837643958644 +0.2877288837036373 0.09196999960831206 0.3768515569196144 +-0.2638412931493026 -0.1036766116893414 0.2391878653767805 +0.5991487400768469 -0.08920454298047388 0.02674751036901173 +0.607540993752861 0.1001621139512669 -0.03389076552791264 +0.5998837187108649 0.08338905575378201 0.04540625595553115 +-0.4743685905329021 0.09628227912602481 0.1566870273403166 +-0.4899423282037244 -0.08777947848176004 0.0496655557590468 +-0.4872238388481392 -0.008111734031781198 0.05133027066828713 +-0.2690792112134239 0.1005271315784323 0.2846467055547287 +-0.1622708114648139 0.01555625283271768 0.5870885011921256 +-0.1696039443719094 0.08373059661137741 0.606094424742615 +-0.4727827962661386 0.08448025899041636 0.06102069089748234 +-0.0605344123561698 0.008905324522109764 -0.4866242428196116 +-0.3815748147572086 0.001616454738300511 0.2542510822105668 +-0.3829317236935794 0.09050305714296698 0.249640564453501 +0.2616995180087382 -0.0944119383604532 0.2673071635684744 +0.2822514647509506 -0.005850493949298635 0.2691987114193257 +0.5935218637257337 0.002482111530269636 -0.3213259738383724 +-0.505464412258112 -0.1833568021761748 -0.3992898990550236 +-0.280967206550657 -0.1069018532045351 -0.2712158017948815 +-0.1161557276237301 0.1330592507396156 0.5699473656025384 +0.1369649530693391 0.1316506868926868 0.5592349600599259 +-0.1563140975 -0.12968538685 -0.247312054 +0.2471092834451507 -0.1351991643392156 -0.1628731266204674 +0.05673806489688069 -0.1305484283378361 -0.2874745836492385 +0.1628260980373148 -0.1376422746858275 -0.2489927473513118 +0.285898666730311 -0.1265875515597322 -0.05186365307744811 +-0.05510728922311799 -0.1288880401778301 -0.2867319091516609 +-0.05504061217906892 -0.1306847878369744 0.287899872612026 +0.05682477422099689 -0.1333662801572196 0.2892682689746576 +0.1581282015648371 -0.1267552300700679 0.2438786222378669 +-0.247312076 -0.12968538685 0.156314045 +0.2422066962597056 -0.1302997933916133 0.164651855644622 +-0.1563140525 -0.12968538685 0.247312076 +-0.1630249122458465 0.1419671064563262 -0.2521384231743916 +-0.289625310045959 -0.1340672575029545 -0.05729459453291589 +-0.2879229197619732 -0.1301596644734891 0.05322815267895153 +0.2896188458856734 0.1357133639383724 -0.06264541548807114 +-0.0627561069358414 0.1340128003260848 -0.2885039532850485 +-0.06003912720029972 0.1284922867886495 0.2854965770306342 +-0.2526884136545073 0.1362608592798777 0.1557278784104276 +-0.1651630450343733 0.1414745578076895 0.2503363810445914 +-0.247311957 0.1296850741 -0.156313896 +-0.2854066045 0.1296850741 -0.06434522086097889 +-0.2821769618407176 0.1225299473665231 0.05746447519469901 +0.2874402478974803 -0.131064917060987 0.05857953496711188 +0.2854065895 0.1296850741 0.064345362760046 +0.09956721556483739 0.008900787700942986 0.3040684694373372 +0.141227164390001 -0.03915237319037788 -0.4606711437015398 +0.7323157185262316 -2.18556941e-08 -0.08890473140017549 +-0.732315708831986 -2.18556941e-08 -0.08890490946352991 +0.08890493042999804 -2.18556941e-08 0.7323156895667963 +-0.08890494921809791 -2.18556941e-08 -0.7323156964349565 +0.08890495872633397 -2.18556941e-08 -0.7323156969995325 +-0.08890496836657437 -2.18556941e-08 0.7323156947198333 +-0.7323156957177165 -2.18556941e-08 0.08890500959611544 +0.7323157060283151 -2.18556941e-08 0.08890520766431409 +0.08886322676908474 -0.247455373 -0.446745351 +-0.08886321373091526 -0.247455373 -0.446745366 +-0.253061019 -0.247455373 -0.378732383 +0.4467454255 -0.247455373 -0.088862923672303 +0.378732547 -0.247455373 -0.2530607585 +0.2530610265 -0.247455373 -0.3787323535 +-0.08886321165025131 -0.247455373 0.446745366 +0.08886316884974869 -0.247455373 0.446745366 +0.253060922 -0.247455373 0.378732428 +0.378732428 -0.247455373 0.2530609295 +-0.3787325175 -0.247455373 -0.253060825 +-0.378732428 -0.247455373 0.253060937 +-0.446745366 -0.247455373 0.08886322906283976 +-0.446745396 -0.247455373 -0.08886309193716024 +0.0888631522690823 0.247455314 -0.4467449785 +-0.08886313923091771 0.247455314 -0.446744993 +-0.2530608105 0.247455314 -0.37873207 +0.446745053 0.247455314 -0.08886284917243099 +0.2610196563250436 0.247455314 -0.3734141119799477 +0.3787322345 0.247455314 -0.2530605495 +-0.0888631371502424 0.247455314 0.446744993 +0.0888630943497576 0.247455314 0.446744993 +0.2530607135 0.247455314 0.378732115 +0.378732115 0.247455314 0.253060721 +-0.446745023 0.247455314 -0.08886302493719224 +-0.378732115 0.247455314 0.2530607285 +-0.446744993 0.247455314 0.08886315456280776 +-0.3787322045 0.247455314 -0.253060624 +-0.253060736 0.247455314 0.378732115 +0.446745366 -0.247455373 0.08886333782769699 +0.446744993 0.247455314 0.088863263327569 +0.6200791714077696 0.03064473749778887 -0.2440277489762376 +-0.2626299684804731 -0.01779926795500601 -0.599686805331662 +-0.6123164101680636 -0.04121299126851069 0.2479495684496193 +-0.6378744981290908 -0.08641631458216771 -0.3245838369211331 +0.3222791452973603 0.06758027157215296 0.6459383261078916 +-0.6432533681683356 -2.18556941e-08 0.3613284019936311 +-0.2395605239587259 0.1861935899383363 -0.4408444524343927 +-0.01815759320534445 -0.1340331295755921 -0.618553481301664 +-0.416173620953785 0.1334507751933589 0.4501201060061978 +-0.4299310368060829 -0.1311833513982786 0.4365280856573984 +0.4154314094009814 -0.1274728968155736 0.4504484112711975 +0.3741153953545832 -0.1242355469020759 -0.0241854340486779 +-0.5578965797509108 0.07758988814764095 0.4488543656622259 +0.066887528377056 0.1134054046445166 -0.3500728402253111 +-0.05292311315347678 0.1260431071072435 0.3580833601168914 +0.3551564114844889 0.1039168763322923 0.03884608765805646 +0.2530163933438245 0.1514527965299385 0.5046020668611034 +0.2170199306452358 0.07035957400422863 -0.6861725016313338 +-0.6886531840337877 0.06831837761274545 0.2075619354184494 +0.2146550888955935 0.06925477135835592 0.6869673050358971 +0.6856670468292471 0.07175132639315042 0.2175067344931936 +-0.6855026363122276 0.06738785333983141 -0.224774707991908 +0.210947856979893 -0.08000473670797401 -0.6845483310126054 +0.6855619969327065 0.07218350698739592 -0.2173972238496296 +0.6854377980262316 -0.06758012992784704 -0.224817394281203 +0.2474381341489587 0.1061938412000234 0.5766180351873803 +0.489503016304909 -0.1785221406910227 0.263169924743284 +0.3037402902914204 -0.1480370568980555 -0.5174410365166965 +-0.4864719094610887 0.1752779821252042 0.2794938371976077 +0.4313217303001755 0.135160565 0.5496715059782117 +-0.5506173006531567 -0.135160238 -0.4299067178972762 +0.1092678841352424 -0.08993497320759923 -0.6208877979904343 +0.3315483361717592 -0.1186488286544302 -0.101273559173753 +-0.05332356464008531 -0.003220860878376586 -0.2495200389000687 +-0.04525869337901792 -0.0002733267622190005 0.2511242429814381 +0.1406911262572085 0.00458300473952665 0.2128336142806865 +-0.212131627 -1.862499999991107e-07 -0.141741749 +0.2502262665 -1.862499999991107e-07 0.049773196710046 +-0.3038750919021984 -0.00420447504443615 0.04991694629414084 +0.3060295077376545 0.01098691065300924 0.05504694712444477 +0.1170500682120619 0.1810802133846133 0.4998806125319112 +0.4856608853215326 0.07434546177884246 -0.4322363107862517 +-0.458826067180756 -0.1539076895358543 -0.2411783655387011 +0.2414409659261295 -0.1395981122085382 -0.4286050346936315 +0.4102733319937368 -0.03911917457333562 0.5089220698446709 +0.6436677085590493 0.05276964120720886 -0.3333546024610379 +-0.6328982967916651 0.06338561222163799 -0.3439693233029654 +0.6393865205766276 -0.06783917936103923 0.3319505522899195 +-0.6254841434299707 -0.07086294435058846 0.3511895693749568 +-0.3416269174305976 -0.06356443637116133 -0.6344016122869763 +0.3434770270001724 -0.06692247982426226 -0.6320022943216725 +-0.3433089855389704 0.06847439970572868 0.631576980383792 +0.01187510501014911 0.09071444418817076 0.3552258624282731 +-0.09777969011320647 0.1858866393441107 0.4930423179985466 +-0.09000200204206606 0.1904619032906356 -0.4874776471335208 +-0.1425452905490057 0.237431735 -0.5057831668270991 +-0.1960150597271896 0.1899289804033522 0.3766604375387921 +0.6036653880207526 -0.1001926936403398 -0.1444334652759952 +-0.5402624007491028 0.1237898832495177 0.2844891380745601 +-0.05006475582362858 -0.01280714490476897 0.3921732275300897 +0.1790506689861273 0.09320743189656971 -0.5309763578678544 +0.6040451972022797 -0.01620572259224715 0.2810845165686729 +0.1895947905490057 -0.135160238 -0.6726005975303229 +0.6726004202115424 0.135160565 0.1895946860490058 +-0.6726006637375268 -0.135160238 -0.1895946565490057 +-0.02211429515907533 0.1594037691029022 0.4252731110919391 +-0.2178001310488206 -0.2187878848473082 0.3282470318331274 +-0.5592332994570895 0.1902521000391926 -0.3047708475982757 +-0.5620171585001306 0.1836874142745606 0.3139790672500916 +0.5719226547333054 -0.184839971894952 0.2968062977771854 +-0.6502893879669944 -0.1778044424086221 -0.05434518036839411 +0.05368215214944767 -0.181284115 -0.6464055185303228 +-0.2158743658231015 0.09526841972257911 -0.2647745309902759 +-0.2114200026182485 0.1010409781318316 0.2608651734868205 +-0.1982647250058633 -0.09896759786522454 0.2555716819455021 +-0.3129920331155432 0.1084669587386941 0.1627058173366869 +-0.1551685730867522 0.1080878068838509 0.3164997837178271 +0.3107971034315091 -0.09707599796195117 -0.154823053830057 +-0.1583120171750342 -0.1054586665971662 0.303083453438425 +0.1842856487044458 0.1328246243631194 0.3071171654625506 +0.3405021210770199 0.1414651450899855 0.1906460150110045 +0.1222497898060191 -0.01459653842951159 0.6716419314541555 +0.6187727551000032 -0.1822425903685795 -0.1870407695448417 +-0.5140658381072688 -0.1017583303142997 -0.1591315148082528 +0.1506872594387387 0.107011086778144 -0.5785905499054989 +-0.4543830012629956 0.02070776700615354 -0.3534233502059753 +0.05208701996476486 0.2369451377659843 0.5271608231354115 +-0.05035418058057255 0.236541723503403 -0.5303113484986198 +-0.0536821586992481 0.237431735 0.5234591482297716 +0.652264938 -2.18556941e-08 -0.347841635 +-0.65226484875 -2.18556941e-08 -0.34784178425 +0.34784194825 -2.18556941e-08 0.652264714 +0.570974946 -2.18556941e-08 0.46950069075 +0.05288088412692972 -0.1696738401445088 0.4812655001975786 +-0.03458365933052948 -0.1696053900123612 0.4469547003571025 +0.5253901567920133 0.01334285814744612 -0.2715949297219139 +0.5008552018403365 0.0008968449184086402 -0.4476622468363466 +-0.4679785893234675 -0.1720388775723341 0.1441529655658877 +0.4608469644229725 -0.1715736804020539 0.1526932380534281 +0.4712710999359984 0.1910190031111572 -0.1336326997259548 +-0.4922261458666373 -0.1795631286234275 -0.1535029704981328 +-0.04003071875929925 -0.01735235223485209 0.6844048178359888 +0.05786895306571511 0.04951594845714467 -0.7239498885560181 +0.2127057635028024 -0.0833398813849658 -0.2538144673578778 +-0.5133981546337892 0.03912537763871422 0.4644387356716861 +0.3773758525022843 -0.1145068351912803 -0.2694092044220085 +0.1576327673835248 -0.00174623569951705 0.3567090232373112 +0.06760794136056919 -0.03105061583133411 -0.4613535665477629 +-0.7234264959800163 -0.05601355432624411 0.0509091710031585 +0.3307809421322569 -0.06714567745126444 0.6404082325370969 +-0.2708684508911888 -0.1157463251588329 0.3750957971723319 +-0.2789744190406261 0.03582508947728972 0.3637404139816443 +0.4699139694816132 0.01791589074177289 0.04241381727681382 +-0.1542487939470152 0.03758487944378665 0.3777753383082115 +0.370206414436605 -0.02919216874927832 0.1646086345337974 +-0.3843560426382542 -0.01459984482335379 -0.05331358427969477 +-0.3756036815077443 0.0655473812595731 0.1739739322222879 +0.3624013269252122 -0.0545436899147785 0.2752232163131648 +-0.4804420812630442 -0.05407407237313248 0.1595268585124839 +-0.1649969073003941 0.07391696382954899 -0.4781800483207995 +0.172943408404652 0.03270492546648051 -0.4770234506938139 +-0.5131791762068501 0.2357481102122256 -0.1642331900472321 +0.4967968321015735 0.01720857935661327 0.2988126091935098 +-0.3058843387849141 -0.09545112865391527 0.1671091894972072 +-0.6105761183708176 -0.01727895628303047 -0.05109497939867216 +-0.1020149918114597 0.1002042812521527 -0.4793742608257536 +0.34784208225 -2.18556941e-08 -0.6522646692499999 + +CELLS 4436 22180 +4 416 356 836 690 +4 0 759 1017 1 +4 0 1 792 759 +4 0 1017 187 876 +4 899 180 560 106 +4 1 665 759 494 +4 667 314 610 668 +4 543 176 732 810 +4 145 370 320 156 +4 10 314 667 588 +4 2 187 668 667 +4 3 563 570 5 +4 812 200 199 553 +4 136 419 424 853 +4 414 573 870 572 +4 193 585 486 379 +4 314 511 10 374 +4 204 477 209 828 +4 492 803 250 1020 +4 6 12 202 730 +4 473 210 597 967 +4 312 296 479 272 +4 6 202 704 786 +4 6 911 202 786 +4 6 202 911 730 +4 22 216 951 1009 +4 10 214 610 21 +4 418 986 799 521 +4 774 400 405 356 +4 808 468 357 833 +4 11 22 951 1009 +4 1025 232 819 818 +4 228 826 819 1025 +4 207 994 608 353 +4 499 146 436 919 +4 953 155 303 919 +4 84 974 632 923 +4 328 1030 643 24 +4 554 212 179 115 +4 735 932 171 909 +4 15 18 755 225 +4 15 18 225 421 +4 525 17 224 352 +4 712 206 210 813 +4 525 224 230 352 +4 352 257 264 796 +4 561 166 929 784 +4 295 392 698 724 +4 617 979 184 1 +4 1027 222 594 817 +4 17 224 401 754 +4 17 352 918 224 +4 483 352 388 796 +4 18 28 225 520 +4 697 829 261 492 +4 1033 668 208 181 +4 752 420 599 266 +4 966 293 991 933 +4 548 991 459 169 +4 19 917 230 712 +4 63 697 395 982 +4 19 917 458 230 +4 478 332 252 426 +4 258 821 558 435 +4 623 557 446 419 +4 21 904 214 232 +4 21 374 610 10 +4 21 733 214 610 +4 21 610 566 733 +4 21 214 733 232 +4 240 589 608 355 +4 23 37 624 219 +4 23 219 1006 12 +4 226 484 536 355 +4 231 34 260 238 +4 25 903 233 636 +4 25 819 232 39 +4 25 636 819 39 +4 826 232 233 819 +4 27 33 220 244 +4 28 371 231 225 +4 28 231 238 34 +4 30 577 856 36 +4 30 857 738 37 +4 30 46 856 577 +4 30 46 577 437 +4 30 46 437 857 +4 30 857 437 738 +4 31 865 253 47 +4 920 445 423 449 +4 127 423 449 920 +4 178 550 744 128 +4 178 694 842 692 +4 178 842 744 692 +4 33 243 889 220 +4 272 115 390 179 +4 33 243 244 1019 +4 179 969 993 312 +4 272 312 179 993 +4 35 262 261 55 +4 723 351 269 182 +4 35 308 262 55 +4 1001 791 158 182 +4 35 262 308 906 +4 953 183 268 303 +4 36 22 344 216 +4 657 401 206 754 +4 37 248 49 857 +4 37 248 1032 49 +4 499 919 303 146 +4 37 790 219 242 +4 37 790 242 1032 +4 303 499 190 415 +4 38 905 643 24 +4 499 116 190 415 +4 728 191 669 503 +4 503 191 669 161 +4 39 818 254 819 +4 40 324 910 42 +4 40 44 538 757 +4 41 43 264 785 +4 41 556 785 746 +4 42 281 647 56 +4 42 245 281 910 +4 42 324 910 281 +4 44 251 757 279 +4 45 310 602 59 +4 46 947 49 47 +4 46 47 253 947 +4 47 49 51 947 +4 47 254 253 947 +4 50 62 945 536 +4 51 697 779 63 +4 68 315 762 72 +4 68 315 641 762 +4 52 480 589 60 +4 72 942 177 74 +4 52 32 888 747 +4 53 61 822 983 +4 53 242 243 822 +4 119 135 427 333 +4 119 333 427 749 +4 584 271 562 403 +4 55 829 697 982 +4 55 829 262 261 +4 558 405 596 821 +4 558 578 138 435 +4 56 281 647 241 +4 57 65 285 603 +4 58 66 330 513 +4 59 310 309 67 +4 59 686 310 67 +4 60 541 945 62 +4 61 781 75 63 +4 61 63 779 781 +4 61 289 983 73 +4 288 132 1000 913 +4 62 541 74 60 +4 62 74 541 981 +4 114 694 949 842 +4 554 212 584 179 +4 179 584 403 271 +4 528 584 271 302 +4 63 297 781 75 +4 63 982 297 75 +4 179 212 584 528 +4 63 395 697 779 +4 55 982 697 63 +4 554 584 403 179 +4 313 511 314 566 +4 314 313 668 620 +4 313 511 620 314 +4 314 313 610 668 +4 566 313 610 314 +4 184 1033 181 763 +4 65 69 975 797 +4 187 763 668 1033 +4 65 69 797 321 +4 537 227 313 208 +4 354 207 307 467 +4 65 884 321 603 +4 960 257 264 270 +4 66 342 963 893 +4 960 264 257 746 +4 960 746 602 45 +4 67 805 965 71 +4 67 343 805 71 +4 67 962 343 898 +4 68 72 848 315 +4 68 64 334 641 +4 69 326 849 73 +4 69 73 987 326 +4 69 284 797 987 +4 404 726 116 415 +4 70 342 306 66 +4 70 342 489 306 +4 404 726 415 416 +4 732 176 644 491 +4 71 75 860 335 +4 71 335 985 75 +4 375 176 644 732 +4 71 923 860 84 +4 360 453 491 644 +4 71 308 985 805 +4 72 177 541 74 +4 72 87 848 438 +4 73 75 781 943 +4 73 849 85 326 +4 73 85 943 326 +4 73 326 289 987 +4 74 358 859 88 +4 74 541 489 177 +4 85 644 375 850 +4 850 198 644 375 +4 75 335 943 86 +4 75 335 985 297 +4 75 297 781 335 +4 76 77 1010 380 +4 76 77 380 277 +4 76 583 767 78 +4 76 1010 767 583 +4 6 347 730 657 +4 77 79 650 664 +4 77 650 329 380 +4 78 760 771 80 +4 78 769 760 80 +4 78 769 580 760 +4 81 83 884 1003 +4 81 83 1003 622 +4 82 995 949 899 +4 82 376 974 611 +4 82 611 974 377 +4 83 375 850 85 +4 83 85 849 375 +4 83 375 849 321 +4 84 86 364 961 +4 84 961 923 86 +4 207 231 328 189 +4 85 86 943 644 +4 86 453 644 868 +4 86 644 335 943 +4 86 335 644 961 +4 87 89 438 845 +4 88 90 363 922 +4 88 922 358 90 +4 88 100 101 387 +4 89 91 565 745 +4 359 528 271 302 +4 359 212 179 528 +4 302 130 271 359 +4 359 212 528 507 +4 302 320 156 362 +4 507 528 302 362 +4 528 320 302 362 +4 176 375 316 1002 +4 316 176 198 375 +4 88 363 100 922 +4 100 363 103 922 +4 112 119 482 103 +4 749 119 482 112 +4 364 86 98 453 +4 364 98 102 453 +4 145 720 320 370 +4 94 666 761 96 +4 365 118 989 134 +4 366 110 118 663 +4 954 171 909 838 +4 95 97 765 381 +4 95 97 381 431 +4 838 909 548 171 +4 102 366 118 988 +4 988 366 118 663 +4 95 324 916 381 +4 869 379 386 1029 +4 506 367 220 657 +4 869 252 1029 386 +4 368 157 292 719 +4 96 311 571 97 +4 368 292 443 719 +4 497 719 368 443 +4 737 490 468 325 +4 18 659 225 369 +4 96 761 311 666 +4 194 479 666 311 +4 950 717 156 370 +4 86 453 868 98 +4 98 405 944 110 +4 129 303 190 415 +4 99 345 111 944 +4 452 155 158 953 +4 100 332 113 101 +4 884 603 65 373 +4 100 101 387 332 +4 683 373 322 884 +4 101 113 1012 332 +4 566 902 374 21 +4 511 902 374 566 +4 98 348 868 99 +4 98 868 348 405 +4 102 576 560 899 +4 178 744 934 128 +4 178 842 934 744 +4 27 220 918 244 +4 105 109 515 952 +4 751 220 243 244 +4 105 319 101 235 +4 107 212 554 115 +4 107 103 339 628 +4 711 382 578 432 +4 711 259 382 432 +4 723 351 382 259 +4 382 282 351 723 +4 110 780 345 111 +4 110 780 111 122 +4 161 555 149 211 +4 110 837 405 345 +4 110 405 837 430 +4 111 836 851 120 +4 111 425 853 124 +4 107 339 554 212 +4 339 410 212 107 +4 112 113 332 346 +4 100 112 482 103 +4 302 320 350 156 +4 362 320 156 145 +4 1012 323 332 346 +4 113 1012 332 346 +4 113 112 123 346 +4 969 179 390 554 +4 213 529 327 322 +4 809 176 732 543 +4 1016 869 379 386 +4 278 691 744 990 +4 278 744 689 277 +4 278 990 744 277 +4 992 200 216 537 +4 166 723 561 391 +4 391 723 561 269 +4 200 537 221 216 +4 568 517 390 892 +4 517 568 631 892 +4 118 558 559 138 +4 119 482 103 628 +4 959 133 434 562 +4 959 562 434 420 +4 122 124 946 780 +4 122 126 867 429 +4 122 429 948 126 +4 436 452 614 919 +4 919 452 614 953 +4 123 428 858 126 +4 46 47 50 253 +4 124 424 127 946 +4 124 424 866 127 +4 124 136 866 424 +4 424 789 425 419 +4 125 127 847 423 +4 125 941 847 137 +4 125 137 986 941 +4 126 924 142 867 +4 126 428 858 142 +4 126 924 428 142 +4 126 948 428 429 +4 206 754 401 813 +4 754 224 401 813 +4 129 1018 278 132 +4 276 218 642 839 +4 614 953 452 349 +4 129 415 116 705 +4 129 303 415 1018 +4 839 26 218 642 +4 130 562 312 133 +4 452 953 158 349 +4 131 133 434 959 +4 547 679 831 841 +4 134 341 989 429 +4 134 989 341 148 +4 547 679 841 686 +4 135 142 858 736 +4 15 421 225 600 +4 135 119 625 333 +4 136 150 1007 446 +4 524 600 648 422 +4 648 600 15 422 +4 458 917 257 230 +4 136 789 424 419 +4 136 446 789 419 +4 678 458 263 257 +4 263 917 257 458 +4 137 151 882 799 +4 137 151 799 445 +4 137 986 941 799 +4 793 1004 463 236 +4 237 293 572 173 +4 141 147 417 443 +4 141 417 591 443 +4 731 548 459 169 +4 142 736 428 858 +4 142 455 924 428 +4 142 428 736 455 +4 719 731 459 169 +4 143 153 445 920 +4 156 320 350 950 +4 144 154 652 282 +4 144 578 435 138 +4 144 578 282 435 +4 231 484 535 238 +4 231 535 371 238 +4 966 459 593 393 +4 433 593 966 459 +4 85 644 850 99 +4 99 198 644 850 +4 40 442 413 671 +4 184 553 354 181 +4 239 207 354 467 +4 677 671 413 442 +4 448 132 278 691 +4 150 162 1007 935 +4 448 691 278 300 +4 150 935 1007 446 +4 151 546 445 881 +4 207 189 467 239 +4 240 355 484 226 +4 152 721 512 164 +4 61 779 63 51 +4 153 445 920 460 +4 155 753 452 158 +4 155 919 452 713 +4 156 950 350 159 +4 159 292 599 157 +4 159 599 292 1005 +4 280 396 403 1029 +4 113 123 125 346 +4 1029 396 403 478 +4 123 428 126 125 +4 52 255 589 840 +4 22 216 36 951 +4 255 52 48 36 +4 125 126 127 428 +4 36 216 255 951 +4 164 773 824 172 +4 165 173 237 651 +4 106 258 180 560 +4 774 821 405 560 +4 170 561 929 758 +4 140 416 404 436 +4 404 146 140 436 +4 166 582 561 259 +4 112 482 749 332 +4 735 414 788 909 +4 351 1031 456 259 +4 167 788 669 909 +4 878 515 193 319 +4 168 170 539 956 +4 878 319 193 89 +4 302 130 562 271 +4 508 701 469 652 +4 235 121 591 323 +4 701 349 469 652 +4 925 701 469 508 +4 105 235 121 883 +4 170 539 970 758 +4 621 876 2 188 +4 876 188 187 2 +4 354 763 930 615 +4 172 825 773 824 +4 538 44 251 757 +4 538 670 910 251 +4 173 237 651 823 +4 173 823 572 237 +4 170 561 970 269 +4 170 956 269 970 +4 270 458 960 257 +4 185 204 203 477 +4 187 477 203 208 +4 203 828 208 477 +4 296 272 96 666 +4 207 307 467 328 +4 154 791 282 182 +4 282 791 452 351 +4 349 282 791 452 +4 349 154 791 282 +4 28 231 371 238 +4 330 915 724 66 +4 330 915 66 58 +4 28 520 504 273 +4 77 650 380 664 +4 274 213 322 529 +4 933 991 548 169 +4 275 357 606 331 +4 966 991 548 933 +4 677 770 761 96 +4 939 283 839 16 +4 277 77 380 664 +4 378 300 278 277 +4 56 64 281 241 +4 241 334 64 281 +4 129 415 705 278 +4 281 318 641 64 +4 129 278 705 300 +4 58 66 513 964 +4 44 279 413 706 +4 279 606 331 275 +4 44 279 706 58 +4 795 131 581 434 +4 737 325 820 490 +4 869 386 1016 319 +4 722 150 162 1007 +4 282 578 526 435 +4 907 150 722 1007 +4 880 241 334 64 +4 64 680 880 241 +4 129 415 278 1018 +4 288 132 1018 1000 +4 288 1018 217 1000 +4 217 1018 268 1000 +4 573 173 572 293 +4 104 108 886 726 +4 649 294 324 95 +4 926 312 130 296 +4 681 879 318 64 +4 148 514 721 160 +4 148 721 514 908 +4 650 77 329 301 +4 639 904 518 214 +4 639 215 518 14 +4 639 214 518 215 +4 519 114 694 949 +4 899 694 949 519 +4 304 704 786 6 +4 651 305 173 742 +4 173 782 742 305 +4 184 181 354 763 +4 537 467 313 226 +4 467 313 226 643 +4 307 551 7 930 +4 314 511 374 566 +4 21 566 610 374 +4 311 357 379 699 +4 566 314 610 374 +4 479 311 379 699 +4 97 431 1011 311 +4 163 719 497 459 +4 743 479 379 312 +4 312 562 434 133 +4 312 403 699 379 +4 163 719 459 169 +4 312 479 379 699 +4 696 133 312 434 +4 459 719 497 443 +4 427 555 454 439 +4 736 427 555 454 +4 181 313 668 208 +4 763 307 620 313 +4 610 313 208 668 +4 315 942 177 72 +4 315 820 325 177 +4 315 72 848 438 +4 848 89 737 438 +4 596 578 526 456 +4 596 821 526 578 +4 478 426 252 396 +4 396 426 252 532 +4 179 528 584 271 +4 359 528 179 271 +4 359 528 302 507 +4 528 320 584 302 +4 353 196 276 563 +4 563 276 353 608 +4 682 317 27 658 +4 27 682 244 317 +4 319 869 386 252 +4 145 720 212 320 +4 720 236 748 320 +4 701 217 469 349 +4 701 934 925 217 +4 925 217 175 186 +4 925 934 175 217 +4 469 217 186 349 +4 346 121 1012 323 +4 113 121 1012 346 +4 123 427 428 125 +4 125 428 127 423 +4 13 976 510 328 +4 58 330 727 279 +4 320 950 236 197 +4 252 386 387 478 +4 72 177 480 541 +4 541 246 534 740 +4 139 720 212 145 +4 68 334 481 762 +4 32 241 747 334 +4 241 246 334 475 +4 52 334 481 68 +4 334 32 52 747 +4 339 103 482 628 +4 564 340 512 152 +4 340 429 811 587 +4 148 807 341 134 +4 989 441 430 429 +4 341 587 429 340 +4 148 908 514 341 +4 809 543 360 361 +4 361 689 543 389 +4 361 543 360 389 +4 213 689 543 361 +4 213 543 809 361 +4 200 216 221 344 +4 677 442 413 44 +4 677 44 413 706 +4 679 556 547 831 +4 621 927 783 549 +4 549 707 783 621 +4 178 692 744 550 +4 30 344 577 36 +4 692 744 550 928 +4 307 620 551 930 +4 82 377 974 576 +4 551 307 709 620 +4 360 389 453 377 +4 185 204 477 188 +4 185 801 204 188 +4 82 576 974 84 +4 552 932 728 788 +4 185 201 203 204 +4 728 552 669 191 +4 728 788 669 552 +4 5 973 812 553 +4 98 99 944 348 +4 98 405 348 944 +4 99 851 111 345 +4 345 836 851 111 +4 345 836 690 397 +4 184 200 553 181 +4 187 188 477 208 +4 112 123 346 749 +4 1033 763 668 181 +4 346 125 986 423 +4 203 828 477 204 +4 188 209 801 204 +4 188 208 209 477 +4 188 801 209 473 +4 137 418 986 799 +4 188 214 802 209 +4 188 209 208 214 +4 365 118 663 989 +4 348 851 198 99 +4 348 99 345 851 +4 348 690 397 345 +4 288 400 175 614 +4 415 400 776 288 +4 415 614 400 288 +4 288 776 810 400 +4 288 175 400 810 +4 212 720 748 320 +4 139 720 748 212 +4 349 953 158 542 +4 938 349 652 154 +4 542 154 158 349 +4 777 708 514 582 +4 584 396 420 350 +4 777 721 514 708 +4 350 562 420 584 +4 791 158 452 753 +4 1001 753 158 791 +4 270 352 257 264 +4 353 196 563 207 +4 5 553 199 563 +4 41 264 658 270 +4 41 960 264 270 +4 7 655 930 3 +4 850 316 198 375 +4 104 316 198 850 +4 40 44 757 413 +4 201 203 204 827 +4 201 222 827 204 +4 202 219 1027 205 +4 279 275 590 413 +4 188 209 204 477 +4 203 200 537 221 +4 204 1027 801 205 +4 477 208 209 828 +4 204 222 828 209 +4 205 801 597 372 +4 205 219 1027 476 +4 206 813 223 210 +4 206 220 223 401 +4 200 992 181 537 +4 209 208 214 832 +4 209 222 828 594 +4 8 215 967 473 +4 210 228 223 372 +4 210 229 813 223 +4 210 223 228 229 +4 210 813 229 712 +4 210 234 712 229 +4 92 390 612 94 +4 92 390 568 612 +4 92 568 390 892 +4 92 501 390 94 +4 501 390 892 92 +4 328 313 1030 13 +4 207 231 994 225 +4 826 215 228 233 +4 353 15 196 267 +4 353 15 939 196 +4 608 246 189 355 +4 189 231 484 535 +4 355 589 246 533 +4 22 216 1009 344 +4 175 400 774 614 +4 821 435 526 578 +4 186 526 821 435 +4 506 27 889 220 +4 218 888 32 747 +4 500 447 140 146 +4 407 447 140 500 +4 115 390 107 501 +4 501 390 107 892 +4 221 815 828 222 +4 221 226 227 1024 +4 221 815 1024 227 +4 895 152 466 503 +4 503 152 466 164 +4 223 243 476 834 +4 223 250 803 224 +4 223 224 751 250 +4 223 250 834 229 +4 224 813 230 803 +4 224 483 803 230 +4 224 244 751 483 +4 161 211 409 502 +4 643 328 24 905 +4 226 247 355 536 +4 508 144 435 411 +4 226 247 488 1024 +4 228 826 233 819 +4 228 817 594 1025 +4 228 229 834 835 +4 826 1025 594 232 +4 228 835 819 233 +4 228 1025 834 817 +4 534 306 238 260 +4 238 306 34 260 +4 279 413 590 757 +4 229 492 250 834 +4 230 256 483 803 +4 728 503 466 164 +4 230 917 257 256 +4 728 466 824 164 +4 728 824 172 164 +4 2 668 620 588 +4 588 314 668 620 +4 314 511 620 588 +4 444 459 384 546 +4 546 593 459 384 +4 364 86 453 961 +4 364 453 102 576 +4 32 241 334 880 +4 242 822 249 243 +4 243 1019 751 244 +4 244 285 388 682 +4 249 395 492 250 +4 249 289 243 822 +4 886 726 404 416 +4 726 397 416 886 +4 28 520 371 225 +4 28 371 520 273 +4 371 493 251 273 +4 493 246 475 814 +4 238 273 34 306 +4 256 492 262 1020 +4 256 796 1020 298 +4 251 475 287 295 +4 287 251 295 590 +4 287 590 910 251 +4 245 287 251 475 +4 910 287 251 245 +4 273 34 306 894 +4 205 801 372 1027 +4 205 476 1027 372 +4 209 1027 594 372 +4 378 278 689 277 +4 601 824 472 487 +4 870 728 472 601 +4 728 601 824 472 +4 870 472 487 601 +4 809 968 327 360 +4 82 376 962 974 +4 337 343 841 376 +4 337 361 376 605 +4 389 377 842 180 +4 82 995 377 949 +4 361 389 377 607 +4 870 487 174 601 +4 96 97 571 873 +4 96 873 571 677 +4 0 876 187 2 +4 284 289 797 987 +4 286 688 290 291 +4 602 310 309 59 +4 602 309 257 678 +4 602 310 299 309 +4 602 299 257 309 +4 57 603 285 286 +4 57 603 286 322 +4 475 457 814 246 +4 603 285 286 322 +4 287 325 1028 295 +4 287 687 325 318 +4 246 814 534 740 +4 257 309 299 796 +4 290 297 298 1022 +4 290 327 1022 336 +4 257 299 746 796 +4 291 337 290 299 +4 291 830 337 299 +4 722 153 460 165 +4 153 461 460 569 +4 907 153 569 461 +4 153 907 722 461 +4 724 342 66 306 +4 724 306 392 342 +4 724 330 66 513 +4 724 342 513 66 +4 295 325 1028 698 +4 306 342 489 392 +4 76 380 1010 583 +4 297 1022 308 298 +4 298 308 309 805 +4 299 336 337 290 +4 76 380 583 277 +4 329 274 322 529 +4 380 274 361 689 +4 381 97 765 571 +4 381 97 311 431 +4 324 486 687 318 +4 66 963 342 513 +4 656 281 245 241 +4 236 426 522 439 +4 439 384 383 1004 +4 384 393 593 459 +4 445 460 385 449 +4 445 460 593 385 +4 385 394 460 593 +4 449 460 385 675 +4 460 385 675 394 +4 184 1033 200 181 +4 203 181 537 200 +4 244 751 483 1019 +4 388 290 286 285 +4 810 732 389 491 +4 378 176 689 776 +4 936 795 420 702 +4 689 744 361 583 +4 583 580 744 361 +4 322 688 329 529 +4 322 529 327 688 +4 447 462 729 451 +4 215 937 233 14 +4 233 215 214 826 +4 325 331 698 833 +4 518 215 233 14 +4 518 214 233 215 +4 280 795 434 420 +4 177 820 325 392 +4 246 814 740 457 +4 795 959 434 420 +4 295 392 325 698 +4 392 698 820 325 +4 420 795 959 702 +4 324 808 275 331 +4 331 778 606 1034 +4 572 394 472 414 +4 700 952 936 117 +4 173 742 572 823 +4 414 393 394 472 +4 394 675 487 464 +4 335 360 343 336 +4 968 336 327 360 +4 336 360 343 337 +4 336 337 327 360 +4 337 361 605 338 +4 337 343 376 360 +4 337 361 360 376 +4 337 360 809 327 +4 698 490 820 325 +4 698 325 833 490 +4 63 781 395 779 +4 63 395 781 297 +4 347 12 730 220 +4 12 506 220 347 +4 952 417 396 532 +4 43 264 286 646 +4 646 286 682 264 +4 42 281 656 647 +4 647 281 656 241 +4 527 656 241 647 +4 117 131 795 702 +4 117 795 936 702 +4 236 211 439 463 +4 370 717 236 950 +4 236 463 439 1004 +4 8 662 967 977 +4 602 59 309 678 +4 45 59 602 678 +4 263 59 678 309 +4 263 59 531 678 +4 504 674 58 727 +4 44 674 727 58 +4 7 207 307 655 +4 655 7 207 955 +4 655 207 354 563 +4 196 563 207 655 +4 207 267 196 655 +4 267 207 955 655 +4 307 207 354 655 +4 399 153 165 460 +4 715 884 1003 81 +4 318 468 687 325 +4 888 402 22 951 +4 886 108 404 726 +4 915 406 66 58 +4 407 935 162 150 +4 64 879 318 565 +4 889 27 33 220 +4 149 503 1008 161 +4 64 565 318 641 +4 161 211 149 409 +4 366 110 663 405 +4 988 366 663 405 +4 339 896 410 107 +4 410 145 139 212 +4 900 258 411 106 +4 411 144 435 138 +4 110 663 405 430 +4 988 663 558 405 +4 663 405 430 596 +4 412 29 234 35 +4 28 510 231 34 +4 328 1030 24 13 +4 458 525 230 352 +4 325 833 490 468 +4 334 641 64 281 +4 334 475 641 281 +4 40 413 910 324 +4 176 732 810 491 +4 40 413 324 671 +4 571 671 324 413 +4 571 413 324 275 +4 354 763 615 184 +4 930 354 615 3 +4 3 354 615 570 +4 735 933 909 171 +4 167 788 909 932 +4 238 273 306 295 +4 915 306 724 66 +4 361 389 360 377 +4 86 868 644 99 +4 98 868 86 99 +4 583 580 760 78 +4 583 78 574 580 +4 689 744 389 361 +4 95 431 381 579 +4 431 379 479 311 +4 381 311 357 379 +4 575 579 431 95 +4 743 431 379 479 +4 138 711 578 901 +4 559 138 578 901 +4 387 101 319 332 +4 165 399 460 433 +4 386 252 1029 478 +4 399 151 546 163 +4 312 403 379 434 +4 743 434 312 379 +4 931 131 434 581 +4 170 166 929 561 +4 689 543 389 810 +4 693 726 116 108 +4 758 474 470 465 +4 784 561 582 758 +4 379 1029 699 386 +4 517 339 554 107 +4 517 103 339 107 +4 991 433 966 459 +4 146 436 919 447 +4 415 499 404 436 +4 436 447 356 452 +4 186 217 175 614 +4 186 175 774 614 +4 102 899 560 106 +4 437 46 947 248 +4 54 714 260 981 +4 714 981 533 260 +4 738 221 222 815 +4 437 815 1024 221 +4 738 248 815 222 +4 72 87 438 942 +4 714 536 260 533 +4 54 863 260 714 +4 863 714 536 260 +4 315 72 438 942 +4 315 737 325 820 +4 774 405 400 440 +4 405 560 440 774 +4 360 389 491 453 +4 365 663 430 989 +4 989 663 430 559 +4 341 587 441 429 +4 110 663 430 365 +4 429 441 450 587 +4 441 800 451 450 +4 663 596 430 559 +4 341 432 514 148 +4 89 845 319 438 +4 89 105 319 845 +4 89 193 438 319 +4 693 81 79 1002 +4 681 91 318 879 +4 683 884 322 715 +4 637 775 201 408 +4 637 9 201 775 +4 553 239 199 563 +4 84 961 364 576 +4 364 961 453 576 +4 218 241 283 246 +4 886 416 140 557 +4 218 32 241 747 +4 886 557 140 120 +4 416 557 436 140 +4 415 303 953 217 +4 415 953 614 217 +4 98 453 868 405 +4 1015 440 400 405 +4 440 453 560 405 +4 56 64 241 680 +4 7 655 307 930 +4 560 106 258 900 +4 558 578 559 138 +4 307 655 354 930 +4 405 821 356 596 +4 68 334 762 641 +4 287 325 295 457 +4 457 295 392 325 +4 457 177 325 392 +4 360 732 644 491 +4 968 732 644 360 +4 809 732 360 543 +4 543 732 360 389 +4 732 360 389 491 +4 968 360 809 732 +4 232 233 214 826 +4 518 904 232 214 +4 518 214 232 233 +4 152 512 466 164 +4 152 564 466 512 +4 895 152 564 466 +4 417 443 532 591 +4 419 446 789 425 +4 222 828 594 815 +4 222 248 815 594 +4 594 227 832 818 +4 370 950 320 156 +4 39 232 818 819 +4 594 248 815 254 +4 346 986 521 423 +4 418 521 1014 323 +4 418 444 882 1014 +4 423 384 445 799 +4 423 445 384 385 +4 423 385 449 445 +4 424 1023 780 425 +4 424 948 429 811 +4 424 450 811 429 +4 425 780 430 1023 +4 425 446 1023 451 +4 356 837 456 1026 +4 356 447 1026 673 +4 356 452 447 673 +4 302 195 562 1035 +4 960 746 257 602 +4 602 678 257 960 +4 746 299 257 602 +4 425 451 1023 430 +4 430 441 451 1023 +4 430 451 441 456 +4 425 451 430 1026 +4 1026 430 456 451 +4 428 449 423 455 +4 429 430 1023 441 +4 429 450 811 587 +4 603 884 321 322 +4 884 322 603 373 +4 373 322 603 57 +4 603 285 322 321 +4 20 30 613 567 +4 344 613 20 30 +4 613 30 221 567 +4 344 221 613 30 +4 17 224 918 401 +4 657 367 401 17 +4 989 432 341 148 +4 240 467 537 226 +4 467 484 226 240 +4 467 643 226 484 +4 505 200 1009 199 +4 5 812 199 553 +4 202 1027 204 205 +4 185 204 205 202 +4 318 486 687 468 +4 446 729 451 447 +4 446 450 451 798 +4 446 729 798 451 +4 196 563 655 741 +4 912 563 196 741 +4 1031 561 462 495 +4 655 267 196 741 +4 441 471 465 514 +4 441 451 800 471 +4 651 305 742 470 +4 1031 495 462 451 +4 742 782 470 305 +4 742 470 487 823 +4 439 454 384 463 +4 742 823 651 470 +4 742 487 470 782 +4 4 914 911 473 +4 473 205 801 597 +4 8 967 210 473 +4 454 592 385 384 +4 8 4 473 914 +4 449 1021 811 450 +4 967 215 228 597 +4 449 385 423 455 +4 450 451 798 800 +4 285 797 290 327 +4 285 327 322 321 +4 322 285 290 327 +4 285 797 327 321 +4 45 556 746 831 +4 451 750 729 798 +4 831 556 746 830 +4 447 462 451 673 +4 476 242 1032 249 +4 455 1021 464 512 +4 223 224 918 751 +4 224 751 244 918 +4 194 479 296 666 +4 117 936 280 952 +4 272 666 479 390 +4 194 479 312 296 +4 143 127 739 920 +4 847 127 143 920 +4 127 449 428 811 +4 739 127 811 449 +4 423 449 428 127 +4 507 212 528 362 +4 212 320 528 362 +4 346 521 485 427 +4 387 100 482 103 +4 480 740 246 541 +4 481 740 457 246 +4 52 334 747 481 +4 481 740 246 480 +4 119 748 628 139 +4 339 628 748 139 +4 40 757 538 910 +4 384 463 454 592 +4 460 823 675 461 +4 385 454 464 592 +4 460 823 394 675 +4 538 757 251 910 +4 40 757 910 413 +4 387 332 478 482 +4 224 352 483 230 +4 224 244 483 317 +4 230 256 257 483 +4 244 483 317 388 +4 707 639 667 621 +4 483 796 256 257 +4 707 667 188 621 +4 264 291 388 796 +4 454 592 466 464 +4 454 463 466 592 +4 464 465 487 825 +4 91 318 565 745 +4 879 91 318 565 +4 328 231 484 189 +4 723 259 382 711 +4 723 259 711 160 +4 346 323 521 418 +4 787 461 729 750 +4 598 787 461 729 +4 798 750 729 461 +4 598 729 461 162 +4 1007 162 461 729 +4 1007 729 461 798 +4 95 579 381 916 +4 381 379 357 468 +4 658 17 918 27 +4 658 17 352 918 +4 394 487 824 464 +4 658 918 317 27 +4 658 918 352 317 +4 38 260 488 643 +4 226 247 536 488 +4 50 863 488 38 +4 70 74 489 859 +4 70 342 859 489 +4 319 490 358 386 +4 319 1016 490 386 +4 568 386 358 490 +4 90 922 358 568 +4 491 810 176 400 +4 491 176 198 400 +4 689 176 543 810 +4 491 389 810 440 +4 491 1015 400 198 +4 491 440 400 1015 +4 701 217 925 469 +4 925 217 186 469 +4 925 469 186 435 +4 137 882 418 799 +4 799 882 418 444 +4 229 492 835 234 +4 492 395 829 1020 +4 250 395 492 1020 +4 492 261 262 829 +4 367 918 401 17 +4 367 220 401 918 +4 731 383 719 459 +4 292 383 443 719 +4 719 383 443 459 +4 292 383 719 731 +4 385 464 454 455 +4 385 464 455 1021 +4 385 1021 675 464 +4 746 299 310 831 +4 746 310 299 602 +4 225 493 251 371 +4 836 1026 425 837 +4 836 557 425 1026 +4 837 430 1026 425 +4 517 390 107 554 +4 892 517 390 107 +4 554 115 390 107 +4 718 775 637 408 +4 718 9 637 775 +4 9 775 613 201 +4 471 582 495 465 +4 471 465 495 800 +4 209 826 214 802 +4 802 214 215 826 +4 802 826 597 209 +4 802 597 826 215 +4 775 567 201 890 +4 775 567 613 201 +4 775 408 890 201 +4 537 226 313 227 +4 991 163 433 459 +4 566 226 227 313 +4 537 227 221 226 +4 572 394 414 966 +4 456 432 259 471 +4 496 703 586 117 +4 163 497 398 459 +4 165 399 433 498 +4 3 7 655 955 +4 4 653 911 6 +4 4 6 911 957 +4 293 498 165 433 +4 5 11 199 812 +4 499 146 404 436 +4 162 935 407 500 +4 162 978 935 500 +4 501 115 390 272 +4 10 639 214 21 +4 504 727 58 406 +4 493 251 475 245 +4 251 493 475 295 +4 506 27 220 367 +4 507 212 362 145 +4 507 145 410 212 +4 16 527 283 26 +4 17 367 918 27 +4 508 652 435 144 +4 18 369 225 28 +4 234 509 523 29 +4 19 531 917 29 +4 509 29 234 412 +4 510 28 231 369 +4 511 13 313 709 +4 511 13 1030 313 +4 239 354 181 467 +4 745 486 468 193 +4 745 93 486 585 +4 193 486 468 379 +4 878 109 496 515 +4 93 496 585 745 +4 455 340 1021 512 +4 279 513 331 606 +4 510 24 328 905 +4 295 306 392 724 +4 891 22 344 36 +4 1028 513 331 279 +4 513 606 1034 331 +4 514 340 587 341 +4 341 441 587 514 +4 35 906 308 635 +4 37 889 219 23 +4 514 512 465 340 +4 40 42 910 958 +4 40 294 324 42 +4 41 43 785 545 +4 42 540 281 56 +4 745 515 585 193 +4 585 515 379 193 +4 43 646 286 57 +4 43 544 57 286 +4 52 619 334 68 +4 759 203 187 477 +4 53 69 284 975 +4 54 38 260 863 +4 1017 187 477 759 +4 187 1017 477 876 +4 876 477 187 188 +4 59 67 309 906 +4 41 785 264 746 +4 746 785 264 291 +4 36 216 577 247 +4 76 766 1010 77 +4 36 247 255 216 +4 76 766 875 1010 +4 386 478 517 387 +4 387 103 482 517 +4 85 644 326 375 +4 82 804 576 84 +4 966 991 293 433 +4 991 498 293 433 +4 212 320 362 145 +4 93 95 916 980 +4 102 84 576 804 +4 127 811 948 424 +4 739 127 424 811 +4 127 811 428 948 +4 106 633 560 102 +4 18 520 225 421 +4 520 251 727 273 +4 520 251 371 225 +4 520 371 251 273 +4 660 421 520 18 +4 520 674 727 251 +4 465 777 582 474 +4 582 784 708 166 +4 117 280 936 795 +4 510 369 231 659 +4 225 659 231 369 +4 659 231 207 225 +4 659 976 207 231 +4 659 510 976 231 +4 120 136 419 623 +4 715 81 1003 1002 +4 715 1003 322 213 +4 129 132 278 448 +4 715 1002 1003 213 +4 300 277 77 764 +4 138 144 578 711 +4 44 279 757 413 +4 139 409 720 145 +4 279 275 331 590 +4 146 595 919 155 +4 147 417 292 157 +4 147 157 292 368 +4 195 350 159 156 +4 149 895 1008 503 +4 748 236 426 320 +4 130 1035 562 133 +4 130 302 562 1035 +4 157 159 292 661 +4 478 426 396 320 +4 478 426 320 748 +4 478 396 584 320 +4 212 478 584 320 +4 212 478 320 748 +4 384 459 383 548 +4 444 443 383 459 +4 166 391 561 170 +4 925 949 180 842 +4 106 925 949 180 +4 539 170 970 956 +4 168 604 539 170 +4 168 598 162 729 +4 269 351 791 182 +4 173 174 572 782 +4 351 791 452 753 +4 269 753 791 351 +4 174 487 877 609 +4 224 317 483 352 +4 483 257 352 796 +4 182 351 791 282 +4 1014 444 443 383 +4 726 316 622 1002 +4 1014 383 443 522 +4 30 221 738 437 +4 30 437 577 221 +4 521 444 383 384 +4 567 30 221 738 +4 521 439 383 522 +4 8 967 215 14 +4 30 344 221 577 +4 937 14 977 509 +4 43 264 785 286 +4 388 286 290 291 +4 2 187 620 668 +4 187 620 668 763 +4 323 485 522 426 +4 349 452 614 526 +4 282 456 452 526 +4 356 526 452 456 +4 614 452 356 526 +4 578 711 144 382 +4 423 521 384 799 +4 288 928 128 744 +4 128 132 288 913 +4 450 676 1021 587 +4 676 464 465 487 +4 132 928 128 288 +4 758 750 465 470 +4 451 800 750 798 +4 461 470 676 750 +4 800 465 495 750 +4 128 288 744 934 +4 758 750 495 465 +4 128 288 934 913 +4 203 537 208 221 +4 203 181 208 537 +4 283 816 225 994 +4 600 493 241 245 +4 283 493 246 241 +4 493 475 241 245 +4 381 324 687 808 +4 381 468 808 687 +4 324 331 687 808 +4 331 325 687 833 +4 687 468 833 325 +4 493 475 246 241 +4 213 809 327 529 +4 329 274 529 361 +4 529 809 327 337 +4 274 213 689 378 +4 380 274 689 378 +4 277 380 689 378 +4 213 378 176 689 +4 359 130 271 179 +4 302 350 195 156 +4 532 522 426 323 +4 62 945 536 541 +4 484 238 260 533 +4 534 306 295 238 +4 534 295 306 392 +4 534 489 392 306 +4 621 794 188 927 +4 876 188 621 794 +4 656 600 241 245 +4 656 527 241 600 +4 355 535 533 246 +4 225 816 535 994 +4 488 50 536 863 +4 484 536 533 260 +4 151 444 546 459 +4 398 151 163 459 +4 151 163 459 546 +4 151 459 398 444 +4 563 276 608 951 +4 608 218 276 283 +4 276 218 608 951 +4 280 795 581 434 +4 117 795 586 280 +4 586 795 581 280 +4 15 421 600 648 +4 648 421 600 251 +4 382 711 144 723 +4 382 144 282 723 +4 825 465 487 474 +4 229 835 492 834 +4 249 395 697 492 +4 168 539 729 956 +4 168 787 729 539 +4 112 332 749 346 +4 332 323 532 426 +4 485 332 426 323 +4 60 480 589 541 +4 541 589 533 246 +4 541 534 246 533 +4 217 268 542 701 +4 349 217 542 701 +4 938 154 542 349 +4 883 235 121 591 +4 328 307 467 313 +4 43 658 264 646 +4 646 264 682 658 +4 223 243 834 250 +4 834 243 249 250 +4 283 493 241 600 +4 546 460 445 153 +4 546 433 459 593 +4 399 546 460 433 +4 546 153 399 460 +4 548 171 909 933 +4 280 434 379 403 +4 723 561 259 166 +4 785 264 291 286 +4 56 318 281 64 +4 56 681 318 64 +4 540 318 281 56 +4 681 56 318 540 +4 115 212 179 359 +4 554 584 478 403 +4 386 390 554 1029 +4 386 478 1029 554 +4 179 115 390 554 +4 211 463 555 439 +4 555 454 463 466 +4 439 463 555 454 +4 281 318 287 641 +4 641 325 287 457 +4 641 325 318 287 +4 397 836 557 120 +4 419 446 425 557 +4 430 596 456 432 +4 989 901 432 148 +4 41 658 264 43 +4 560 405 558 821 +4 560 633 988 102 +4 8 215 473 783 +4 215 707 783 8 +4 430 432 441 989 +4 430 559 432 989 +4 561 970 758 170 +4 121 141 591 882 +4 561 462 495 970 +4 121 418 137 882 +4 121 882 591 418 +4 878 109 515 105 +4 878 515 319 105 +4 878 105 319 89 +4 3 655 354 563 +4 563 354 239 207 +4 741 563 655 3 +4 264 746 796 257 +4 142 455 736 564 +4 564 464 455 454 +4 630 736 564 142 +4 565 318 325 468 +4 565 737 468 325 +4 1003 83 321 375 +4 1003 321 322 327 +4 1003 213 327 322 +4 1003 327 213 375 +4 226 643 313 566 +4 24 643 634 902 +4 567 222 827 201 +4 922 568 90 631 +4 143 569 920 739 +4 569 449 450 675 +4 640 739 569 143 +4 319 387 386 358 +4 319 386 387 252 +4 571 808 275 324 +4 735 573 414 293 +4 572 487 472 394 +4 870 572 174 487 +4 82 899 576 804 +4 102 804 576 899 +4 901 118 559 138 +4 989 901 118 559 +4 989 134 118 901 +4 148 134 989 901 +4 735 728 472 870 +4 414 573 572 293 +4 870 573 174 572 +4 908 152 340 806 +4 76 574 872 583 +4 148 908 341 807 +4 743 379 431 940 +4 874 431 97 575 +4 908 806 340 807 +4 908 340 341 807 +4 577 344 221 216 +4 902 1030 24 643 +4 46 253 50 247 +4 437 46 247 253 +4 437 253 247 1024 +4 1024 247 488 253 +4 596 578 456 432 +4 579 431 381 379 +4 940 379 431 579 +4 93 916 486 585 +4 579 379 381 486 +4 93 916 585 980 +4 580 607 389 361 +4 361 580 744 389 +4 744 842 389 580 +4 105 515 319 952 +4 105 319 235 952 +4 319 515 252 952 +4 319 252 235 952 +4 796 299 291 290 +4 796 298 299 290 +4 943 75 781 335 +4 280 581 379 434 +4 943 335 781 326 +4 743 581 434 379 +4 940 743 379 581 +4 582 758 465 474 +4 939 283 16 15 +4 582 495 465 758 +4 283 16 15 600 +4 563 276 627 629 +4 292 197 443 383 +4 583 380 361 689 +4 197 522 443 383 +4 96 311 761 571 +4 381 571 324 808 +4 381 571 357 311 +4 197 236 383 192 +4 292 197 383 192 +4 197 236 522 383 +4 950 192 236 197 +4 705 776 726 378 +4 212 584 478 554 +4 590 275 331 324 +4 910 413 590 324 +4 287 324 910 590 +4 287 331 324 590 +4 413 275 590 324 +4 745 585 486 193 +4 585 579 486 379 +4 585 579 379 940 +4 238 493 273 295 +4 371 238 493 273 +4 181 354 313 467 +4 471 514 582 465 +4 465 512 514 777 +4 585 940 379 586 +4 515 586 379 280 +4 585 515 586 379 +4 586 581 379 280 +4 586 379 581 940 +4 838 548 731 171 +4 200 973 812 505 +4 572 742 487 823 +4 572 174 487 782 +4 572 487 742 782 +4 570 563 553 5 +4 514 465 587 340 +4 514 465 441 587 +4 587 450 811 1021 +4 52 589 48 60 +4 52 255 48 589 +4 240 589 247 255 +4 355 247 589 536 +4 590 1028 331 279 +4 287 590 295 1028 +4 121 591 323 418 +4 591 1014 323 418 +4 591 882 1014 418 +4 616 911 185 801 +4 616 473 911 801 +4 394 592 464 824 +4 592 463 466 472 +4 237 593 460 394 +4 433 460 237 593 +4 546 460 593 445 +4 546 433 593 460 +4 733 21 232 31 +4 172 824 487 825 +4 464 825 824 512 +4 427 423 428 125 +4 427 125 346 423 +4 465 777 514 582 +4 412 25 903 233 +4 209 826 832 214 +4 209 222 594 1027 +4 214 826 832 232 +4 217 303 953 268 +4 1018 303 415 217 +4 217 303 268 1018 +4 149 555 630 135 +4 135 427 555 736 +4 555 736 630 135 +4 135 333 149 555 +4 35 29 234 263 +4 126 428 948 127 +4 31 253 733 488 +4 436 919 614 415 +4 415 919 614 953 +4 614 356 452 436 +4 558 821 578 435 +4 596 356 837 456 +4 597 210 372 228 +4 372 834 223 476 +4 478 332 426 482 +4 35 906 263 262 +4 86 961 644 453 +4 252 319 235 332 +4 420 959 562 266 +4 752 157 599 710 +4 225 251 493 600 +4 648 600 524 245 +4 648 600 245 251 +4 525 458 230 19 +4 155 713 452 753 +4 269 351 462 753 +4 269 716 753 462 +4 525 230 1013 19 +4 525 230 224 754 +4 654 754 206 712 +4 921 1013 19 525 +4 525 17 754 224 +4 525 754 1013 230 +4 654 525 754 1013 +4 207 353 196 267 +4 353 207 659 267 +4 51 39 254 984 +4 45 41 746 556 +4 239 216 951 240 +4 114 178 934 128 +4 349 452 526 282 +4 349 791 158 452 +4 353 225 283 15 +4 225 283 15 600 +4 225 283 600 493 +4 952 591 417 532 +4 578 144 282 382 +4 80 611 997 82 +4 82 997 376 611 +4 337 605 376 841 +4 337 605 841 338 +4 92 612 996 94 +4 94 761 770 96 +4 80 995 611 82 +4 82 611 377 995 +4 607 389 377 842 +4 580 842 389 607 +4 584 320 396 350 +4 350 320 396 197 +4 227 313 208 610 +4 610 832 214 208 +4 610 313 566 227 +4 80 607 605 611 +4 611 376 360 361 +4 611 361 360 377 +4 611 605 376 361 +4 611 361 377 607 +4 612 778 342 606 +4 612 342 778 568 +4 612 390 568 357 +4 9 613 200 665 +4 9 613 665 201 +4 613 203 201 827 +4 613 200 203 221 +4 618 89 565 737 +4 45 746 310 831 +4 618 89 91 565 +4 151 137 881 445 +4 619 64 334 68 +4 880 32 619 334 +4 235 952 591 883 +4 310 45 831 547 +4 591 121 883 141 +4 235 105 952 883 +4 622 104 726 108 +4 885 1002 622 81 +4 888 52 255 36 +4 36 255 888 951 +4 104 120 397 886 +4 120 623 419 557 +4 37 53 242 889 +4 624 738 30 567 +4 624 567 30 20 +4 624 738 37 30 +4 254 47 51 947 +4 30 891 344 36 +4 891 344 20 30 +4 107 628 339 896 +4 894 70 306 66 +4 70 306 54 894 +4 149 555 1008 630 +4 149 1008 895 630 +4 568 92 631 892 +4 631 103 517 107 +4 106 900 560 633 +4 633 118 138 558 +4 899 949 576 180 +4 634 488 31 733 +4 634 733 31 21 +4 634 31 488 38 +4 905 54 260 34 +4 905 38 260 54 +4 635 67 965 71 +4 71 635 55 308 +4 636 35 261 55 +4 636 55 261 39 +4 638 31 232 21 +4 150 1007 640 136 +4 150 1007 907 640 +4 641 565 318 325 +4 624 37 790 219 +4 1006 201 202 1027 +4 1006 219 1027 202 +4 567 222 201 1006 +4 1006 222 790 567 +4 1006 790 219 624 +4 136 1007 789 446 +4 1007 450 446 798 +4 1007 450 569 789 +4 1007 789 640 136 +4 386 390 517 554 +4 386 478 554 517 +4 568 386 390 517 +4 386 568 922 517 +4 226 484 488 536 +4 333 555 427 439 +4 555 564 454 466 +4 555 454 564 736 +4 660 520 645 18 +4 645 674 504 520 +4 255 48 247 36 +4 48 255 247 589 +4 123 135 427 119 +4 123 119 427 749 +4 674 251 520 660 +4 674 520 645 660 +4 544 650 329 301 +4 785 544 329 301 +4 650 683 322 79 +4 787 305 651 470 +4 651 722 460 165 +4 787 461 470 651 +4 653 304 786 6 +4 616 653 494 185 +4 743 194 479 312 +4 431 479 194 311 +4 502 161 211 236 +4 717 161 502 236 +4 349 614 186 526 +4 186 614 356 526 +4 157 661 292 719 +4 661 192 731 265 +4 759 184 1033 200 +4 979 200 184 759 +4 979 9 200 665 +4 664 274 380 378 +4 277 664 380 378 +4 300 378 664 277 +4 664 693 378 300 +4 164 512 466 824 +4 728 824 466 472 +4 916 486 324 318 +4 649 916 324 318 +4 650 79 322 274 +4 650 274 322 329 +4 665 201 203 185 +4 665 9 201 637 +4 94 390 612 666 +4 296 666 479 272 +4 272 94 666 390 +4 667 214 610 10 +4 667 188 208 214 +4 667 639 214 10 +4 10 314 610 667 +4 763 313 620 668 +4 2 667 668 588 +4 324 281 318 287 +4 540 324 281 318 +4 785 688 322 286 +4 544 322 286 785 +4 12 201 637 704 +4 704 12 201 202 +4 705 278 378 300 +4 300 693 378 705 +4 973 200 553 184 +4 617 973 184 200 +4 272 115 179 130 +4 14 707 639 215 +4 802 214 188 707 +4 669 472 466 463 +4 728 472 466 669 +4 503 669 466 161 +4 441 471 514 432 +4 521 384 383 439 +4 423 385 384 454 +4 356 673 1026 456 +4 356 452 673 456 +4 423 454 521 427 +4 673 1031 451 456 +4 423 384 521 454 +4 521 384 439 454 +4 384 548 383 1004 +4 675 823 676 461 +4 675 385 464 394 +4 449 450 675 1021 +4 450 1021 676 675 +4 675 487 464 676 +4 676 470 465 750 +4 416 415 400 726 +4 149 1008 555 161 +4 555 466 669 161 +4 161 669 555 211 +4 1008 466 555 161 +4 920 127 739 449 +4 920 569 449 739 +4 979 665 200 759 +4 287 331 325 687 +4 979 665 759 1 +4 291 688 290 337 +4 688 529 327 337 +4 744 689 389 810 +4 543 810 732 389 +4 1015 405 400 690 +4 345 837 405 690 +4 348 1015 690 405 +4 348 405 690 345 +4 304 665 185 704 +4 304 704 637 665 +4 496 109 117 515 +4 496 515 117 586 +4 515 117 586 280 +4 218 241 246 747 +4 172 474 773 825 +4 172 825 487 474 +4 609 474 725 172 +4 725 172 474 773 +4 609 172 487 474 +4 975 53 243 284 +4 975 243 1019 284 +4 678 458 531 263 +4 531 917 263 458 +4 228 834 1025 835 +4 254 984 697 51 +4 698 342 1028 724 +4 698 331 1034 778 +4 295 698 1028 724 +4 57 682 285 65 +4 666 357 699 390 +4 479 666 699 390 +4 699 1029 390 386 +4 974 84 632 82 +4 847 423 127 920 +4 568 92 90 631 +4 90 103 922 631 +4 123 427 858 428 +4 966 393 394 414 +4 663 405 596 558 +4 663 558 596 559 +4 271 403 179 312 +4 271 403 312 562 +4 703 581 131 971 +4 677 706 275 684 +4 706 279 275 684 +4 706 279 684 58 +4 310 547 831 841 +4 547 59 686 310 +4 679 841 338 831 +4 114 694 842 178 +4 725 777 474 582 +4 7 307 709 551 +4 728 669 466 503 +4 731 383 459 548 +4 192 383 731 838 +4 838 548 383 731 +4 292 192 383 731 +4 421 520 225 251 +4 660 251 520 421 +4 600 421 225 251 +4 648 421 251 530 +4 660 530 251 421 +4 656 600 245 524 +4 234 523 210 712 +4 654 210 516 712 +4 713 716 462 753 +4 595 462 447 713 +4 657 220 206 401 +4 353 659 207 225 +4 483 1019 250 290 +4 1020 483 250 290 +4 658 352 264 317 +4 584 302 562 271 +4 302 562 195 350 +4 125 423 847 941 +4 125 941 986 423 +4 941 986 423 799 +4 941 445 423 920 +4 847 423 920 941 +4 941 799 423 445 +4 375 968 326 327 +4 634 488 733 566 +4 634 566 733 21 +4 110 430 780 122 +4 122 780 429 430 +4 122 365 430 989 +4 122 430 429 989 +4 122 110 430 365 +4 322 650 329 544 +4 785 322 329 544 +4 211 333 409 139 +4 211 748 333 139 +4 211 139 409 720 +4 211 748 139 720 +4 837 430 456 1026 +4 596 837 430 456 +4 405 837 430 596 +4 330 273 295 724 +4 724 392 698 342 +4 1028 330 724 513 +4 1028 342 513 724 +4 273 306 295 724 +4 726 397 400 416 +4 176 378 726 776 +4 207 307 328 976 +4 976 207 231 328 +4 7 207 976 307 +4 659 7 207 976 +4 251 273 330 727 +4 44 674 251 727 +4 44 251 279 727 +4 595 729 447 462 +4 716 168 729 956 +4 716 729 595 462 +4 730 202 205 220 +4 657 730 206 220 +4 42 281 245 656 +4 643 902 1030 566 +4 511 902 566 1030 +4 936 280 420 795 +4 920 445 449 460 +4 613 567 827 201 +4 221 200 344 613 +4 564 455 464 512 +4 455 340 512 564 +4 455 142 340 564 +4 733 832 214 610 +4 733 610 566 227 +4 733 214 832 232 +4 974 360 376 343 +4 974 376 360 611 +4 974 611 360 377 +4 974 377 360 576 +4 320 370 236 950 +4 502 370 236 720 +4 196 276 563 629 +4 912 563 741 3 +4 680 527 241 647 +4 117 700 702 936 +4 60 589 48 945 +4 945 247 536 589 +4 651 460 461 823 +4 165 237 460 651 +4 237 460 651 823 +4 736 454 428 427 +4 736 428 454 455 +4 736 455 454 564 +4 227 566 488 226 +4 488 1024 227 226 +4 643 226 488 566 +4 634 488 643 38 +4 922 358 386 387 +4 922 386 358 568 +4 922 517 387 386 +4 143 153 920 569 +4 153 920 569 460 +4 641 737 565 325 +4 375 327 326 321 +4 1003 375 321 327 +4 569 920 449 460 +4 738 248 790 37 +4 567 738 221 222 +4 790 222 738 567 +4 624 790 37 738 +4 136 739 424 789 +4 739 450 811 424 +4 739 569 449 450 +4 789 450 569 739 +4 640 789 739 136 +4 236 522 383 439 +4 445 593 384 385 +4 385 393 593 384 +4 740 295 534 392 +4 740 177 392 534 +4 740 295 392 457 +4 740 177 457 392 +4 656 422 600 524 +4 966 593 394 393 +4 140 407 557 447 +4 146 140 436 447 +4 140 447 557 436 +4 385 393 592 394 +4 385 592 464 394 +4 471 800 495 451 +4 451 800 495 750 +4 493 251 273 295 +4 251 273 295 330 +4 295 251 330 590 +4 696 194 743 312 +4 696 434 312 743 +4 695 743 696 575 +4 695 696 743 581 +4 300 691 278 990 +4 990 574 691 744 +4 928 744 691 574 +4 404 416 415 436 +4 0 187 1017 759 +4 0 759 871 187 +4 759 203 477 185 +4 745 318 565 468 +4 745 193 468 565 +4 745 318 468 486 +4 252 332 235 532 +4 441 432 514 341 +4 989 432 441 341 +4 52 747 255 840 +4 747 241 246 334 +4 481 747 52 840 +4 416 356 436 557 +4 557 447 356 436 +4 557 447 1026 356 +4 426 748 478 482 +4 119 333 749 748 +4 339 482 478 748 +4 288 614 175 217 +4 415 217 614 288 +4 570 553 973 5 +4 749 119 748 482 +4 482 426 749 332 +4 749 332 426 485 +4 52 840 589 480 +4 570 553 184 973 +4 481 52 480 840 +4 480 246 589 541 +4 199 200 812 505 +4 970 750 462 495 +4 539 750 462 970 +4 283 527 241 26 +4 527 283 241 600 +4 147 417 443 292 +4 147 700 417 157 +4 700 710 417 157 +4 919 447 452 713 +4 146 595 447 919 +4 595 713 447 919 +4 918 367 220 27 +4 657 220 401 367 +4 918 317 244 224 +4 27 317 244 918 +4 276 218 839 283 +4 283 26 218 839 +4 147 292 443 368 +4 917 234 230 712 +4 234 523 712 917 +4 234 523 917 29 +4 144 652 435 282 +4 539 604 758 170 +4 917 234 256 230 +4 917 531 263 29 +4 539 604 787 758 +4 225 369 231 28 +4 745 878 515 193 +4 702 710 752 420 +4 270 352 658 525 +4 485 749 427 439 +4 749 439 333 427 +4 521 454 439 427 +4 521 485 427 439 +4 723 351 182 282 +4 682 285 65 33 +4 755 353 659 267 +4 717 156 756 950 +4 717 265 192 756 +4 245 656 524 958 +4 211 555 149 333 +4 211 333 149 409 +4 355 189 484 535 +4 371 816 493 238 +4 225 816 493 371 +4 535 816 371 238 +4 225 816 371 535 +4 467 313 643 328 +4 89 193 737 438 +4 438 193 737 490 +4 672 338 329 785 +4 672 338 785 556 +4 911 653 786 6 +4 616 801 185 188 +4 616 911 653 185 +4 616 473 801 188 +4 473 8 783 927 +4 168 604 787 539 +4 604 474 470 758 +4 734 474 604 758 +4 166 561 582 784 +4 615 354 184 570 +4 735 414 472 788 +4 181 537 313 208 +4 181 467 313 537 +4 239 467 181 537 +4 759 665 203 185 +4 2 667 588 10 +4 667 208 188 187 +4 667 187 668 208 +4 760 607 605 80 +4 760 338 605 361 +4 760 607 580 361 +4 583 580 361 760 +4 583 361 338 760 +4 94 612 606 761 +4 94 666 612 761 +4 761 357 275 571 +4 761 357 311 666 +4 761 357 606 275 +4 761 311 357 571 +4 614 356 436 416 +4 132 691 928 288 +4 691 278 744 288 +4 132 278 691 288 +4 288 691 928 744 +4 240 355 247 589 +4 216 247 255 240 +4 240 226 247 355 +4 216 240 226 247 +4 22 36 888 951 +4 432 514 259 471 +4 139 119 333 625 +4 453 180 560 576 +4 139 119 748 333 +4 139 897 333 409 +4 139 625 333 897 +4 735 870 472 414 +4 554 339 478 212 +4 211 439 555 333 +4 762 315 177 72 +4 762 315 325 177 +4 762 177 480 72 +4 762 177 457 481 +4 762 177 325 457 +4 762 177 481 480 +4 538 530 251 674 +4 307 620 930 763 +4 620 763 615 930 +4 677 671 571 413 +4 677 413 571 275 +4 83 321 69 884 +4 1003 83 884 321 +4 990 764 300 691 +4 95 294 324 765 +4 765 324 671 294 +4 766 301 329 77 +4 766 545 672 329 +4 287 457 295 475 +4 641 457 287 475 +4 556 767 672 338 +4 768 79 664 693 +4 768 693 664 300 +4 769 694 607 80 +4 769 694 842 607 +4 692 694 842 769 +4 677 684 275 770 +4 94 606 684 770 +4 770 606 684 275 +4 771 605 686 80 +4 771 338 841 605 +4 679 771 338 841 +4 772 9 665 637 +4 772 304 637 665 +4 621 639 667 10 +4 164 721 512 773 +4 773 825 777 512 +4 725 773 474 777 +4 332 252 387 478 +4 175 774 400 440 +4 965 805 308 71 +4 635 965 308 71 +4 906 309 308 965 +4 355 536 589 533 +4 541 536 533 589 +4 906 965 308 635 +4 965 309 308 805 +4 532 522 323 591 +4 582 495 561 259 +4 582 561 495 758 +4 859 74 489 358 +4 47 31 864 253 +4 47 864 50 253 +4 667 214 208 610 +4 667 208 668 610 +4 605 607 361 611 +4 760 607 361 605 +4 612 390 357 666 +4 612 357 606 761 +4 612 666 357 761 +4 665 613 200 203 +4 665 613 203 201 +4 759 665 200 203 +4 745 515 496 585 +4 496 515 586 585 +4 564 142 340 152 +4 278 378 689 776 +4 705 776 378 278 +4 142 924 455 340 +4 415 776 278 288 +4 216 951 240 255 +4 515 952 280 252 +4 1033 203 200 181 +4 759 1033 203 200 +4 81 622 1003 1002 +4 316 375 622 1002 +4 1002 622 1003 375 +4 497 147 398 443 +4 398 147 141 443 +4 28 273 504 406 +4 28 273 406 34 +4 310 547 841 686 +4 771 841 686 605 +4 679 771 841 686 +4 465 825 512 777 +4 160 514 721 708 +4 725 721 777 708 +4 773 777 721 512 +4 725 773 777 721 +4 778 568 358 490 +4 778 490 357 568 +4 778 833 357 490 +4 681 93 318 91 +4 91 93 318 745 +4 649 93 318 681 +4 93 916 318 486 +4 916 93 318 649 +4 745 93 318 486 +4 49 254 779 51 +4 51 697 254 779 +4 779 395 697 249 +4 61 289 73 781 +4 61 781 779 289 +4 781 289 395 779 +4 781 395 289 297 +4 780 111 124 425 +4 780 425 345 111 +4 780 837 110 345 +4 780 110 837 430 +4 224 751 250 483 +4 243 1019 250 751 +4 751 250 483 1019 +4 780 124 424 425 +4 254 697 249 779 +4 73 781 289 326 +4 934 288 175 217 +4 934 288 744 175 +4 558 596 559 578 +4 782 604 470 305 +4 782 174 487 877 +4 644 968 335 326 +4 644 335 968 360 +4 375 644 326 968 +4 179 403 969 312 +4 403 179 969 554 +4 312 403 969 699 +4 1029 969 554 403 +4 699 403 969 1029 +4 831 746 299 830 +4 679 556 831 338 +4 783 802 473 188 +4 802 707 188 783 +4 473 927 188 616 +4 794 616 188 927 +4 783 707 188 621 +4 784 758 582 474 +4 758 784 734 474 +4 609 725 474 784 +4 725 582 474 784 +4 785 286 291 688 +4 545 672 329 785 +4 301 545 329 785 +4 304 704 185 786 +4 653 494 185 304 +4 911 653 185 786 +4 787 750 729 539 +4 787 470 750 758 +4 787 604 470 758 +4 384 459 548 393 +4 305 604 470 787 +4 384 393 548 463 +4 617 184 973 570 +4 570 354 184 553 +4 788 472 669 463 +4 788 735 728 472 +4 594 227 818 815 +4 594 254 815 818 +4 728 472 669 788 +4 389 180 453 377 +4 541 981 533 714 +4 440 389 180 453 +4 541 536 714 533 +4 584 320 350 302 +4 641 315 325 762 +4 641 762 325 457 +4 641 737 325 315 +4 789 1007 450 446 +4 789 739 424 450 +4 790 222 219 476 +4 790 222 476 248 +4 1006 790 222 219 +4 738 248 222 790 +4 135 333 555 427 +4 871 615 620 763 +4 620 763 187 871 +4 620 187 2 871 +4 677 571 671 873 +4 876 188 794 616 +4 717 236 192 793 +4 282 456 526 578 +4 596 526 356 456 +4 220 223 751 243 +4 223 751 243 250 +4 160 582 708 166 +4 1019 285 797 290 +4 244 1019 388 285 +4 1019 388 285 290 +4 1020 297 290 289 +4 250 395 1020 289 +4 395 1020 289 297 +4 796 388 290 291 +4 483 796 388 290 +4 256 298 1020 262 +4 262 308 298 297 +4 309 310 299 298 +4 286 285 290 322 +4 810 776 176 400 +4 415 400 726 776 +4 176 776 726 400 +4 731 169 171 548 +4 569 449 675 460 +4 569 461 460 675 +4 798 676 750 461 +4 553 992 200 199 +4 973 200 812 553 +4 704 202 201 185 +4 786 202 704 185 +4 789 424 425 1023 +4 789 446 1023 425 +4 418 799 444 521 +4 799 384 445 444 +4 521 799 444 384 +4 449 385 455 1021 +4 1021 676 464 465 +4 449 1021 675 385 +4 1021 464 676 675 +4 441 587 800 450 +4 441 800 465 471 +4 450 800 676 587 +4 800 465 750 676 +4 564 466 464 454 +4 564 464 466 512 +4 911 473 205 801 +4 215 214 802 707 +4 783 215 473 802 +4 215 707 802 783 +4 458 352 230 257 +4 352 257 483 230 +4 352 317 388 264 +4 352 317 483 388 +4 224 813 803 223 +4 224 483 250 803 +4 803 1020 483 250 +4 234 256 492 262 +4 234 256 262 263 +4 297 1022 781 335 +4 1022 968 327 326 +4 290 336 337 327 +4 298 308 805 1022 +4 298 336 1022 805 +4 805 343 336 335 +4 310 343 337 336 +4 808 357 275 331 +4 381 468 357 808 +4 808 331 687 833 +4 571 357 275 808 +4 381 571 808 357 +4 337 360 361 809 +4 529 361 809 337 +4 175 440 400 810 +4 491 810 400 440 +4 428 811 449 455 +4 429 1023 450 441 +4 1023 441 451 450 +4 712 206 813 754 +4 754 230 224 813 +4 206 401 223 813 +4 790 476 219 242 +4 790 476 242 1032 +4 814 493 238 295 +4 814 534 295 238 +4 493 814 475 295 +4 475 457 295 814 +4 814 295 534 740 +4 814 295 740 457 +4 437 248 947 815 +4 815 248 947 254 +4 536 260 484 488 +4 316 176 726 400 +4 316 726 397 400 +4 222 248 594 817 +4 817 248 594 254 +4 817 254 249 248 +4 222 248 817 476 +4 476 249 248 817 +4 815 227 818 253 +4 815 254 253 818 +4 31 253 818 733 +4 31 818 253 865 +4 826 228 594 1025 +4 228 835 1025 819 +4 319 438 358 490 +4 438 820 358 490 +4 315 438 820 358 +4 342 568 358 778 +4 90 568 358 342 +4 859 342 358 489 +4 90 342 358 859 +4 918 220 751 244 +4 220 223 918 751 +4 425 1026 446 451 +4 1026 451 447 446 +4 557 425 1026 446 +4 417 532 443 197 +4 417 396 532 197 +4 417 710 197 292 +4 417 197 443 292 +4 417 420 396 197 +4 417 420 197 710 +4 205 223 210 206 +4 205 223 372 210 +4 205 597 210 372 +4 473 205 597 210 +4 911 210 206 205 +4 911 210 205 473 +4 225 535 231 994 +4 225 535 371 231 +4 428 423 454 455 +4 423 385 454 455 +4 117 586 795 703 +4 586 581 795 703 +4 475 287 641 281 +4 891 200 1009 505 +4 344 200 1009 891 +4 186 435 821 258 +4 560 558 900 258 +4 258 558 900 435 +4 239 467 537 240 +4 53 822 284 983 +4 785 329 322 688 +4 722 153 461 460 +4 651 722 461 460 +4 68 89 737 848 +4 618 68 89 737 +4 68 737 641 315 +4 618 68 737 641 +4 173 823 651 742 +4 823 470 676 461 +4 651 823 461 470 +4 787 461 750 470 +4 487 465 470 474 +4 676 487 465 470 +4 823 470 487 676 +4 251 330 590 279 +4 251 279 590 757 +4 465 825 777 474 +4 727 330 251 279 +4 773 474 777 825 +4 209 372 826 597 +4 597 826 215 228 +4 209 372 594 826 +4 826 232 819 1025 +4 827 203 204 828 +4 827 222 828 204 +4 567 222 221 827 +4 613 203 827 221 +4 613 567 221 827 +4 201 222 204 1027 +4 1006 201 1027 222 +4 1006 219 222 1027 +4 208 828 221 227 +4 219 889 243 220 +4 243 242 476 249 +4 219 476 243 242 +4 493 251 245 600 +4 239 189 467 240 +4 981 306 534 260 +4 982 297 829 395 +4 55 829 982 308 +4 982 297 395 63 +4 291 688 337 830 +4 785 291 830 688 +4 785 338 329 830 +4 299 830 337 831 +4 831 841 338 337 +4 209 208 832 828 +4 209 594 828 832 +4 610 227 832 208 +4 733 227 832 610 +4 833 357 490 468 +4 808 331 833 357 +4 687 468 808 833 +4 329 337 338 361 +4 380 274 329 361 +4 529 337 329 361 +4 583 329 338 361 +4 583 380 329 361 +4 331 357 606 778 +4 612 357 778 606 +4 612 778 357 568 +4 833 331 778 357 +4 834 492 250 249 +4 834 697 492 249 +4 835 261 492 697 +4 179 969 390 993 +4 272 993 179 390 +4 993 272 479 390 +4 993 969 390 699 +4 993 479 699 390 +4 64 618 565 641 +4 64 618 879 565 +4 809 375 327 968 +4 375 732 644 968 +4 375 968 809 732 +4 226 484 643 488 +4 488 260 484 643 +4 280 403 396 420 +4 403 584 396 420 +4 871 187 2 0 +4 280 434 403 420 +4 584 420 403 562 +4 434 562 403 420 +4 735 414 909 933 +4 548 933 909 414 +4 616 4 911 473 +4 627 5 11 199 +4 967 597 228 210 +4 4 8 473 927 +4 664 79 274 378 +4 664 79 378 693 +4 79 213 274 378 +4 693 1002 79 378 +4 79 1002 213 378 +4 627 951 199 11 +4 627 642 951 11 +4 408 12 23 1006 +4 6 12 704 202 +4 14 412 233 25 +4 967 215 14 937 +4 473 967 597 215 +4 202 205 220 219 +4 210 234 229 228 +4 234 835 229 228 +4 655 999 741 3 +4 422 600 15 16 +4 563 608 207 239 +4 111 853 836 120 +4 120 836 419 853 +4 345 425 836 111 +4 345 425 837 836 +4 836 356 1026 837 +4 836 425 557 419 +4 836 557 1026 356 +4 211 236 439 748 +4 439 236 426 748 +4 780 425 837 345 +4 780 837 425 430 +4 333 439 749 748 +4 654 712 206 210 +4 211 439 333 748 +4 426 439 748 749 +4 16 26 283 839 +4 793 909 463 1004 +4 1004 463 548 909 +4 527 16 283 600 +4 717 838 192 265 +4 265 192 731 838 +4 717 838 793 192 +4 839 629 627 276 +4 645 520 28 18 +4 353 283 939 15 +4 749 748 426 482 +4 840 255 589 246 +4 917 523 712 19 +4 840 747 255 246 +4 917 523 19 29 +4 481 747 840 246 +4 840 246 589 480 +4 481 840 480 246 +4 160 582 514 708 +4 512 721 514 777 +4 841 343 962 376 +4 841 605 376 962 +4 279 684 606 275 +4 279 513 606 684 +4 513 963 342 606 +4 842 377 607 949 +4 890 567 624 20 +4 607 842 949 694 +4 307 763 930 354 +4 520 727 504 273 +4 520 674 504 727 +4 902 566 634 21 +4 68 843 762 481 +4 68 52 843 481 +4 68 843 72 762 +4 904 638 232 21 +4 137 418 121 844 +4 137 844 125 986 +4 87 845 438 101 +4 846 101 113 1012 +4 846 113 121 1012 +4 847 920 143 137 +4 848 87 89 438 +4 852 1032 61 49 +4 852 53 61 822 +4 136 853 120 419 +4 124 424 425 853 +4 69 284 854 53 +4 69 987 73 854 +4 70 306 855 54 +4 70 489 74 855 +4 856 247 48 36 +4 906 29 35 263 +4 856 46 48 247 +4 857 248 49 46 +4 23 1006 219 624 +4 954 998 838 265 +4 265 838 731 998 +4 864 31 38 488 +4 363 90 103 922 +4 864 38 50 488 +4 24 634 643 38 +4 123 427 135 858 +4 865 39 254 51 +4 25 39 232 638 +4 655 267 741 999 +4 267 655 955 999 +4 859 358 90 88 +4 119 749 123 112 +4 860 75 86 335 +4 860 923 86 84 +4 15 353 755 267 +4 84 364 102 576 +4 861 51 63 697 +4 861 697 63 55 +4 71 55 862 308 +4 71 862 75 985 +4 269 791 1001 182 +4 269 753 1001 791 +4 253 31 864 488 +4 253 864 50 488 +4 47 865 254 51 +4 953 183 158 268 +4 953 268 158 542 +4 866 739 143 127 +4 866 136 143 739 +4 122 867 134 429 +4 867 924 142 134 +4 496 695 585 703 +4 868 198 644 99 +4 868 348 198 99 +4 868 1015 348 405 +4 868 198 453 644 +4 868 453 1015 405 +4 280 379 1029 403 +4 280 1029 379 869 +4 515 379 869 280 +4 635 35 55 308 +4 515 252 280 869 +4 478 482 517 387 +4 478 339 554 517 +4 334 641 475 457 +4 295 330 724 1028 +4 330 513 1028 279 +4 295 590 330 1028 +4 590 330 1028 279 +4 870 572 472 414 +4 735 573 870 414 +4 871 615 763 184 +4 792 871 184 615 +4 872 574 691 990 +4 990 872 764 691 +4 571 765 671 873 +4 875 766 672 329 +4 338 672 329 875 +4 767 875 672 338 +4 188 876 185 616 +4 494 616 185 876 +4 877 474 734 609 +4 470 877 474 604 +4 474 734 604 877 +4 974 376 962 343 +4 898 962 343 974 +4 898 974 343 632 +4 482 103 339 517 +4 670 40 910 958 +4 207 189 239 608 +4 478 339 517 482 +4 467 643 484 328 +4 608 189 239 240 +4 879 618 91 565 +4 64 880 619 334 +4 881 546 445 153 +4 672 556 785 41 +4 881 153 399 546 +4 540 42 281 324 +4 882 151 398 444 +4 544 785 286 43 +4 417 591 883 141 +4 122 365 989 134 +4 122 989 429 134 +4 700 883 141 417 +4 885 108 726 693 +4 108 726 622 885 +4 148 432 514 160 +4 140 886 404 416 +4 432 711 160 148 +4 432 160 259 514 +4 711 259 432 160 +4 887 150 446 407 +4 623 887 150 446 +4 49 249 1032 61 +4 49 249 248 1032 +4 49 61 779 249 +4 49 254 248 249 +4 49 249 779 254 +4 32 402 888 218 +4 890 408 23 1006 +4 37 1032 852 49 +4 23 1006 624 890 +4 952 396 417 420 +4 936 952 417 420 +4 891 1009 22 505 +4 344 1009 22 891 +4 33 65 975 285 +4 37 53 852 242 +4 854 983 61 53 +4 915 894 306 66 +4 915 894 66 406 +4 895 564 152 630 +4 680 647 241 56 +4 896 628 339 139 +4 897 149 333 409 +4 897 625 333 149 +4 898 962 974 82 +4 373 603 65 57 +4 898 82 974 632 +4 138 435 411 900 +4 900 558 138 435 +4 273 34 894 406 +4 900 138 558 633 +4 901 711 432 148 +4 78 338 771 760 +4 583 760 338 78 +4 767 78 338 679 +4 679 78 338 771 +4 767 583 338 78 +4 903 35 234 261 +4 412 35 234 903 +4 903 35 261 636 +4 854 983 73 61 +4 25 638 232 904 +4 905 34 260 231 +4 510 905 231 34 +4 906 309 965 67 +4 906 67 965 635 +4 907 569 153 640 +4 908 721 512 152 +4 908 152 512 340 +4 64 68 618 641 +4 65 321 884 69 +4 66 70 342 626 +4 67 632 343 71 +4 76 78 574 583 +4 767 875 1010 76 +4 277 872 583 76 +4 277 76 764 872 +4 381 431 311 379 +4 381 571 311 97 +4 67 898 343 632 +4 314 511 588 10 +4 322 884 1003 715 +4 66 626 342 893 +4 272 94 96 666 +4 194 96 311 666 +4 134 341 429 340 +4 807 806 340 134 +4 134 340 924 142 +4 782 877 470 604 +4 807 340 341 134 +4 793 909 1004 838 +4 838 1004 548 909 +4 806 142 340 134 +4 134 340 429 924 +4 105 101 846 235 +4 312 403 434 562 +4 746 291 299 830 +4 315 848 737 438 +4 68 848 737 315 +4 212 410 115 107 +4 81 1002 693 885 +4 404 108 116 726 +4 1019 285 244 33 +4 1019 975 797 285 +4 140 887 623 557 +4 557 407 446 447 +4 262 309 308 906 +4 262 906 263 309 +4 903 234 233 261 +4 700 109 883 952 +4 883 105 952 109 +4 104 397 120 851 +4 629 563 196 912 +4 629 5 563 912 +4 128 913 934 701 +4 217 913 268 701 +4 105 846 121 235 +4 914 210 516 654 +4 844 346 121 113 +4 654 206 957 914 +4 210 914 206 654 +4 844 113 125 346 +4 774 356 405 821 +4 349 282 652 154 +4 555 466 463 669 +4 669 463 555 211 +4 236 669 211 463 +4 793 669 909 167 +4 793 669 236 463 +4 439 384 1004 463 +4 384 548 1004 463 +4 908 340 514 341 +4 908 512 514 340 +4 33 53 242 243 +4 53 889 33 242 +4 33 243 242 889 +4 743 940 431 575 +4 695 940 743 575 +4 575 940 431 579 +4 695 940 575 579 +4 583 580 574 744 +4 692 744 574 580 +4 330 273 724 915 +4 330 727 915 58 +4 727 406 915 58 +4 273 306 724 915 +4 273 894 306 915 +4 273 894 915 406 +4 757 413 590 910 +4 332 323 235 532 +4 251 757 590 910 +4 218 246 608 255 +4 218 246 283 608 +4 246 747 255 218 +4 335 336 968 360 +4 1022 335 968 326 +4 1022 968 335 336 +4 1002 726 176 378 +4 726 176 316 1002 +4 237 966 572 293 +4 966 293 414 572 +4 360 377 453 576 +4 377 180 453 576 +4 717 669 793 167 +4 717 669 236 793 +4 334 457 475 246 +4 481 334 246 457 +4 87 101 358 88 +4 88 387 101 358 +4 319 101 387 358 +4 87 438 358 101 +4 438 101 319 358 +4 942 74 88 358 +4 942 358 88 87 +4 942 87 438 358 +4 315 942 438 358 +4 747 334 246 481 +4 381 486 687 324 +4 916 486 381 324 +4 650 274 329 380 +4 217 268 953 542 +4 349 217 953 542 +4 916 579 381 486 +4 195 599 420 266 +4 195 420 599 350 +4 630 736 142 135 +4 919 436 452 447 +4 235 591 532 323 +4 640 739 143 136 +4 270 264 658 352 +4 170 391 561 269 +4 269 723 561 351 +4 293 433 165 237 +4 677 413 275 706 +4 413 279 275 706 +4 654 1013 921 525 +4 654 712 516 921 +4 137 445 941 920 +4 847 941 920 137 +4 577 247 856 36 +4 577 46 856 247 +4 577 46 247 437 +4 577 437 1024 221 +4 69 326 321 849 +4 849 85 326 375 +4 849 375 326 321 +4 136 623 150 446 +4 857 248 738 37 +4 857 46 437 248 +4 857 248 437 738 +4 135 858 427 736 +4 858 736 428 427 +4 866 424 739 127 +4 866 136 739 424 +4 88 922 100 387 +4 88 387 358 922 +4 922 103 387 517 +4 100 922 103 387 +4 71 335 860 923 +4 923 961 335 86 +4 71 343 335 923 +4 923 360 343 335 +4 860 335 86 923 +4 865 254 253 47 +4 700 141 147 417 +4 594 254 818 1025 +4 865 39 818 254 +4 865 818 253 254 +4 126 429 924 867 +4 126 429 428 924 +4 924 811 429 428 +4 924 429 811 340 +4 867 429 924 134 +4 762 334 481 457 +4 762 334 457 641 +4 504 273 727 406 +4 330 273 915 727 +4 273 406 915 727 +4 484 231 260 238 +4 905 231 260 484 +4 630 564 152 142 +4 806 152 340 142 +4 881 143 153 445 +4 1013 230 712 19 +4 921 712 19 1013 +4 1013 754 712 230 +4 640 569 153 143 +4 654 1013 754 712 +4 654 712 921 1013 +4 502 211 409 720 +4 502 717 236 370 +4 925 175 258 186 +4 186 435 258 925 +4 696 194 312 926 +4 696 133 926 312 +4 40 44 413 442 +4 473 927 783 188 +4 4 927 473 616 +4 621 188 783 927 +4 758 929 734 784 +4 170 929 734 758 +4 609 725 784 929 +4 140 557 407 887 +4 696 931 133 434 +4 695 696 581 931 +4 932 735 728 788 +4 167 932 909 171 +4 40 671 324 294 +4 41 545 785 672 +4 735 293 414 933 +4 555 736 564 630 +4 141 882 398 443 +4 634 643 488 566 +4 922 568 631 517 +4 618 737 565 641 +4 1006 790 624 567 +4 624 790 738 567 +4 1007 789 569 640 +4 640 789 569 739 +4 151 881 399 546 +4 258 180 774 175 +4 258 175 774 186 +4 774 180 440 175 +4 114 842 925 934 +4 175 842 744 934 +4 276 283 839 939 +4 939 629 839 276 +4 353 283 276 939 +4 939 629 276 196 +4 282 154 182 723 +4 277 744 689 583 +4 282 144 154 723 +4 583 380 689 277 +4 237 823 394 460 +4 164 773 512 824 +4 756 156 159 950 +4 824 825 773 512 +4 608 239 951 240 +4 199 1009 992 200 +4 992 200 1009 216 +4 288 278 744 776 +4 278 689 744 776 +4 459 497 398 443 +4 276 642 218 951 +4 642 951 402 218 +4 510 976 231 328 +4 13 510 24 328 +4 150 935 446 407 +4 935 446 447 729 +4 935 447 407 500 +4 935 595 447 500 +4 595 935 447 729 +4 12 23 219 889 +4 12 202 730 220 +4 12 220 219 202 +4 657 347 730 220 +4 12 506 889 220 +4 347 506 220 657 +4 411 258 925 106 +4 925 508 435 411 +4 109 117 515 952 +4 700 952 117 109 +4 234 937 523 509 +4 233 412 14 937 +4 215 228 233 937 +4 967 215 937 228 +4 937 509 234 412 +4 643 260 484 905 +4 535 484 533 238 +4 355 535 484 533 +4 508 469 435 652 +4 469 349 435 652 +4 925 469 435 508 +4 701 349 652 938 +4 701 938 542 349 +4 353 939 276 196 +4 198 176 316 400 +4 104 886 397 726 +4 991 459 169 163 +4 695 743 940 581 +4 585 579 940 695 +4 585 695 940 703 +4 703 940 581 695 +4 692 842 744 580 +4 745 878 496 515 +4 908 721 514 512 +4 758 561 929 784 +4 929 972 784 166 +4 954 909 171 167 +4 644 176 198 491 +4 375 176 198 644 +4 58 513 330 279 +4 58 513 279 684 +4 598 168 787 729 +4 991 163 498 433 +4 936 420 417 710 +4 702 710 420 936 +4 936 700 702 710 +4 700 936 417 710 +4 933 293 991 169 +4 237 433 165 460 +4 169 171 548 933 +4 60 541 74 72 +4 60 480 541 72 +4 734 758 604 170 +4 756 265 1005 159 +4 100 332 112 113 +4 85 644 99 86 +4 609 172 174 487 +4 944 345 111 110 +4 111 780 124 122 +4 49 779 61 51 +4 61 781 73 75 +4 122 946 126 948 +4 946 948 127 126 +4 471 259 495 582 +4 471 514 259 582 +4 46 50 48 247 +4 85 943 326 644 +4 943 644 335 326 +4 46 248 49 947 +4 947 49 51 254 +4 122 429 780 948 +4 122 946 948 780 +4 946 424 127 948 +4 549 927 783 8 +4 899 949 180 106 +4 82 949 576 899 +4 377 949 180 576 +4 82 949 377 576 +4 576 180 560 899 +4 653 185 786 304 +4 129 116 415 190 +4 717 950 192 236 +4 350 1005 599 159 +4 717 950 756 192 +4 756 950 159 1005 +4 484 231 328 905 +4 510 328 231 905 +4 882 398 443 444 +4 398 459 443 444 +4 900 435 411 258 +4 411 435 925 258 +4 234 412 903 233 +4 233 234 412 937 +4 888 402 951 218 +4 218 747 255 888 +4 887 407 446 557 +4 407 935 446 447 +4 12 889 219 220 +4 682 244 285 33 +4 417 591 952 883 +4 700 952 883 417 +4 700 417 936 952 +4 953 155 158 183 +4 599 292 710 157 +4 415 499 436 919 +4 953 155 919 452 +4 499 919 415 303 +4 60 541 589 945 +4 945 589 536 541 +4 598 305 651 787 +4 598 461 787 651 +4 540 294 324 649 +4 540 649 324 318 +4 717 954 838 265 +4 717 954 793 838 +4 717 793 954 167 +4 955 7 207 659 +4 267 207 659 955 +4 956 716 269 462 +4 729 956 462 716 +4 914 516 210 8 +4 670 958 245 524 +4 538 674 251 44 +4 966 433 293 237 +4 560 900 558 633 +4 989 559 432 901 +4 84 974 923 961 +4 961 335 644 360 +4 84 961 576 974 +4 961 360 644 453 +4 961 453 576 360 +4 923 360 335 961 +4 382 456 578 432 +4 382 259 456 432 +4 382 351 456 259 +4 456 282 351 382 +4 456 578 282 382 +4 759 792 0 871 +4 67 686 962 898 +4 67 310 962 686 +4 82 376 997 962 +4 841 962 686 605 +4 310 841 962 686 +4 898 997 962 82 +4 66 963 964 893 +4 66 964 963 513 +4 92 612 963 996 +4 513 684 963 606 +4 893 963 996 92 +4 350 396 420 197 +4 350 197 420 599 +4 1 9 665 772 +4 58 964 513 684 +4 617 200 184 979 +4 964 963 684 893 +4 964 684 963 513 +4 979 9 665 1 +4 518 904 25 232 +4 518 233 25 14 +4 106 114 519 949 +4 899 519 949 106 +4 244 483 388 1019 +4 483 388 1019 290 +4 621 10 667 2 +4 395 829 1020 297 +4 616 4 653 911 +4 776 176 689 810 +4 912 5 563 3 +4 200 505 9 979 +4 1 665 494 304 +4 1 304 772 665 +4 657 957 730 6 +4 8 707 783 549 +4 662 8 210 516 +4 177 358 392 489 +4 177 358 820 392 +4 392 698 358 820 +4 489 342 358 392 +4 392 342 358 698 +4 394 823 487 675 +4 505 1009 22 11 +4 11 22 402 951 +4 627 563 629 5 +4 637 408 201 12 +4 8 977 967 14 +4 662 967 210 8 +4 215 14 707 8 +4 977 967 14 937 +4 523 967 234 210 +4 523 967 937 234 +4 15 755 353 225 +4 999 655 955 3 +4 525 17 352 658 +4 1018 217 415 288 +4 754 206 957 654 +4 74 177 489 358 +4 315 358 820 177 +4 942 358 177 74 +4 315 358 177 942 +4 656 16 600 422 +4 656 527 600 16 +4 754 657 957 206 +4 657 401 754 17 +4 225 755 659 18 +4 712 210 516 662 +4 712 523 210 662 +4 712 662 921 19 +4 712 19 523 662 +4 531 917 458 19 +4 639 21 904 214 +4 880 26 32 241 +4 682 244 33 27 +4 14 509 937 412 +4 541 740 534 177 +4 685 263 531 29 +4 685 906 263 29 +4 480 177 740 541 +4 481 177 457 740 +4 619 32 52 334 +4 481 177 740 480 +4 245 656 958 42 +4 649 95 324 916 +4 540 42 324 294 +4 544 301 785 43 +4 301 545 785 43 +4 44 727 279 58 +4 45 678 602 960 +4 45 59 547 310 +4 193 490 468 737 +4 319 193 438 490 +4 565 193 468 737 +4 353 225 994 283 +4 918 352 317 224 +4 547 556 45 831 +4 39 51 861 984 +4 843 52 60 480 +4 438 737 820 490 +4 855 981 62 54 +4 39 261 861 55 +4 862 55 63 982 +4 28 645 504 520 +4 263 59 309 906 +4 263 59 906 685 +4 843 60 72 480 +4 855 981 74 62 +4 349 435 652 282 +4 862 63 75 982 +4 560 821 558 258 +4 264 317 682 658 +4 682 264 388 317 +4 57 286 682 646 +4 682 57 285 286 +4 346 332 485 323 +4 749 332 485 346 +4 764 277 77 76 +4 77 79 664 768 +4 729 956 539 462 +4 970 561 462 269 +4 970 956 269 462 +4 539 970 462 956 +4 911 6 730 957 +4 914 206 957 911 +4 210 911 206 914 +4 914 210 911 473 +4 692 580 574 78 +4 692 769 580 78 +4 8 914 473 210 +4 41 264 960 746 +4 910 42 245 958 +4 670 910 245 958 +4 910 670 245 251 +4 131 959 434 795 +4 752 710 599 420 +4 878 745 91 89 +4 703 581 971 695 +4 695 931 581 971 +4 95 93 916 649 +4 929 725 784 972 +4 725 708 784 972 +4 575 431 97 95 +4 167 932 552 788 +4 552 167 669 191 +4 552 788 669 167 +4 695 579 575 95 +4 426 332 252 532 +4 97 311 1011 96 +4 677 761 571 96 +4 874 97 431 1011 +4 280 396 952 420 +4 936 280 952 420 +4 411 925 114 106 +4 523 967 210 662 +4 91 878 496 745 +4 227 566 733 488 +4 733 253 227 488 +4 733 818 832 227 +4 733 253 818 227 +4 974 360 343 923 +4 974 360 923 961 +4 974 961 576 360 +4 94 501 390 272 +4 186 774 356 614 +4 934 913 217 701 +4 934 288 217 913 +4 93 496 745 91 +4 93 980 585 496 +4 550 744 128 928 +4 258 180 560 774 +4 560 180 440 774 +4 440 453 180 560 +4 114 949 925 842 +4 842 377 949 180 +4 106 114 949 925 +4 77 768 664 300 +4 220 33 243 244 +4 35 234 262 263 +4 931 131 133 434 +4 971 931 581 131 +4 561 970 495 758 +4 758 750 970 495 +4 539 750 970 758 +4 195 266 562 1035 +4 953 155 183 303 +4 117 795 131 703 +4 795 131 959 702 +4 926 133 130 312 +4 309 678 263 257 +4 263 685 531 59 +4 114 508 925 411 +4 115 507 410 212 +4 79 81 715 1002 +4 79 213 322 274 +4 375 327 213 809 +4 375 176 809 213 +4 937 977 523 509 +4 523 967 977 937 +4 662 523 967 977 +4 978 595 935 500 +4 595 978 935 729 +4 716 978 595 729 +4 200 505 979 617 +4 349 154 158 791 +4 182 791 158 154 +4 980 95 579 695 +4 980 579 585 695 +4 980 695 585 496 +4 595 713 919 155 +4 713 462 716 595 +4 713 155 595 716 +4 752 157 159 599 +4 288 776 744 810 +4 288 175 810 744 +4 417 710 292 157 +4 119 748 482 628 +4 339 482 748 628 +4 702 752 710 157 +4 702 157 710 700 +4 748 139 212 339 +4 339 139 212 410 +4 339 139 410 896 +4 981 74 541 489 +4 981 489 534 306 +4 855 306 981 54 +4 855 489 74 981 +4 55 829 261 697 +4 697 395 829 492 +4 861 51 697 984 +4 861 261 697 55 +4 982 985 297 75 +4 862 55 982 308 +4 862 982 75 985 +4 54 62 714 981 +4 50 62 536 863 +4 54 863 714 62 +4 61 249 1032 822 +4 852 1032 822 61 +4 852 53 822 242 +4 851 836 397 120 +4 345 836 397 851 +4 236 161 211 669 +4 983 289 987 73 +4 854 284 983 53 +4 854 987 73 983 +4 346 121 323 418 +4 844 418 121 346 +4 844 346 125 986 +4 863 260 488 38 +4 488 863 536 260 +4 863 62 536 714 +4 978 162 935 729 +4 39 984 861 261 +4 861 984 697 261 +4 71 862 985 308 +4 982 308 297 985 +4 862 982 985 308 +4 722 162 598 461 +4 70 306 489 855 +4 855 306 489 981 +4 346 986 418 521 +4 986 423 799 521 +4 137 844 986 418 +4 844 346 986 418 +4 348 851 345 397 +4 124 424 853 136 +4 37 242 852 1032 +4 1032 249 242 822 +4 852 242 822 1032 +4 69 284 987 854 +4 983 289 284 987 +4 854 284 987 983 +4 723 351 259 561 +4 129 448 278 300 +4 983 61 822 289 +4 983 822 284 289 +4 111 425 836 853 +4 853 836 419 425 +4 972 708 784 166 +4 982 697 395 829 +4 982 829 297 308 +4 735 932 909 788 +4 102 118 633 988 +4 98 110 366 405 +4 102 98 366 988 +4 989 118 663 559 +4 717 161 669 167 +4 191 167 669 161 +4 598 168 305 787 +4 978 168 162 729 +4 305 604 787 168 +4 541 981 534 533 +4 933 293 414 966 +4 541 981 714 62 +4 541 536 62 714 +4 159 1005 661 265 +4 159 1005 292 661 +4 98 988 453 405 +4 988 453 405 560 +4 560 558 405 988 +4 988 118 558 663 +4 988 98 366 405 +4 110 118 663 365 +4 601 487 174 172 +4 181 354 763 313 +4 1033 187 203 208 +4 181 313 763 668 +4 573 173 174 572 +4 146 919 303 155 +4 953 919 303 415 +4 951 218 255 888 +4 914 911 957 4 +4 300 990 278 277 +4 277 990 744 583 +4 277 764 300 990 +4 277 990 583 872 +4 277 872 764 990 +4 642 11 402 951 +4 402 218 32 26 +4 670 524 245 648 +4 648 538 530 251 +4 186 526 356 821 +4 596 821 356 526 +4 26 241 880 680 +4 26 527 241 680 +4 660 251 530 674 +4 571 765 873 97 +4 541 534 489 177 +4 534 177 392 489 +4 355 536 533 484 +4 716 168 978 729 +4 6 12 730 347 +4 116 499 404 415 +4 114 128 934 701 +4 114 934 925 701 +4 114 701 925 508 +4 199 951 239 992 +4 239 992 951 216 +4 199 1009 951 992 +4 951 992 1009 216 +4 627 276 563 951 +4 627 642 276 951 +4 469 349 186 435 +4 359 130 179 115 +4 186 821 774 258 +4 186 356 774 821 +4 901 711 578 432 +4 559 901 578 432 +4 497 368 147 443 +4 500 595 447 146 +4 502 720 409 145 +4 502 370 720 145 +4 240 355 189 484 +4 467 189 484 240 +4 717 161 236 669 +4 207 231 189 994 +4 994 535 231 189 +4 608 816 994 189 +4 994 816 535 189 +4 389 440 491 453 +4 40 670 910 538 +4 1035 959 562 133 +4 430 456 441 432 +4 441 456 471 432 +4 441 451 471 456 +4 995 694 949 899 +4 995 607 377 949 +4 80 694 607 995 +4 995 607 949 694 +4 996 606 684 94 +4 996 606 963 684 +4 893 963 684 996 +4 80 605 686 997 +4 997 962 376 605 +4 997 605 686 962 +4 898 686 962 997 +4 648 251 245 670 +4 648 670 538 251 +4 718 20 775 408 +4 718 9 775 20 +4 930 655 354 3 +4 3 354 570 563 +4 570 354 553 563 +4 563 553 239 354 +4 349 217 186 614 +4 300 664 77 277 +4 767 679 338 556 +4 766 545 329 301 +4 9 20 200 613 +4 613 200 344 20 +4 20 200 891 505 +4 344 200 891 20 +4 1002 378 176 213 +4 884 1003 321 322 +4 683 322 79 715 +4 79 715 322 213 +4 9 20 613 775 +4 20 567 775 890 +4 20 567 613 775 +4 20 408 890 775 +4 769 607 760 80 +4 769 607 580 760 +4 94 606 770 761 +4 761 606 770 275 +4 771 760 605 80 +4 771 338 605 760 +4 793 236 192 1004 +4 838 1004 383 548 +4 192 236 383 1004 +4 793 838 1004 192 +4 192 1004 383 838 +4 1005 197 292 192 +4 756 265 192 1005 +4 950 192 197 1005 +4 756 950 1005 192 +4 1005 192 661 265 +4 1005 192 292 661 +4 12 1006 201 202 +4 408 12 1006 201 +4 890 567 201 1006 +4 890 408 1006 201 +4 1007 907 569 461 +4 1007 729 798 446 +4 722 1007 162 461 +4 907 1007 722 461 +4 1008 895 564 466 +4 1008 503 466 161 +4 1008 895 466 503 +4 1008 564 555 466 +4 705 726 116 693 +4 1002 693 726 378 +4 200 216 344 1009 +4 505 199 1009 11 +4 515 117 280 952 +4 416 436 614 415 +4 193 515 379 1016 +4 515 1016 193 319 +4 193 1016 379 468 +4 193 1016 468 490 +4 319 193 490 1016 +4 135 625 149 333 +4 1006 567 624 890 +4 517 892 631 107 +4 1007 569 907 640 +4 643 1030 313 566 +4 902 643 634 566 +4 1008 555 564 630 +4 1008 564 895 630 +4 48 589 247 945 +4 870 572 487 472 +4 871 1033 184 763 +4 763 1033 187 871 +4 871 759 184 1033 +4 95 765 324 381 +4 381 765 324 571 +4 571 324 671 765 +4 1010 77 329 380 +4 1010 329 338 583 +4 1010 380 329 583 +4 1010 766 329 77 +4 1010 766 875 329 +4 338 875 329 1010 +4 767 1010 338 583 +4 338 875 1010 767 +4 1017 759 494 1 +4 1017 477 185 759 +4 477 1017 185 876 +4 494 876 185 1017 +4 876 185 477 188 +4 173 572 742 782 +4 782 487 470 877 +4 470 487 474 877 +4 487 474 877 609 +4 416 415 614 400 +4 1011 431 194 311 +4 1011 311 194 96 +4 874 1011 431 194 +4 194 312 926 296 +4 195 159 599 266 +4 195 599 159 350 +4 101 1012 235 332 +4 846 101 1012 235 +4 649 681 318 540 +4 650 544 322 683 +4 651 598 461 722 +4 532 426 522 197 +4 532 396 426 197 +4 599 292 197 710 +4 123 346 749 427 +4 749 346 485 427 +4 521 439 522 485 +4 323 521 522 485 +4 444 383 384 459 +4 244 682 388 317 +4 1014 521 522 323 +4 591 522 323 1014 +4 591 443 522 1014 +4 418 444 1014 521 +4 521 444 1014 383 +4 521 383 1014 522 +4 443 532 522 197 +4 443 522 532 591 +4 444 546 384 445 +4 198 316 397 400 +4 198 690 400 397 +4 348 198 397 690 +4 348 397 198 851 +4 198 1015 400 690 +4 348 198 690 1015 +4 868 198 348 1015 +4 868 453 198 1015 +4 533 534 238 260 +4 981 534 533 260 +4 644 453 491 198 +4 453 440 1015 405 +4 491 453 1015 198 +4 491 440 1015 453 +4 240 608 189 355 +4 189 246 535 355 +4 608 255 246 589 +4 608 246 816 189 +4 816 246 535 189 +4 207 328 467 189 +4 467 328 484 189 +4 456 259 1031 471 +4 471 259 1031 495 +4 471 495 1031 451 +4 456 471 1031 451 +4 468 357 1016 379 +4 490 357 1016 468 +4 188 802 473 209 +4 473 802 597 209 +4 473 597 802 215 +4 403 478 396 584 +4 563 951 239 199 +4 563 951 608 239 +4 537 208 221 227 +4 225 493 816 283 +4 207 225 994 353 +4 608 276 353 283 +4 207 563 353 608 +4 207 994 189 608 +4 316 375 83 622 +4 910 324 287 281 +4 911 185 202 786 +4 909 788 669 463 +4 793 669 463 909 +4 130 271 179 312 +4 130 271 312 562 +4 349 526 186 435 +4 349 526 435 282 +4 341 441 989 429 +4 114 842 934 178 +4 118 558 663 559 +4 752 959 420 266 +4 702 959 420 752 +4 712 662 516 921 +4 678 458 257 960 +4 155 716 713 753 +4 353 659 225 755 +4 725 777 582 708 +4 725 708 582 784 +4 572 823 394 237 +4 572 823 487 394 +4 667 314 668 588 +4 374 314 610 10 +4 762 843 480 481 +4 762 843 72 480 +4 387 332 482 100 +4 642 218 402 26 +4 496 703 585 586 +4 585 703 940 586 +4 586 940 581 703 +4 734 609 474 784 +4 734 609 784 929 +4 692 744 928 574 +4 615 570 184 617 +4 617 792 184 615 +4 41 746 960 45 +4 730 202 911 205 +4 657 957 206 730 +4 911 730 206 957 +4 104 316 397 198 +4 622 104 316 726 +4 104 726 397 316 +4 850 198 104 99 +4 83 104 316 622 +4 211 236 748 720 +4 478 748 212 339 +4 83 316 850 375 +4 99 851 198 104 +4 851 397 198 104 +4 98 102 453 988 +4 102 453 988 560 +4 102 453 560 576 +4 599 420 710 197 +4 548 393 966 414 +4 548 459 966 393 +4 80 995 607 611 +4 611 607 377 995 +4 612 606 996 94 +4 612 606 342 963 +4 612 606 963 996 +4 80 605 997 611 +4 611 997 376 605 +4 511 1030 566 313 +4 950 320 350 197 +4 950 1005 350 159 +4 274 213 361 689 +4 213 689 176 543 +4 274 213 529 361 +4 213 361 809 529 +4 213 176 809 543 +4 1002 1003 213 375 +4 79 1002 715 213 +4 1016 515 379 869 +4 515 869 1016 319 +4 319 515 869 252 +4 216 1024 226 221 +4 240 537 216 226 +4 537 226 221 216 +4 556 338 785 830 +4 746 291 830 785 +4 746 556 785 830 +4 195 420 562 266 +4 195 562 420 350 +4 707 639 214 667 +4 707 214 188 667 +4 922 103 517 631 +4 89 565 737 193 +4 89 745 565 193 +4 878 193 745 89 +4 451 495 462 750 +4 346 427 423 521 +4 346 323 485 521 +4 381 379 468 486 +4 381 486 468 687 +4 283 816 246 493 +4 677 770 275 761 +4 677 275 571 761 +4 296 96 194 666 +4 557 447 446 1026 +4 28 238 273 34 +4 28 238 371 273 +4 288 1000 217 913 +4 217 1000 268 913 +4 614 217 953 349 +4 774 400 356 614 +4 430 559 596 432 +4 559 578 596 432 +4 776 689 744 810 +4 351 452 456 1031 +4 447 462 673 452 +4 351 753 452 462 +4 673 1031 456 452 +4 713 447 452 462 +4 713 462 452 753 +4 243 289 250 1019 +4 553 239 354 181 +4 553 200 992 181 +4 682 286 388 264 +4 1020 796 256 483 +4 250 1019 289 290 +4 1020 250 289 290 +4 1020 492 262 829 +4 1020 290 297 298 +4 1020 298 297 262 +4 256 257 796 309 +4 796 299 298 309 +4 262 298 308 309 +4 882 444 443 1014 +4 141 591 882 443 +4 591 443 1014 882 +4 485 426 749 439 +4 485 439 522 426 +4 151 444 445 546 +4 445 593 546 384 +4 512 464 465 1021 +4 1021 340 465 512 +4 340 587 1021 465 +4 911 202 185 205 +4 185 205 204 801 +4 911 185 801 205 +4 229 230 803 256 +4 229 250 492 803 +4 229 256 234 230 +4 229 256 492 234 +4 29 917 234 263 +4 69 797 321 326 +4 65 285 603 321 +4 797 321 326 327 +4 287 318 324 687 +4 287 687 324 331 +4 289 781 297 290 +4 289 290 797 326 +4 290 797 326 327 +4 290 297 1022 781 +4 290 327 326 1022 +4 298 336 299 290 +4 290 322 327 688 +4 290 688 327 337 +4 297 985 308 1022 +4 1022 327 968 336 +4 1022 308 805 985 +4 1022 336 335 805 +4 298 805 309 310 +4 298 310 299 336 +4 310 336 337 299 +4 71 805 335 343 +4 67 343 310 805 +4 67 310 343 962 +4 310 337 343 841 +4 310 841 343 962 +4 137 799 941 445 +4 739 450 449 811 +4 424 450 429 1023 +4 1023 446 450 451 +4 789 424 1023 450 +4 789 446 450 1023 +4 340 811 1021 587 +4 924 455 811 428 +4 924 811 455 340 +4 450 800 798 676 +4 800 676 750 798 +4 981 306 260 54 +4 218 255 608 951 +4 608 255 589 240 +4 608 589 246 355 +4 577 247 216 1024 +4 577 437 247 1024 +4 216 247 226 1024 +4 401 220 223 918 +4 712 754 813 230 +4 401 224 223 813 +4 488 253 227 1024 +4 712 813 229 230 +4 712 234 230 229 +4 39 819 254 984 +4 594 1025 818 232 +4 1025 817 594 254 +4 1025 254 249 817 +4 1025 249 254 697 +4 1025 697 254 984 +4 1025 818 819 254 +4 1025 984 254 819 +4 778 490 358 698 +4 698 490 358 820 +4 342 778 358 698 +4 26 241 283 218 +4 26 32 241 218 +4 400 356 614 416 +4 1026 447 451 673 +4 241 475 334 281 +4 394 487 472 824 +4 394 592 824 472 +4 592 472 466 824 +4 675 823 487 676 +4 203 221 208 828 +4 827 203 828 221 +4 827 222 221 828 +4 204 222 209 1027 +4 1027 219 222 476 +4 1027 476 817 372 +4 1027 476 222 817 +4 778 698 833 490 +4 698 331 778 833 +4 372 1027 594 817 +4 372 228 826 597 +4 372 228 594 826 +4 53 822 243 284 +4 249 250 243 289 +4 249 289 395 250 +4 61 779 249 289 +4 779 289 395 249 +4 822 61 249 289 +4 55 308 262 829 +4 785 688 830 329 +4 287 325 331 1028 +4 1028 325 331 698 +4 1028 1034 331 513 +4 287 590 1028 331 +4 1028 698 331 1034 +4 831 556 830 338 +4 830 338 337 831 +4 357 386 379 699 +4 1016 357 386 379 +4 490 357 386 1016 +4 568 490 357 386 +4 568 390 386 357 +4 357 386 699 390 +4 828 208 832 227 +4 828 594 227 832 +4 379 403 699 1029 +4 1029 478 403 554 +4 234 492 261 262 +4 262 261 234 35 +4 835 233 234 261 +4 835 492 261 234 +4 1025 835 834 697 +4 835 697 492 834 +4 834 243 476 249 +4 219 242 243 889 +4 967 228 234 210 +4 228 234 233 937 +4 967 228 937 234 +4 205 206 220 223 +4 205 219 476 220 +4 205 223 476 372 +4 476 220 219 243 +4 228 834 223 372 +4 228 223 834 229 +4 345 837 690 836 +4 836 356 837 690 +4 120 557 140 623 +4 120 836 557 419 +4 270 458 352 525 +4 270 257 352 458 +4 269 351 561 462 +4 252 235 952 532 +4 172 824 601 487 +4 728 172 824 601 +4 1 617 792 184 +4 979 759 184 1 +4 792 1 184 759 +4 759 792 871 184 +4 621 2 667 188 +4 2 188 187 667 +4 494 665 759 185 +4 494 665 185 304 +4 1017 759 185 494 +4 925 180 258 175 +4 925 842 180 175 +4 925 842 175 934 +4 25 233 232 819 +4 25 636 233 819 +4 67 309 965 805 +4 67 310 309 805 +4 799 151 882 444 +4 799 151 444 445 +4 65 797 975 285 +4 65 797 285 321 +4 696 434 743 581 +4 696 434 581 931 +4 165 293 237 173 +4 311 357 699 666 +4 479 311 699 666 +4 769 842 580 607 +4 692 842 580 769 +4 643 484 328 905 +4 665 201 185 704 +4 665 704 637 201 +4 839 627 642 276 +4 1002 176 375 213 +4 944 405 345 110 +4 944 99 345 348 +4 944 405 348 345 +4 239 537 216 240 +4 239 992 216 537 +4 1002 885 726 693 +4 885 726 622 1002 +4 622 83 1003 375 +4 375 732 809 176 +4 272 312 130 179 +4 272 296 130 312 +4 312 272 479 993 +4 312 969 993 699 +4 312 479 699 993 +4 440 180 389 175 +4 180 842 389 175 +4 175 842 389 744 +4 92 342 612 568 +4 793 954 909 838 +4 793 909 954 167 +4 845 101 319 438 +4 845 105 319 101 +4 202 1006 219 12 +4 236 439 383 1004 +4 197 426 522 236 +4 320 236 426 197 +4 320 426 396 197 +4 599 197 292 1005 +4 350 1005 197 599 +4 950 197 350 1005 +4 246 534 238 533 +4 246 493 238 814 +4 246 534 814 238 +4 816 246 493 238 +4 535 533 246 238 +4 535 246 816 238 +4 560 558 988 633 +4 633 118 558 988 +4 414 472 463 393 +4 548 414 463 393 +4 414 788 463 472 +4 414 909 463 788 +4 548 909 463 414 +4 981 541 534 489 +4 933 548 966 414 +4 966 991 459 548 +4 966 593 237 394 +4 433 237 966 593 +4 175 440 810 389 +4 744 175 810 389 +4 787 750 539 758 +4 282 452 456 351 +4 415 726 116 705 +4 415 776 726 705 +4 415 776 705 278 +4 104 316 850 83 +4 498 399 433 163 +4 9 505 200 20 +4 328 313 643 1030 +4 935 162 1007 729 +4 935 729 1007 446 +4 11 951 199 1009 +4 720 236 320 370 +4 33 53 243 975 +4 33 243 1019 975 +4 397 416 886 557 +4 397 557 886 120 +4 894 306 54 34 +4 260 306 34 54 +4 315 438 737 820 +4 437 221 738 815 +4 437 248 815 738 +4 401 918 223 224 +4 450 676 461 675 +4 569 461 675 450 +4 1007 569 450 461 +4 450 798 461 676 +4 1007 450 798 461 +4 592 393 385 384 +4 384 393 463 592 +4 1019 289 797 284 +4 1019 797 289 290 +4 223 250 229 803 +4 813 229 230 803 +4 813 229 803 223 +4 587 676 1021 465 +4 441 465 800 587 +4 587 800 676 465 +4 351 462 1031 561 +4 673 462 451 1031 +4 351 452 1031 462 +4 673 462 1031 452 +4 803 256 483 1020 +4 229 803 492 256 +4 492 803 1020 256 +4 558 596 578 821 +4 822 289 243 284 +4 243 284 289 1019 +4 245 475 281 287 +4 910 245 281 287 +4 245 241 281 475 +4 354 307 313 467 +4 354 307 763 313 +4 992 239 181 537 +4 553 239 992 199 +4 553 992 239 181 +4 69 987 797 326 +4 987 289 797 326 +4 424 419 425 853 +4 201 1027 204 202 +4 185 204 202 201 +4 352 264 388 796 +4 746 299 291 796 +4 746 264 796 291 +4 286 322 290 688 +4 829 262 297 308 +4 1020 829 262 297 +4 45 310 746 602 +4 37 790 1032 248 +4 476 1032 248 249 +4 790 476 1032 248 +4 256 298 262 309 +4 263 256 262 309 +4 256 298 309 796 +4 256 309 263 257 +4 796 290 1020 298 +4 1020 290 796 483 +4 951 255 608 240 +4 393 463 592 472 +4 385 393 394 593 +4 283 816 994 608 +4 283 246 816 608 +4 353 994 608 283 +4 805 310 336 343 +4 298 336 805 310 +4 781 1022 326 335 +4 289 326 781 290 +4 290 781 1022 326 +4 424 1023 429 780 +4 780 429 430 1023 +4 423 427 428 454 +4 1033 208 203 181 +4 187 668 208 1033 +4 759 1033 187 203 +4 871 759 1033 187 +4 437 46 253 947 +4 437 947 253 815 +4 815 947 253 254 +4 71 985 335 805 +4 297 335 985 1022 +4 1022 985 805 335 +4 815 253 1024 227 +4 437 253 1024 815 +4 948 428 429 811 +4 465 825 464 512 +4 372 228 834 817 +4 372 817 594 228 +4 464 824 466 512 +4 464 592 466 824 +4 834 1025 249 817 +4 834 249 1025 697 +4 476 249 817 834 +4 204 1027 209 801 +4 801 209 597 372 +4 801 209 372 1027 +4 473 801 209 597 +4 221 815 227 828 +4 828 227 594 815 +4 835 261 819 233 +4 835 697 1025 261 +4 835 261 1025 819 +4 1029 390 554 969 +4 699 969 390 1029 +4 290 336 1022 298 +4 39 819 984 261 +4 1025 697 984 261 +4 1025 261 984 819 +4 299 337 310 831 +4 831 337 310 841 +4 594 832 232 818 +4 733 818 232 832 +4 449 1021 455 811 +4 340 811 455 1021 +4 917 263 257 256 +4 917 263 256 234 +4 280 952 396 252 +4 252 952 396 532 +4 252 387 319 332 +4 101 235 319 332 +4 1034 778 606 342 +4 513 606 342 1034 +4 698 1034 342 778 +4 1028 342 1034 513 +4 1028 698 1034 342 +4 209 826 594 832 +4 832 826 594 232 +4 393 472 592 394 +4 280 396 1029 252 +4 252 396 1029 478 +4 280 252 1029 869 +4 688 337 329 529 +4 830 329 337 338 +4 688 329 337 830 +4 464 825 487 824 +4 397 557 836 416 +4 416 557 836 356 +4 397 400 416 690 +4 690 400 416 356 +4 397 416 836 690 +4 730 205 206 220 +4 730 205 911 206 +4 205 220 476 223 +4 476 220 243 223 +4 451 750 462 729 +4 539 729 462 750 +4 234 233 835 228 +4 372 817 834 476 +4 1026 673 451 456 +4 405 356 837 596 +4 690 356 837 405 +4 690 356 405 400 +4 52 888 255 747 +4 650 79 274 664 +4 650 274 380 664 +4 623 887 446 557 +4 136 623 446 419 +4 37 889 242 219 +4 975 69 284 797 +4 33 975 1019 285 +4 975 797 284 1019 +4 38 260 643 905 +4 636 903 233 261 +4 636 261 819 39 +4 636 261 233 819 +4 774 821 560 258 +4 258 106 180 925 +4 200 973 505 617 +4 199 812 11 505 +4 92 612 342 963 +4 893 342 963 92 +4 893 626 342 92 +4 100 482 112 332 +4 843 52 480 481 +4 502 236 211 720 +4 237 394 572 966 +4 166 582 259 160 +4 582 514 259 160 +4 723 259 160 166 +4 1031 259 561 495 +4 351 561 1031 259 +4 627 5 199 563 +4 627 951 563 199 +4 682 286 285 388 +4 235 591 952 532 +4 1012 121 235 323 +4 1012 323 235 332 +4 846 1012 121 235 +4 137 445 920 143 +4 881 137 143 445 +4 626 70 342 90 +4 90 342 859 70 +4 568 92 342 90 +4 626 90 342 92 +4 632 923 343 71 +4 632 84 923 71 +4 632 974 343 923 +4 31 39 232 818 +4 31 818 232 733 +4 31 39 818 865 +4 638 39 232 31 +4 69 849 321 83 +4 1018 288 278 132 +4 1018 415 278 288 +4 36 216 344 577 +4 221 577 216 1024 +4 780 124 946 424 +4 780 429 424 948 +4 780 946 948 424 +4 947 49 254 248 +4 73 943 781 326 +4 48 50 945 247 +4 488 50 247 536 +4 253 50 247 488 +4 50 945 247 536 +4 123 125 346 427 +4 954 171 838 998 +4 998 838 731 171 +4 266 959 562 1035 +4 159 752 599 266 +4 661 192 292 731 +4 719 661 292 731 +4 291 264 388 286 +4 976 307 328 13 +4 307 709 313 13 +4 7 307 13 709 +4 7 976 13 307 +4 328 307 313 13 +4 544 57 286 322 +4 683 57 322 373 +4 683 57 544 322 +4 378 726 705 693 +4 215 707 639 214 +4 518 232 25 233 +4 916 95 579 980 +4 916 579 486 585 +4 916 579 585 980 +4 115 212 359 507 +4 212 320 584 528 +4 350 302 562 584 +4 307 620 313 709 +4 511 709 313 620 +4 795 581 131 703 +4 163 433 459 546 +4 399 163 546 433 +4 743 431 479 194 +4 696 431 743 194 +4 696 743 431 575 +4 696 431 874 575 +4 696 874 431 194 +4 583 574 990 744 +4 872 574 990 583 + +CELL_TYPES 4436 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 diff --git a/data/tube.vtk b/data/tube.vtk new file mode 100644 index 000000000..c9b4e2783 --- /dev/null +++ b/data/tube.vtk @@ -0,0 +1,5051 @@ +# vtk DataFile Version 2.0 +tube_, Created by Gmsh +ASCII +DATASET UNSTRUCTURED_GRID +POINTS 600 double +-0.43392393 -0.311972111 0.0333728343 +-0.43036893 2.32001374e-09 0.0366321243 +-0.4286083605812229 -0.1548227162444012 -0.07870662409827885 +-0.427165151 0.268384814 0.0434715487 +-0.426282167 -0.40102157 -0.0885160863 +-0.4248742716033475 0.1410052646995191 -0.09308352158146983 +-0.4226862962377595 0.4036483338850155 -0.07248494876062317 +-0.4148462939982124 -0.1606000235108145 0.1305439710459489 +-0.405665636 0.438549072 0.108697869 +-0.405602992 -0.409194499 0.151965067 +-0.394650161 0.102693133 0.15640755 +-0.386213899 0.58921212 0.00537055824 +-0.3802612593660542 0.2864909740873189 -0.1987288382952311 +-0.370914072 1.16000685e-08 -0.203572571 +-0.367548883 -0.555591464 -0.0110354125 +-0.3614593661407063 -0.2921865786891039 -0.2093182031943139 +-0.360874087 -0.565837502 0.188110918 +-0.356921107 0.558154047 -0.199895486 +-0.354328841 -0.0454262719 0.249092609 +-0.350523829 -0.265266985 0.247744054 +-0.343385816 0.309375048 0.232902557 +-0.340997577 -0.538326144 -0.196874991 +-0.328534335 0.588007808 0.211146206 +-0.305292577 0.416842222 -0.304209173 +-0.296967864 -0.438549072 0.296967983 +-0.287507892 0.438549101 0.29950276 +-0.281619549 -0.154687494 -0.333091825 +-0.2812237666928784 0.1167213091284394 0.3317211860741869 +-0.274980396 0.154687494 -0.327712238 +-0.2674827782051299 -0.103707488520199 0.3394645163888013 +-0.26856786 -0.405997604 -0.335466623 +-0.2235936442835671 0.2745117354390157 0.369093209520713 +-0.2070051929088297 -0.05440397781666514 -0.3800382138956825 +-0.208256111 -0.309374988 0.360710174 +-0.205481768 -0.264033765 -0.386691958 +-0.199680731 0.58716923 0.359837919 +-0.197757959 0.58921212 -0.331785828 +-0.19775793 -0.589212179 0.331785828 +-0.188455969 -0.589212179 -0.337156355 +-0.186802402 0.0345360823 0.39680472 +-0.157288939 -0.618750036 -0.09081077579999999 +-0.157288924 -0.618749976 0.0908108577 +-0.157288924 0.618750036 -0.0908107907 +-0.156058535 -0.433390796 0.392947853 +-0.154789731 0.325729638 -0.375732571 +-0.145831198 0.472297728 -0.38534826 +-0.1371419486110808 0.6187499301750019 0.1088765956236134 +-0.121850766 0.121170074 -0.411161453 +-0.115331769 -0.41934678 -0.415485471 +-0.111946605 -0.154687494 0.413318127 +-0.1062652782198199 -0.1487127456518896 -0.4213356449043473 +-0.103493579 0.21100077 0.422269017 +-0.0978464335 0.405847311 0.408109546 +-0.0774570405 0.618750036 0.258641839 +-0.02159283106135917 0.03174746402796991 0.4310024877060488 +-0.0179646518 -0.34092015 0.415113211 +-0.009688984621022842 -0.2834879017431834 -0.4314905816389696 +-0.00670286594 -0.542773843 0.398656815 +-0.00580689404 0.586812198 -0.405520171 +-2.57229615e-08 -0.55920428 -0.41116789 +1.208989e-08 -0.618750036 0.181621701 +1.66236021e-08 -0.618749976 -0.181621596 +-0.0006813753081407747 0.6187499188330678 -0.1796679628383584 +0.00768853026 0.593404174 0.406762034 +0.009157993830000001 -4.64002747e-09 -0.427915066 +0.022765955 0.253169477 -0.427350998 +0.0322226956 0.423056841 -0.416164607 +0.0342804080322591 0.2741407779637947 0.4305460627238096 +0.102442801 -0.105191968 0.411583781 +0.107514463 0.618750036 0.213972136 +0.108697779 0.438549221 0.405665755 +0.112628661 -0.41944927 -0.413815916 +0.1200034356436272 -0.1504612347289486 -0.4177121624845779 +0.1259923298012365 0.1008049430284386 0.413912608595941 +0.131532967 -0.44388473 0.404732376 +0.149062276 0.109624252 -0.401738286 +0.1614345373687059 -0.618185958539867 -0.08991265034623711 +0.1570795572724424 -0.6185728891214657 0.09255173702308912 +0.164137155 0.618750036 -0.116368696 +0.184367105 0.618750036 0.0396215059 +0.188251793 -0.309374988 0.3660703 +0.193106964 -0.589863837 0.334471077 +0.193106979 -0.589863837 -0.334471077 +0.193106979 0.559219062 -0.334471077 +0.19829841 0.345619023 -0.369212896 +0.200934023 0.309374958 0.368032217 +0.203760475 0.585115612 0.355648518 +0.214589223 2.96139469e-09 0.365892023 +0.232867911 -0.264706075 -0.354089141 +0.244279236 -0.0373887569 -0.356493652 +0.271552861 0.154687494 0.33706668 +0.287507921 -0.438549072 0.299502701 +0.290042728 -0.438549072 -0.290042698 +0.294669807 -0.154687494 0.284373343 +0.29950273 0.438549072 0.287507921 +0.303710341 0.197228432 -0.308855116 +0.327608764 -0.154687509 -0.26973334 +0.3295471189815843 0.4033896671692497 -0.2743618720540265 +0.336392879 -2.1006894e-09 0.254037082 +0.337100565 0.590643466 0.19821693 +0.3380411813209452 0.3065623909331096 0.231382172919061 +0.340997547 -0.576896846 0.196874946 +0.351426065 -0.309374958 0.202895924 +0.354094207 -0.586812198 -0.197731182 +0.354094207 0.586812198 -0.197731227 +0.3634705886775586 0.05646550612254668 -0.2211121553866255 +0.366915405 -0.309374988 -0.189565405 +0.386213958 -0.58921212 0.00537049538 +0.3902539486477201 0.2682264984573341 -0.1853072423004415 +0.391411364 0.589884758 -0.00872785132 +0.39874053 0.438549072 0.115622908 +0.3996165976067366 0.1078079946597189 0.1450512970580487 +0.403130919 -0.438549072 -0.09923780710000001 +0.405665725 0.438549072 -0.108697794 +0.405665755 -0.438549101 0.108697727 +0.414115161 -0.115011699 -0.117519721 +0.4171096450501141 0.2623495648336722 0.01817013346520394 +0.4186678292799705 -0.1258407075627407 0.0912040943110187 +0.422268957 0.0983742326 -0.103493609 +0.425325125 -0.265959144 -5.60110935e-09 +0.432822824 2.32001351e-09 0.00915800221 +0.4264881306376765 0.1043503090936977 0.009065702921230885 +0.01282970746594949 0.6187499854606945 0.1052451324253897 +-0.29662019504468 0.4760338142619953 -0.07361262465944955 +-0.3757740657653892 0.1345278628306286 -0.2006755917821758 +-0.2397449752856222 -0.4507866486199946 -0.1344888983435708 +-0.05784472221474672 -0.2889152305229949 0.1334683366474528 +0.1373849146066041 -0.008647318170871773 -0.408255121743103 +-0.0497864492314431 0.4186415502110509 -0.3308679277507436 +-0.1068402246916053 -0.2886106754735896 -0.4190388735544455 +0.1148757983178093 -0.2793517264377015 -0.4161891046525698 +0.2150665869469894 0.2869858867014591 0.2079573302155094 +0.0852060005806099 0.5048881233271627 0.3148936710219518 +-0.4052578716598826 -0.02819115175653908 0.1422188420260218 +-0.4036895935426315 -0.4228041598857669 0.01512185153862065 +-0.3025402776493372 0.3486981790291262 0.06077753954491506 +0.1215440936711272 -0.2039120282695757 -0.1723173719678037 +0.015961974415 0.1265847361799863 -0.427633032 +-0.2976496345340369 -0.3900174051230375 -0.04500469358228095 +-0.3154025055307645 -0.3119338238618833 0.1062355327174276 +-0.3353990715793744 -0.1738631628551588 0.02348049956332405 +0.02207609537734997 -0.1089954300690458 -0.1625141711949978 +-0.2971498451679472 -0.009232606887089139 0.1017991092328016 +-0.2445469331097973 0.2381970876494945 -0.1739198133452223 +-0.305024684148987 0.1235703327504227 -0.08887239313600584 +-0.427778989 -0.277854532 -0.08292990920000001 +0.2648636372768667 -0.6042866716290831 0.05627149600745533 +-0.1773428900176362 -0.6039850691007004 0.2113668549128281 +0.173680343 0.2276216375 -0.385475591 +0.2569294590224957 -0.1714117898043101 -0.1464545056391314 +-0.2585472507749651 -0.493541333159672 0.08633133736428632 +-0.2074631635125739 -0.2285435515267166 0.256748556173928 +-0.2596026135355042 -0.1302844668122674 -0.1198275061585429 +-0.1312881909318755 0.4719405907103383 0.03233000934316037 +-0.2511564666760328 0.4183310736796829 -0.2108663662651638 +-0.2325704833159379 0.4734962502422281 0.1970477237812316 +-0.1546729022455 0.4771442570816429 -0.2538953762082819 +0.3810605572651261 0.2803332799354298 0.1165512711676113 +0.2634639973470491 -0.307942502552803 0.2910869758166492 +-0.003351426925055 -0.5807619395 0.290139258 +0.1367282512790136 -0.5007418383012656 -0.2475823070852039 +-0.1713734924053825 -0.3593067437011747 0.07181706480607103 +-0.1545294804924382 -0.3590599853646426 0.2664059351810635 +-0.2720421435163184 -8.39308019519704e-05 0.3371479242130709 +0.1630979828135925 0.2137525401035661 0.3902986653653894 +-0.1297771715689294 -0.2016628784488526 -0.3280418272988853 +0.1747486530667969 0.5940267238491674 -0.2075113828084235 +-0.1345088126151114 -0.2521123245789554 -0.007138893680080085 +0.04119794851787109 0.1890220404343686 0.3338634377095627 +0.3750534805436309 0.1484263380529169 -0.205883121642474 +0.2385735735 -0.15104741595 -0.3552913965 +-0.09629067191961346 -0.003789267399297132 -0.1864760841327101 +-0.263496575069674 -0.5718973905647539 -0.1572605645687737 +-0.3690179885 0.2060340905 0.1946550535 +-0.1800419225400152 0.1025104681991464 -0.1402048048393966 +-0.1767320757406734 0.01666131919940725 0.199914810717757 +-0.1936204025914483 0.1032728326789746 -0.2591995911539768 +-0.1386314869060407 -0.5067998309115177 -0.2472164391034785 +-0.2325954935309992 0.1208466627191255 0.1851798653025605 +0.372296163485709 -0.06376906585540616 0.18101953664619 +0.2041002545 0.4385491465 0.346586838 +-0.344366429864124 0.4355719718286908 0.2082304638604732 +-0.1838395646679504 0.3065780583882377 0.2796089169730213 +0.3465868235 -0.438549072 -0.19464025255 +-0.1697768760650009 0.4779495713028323 -0.1254613247934251 +0.1543532946390103 0.5278121924826857 -0.07248267603513611 +0.2043335808756595 0.03727509571503026 0.2013690321284192 +-0.321091676906617 -0.07714360395641504 -0.2754098716300964 +-0.3111585546066423 0.2185527358064106 0.2832064853618915 +0.009975845895331225 -0.1203559445606227 0.4130195549567683 +-0.352426335 -0.15534662845 0.2484183315 +0.4120339200564548 0.3397068620381402 -0.03586168864925547 +-0.2793160085 -0.5775248405 0.259948373 +0.05149880183718576 0.6053722933348005 0.316531536223693 +-0.08429267546662036 -0.5188346523655162 -0.09483261723942449 +0.1896049811915942 -0.4254431813272911 -0.3604436196077018 +0.299891658 -0.2870405315 -0.271827273 +0.1453408259069221 0.2175033037741923 0.2943730396106764 +-0.1049283193905183 -0.4918968176539089 0.1960489771983808 +-0.05794381082420919 -0.2884138392167545 -0.3441350457464294 +0.2645362729435945 0.4734144889096134 -0.303835302310591 +-0.07097393778326552 0.3746285365659218 -0.3941391548419448 +-0.2194040861640318 0.2379232043983964 -0.3497622002229657 +0.07839437870228416 -0.3250058059786342 0.3923325222035232 +0.418192059 -0.008318733199999997 -0.110506665 +-0.07491671397188383 -0.1191855003686487 -0.267868804854518 +-0.3605887421988807 0.5886111269854412 0.09686540490883234 +-0.08774343065812315 -0.07982323469022345 0.1925189209657307 +-0.3300721920133637 0.2252848062693257 -0.2603161961487446 +-0.07218807448969088 0.004985979939928538 -0.3287747884512898 +-0.06774809740800083 -0.06390680831985952 0.4219223236450746 +-0.1237309672070008 -0.05204751538436354 0.3178561647938162 +-0.09365125816646536 0.5903572040586901 0.3838305741620979 +-0.1156809156752381 0.01379056928841999 -0.04276575735932642 +0.316786006 0.301162586 -0.291431129 +0.3456409613134585 -0.05358141948712246 -0.2450831762463563 +-0.0551356902509216 0.2032268768794367 -0.3228893742867943 +-0.07717773729748827 0.1757293303066977 -0.1948310416216324 +0.273600593 -0.5883380174999999 -0.2661011295 +-0.03188984327996716 0.344732853480407 -0.2496765472917243 +-0.05940506586549304 0.4119467401513565 -0.1116521164371273 +-0.0994591090270818 0.5403263832334385 0.1621456508785945 +-0.07958576136895874 0.4675242360436406 0.2673446312272306 +0.1962823586076047 0.2525197728585637 -0.2556348991008133 +0.1159252652410223 -0.3389931874965461 -0.1634637160030722 +0.04629419328072763 -0.5116293057604204 0.2295684894216329 +0.2364581447637978 -0.1172720920625482 0.1616555637803476 +0.02193724523739948 -0.476161475783222 -0.1722279406470487 +-0.06918982651889551 -0.5195401185790596 0.07261084288283663 +-0.06724142681773403 -0.4094396248717473 0.00856003960298338 +0.05015198338073645 -0.3521781610291909 0.06663336609505546 +0.07945394962218595 -0.3477443796963735 0.2881008711357347 +0.008042545793192867 -0.3008719221688835 -0.1841624054311184 +-0.02411665063095021 -0.3112136095562342 0.01863403332805848 +0.001937677109670462 -0.2025488847720376 -0.362650665061153 +0.02572134316091138 -0.1039114112743602 -0.3280197579591284 +-0.03710230138546571 -0.1558607877637171 0.1027267922284501 +-0.204330891639503 -0.1645926163598535 -0.3842454630309592 +-0.138968865804752 0.2208673797020027 -0.3933348368864564 +0.03297372404525644 -0.02158433483567634 -0.2337867907437903 +-0.3862222982494936 0.4874376848606421 -0.1435839826779926 +-0.371567503 0.5736830835 -0.09726246388000001 +0.01217011846088707 -0.0879320849699389 0.3097591410704686 +-0.04391340571988969 0.03872540720041667 0.1102368812253893 +-0.02698374044602615 0.01981868621963806 0.2585893635358654 +0.005425672749999999 0.422198266 0.4068876505 +0.259115681 0.6027811169999999 -0.1570499615 +-0.00152786128928381 0.2504930825830123 -0.107750543589258 +-0.277339533 0.5736830835 -0.265840657 +-0.06495562840000001 -0.247803822 0.414215669 +0.04845803530748577 0.34897332566183 0.0271195499408075 +-0.03951206661759365 0.3121927523919646 0.1993607795224966 +-0.02699099405471267 0.2890281234155285 0.3356604936086811 +-0.2072878548729626 -0.008958418602296238 -0.2833429840570337 +0.4049250623858598 -0.4329478303229082 -0.007927972339998739 +-0.10223039797 -0.565993011 0.3652213215 +0.3542216134660791 0.00489113120285183 -0.05002472829534126 +0.1048684266296539 0.2981370222008701 -0.4000735513478448 +-0.2391175396479288 0.2178915621675852 -0.2681881191528645 +0.09036162512920722 -0.5404076829594197 -0.06933077045201948 +-0.2528251334974196 -0.2603523177034787 0.04385376384692458 +0.09851485868138612 -0.2949674844401479 -0.3031807428653767 +-0.3140021112378588 -0.2101235568397073 0.1380061934928258 +0.08440293750897293 -0.04420736017228444 0.1436602581091253 +-0.02224979703453388 0.1743029063582383 0.04243223892449446 +0.07461914861764454 0.1331436130234333 0.1911155637205438 +-0.1968430438057257 -0.1211413739038311 0.04454093998161739 +0.1151556774315287 0.2791812640687203 0.1218668402907316 +0.03928241773139791 0.1105359254854796 -0.2872636722740341 +0.06835244865225948 0.478385599526645 0.04654729508344334 +0.06271010040723136 0.5197528409700275 0.1994680044238338 +-0.3218161820854382 -0.0121909440363 -0.02889026306109014 +0.1510878182644197 -0.4918534681620604 0.2842441321416133 +0.1630499396512932 -0.4678918539400953 0.1813992608257213 +0.1867410204418718 -0.2964984674561385 0.1816486799006869 +0.101374547109088 -0.1960324081248217 0.2260718324610199 +0.3701540825 -0.588012159 -0.09618034331 +-0.10178242652 0.588012159 -0.3686529995 +0.405059743097103 0.2642231702432709 -0.07504102229496637 +0.1315445277667835 -0.02866163075991395 -0.08671437098155267 +0.4079678051465175 0.3500395641184872 0.06666989300875732 +0.1266420257077923 -0.06761477306688723 0.2897432017669022 +0.114094645 -0.003415345949999996 0.4129050075 +0.1738891370569094 -0.3425181478490261 -0.3831108481171535 +0.2414608 -0.232031241 0.3252218215 +0.1283151312815524 0.1206816094200846 0.06034993776227372 +-0.09422799736148076 -0.5742082294999999 -0.3741621225 +0.09263732873305598 0.254814643829168 -0.007107500797577666 +0.1515930410073318 -0.5056512535367123 -0.3742899918472581 +-0.1556413672563617 -0.04911828145478989 0.4031145395415115 +0.170865961153544 0.3072130347450495 -0.03563482349207218 +0.10572450263 0.5892598929999999 0.381205276 +-0.1537056214965078 -0.4992746893272231 -0.3764789016278572 +-0.1131103814 -0.325147569 0.3879116925 +0.4144549258320417 -0.3507168692032572 -0.04633784851160894 +0.3862395044373448 -0.03210586811422664 -0.1738651116623304 +0.2349577827622588 -0.4956572888497579 -0.07912768845784084 +0.2434659010629875 -0.4948935140120569 0.08169907972041521 +-0.3098215905 -0.1858893485 0.293022722 +-0.2259627452936632 -0.4984548983530693 -0.3374996123827595 +-0.364211485 -0.560714483 0.08853775274999999 +-0.2386694053206152 0.6030649836476458 0.1511868136736786 +0.2991177601130163 0.002215679013316561 -0.2941989508341468 +0.2869326115166015 -0.3872935830653446 0.1667810515198034 +0.2694621412862401 -0.2645248647220081 0.1081261462321951 +0.2135605528373467 -0.133803096527523 0.3380491711918227 +-0.066011888 0.2894495575 -0.4015417845 +0.4077942462082305 0.181234952486269 0.08491595142613526 +0.341977939 0.495954469 -0.2358691845 +-0.4235032613351645 0.2920093152001281 -0.08236506085832325 +-0.165180843 0.03366031695 -0.3952975425 +-0.4020138927764877 0.08319473318340173 -0.1399346871788395 +0.2880926994740734 0.03605844768813873 0.06056348689155579 +0.2405533542055085 0.04307696232359434 -0.2113927681170368 +0.2854946832077809 0.08045828471513498 -0.07736228468054485 +-0.3670999855 0.51327844 0.1599220375 +-0.1451479905 0.12276842615 0.4095368685 +0.2262414854442736 0.1927602763482975 -0.007230183018256209 +-0.278967318357596 -0.06825049209415004 -0.3321293215615821 +0.395075947 0.514216915 0.05344752833999999 +0.2904797784436757 0.274359770491243 -0.1007892902531596 +0.2355844369704628 0.3504651328307318 -0.2332665916632704 +0.4060338885 0.1851802393 -0.145043258 +0.2822591372870038 0.5030762614606762 0.03745143901083643 +-0.383639872 -0.469673857 -0.14269553865 +0.08389269937529492 0.3563341985225077 -0.1338971290526479 +0.2614553195 -0.3516275735 -0.3220659195 +0.3190108802617111 -0.2715037577006746 -0.08113920551927109 +0.3041733323134772 -0.3201424342999669 0.01579750922284979 +0.3466760560481353 -0.1845077656390903 -0.009292743203420809 +-0.1874218478864073 -0.5087630406904317 -0.02140662892452972 +0.3362647210612315 -0.09115535461027197 0.04657122050901688 +0.3479799289675536 0.1963419398124875 0.007910958075283069 +0.3293803770880532 0.3608445371194623 -0.1210602211744184 +-0.1168599911487053 -0.3546319136602739 -0.150362236057407 +-0.1524876697989041 0.2568314096355652 -0.2773206761428327 +-0.205582907941179 0.2720319925127396 0.1345678474398859 +0.0830104638395861 0.1919970943684773 -0.4145699018671125 +-0.0484320585573853 -0.0665577781929302 -0.4244493544854975 +-0.4309051355334645 -0.2535852874892913 -0.03096328332292416 +0.254629515 -0.07734374551930266 0.325132683 +0.1319786534925405 -0.1380220021761248 -0.2665243600145845 +0.06230234036306442 0.2396841932109335 -0.2747508984055904 +-0.1644669848243415 0.3530120070901507 -0.2230291592781949 +-0.2286243159029093 -0.2683623535579892 -0.1604439586769995 +0.2536386366462398 0.2713123009941345 -0.337233503454231 +0.2377438005897988 0.4377274987754453 -0.116281125378923 +-0.05899007617867852 -0.2167901996320974 0.2937090349087398 +0.419720143 -0.1904854215 -0.05875986330055467 +-0.2549799085 0.35636428 0.33494699 +0.01502871125 0.618750036 0.2363069875 +0.064344618915 -0.07734374932001374 -0.422943398 +-0.2174650527407027 0.3645609667649181 -0.3459787285077483 +-0.4286974078090693 0.1245435568021535 0.04043368546084054 +-0.3952180688776861 -0.2064023623861076 -0.1449879660355683 +-0.35427323 -0.546958804 -0.10395520175 +0.04333476427143541 -0.03915311286781552 0.4209245197729896 +-0.1519778179163347 0.2763697844595666 -0.0593644993317976 +-0.08281960676703523 -0.1829448564015596 -0.1313075990423341 +-0.1825709294463055 -0.1968290909483878 0.1451291269005188 +-0.2784748018663556 -0.2442796968546749 -0.03391297538111303 +-0.2460555063115908 0.6064196156059729 0.04609717912467848 +-0.3668968999654801 -0.1245435568021535 -0.2063888862893526 +-0.2862960552406257 -0.5794846866594859 -0.04544143569360261 +0.2393801639504664 0.4437593633402547 0.1595257600806125 +-0.2162539309092529 0.4447255385893123 -0.3494062710706623 +0.0885994421904466 -0.2247638141625985 -0.02538800923934454 +0.2431488602374934 0.3726027158437374 0.006982333426567117 +0.1966910090225644 0.4117551059930884 -0.3584559324925408 +0.00420300378287474 -0.3892955799486688 -0.1119662676604982 +-0.09978139984030811 0.6038800974356864 -0.2570858661536634 +-0.4219792014765823 -0.2408934020051884 0.09232407414519281 +-0.2847175105054598 0.2881682091333141 0.3002954082992862 +-0.3469439908444398 0.3506159391243009 -0.2448839748870988 +-0.08362315895726202 -0.4834319647105369 0.3959789895004271 +-0.16014917925 0.340013385 0.389250383 +0.06233924307559777 0.5138279215294546 0.4054637884526613 +0.06186636756223052 -0.1962779432060841 -0.4239082979348296 +0.378612563 -0.5126806349999999 -0.14848449455 +0.3977322725 0.355267659 -0.1476453505 +0.2304386588461684 -0.0914123632455083 -0.255674587080891 +0.3948882798113681 -0.5121633409630968 -0.04623745618569041 +-0.3967847503243356 0.5085799606803566 0.05808666702008818 +0.3959398565 -0.5138806105 0.05703411119 +-0.3510553741236231 -0.4318851748961799 0.223477862601599 +-0.4164153935 0.353466943 0.07608470885 +0.3204514384624537 -0.5100172219646568 -0.02228808694030203 +0.1139034239690002 0.2829304988161253 0.4013098291494395 +-0.2435943115 0.5128591655 0.3296703395 +-0.396915525 -0.478306517 -0.0497757494 +0.333415791 0.12283374385 -0.265174143 +-0.4206592784602669 -0.07070692068656032 0.09019771812872944 +-0.3174321084227918 0.228949224036482 -0.01316251101145547 +-0.05516033039557043 0.4559700450121313 -0.4008090479948098 +0.04670182185986002 -0.3598807412025519 -0.4224595737198194 +-0.0753246530018241 0.5327770280717243 -0.3946907440106561 +0.1850513836145607 -0.1064744570350409 -0.38518571804007 +-0.1633465269794671 -0.332412596604321 -0.4001961989452403 +0.0567841576 -0.39240244 0.4099227935 +0.2354462105301205 -0.5227026138377499 0.3185273898011249 +0.156229127 0.5118324165 0.3806571365 +-0.001124520986701967 -0.4270772061531626 -0.4207690113361229 +0.08440322632517661 -0.6187499721431172 0.1289810930398944 +-0.04761641735829022 -0.6187500320278504 -0.01546753254961011 +-0.07286839194491498 -0.6182730930599609 0.1438191058291024 +-0.1572889315 -0.618750006 4.095000000203797e-08 +-0.07796893471804928 0.618454131006582 -0.1392537755150663 +0.1537131490164399 -0.6187499470464712 0.004581258105823563 +0.07864447781180105 -0.618749976 -0.13621619335 +-0.4280558785271573 -0.06403804778140726 -0.08189659112323915 +-0.0005505530000000369 -0.1245435568021535 -0.4293746220558928 +0.2503933051422422 0.3741912586723843 0.3276271635465807 +-0.06472229932769863 -0.4834689704477347 -0.4127284372094703 +0.1963205657486748 0.04899727356338292 -0.3785490052802633 +-0.1938468090571603 -0.1352933915683426 0.3740222817360567 +0.09722910449821125 0.618750033661861 0.007674333021242171 +0.314252734 -0.507722959 0.2481888235 +0.3165597031069344 0.5183948933844975 0.243764548977033 +0.04855409354029682 -0.4956131534462813 -0.4125504876645361 +-0.374489501 0.02863343055 0.2027500795 +-0.3279313375395712 -0.5002221258776881 0.2442251874865979 +-0.4249186665 0.336740777 -0.0144473668 +-0.04984090271161375 0.04377040454934983 -0.4207215452132406 +-0.3969224331095201 -0.3433666561666903 -0.1437510793688668 +0.08582942828815208 -0.5866806079441573 -0.3236906470685441 +-0.3086523610479485 0.5078570070489576 0.2551069854858188 +-0.2939087332171976 0.4958617222160686 0.07986809551319543 +-0.0001871898906716102 0.6061099761556343 -0.267495731878639 +0.2541728705217015 -0.3434467904202981 -0.139907367062397 +0.08299625986508601 0.4651298307427137 -0.3905369624424223 +0.373331651 -0.5077229735 0.1527863365 +0.0526237241464986 -0.2075725946702558 0.4124840991827641 +0.1537400986387132 0.6008008305298601 0.2921423915909329 +-0.227960877 -0.03598781484999999 0.367553055 +0.07835933691956778 0.1873647048467206 0.4227592249998333 +0.1845597880596481 -0.6041460192715369 -0.2045281086160735 +0.2444687267693118 -0.6075012876226753 -0.02276330353941064 +0.2649362829031882 -0.6004647312270243 -0.1572234699793945 +0.2705205372193197 -0.602693840804577 -0.08513295022787484 +0.2485825210266455 0.608105082692182 -0.07180685989706868 +-0.405452791766178 0.2210241244320134 -0.1389338076357439 +0.2684389575251179 0.6060757873160907 0.0471700969802261 +0.284889189807686 0.6043755309615064 -0.004373418555900916 +0.2814227402489604 0.6017325353361151 0.116364724049557 +0.1593494079671539 -0.5145906598089254 0.3711640267104671 +0.3446605366874384 -0.1971780404712199 0.208584075487942 +0.2618104732162249 0.3729042815082538 -0.3233683434261493 +0.2334502583313306 0.2381495721867878 0.3537742269683172 +-0.08501481940235303 -0.2877093622232539 -0.2506278013990226 +0.1546446792908862 -0.3930971130834396 0.05862459414737801 +0.2917137415812378 -0.04112417818067522 -0.1198668642658359 +0.3460870906526887 0.2438157259470327 -0.2487931343865797 +0.0107699541799139 -0.4868247476908478 -0.01432056850264958 +0.348166953639337 0.4611503949921887 0.1996273467850661 +0.3687560158123723 0.3736306704064606 0.1727918362929567 +0.2627896374429577 0.1603129404258788 0.1600648271916091 +-0.3043775756038896 0.3205913939969904 -0.1014664407004432 +-0.1777982250772295 -0.5103135672959384 0.3619772896391597 +-0.3869324447656813 -0.20150270092572 0.1820793011701245 +0.2251018292456612 0.6041010879541899 0.2076234831499581 +0.3564547198774167 0.5396887461426652 0.1727918362929567 +-0.03006889510103946 0.504032751172212 -0.2976480129230574 +0.2577149888932548 -0.5932214215390774 0.177292474045204 +-0.387114599579773 -0.1038346891059945 0.1853938536767072 +-0.3094667774488816 0.1402522348023385 0.1079374900296878 +0.3813798717054602 -0.2906016325383582 0.1212680363783779 +0.0274943253 0.338113159 -0.4217578025 +0.1730200509625188 -0.2003637807940751 -0.3880541267606268 +0.3598302455 0.338541493 -0.2303000245 +0.06241505053 -0.4933292865 0.4016945955 +0.08264885828275022 0.05337906645966909 0.3241875625787943 +0.387900761204709 -0.3303677430916976 -0.12783664801219 +0.3868704183525272 -0.2906016325383582 -0.1268100426242272 +-0.02524856440865056 -0.4306648752998071 0.3167793108862672 +0.01979972953853895 -0.3907745154765107 0.1778720638967805 +0.4032335734887317 0.4273841492419995 0.001612326202434023 +0.285944 -0.09603813294999999 -0.313113496 +0.2802383375 -0.209696792 -0.3119112405 +-0.0870115934 -0.387155473 0.404030532 +-0.2519947735 0.198344488 0.350970894 +0.3995632312192625 -0.175474684878214 -0.1394568135993472 +0.4172642666508833 0.2075725946702559 -0.03535778308667843 +0.41980906598118 0.202310618049905 -0.009010877574715371 +0.367880836 0.0550069799496553 0.199948728 +0.02548943760840382 -0.1912172186077626 -0.2141662623699391 +-0.1740072739596234 -0.6026581355342431 -0.2265087888918866 +-0.1800898376708286 0.6031643387497339 -0.213179381146714 +-0.04675355805123909 -0.3141568396456604 -0.06061845794837209 +0.1636679114987711 -0.6085793587941423 0.1801999149084853 +0.2160051174006993 -0.5953590262755591 0.2324466097442588 +-0.4268359460543146 0.0266113984371855 -0.08644945014647828 +-0.4094579507268242 -0.2875445389494477 0.1432699569682873 +-0.4320314521474286 -0.1855707377491023 0.03719731551326159 +-0.1841945964913504 -0.1262509638374857 -0.2567509871790516 +-0.3282601421684787 0.1143241167845003 0.259205598439435 +-0.3198399673875409 0.456659708274563 -0.2748166660362582 +-0.2142194215001074 -0.09649261089031481 0.2454175514642232 +-0.2731418146605293 -0.5609620054061417 -0.259276974439435 +-0.3670314850605868 0.4293121318602908 -0.2010306940847976 +-0.2774090755186172 0.0415145189340512 -0.3296801536009085 +-0.2389074174532482 0.0415145189340512 -0.3557814337940227 +-0.2387989658812601 -0.2075725946702558 0.3494648274405306 +-0.2750205287339846 -0.2817515474680656 -0.3342925385727562 +-0.3155906632479173 -0.4919079065420375 -0.245490197393591 +-0.1136822112606668 -0.04024662703879107 -0.4167899257199114 +-0.07029392308134419 0.5241609965026423 -0.2010497458031905 +-0.2628036122609522 -0.591247715768052 0.139370424772662 +-0.2647013366587084 0.5857310565499809 -0.1547708061977015 +-0.009965806005039501 -0.4373653974545303 0.4072142037190906 +0.08617780747981155 -0.5646634084701685 0.368820372162439 +0.08617780747981155 -0.5728867157718533 -0.3769404150962252 +0.4223157315 -0.197478414 0.04488322604944532 +0.07287550057786323 -0.60784884450035 0.2393046214277794 +0.08617780747981155 -0.6058589667129644 -0.2498336917421684 +-0.237024814 -0.3350156845 -0.3610792905 +0.01656523932727127 0.194138802780305 0.4309515016686922 +0.1310442890753476 -0.168834104990631 0.3961400857981809 +-0.1186453541862984 0.03152218305803531 -0.4137601457964857 +-0.06033648169213519 -0.2169063126834695 -0.4263517658860488 +0.3262953452186929 -0.4063267505109554 -0.08744936556237655 +0.1175294413262383 0.5697031033778372 -0.3614662558500535 +0.2596345284394349 0.5706218530302862 -0.277963692878721 +0.2690450145008758 0.4851751095527085 0.3091849424715172 +0.385023162 -0.37396203 -0.14440160605 +0.3665207595820238 -0.1379917387913006 0.1726350051253442 +0.366451668139239 0.5902334385805807 0.08637807414647838 +0.3697015660635281 0.2075725946702559 0.1871434885401562 +0.3670871337211838 -0.5840026821756783 0.08637807414647838 +0.378406773682972 -0.3736306704064606 0.1560384638685314 +0.2773731011822756 0.1715671271150959 -0.1767229014447427 +0.4288514527437218 -0.1407164122427199 0.004277586245099149 +0.4120087875691528 -0.04151451893405114 0.1102979816696245 +-0.3133076042027405 0.04921335438791095 0.2955615033038269 +-0.282869890741592 -0.5810275929601582 0.02618419015345438 +-0.2906957485296473 0.2906016325383584 -0.3155270721750066 +-0.2653844001494128 0.4808120254088119 -0.314443403103348 +0.05919631862280739 0.06211709286707583 0.4218717592040434 +-0.1865342253963684 0.6058793549467693 0.2288202231133549 +-0.09036569322013432 -0.6045864354560753 -0.2562013916796191 +-0.04063291794337065 0.5094552525280088 0.4071152212280699 +0.07938632791194553 0.5954235692232808 -0.2400346949950579 +0.1404374875993993 -0.003998677096152696 -0.2987924187335836 +0.2623650540095189 -0.5837913135734705 0.2700339435973981 +0.3908903071787997 -0.204507194361399 0.1371246997796501 +-0.2881307954040521 -0.4033243120519729 0.1397584870042364 +0.1754541778956834 0.618750036 -0.02910477857041754 +0.3085227538915116 -0.5887208966174488 0.1355444473109699 +-0.419763461 -0.360583305 0.09266895065 +0.2873180539687482 0.5885796421887655 0.2569939997190732 +0.06871134448077476 0.5108917664393 -0.3167476194681131 +-0.2113219521827127 0.1993615079010768 0.3786376567618444 +0.0338375052900655 0.5132309461219096 -0.1513174955158766 +-0.2184110636740786 -0.6003899325901871 0.04222282556408408 +-0.1593330056971158 -0.1053001532294161 -0.3997211323251008 +-0.2309195609559901 -0.4838117221254626 0.2184868730407915 +0.2612149753088364 0.03281246662472402 -0.3427196376591594 +-0.08812112996638422 -0.3727102667327472 -0.3563389698511792 +0.139183852380513 -0.2548650873924763 0.3121067363094126 +0.1457181293862169 0.2347487981198268 -0.1169845248825207 +0.09760614862739125 0.4079580925113135 -0.268578942126128 +0.2342868307757104 -0.444851299718482 -0.198979199810223 +-0.03244267835128035 -0.2068589984777075 -0.2931444178144002 +0.2407589068531709 -0.1438305059565873 -0.01518699028636235 +-0.3099476464765188 -0.09738141957885726 0.1614385238054677 +-0.155849162201725 -0.4115946364705091 -0.2923697324580832 +-0.0007966346287849452 0.5968885789767087 -0.3307579993586976 +-0.1503104645 0.399013683 -0.3805404155 +0.319123283 0.373962015 0.258865155 +0.1776483453950436 0.1317241940902189 -0.2812924652402017 +-0.257739609969181 0.5966760055063848 0.2245382583761247 +0.2517681159805457 -0.4965294997132701 0.2140331092378601 +-0.1592413480132685 0.2611979422470886 0.3962275334917052 +0.2144675324926161 -0.227112475594296 -0.248018241106912 +-0.1251450534721542 0.3712593273878062 -0.3105872446307932 +-0.3343938985466754 -0.21874505739384 -0.09717177095562905 +-0.00588819898035662 0.6187500340529887 -0.04488268217302764 +0.1616425454593239 -0.2460581211291851 0.3801839663435792 +-0.1425184217399059 -0.5974629560787548 0.2898406477148215 +-0.1591297548217757 0.5149658466756449 0.3790599458084152 +-0.283175165259288 0.5877126109650546 0.2634888059710822 +0.4213915375277536 0.1922114984010768 0.01481308382013163 +-1.51363206e-08 -0.5740907040000001 -0.3537813165 +0.3429823434069847 0.1599673930623294 -0.08982767615406438 +-0.107934516 -0.22085232675 -0.4201761405 +-0.2015765651897185 0.4237326579229729 0.3487100438382201 +0.08968178357708449 0.3664922138845957 0.2594554147074725 +0.3415296036390353 -0.4605725180419376 0.2096798103502091 +0.4033524983527301 -0.2782803882691791 0.06063401538863428 +0.1990743363339474 0.4101429010464731 0.2613166940500995 +0.4199200619298634 0.1607548848723006 -0.06058703817606816 +0.4310638862814464 -0.06239321646038666 0.007009561019473583 +-0.1765646731284764 -0.2584737913351279 0.3780212551517145 +0.1052768039710378 -0.4220620182873015 -0.05750472858321085 +-0.08617747972161377 0.123255169973587 0.3081313557740759 +-0.2000506246411184 0.1169252184232824 0.04120677523089692 +-0.1942008717919523 -0.2866733468276128 -0.2879256543362027 +-0.1519800008119504 0.1931690834712601 0.2532873547587903 +0.3051128675824679 0.3210593446968433 0.07799341403941382 +0.1036867579552456 0.1140815414719658 -0.1553292047482978 +0.0165429201288857 -0.4610107429521613 -0.3071063528622973 + +CELLS 2221 11105 +4 219 220 247 325 +4 144 357 174 143 +4 175 243 596 593 +4 594 178 175 243 +4 3 173 464 135 +4 231 272 74 473 +4 93 102 304 445 +4 221 153 155 301 +4 65 342 306 216 +4 1 271 391 492 +4 32 209 493 553 +4 246 439 346 109 +4 82 92 160 218 +4 232 227 599 224 +4 409 152 140 574 +4 273 489 488 462 +4 593 168 251 252 +4 76 259 407 296 +4 368 83 549 200 +4 228 449 230 474 +4 571 596 252 51 +4 473 159 225 469 +4 296 297 592 259 +4 225 231 272 273 +4 549 427 565 461 +4 384 24 554 19 +4 363 125 355 138 +4 391 492 140 7 +4 161 151 162 126 +4 149 329 480 115 +4 598 285 279 317 +4 1 142 271 464 +4 556 595 448 199 +4 276 386 438 107 +4 143 357 217 343 +4 557 305 275 516 +4 411 100 131 567 +4 322 108 529 320 +4 108 320 278 333 +4 154 357 143 343 +4 251 269 585 250 +4 191 367 333 320 +4 312 317 332 314 +4 151 347 496 49 +4 486 156 505 184 +4 279 149 366 136 +4 165 448 199 561 +4 139 260 359 161 +4 485 194 177 172 +4 573 201 44 566 +4 505 551 427 62 +4 226 186 98 179 +4 507 248 156 154 +4 484 136 366 232 +4 419 133 142 563 +4 284 274 275 93 +4 201 219 128 573 +4 495 154 535 248 +4 135 153 456 123 +4 380 302 313 215 +4 134 138 4 0 +4 4 138 134 389 +4 56 394 199 401 +4 358 334 448 232 +4 357 247 220 250 +4 275 231 474 274 +4 320 367 346 290 +4 9 384 544 19 +4 334 369 227 232 +4 450 105 256 204 +4 522 364 94 588 +4 503 30 564 299 +4 311 5 144 124 +4 332 121 582 589 +4 538 599 286 177 +4 142 266 213 175 +4 577 457 198 554 +4 267 131 285 317 +4 22 425 155 569 +4 25 388 584 155 +4 27 178 596 175 +4 27 593 175 596 +4 29 433 496 163 +4 29 151 496 414 +4 202 258 47 335 +4 28 202 258 47 +4 468 379 333 108 +4 233 230 366 126 +4 349 584 182 25 +4 31 550 182 571 +4 31 375 571 182 +4 41 198 228 150 +4 161 229 198 228 +4 34 26 595 237 +4 127 64 541 75 +4 75 413 541 127 +4 421 392 135 3 +4 37 457 577 554 +4 326 261 560 428 +4 560 106 92 326 +4 117 329 511 543 +4 41 403 405 228 +4 41 552 150 228 +4 42 406 153 184 +4 43 478 473 162 +4 20 182 155 25 +4 25 584 182 155 +4 44 352 202 335 +4 260 167 359 161 +4 290 267 317 367 +4 48 401 556 412 +4 197 585 85 131 +4 219 559 128 461 +4 265 186 455 90 +4 271 140 142 391 +4 362 409 152 271 +4 61 599 227 513 +4 408 227 513 61 +4 132 432 522 69 +4 490 271 409 362 +4 199 261 599 394 +4 428 106 560 326 +4 560 106 428 183 +4 64 127 235 351 +4 435 160 259 592 +4 408 435 160 259 +4 64 209 541 75 +4 122 270 79 69 +4 357 247 219 220 +4 220 269 325 551 +4 220 269 250 325 +4 65 466 306 257 +4 53 222 270 132 +4 100 90 455 526 +4 41 228 198 404 +4 228 60 198 404 +4 414 501 151 591 +4 69 270 79 364 +4 69 270 364 522 +4 7 563 140 142 +4 47 176 209 216 +4 72 235 261 341 +4 72 235 341 541 +4 75 568 541 413 +4 75 568 268 541 +4 535 45 156 365 +4 61 408 194 403 +4 403 408 194 259 +4 373 498 456 154 +4 80 203 576 557 +4 444 272 74 91 +4 486 370 156 36 +4 184 406 220 505 +4 88 261 572 467 +4 440 12 309 456 +4 122 79 270 269 +4 560 261 224 428 +4 251 265 267 168 +4 307 455 526 332 +4 31 375 182 349 +4 455 307 312 332 +4 97 200 321 346 +4 99 460 417 443 +4 100 455 131 597 +4 434 73 168 164 +4 574 360 152 140 +4 36 45 156 535 +4 18 29 496 163 +4 298 18 29 496 +4 449 297 296 328 +4 114 304 297 303 +4 116 320 332 597 +4 116 597 191 320 +4 562 328 366 327 +4 486 36 156 248 +4 172 194 177 125 +4 8 20 385 135 +4 455 526 90 111 +4 227 592 259 160 +4 23 154 373 352 +4 14 150 533 138 +4 352 373 258 335 +4 148 342 337 568 +4 158 102 303 274 +4 159 60 225 512 +4 153 221 269 122 +4 96 196 572 477 +4 46 221 153 122 +4 83 521 166 200 +4 90 100 455 447 +4 341 467 72 396 +4 380 89 476 170 +4 414 591 151 49 +4 40 330 194 172 +4 485 40 194 172 +4 188 20 336 173 +4 94 522 588 180 +4 155 315 425 22 +4 93 226 275 305 +4 19 190 298 151 +4 42 507 184 123 +4 42 507 123 241 +4 526 332 455 597 +4 193 432 132 69 +4 9 16 544 384 +4 163 593 27 39 +4 200 83 540 166 +4 363 172 125 330 +4 194 330 125 172 +4 331 117 543 329 +4 67 70 387 252 +4 387 70 585 252 +4 67 387 168 252 +4 108 468 451 320 +4 322 278 320 582 +4 108 320 451 529 +4 123 184 153 456 +4 241 507 123 17 +4 190 496 298 151 +4 203 431 576 557 +4 382 315 8 426 +4 503 564 595 344 +4 409 140 152 271 +4 28 208 258 534 +4 72 261 130 467 +4 234 261 130 72 +4 138 15 125 324 +4 539 63 222 212 +4 146 462 546 297 +4 176 209 217 171 +4 174 217 171 176 +4 373 335 143 258 +4 446 345 321 84 +4 143 373 343 335 +4 56 261 199 394 +4 89 302 380 476 +4 450 105 295 215 +4 130 56 394 261 +4 574 344 138 15 +4 568 313 390 529 +4 135 336 464 392 +4 17 507 123 495 +4 154 156 535 248 +4 596 252 251 182 +4 194 334 229 369 +4 251 585 222 245 +4 357 184 220 343 +4 153 184 220 357 +4 138 344 360 167 +4 271 266 213 142 +4 440 456 124 12 +4 353 421 3 392 +4 12 208 143 124 +4 270 132 588 522 +4 243 266 213 236 +4 18 133 419 563 +4 419 464 142 10 +4 8 135 123 426 +4 190 18 298 496 +4 543 304 445 226 +4 11 361 426 123 +4 11 123 42 361 +4 561 234 261 199 +4 448 261 199 561 +4 224 261 572 428 +4 141 239 279 341 +4 293 55 347 249 +4 225 273 402 474 +4 13 144 213 174 +4 594 392 464 336 +4 544 162 139 19 +4 41 552 228 405 +4 1 271 353 464 +4 464 271 353 144 +4 358 167 236 266 +4 344 334 493 358 +4 360 260 167 266 +4 540 551 559 166 +4 575 153 551 269 +4 406 153 220 551 +4 406 153 551 575 +4 563 359 266 496 +4 532 142 178 175 +4 595 334 493 344 +4 532 496 175 163 +4 592 297 449 402 +4 241 17 123 240 +4 498 17 240 123 +4 178 532 175 27 +4 377 130 234 56 +4 532 27 163 175 +4 5 353 144 392 +4 456 144 143 357 +4 3 135 464 392 +4 349 20 25 182 +4 398 80 74 231 +4 273 570 297 303 +4 135 336 153 155 +4 253 318 500 32 +4 159 255 57 473 +4 57 374 473 255 +4 83 200 540 549 +4 540 83 549 520 +4 483 179 186 312 +4 90 186 483 98 +4 562 115 450 331 +4 297 77 402 407 +4 432 459 86 522 +4 405 40 194 403 +4 432 522 86 132 +4 161 162 198 126 +4 359 347 151 126 +4 595 448 165 493 +4 178 596 264 336 +4 334 493 358 448 +4 334 487 358 167 +4 151 347 162 126 +4 247 558 342 325 +4 247 558 325 287 +4 585 270 364 269 +4 496 266 207 359 +4 496 211 175 163 +4 163 593 175 27 +4 163 211 175 244 +4 574 344 360 138 +4 144 594 213 357 +4 594 264 336 178 +4 577 159 60 198 +4 594 264 243 213 +4 255 159 577 198 +4 335 573 44 352 +4 249 347 49 189 +4 47 176 258 28 +4 182 52 222 584 +4 343 156 219 573 +4 64 209 235 541 +4 205 239 235 209 +4 171 213 358 141 +4 317 332 582 320 +4 403 402 452 228 +4 159 225 60 198 +4 346 113 246 109 +4 198 126 474 229 +4 198 126 162 474 +4 198 228 225 60 +4 473 474 225 198 +4 564 334 599 448 +4 187 318 493 26 +4 318 26 32 493 +4 493 209 171 205 +4 435 76 296 259 +4 232 369 227 224 +4 161 229 487 233 +4 213 171 217 598 +4 211 244 242 207 +4 207 244 175 211 +4 207 244 243 175 +4 211 54 242 244 +4 244 243 593 265 +4 244 175 593 243 +4 594 243 175 213 +4 213 247 357 264 +4 178 596 243 264 +4 561 484 261 235 +4 106 428 471 327 +4 176 143 174 217 +4 182 251 222 52 +4 182 52 252 251 +4 52 252 251 245 +4 219 461 128 156 +4 251 222 269 153 +4 406 505 370 62 +4 150 161 138 544 +4 460 323 525 319 +4 197 90 265 455 +4 186 90 265 470 +4 228 452 449 402 +4 474 402 225 228 +4 128 66 559 466 +4 272 273 488 225 +4 74 80 272 231 +4 232 366 358 487 +4 12 143 456 124 +4 12 373 456 143 +4 55 347 431 231 +4 561 484 235 205 +4 126 230 366 275 +4 551 269 325 185 +4 592 296 449 297 +4 171 239 268 598 +4 171 279 239 598 +4 213 243 279 264 +4 470 593 168 265 +4 198 161 126 229 +4 213 264 598 247 +4 186 90 470 87 +4 65 337 257 342 +4 357 250 153 251 +4 191 280 597 116 +4 164 73 168 197 +4 556 56 199 401 +4 263 275 226 281 +4 359 266 207 236 +4 88 326 261 283 +4 283 88 130 261 +4 284 93 275 305 +4 387 85 197 585 +4 387 164 197 85 +4 292 564 412 48 +4 286 599 581 59 +4 211 210 289 49 +4 62 551 540 78 +4 352 23 534 373 +4 11 241 123 6 +4 10 464 353 3 +4 3 10 464 173 +4 250 367 267 290 +4 364 367 267 250 +4 47 238 202 335 +4 335 216 47 238 +4 160 599 224 261 +4 21 172 497 503 +4 177 497 172 503 +4 272 74 91 80 +4 172 125 503 324 +4 275 366 263 226 +4 122 350 270 69 +4 226 562 279 312 +4 366 263 279 243 +4 242 207 244 263 +4 242 281 263 244 +4 294 114 119 328 +4 234 261 235 561 +4 72 261 235 234 +4 115 450 256 204 +4 268 216 337 137 +4 279 285 264 243 +4 598 264 279 285 +4 470 197 168 73 +4 370 461 277 427 +4 574 152 360 344 +4 15 152 344 187 +4 299 292 177 38 +4 342 247 598 558 +4 342 223 598 568 +4 247 287 250 264 +4 250 251 269 153 +4 596 593 265 251 +4 596 252 593 251 +4 164 197 85 447 +4 527 430 297 546 +4 8 426 123 382 +4 313 105 450 215 +4 302 105 313 215 +4 390 105 313 302 +4 166 551 559 185 +4 325 346 269 250 +4 250 367 346 269 +4 250 346 290 325 +4 593 168 265 251 +4 516 305 281 68 +4 494 532 178 27 +4 5 392 144 440 +4 124 5 144 440 +4 366 236 126 275 +4 306 65 216 47 +4 307 116 580 332 +4 119 327 329 348 +4 303 158 274 273 +4 209 47 517 310 +4 311 144 13 124 +4 366 449 428 328 +4 274 226 366 275 +4 22 315 301 155 +4 206 22 315 301 +4 154 456 184 123 +4 456 357 154 184 +4 596 265 243 264 +4 279 149 136 341 +4 151 19 139 162 +4 151 262 359 139 +4 598 279 541 313 +4 194 229 452 369 +4 263 186 285 265 +4 336 251 222 182 +4 568 529 95 223 +4 568 95 390 555 +4 568 390 95 529 +4 279 314 317 312 +4 285 558 287 317 +4 223 529 95 451 +4 287 317 290 267 +4 287 558 290 317 +4 200 346 166 559 +4 185 166 246 346 +4 559 346 166 185 +4 447 197 85 131 +4 345 223 95 214 +4 223 214 451 95 +4 118 589 322 582 +4 538 599 177 61 +4 558 320 346 290 +4 185 166 78 246 +4 436 407 297 296 +4 404 60 198 577 +4 128 201 393 66 +4 57 469 473 508 +4 78 185 246 439 +4 2 409 574 362 +4 354 2 574 362 +4 329 480 348 327 +4 562 329 115 331 +4 313 541 568 555 +4 326 92 560 195 +4 378 519 386 112 +4 386 107 381 383 +4 455 483 186 312 +4 90 186 455 483 +4 296 560 428 519 +4 334 232 358 487 +4 232 448 599 334 +4 247 250 357 264 +4 450 562 149 115 +4 328 329 327 562 +4 543 331 304 226 +4 543 102 445 304 +4 291 86 132 432 +4 128 201 566 393 +4 304 331 562 226 +4 405 330 228 194 +4 40 194 330 405 +4 330 194 229 228 +4 330 125 229 194 +4 126 474 230 275 +4 331 117 120 531 +4 32 209 253 493 +4 92 160 560 195 +4 529 320 317 582 +4 144 464 271 594 +4 511 543 328 587 +4 584 375 182 52 +4 597 475 191 367 +4 584 349 182 375 +4 367 317 320 597 +4 54 210 242 356 +4 448 599 199 261 +4 346 113 308 246 +4 166 200 246 346 +4 269 79 185 415 +4 562 450 312 331 +4 450 312 331 256 +4 543 445 524 226 +4 167 126 366 236 +4 153 551 269 220 +4 406 551 505 62 +4 406 551 62 575 +4 113 104 308 246 +4 594 392 336 357 +4 464 178 594 336 +4 226 179 312 186 +4 336 251 264 357 +4 114 304 328 297 +4 254 114 328 297 +4 551 461 427 540 +4 498 123 456 154 +4 73 90 197 164 +4 522 132 180 86 +4 30 514 595 564 +4 338 64 235 410 +4 339 574 145 2 +4 93 524 226 179 +4 271 266 152 213 +4 140 271 266 152 +4 124 13 28 176 +4 585 132 222 245 +4 484 341 261 235 +4 265 197 267 168 +4 54 593 39 316 +4 224 572 149 428 +4 557 284 274 275 +4 284 102 274 93 +4 409 140 492 2 +4 226 562 312 331 +4 344 138 125 334 +4 58 461 277 395 +4 171 209 217 268 +4 217 268 216 342 +4 592 560 224 428 +4 160 560 261 224 +4 125 177 564 334 +4 140 360 152 266 +4 468 333 320 108 +4 456 357 392 144 +4 144 392 594 357 +4 334 161 167 138 +4 1 10 464 353 +4 41 506 147 198 +4 150 554 161 544 +4 495 23 154 373 +4 452 230 229 228 +4 162 591 293 347 +4 15 595 26 344 +4 22 425 569 579 +4 206 11 361 426 +4 23 535 154 365 +4 23 365 154 352 +4 530 119 329 348 +4 456 143 144 124 +4 29 414 496 433 +4 29 501 151 414 +4 321 468 320 451 +4 33 151 19 298 +4 388 35 578 537 +4 242 211 347 210 +4 103 560 437 378 +4 276 437 296 378 +4 270 193 132 69 +4 40 61 194 403 +4 205 235 239 141 +4 352 566 573 44 +4 20 155 135 181 +4 47 422 209 517 +4 38 485 538 177 +4 49 347 210 189 +4 249 591 49 347 +4 234 261 199 56 +4 268 209 541 239 +4 299 292 48 564 +4 194 259 227 452 +4 62 551 78 575 +4 272 399 91 444 +4 122 53 270 350 +4 356 68 281 282 +4 69 459 432 522 +4 598 529 223 558 +4 130 283 261 71 +4 118 322 169 582 +4 118 169 105 582 +4 145 138 4 423 +4 274 304 226 93 +4 267 131 317 597 +4 79 323 441 443 +4 80 284 557 576 +4 81 542 272 399 +4 82 424 513 160 +4 288 599 71 510 +4 92 106 560 183 +4 358 141 205 171 +4 358 232 561 484 +4 94 453 364 417 +4 494 173 464 10 +4 494 464 419 10 +4 99 417 459 443 +4 416 570 91 586 +4 101 430 527 546 +4 334 369 232 487 +4 431 275 231 347 +4 461 551 559 540 +4 336 135 153 357 +4 70 67 245 252 +4 112 254 294 519 +4 224 366 592 428 +4 296 449 428 592 +4 32 253 318 493 +4 307 121 111 312 +4 245 132 70 585 +4 270 222 585 132 +4 274 226 304 366 +4 370 45 156 36 +4 277 370 36 45 +4 48 412 556 564 +4 325 321 559 346 +4 223 321 559 325 +4 171 239 141 205 +4 353 464 392 3 +4 20 173 135 336 +4 257 219 342 559 +4 330 125 138 229 +4 330 138 161 229 +4 13 171 152 493 +4 140 142 563 266 +4 229 452 592 230 +4 452 369 592 227 +4 194 369 452 227 +4 423 4 324 138 +4 365 45 156 573 +4 128 201 66 466 +4 338 209 235 64 +4 357 250 251 264 +4 232 366 484 358 +4 493 358 448 205 +4 126 236 347 275 +4 359 347 207 496 +4 116 278 320 191 +4 335 216 44 573 +4 266 358 213 236 +4 209 268 137 216 +4 209 216 217 268 +4 250 346 367 290 +4 142 391 140 7 +4 279 317 285 312 +4 544 138 150 134 +4 154 343 156 184 +4 343 156 184 220 +4 205 239 209 171 +4 47 216 209 137 +4 229 369 334 487 +4 178 336 188 596 +4 364 323 110 597 +4 110 323 364 460 +4 219 551 505 220 +4 262 7 140 371 +4 492 371 140 7 +4 556 401 199 599 +4 218 92 560 103 +4 42 46 361 153 +4 293 249 347 591 +4 92 82 160 195 +4 286 599 412 177 +4 135 6 8 123 +4 3 421 385 135 +4 6 123 382 8 +4 379 278 191 333 +4 245 70 132 376 +4 376 70 132 400 +4 456 135 357 153 +4 55 478 473 508 +4 519 112 378 183 +4 386 378 296 519 +4 333 191 379 113 +4 307 157 332 526 +4 570 101 462 546 +4 570 272 273 489 +4 542 489 272 570 +4 542 101 462 570 +4 380 279 341 149 +4 380 279 450 313 +4 435 218 560 437 +4 378 386 381 112 +4 112 254 386 381 +4 493 448 165 205 +4 503 595 564 30 +4 242 244 470 281 +4 37 457 554 24 +4 382 426 123 11 +4 6 123 11 382 +4 11 206 382 426 +4 254 114 297 383 +4 383 114 297 430 +4 259 592 227 452 +4 366 224 149 428 +4 385 6 8 135 +4 19 139 262 151 +4 151 359 161 139 +4 183 523 519 112 +4 578 53 537 35 +4 14 138 355 389 +4 297 407 146 77 +4 77 488 297 402 +4 577 255 198 457 +4 227 599 224 160 +4 135 392 456 357 +4 394 261 599 71 +4 71 130 394 261 +4 277 461 45 395 +4 396 89 541 380 +4 380 170 396 89 +4 127 89 541 396 +4 69 364 79 459 +4 30 514 564 48 +4 61 194 177 485 +4 176 28 500 499 +4 28 47 176 500 +4 180 132 400 86 +4 41 403 228 404 +4 403 408 259 407 +4 408 76 435 259 +4 408 76 259 407 +4 1 490 271 409 +4 199 394 599 401 +4 228 452 230 449 +4 42 46 153 122 +4 94 180 588 411 +4 411 567 588 94 +4 286 599 59 412 +4 554 16 506 192 +4 339 574 140 360 +4 413 89 541 127 +4 541 413 555 89 +4 49 591 151 347 +4 414 49 211 289 +4 551 185 575 269 +4 97 468 321 214 +4 468 214 451 321 +4 542 101 570 416 +4 24 33 162 19 +4 57 159 469 509 +4 450 115 215 295 +4 271 213 144 594 +4 419 532 178 494 +4 572 341 149 380 +4 96 572 380 477 +4 176 124 143 258 +4 72 341 261 467 +4 418 71 401 599 +4 418 510 71 599 +4 498 123 240 6 +4 363 125 138 330 +4 257 342 337 148 +4 309 456 6 421 +4 422 209 338 64 +4 137 422 64 209 +4 458 19 262 190 +4 177 564 334 599 +4 337 568 75 148 +4 75 148 568 95 +4 15 423 324 138 +4 155 181 25 425 +4 425 25 155 388 +4 331 179 117 531 +4 179 524 331 117 +4 9 544 150 134 +4 241 240 123 6 +4 144 176 174 13 +4 176 143 144 174 +4 410 377 72 234 +4 235 72 234 410 +4 410 50 518 234 +4 410 50 234 235 +4 12 456 6 309 +4 75 268 568 337 +4 75 268 337 137 +4 309 392 456 421 +4 239 541 341 235 +4 575 122 153 269 +4 157 597 332 526 +4 485 61 194 40 +4 452 369 229 592 +4 114 586 297 430 +4 469 74 473 398 +4 510 599 581 424 +4 88 130 261 467 +4 149 450 115 215 +4 149 215 115 480 +4 303 304 274 102 +4 274 304 303 297 +4 61 227 177 194 +4 414 211 49 496 +4 496 211 49 347 +4 43 33 478 162 +4 473 162 293 347 +4 91 102 303 158 +4 102 528 91 303 +4 334 599 227 177 +4 211 496 175 207 +4 356 470 242 54 +4 54 242 244 470 +4 81 272 444 399 +4 509 81 272 444 +4 32 500 253 310 +4 41 198 150 506 +4 374 43 473 457 +4 503 564 177 299 +4 97 214 321 446 +4 446 97 200 321 +4 38 177 538 286 +4 342 559 219 325 +4 219 325 247 342 +4 213 236 366 243 +4 358 213 236 366 +4 213 366 279 243 +4 239 341 541 279 +4 262 266 359 260 +4 260 266 359 167 +4 344 334 358 167 +4 498 495 154 373 +4 176 209 216 217 +4 460 110 323 319 +4 296 297 386 328 +4 115 450 331 256 +4 185 346 323 269 +4 346 323 367 475 +4 142 464 178 594 +4 596 265 264 251 +4 557 158 274 284 +4 437 438 296 76 +4 437 76 296 435 +4 504 209 553 50 +4 227 160 224 592 +4 221 155 222 537 +4 209 171 176 253 +4 578 388 537 222 +4 503 299 177 497 +4 63 53 222 212 +4 272 273 158 570 +4 347 242 210 189 +4 185 323 346 439 +4 577 404 147 198 +4 498 123 6 456 +4 443 79 323 364 +4 139 547 0 134 +4 281 98 226 186 +4 133 463 563 18 +4 18 463 563 190 +4 325 287 558 290 +4 247 287 325 250 +4 250 287 325 290 +4 457 162 24 43 +4 572 88 467 170 +4 475 110 319 323 +4 187 152 493 13 +4 496 414 211 433 +4 93 98 226 340 +4 55 398 508 473 +4 57 508 473 374 +4 153 155 222 221 +4 327 348 472 480 +4 95 148 223 345 +4 321 223 345 214 +4 305 226 275 281 +4 380 476 96 477 +4 476 215 380 96 +4 210 242 356 189 +4 469 74 272 473 +4 55 293 473 478 +4 306 47 216 238 +4 451 108 529 169 +4 133 10 142 1 +4 10 464 142 1 +4 292 564 299 177 +4 292 412 177 286 +4 577 147 554 198 +4 322 481 278 582 +4 111 483 455 312 +4 90 455 111 483 +4 123 507 154 495 +4 165 205 50 553 +4 561 583 50 234 +4 165 583 561 199 +4 50 235 209 205 +4 50 205 561 235 +4 553 205 50 209 +4 549 200 540 559 +4 451 320 321 223 +4 451 320 223 529 +4 455 131 317 285 +4 44 238 335 202 +4 464 188 178 336 +4 220 325 219 551 +4 358 484 561 205 +4 230 274 366 275 +4 230 474 274 275 +4 80 557 231 203 +4 274 304 93 102 +4 423 145 138 574 +4 339 574 138 145 +4 339 574 360 138 +4 190 563 359 262 +4 493 334 595 448 +4 151 496 347 359 +4 278 320 191 333 +4 189 242 431 347 +4 141 279 239 171 +4 251 269 222 585 +4 71 195 261 599 +4 80 91 272 158 +4 242 275 263 281 +4 186 265 244 470 +4 142 175 213 594 +4 271 142 213 594 +4 27 178 188 596 +4 494 188 178 464 +4 174 213 217 357 +4 174 213 357 144 +4 473 231 225 474 +4 225 488 402 273 +4 297 546 570 462 +4 266 358 152 213 +4 13 213 171 174 +4 13 171 253 176 +4 142 175 496 266 +4 266 207 175 496 +4 532 175 496 142 +4 266 243 175 207 +4 266 243 213 175 +4 551 427 62 540 +4 505 427 461 370 +4 369 592 487 229 +4 369 366 232 487 +4 393 66 461 128 +4 267 131 585 197 +4 354 574 15 362 +4 539 245 132 376 +4 98 90 186 87 +4 98 186 281 87 +4 42 153 406 575 +4 395 461 45 393 +4 98 93 226 179 +4 115 480 348 329 +4 530 329 331 115 +4 392 440 309 456 +4 386 296 438 436 +4 107 386 438 436 +4 530 329 119 511 +4 454 597 364 110 +4 453 454 364 110 +4 380 450 149 215 +4 156 365 154 535 +4 502 34 26 595 +4 514 34 595 397 +4 514 34 502 595 +4 303 91 586 528 +4 586 546 570 297 +4 430 586 297 546 +4 67 245 252 52 +4 106 327 149 428 +4 585 85 180 70 +4 387 70 85 585 +4 5 353 392 309 +4 5 309 392 440 +4 209 517 504 310 +4 150 198 228 161 +4 552 330 533 150 +4 150 161 554 198 +4 133 7 142 563 +4 560 378 92 183 +4 129 199 56 518 +4 518 234 199 56 +4 410 518 56 234 +4 198 474 225 228 +4 378 519 560 296 +4 560 519 378 183 +4 183 428 560 519 +4 123 153 42 361 +4 160 82 288 195 +4 273 272 488 489 +4 33 151 298 501 +4 471 112 519 523 +4 177 564 412 292 +4 237 553 165 50 +4 198 255 473 457 +4 198 473 255 159 +4 84 66 257 559 +4 84 66 559 368 +4 54 536 356 470 +4 510 418 59 599 +4 333 97 321 346 +4 456 357 184 153 +4 55 473 293 347 +4 55 398 473 231 +4 336 251 596 264 +4 263 186 265 244 +4 185 439 346 246 +4 346 475 113 109 +4 187 152 13 362 +4 131 455 197 265 +4 536 73 470 168 +4 536 282 470 73 +4 434 168 73 536 +4 539 222 578 212 +4 168 197 267 585 +4 387 168 585 197 +4 513 424 581 599 +4 471 519 294 327 +4 294 328 327 519 +4 114 328 304 465 +4 124 144 13 176 +4 12 373 143 208 +4 581 599 538 61 +4 379 113 97 333 +4 97 346 333 113 +4 468 97 321 333 +4 379 97 468 333 +4 363 330 533 40 +4 330 40 552 533 +4 258 28 176 124 +4 149 380 96 572 +4 406 551 220 505 +4 297 146 436 386 +4 53 222 578 537 +4 399 570 272 91 +4 542 570 272 399 +4 557 431 231 203 +4 569 388 537 35 +4 226 524 331 179 +4 564 397 595 556 +4 13 144 271 213 +4 13 152 171 213 +4 271 152 13 213 +4 467 261 572 341 +4 206 315 382 426 +4 70 132 180 585 +4 588 180 132 585 +4 0 260 140 139 +4 301 426 206 361 +4 415 79 185 545 +4 404 403 228 402 +4 61 227 194 408 +4 592 560 435 160 +4 569 155 537 388 +4 155 388 222 537 +4 174 171 217 213 +4 356 282 281 470 +4 366 562 149 279 +4 337 342 268 568 +4 216 268 337 342 +4 363 330 40 172 +4 129 199 518 583 +4 583 234 199 518 +4 199 234 583 561 +4 480 149 96 106 +4 158 102 274 284 +4 269 415 185 575 +4 122 575 415 269 +4 190 563 496 359 +4 200 246 346 308 +4 521 104 246 308 +4 308 246 521 200 +4 597 323 110 475 +4 285 455 131 265 +4 285 265 186 455 +4 421 6 385 135 +4 139 9 547 134 +4 19 9 491 139 +4 159 512 225 509 +4 9 544 134 139 +4 424 510 599 288 +4 184 154 123 507 +4 486 184 507 156 +4 387 434 168 164 +4 579 388 569 35 +4 51 593 252 168 +4 144 456 124 440 +4 355 172 324 125 +4 138 355 324 125 +4 291 432 132 193 +4 141 136 366 484 +4 46 537 301 221 +4 326 195 261 283 +4 196 428 326 106 +4 196 572 428 106 +4 177 38 485 497 +4 299 38 177 497 +4 393 45 128 461 +4 560 195 160 261 +4 326 560 261 195 +4 461 395 58 393 +4 316 51 54 593 +4 520 427 549 540 +4 85 131 588 411 +4 85 588 180 411 +4 585 85 131 588 +4 85 585 180 588 +4 85 100 131 411 +4 552 330 150 228 +4 462 273 570 297 +4 437 296 560 435 +4 276 378 296 386 +4 428 149 366 327 +4 25 155 20 181 +4 258 208 373 534 +4 534 373 258 352 +4 167 236 366 358 +4 376 400 132 291 +4 595 502 15 26 +4 435 218 160 560 +4 16 300 9 150 +4 123 153 361 426 +4 34 50 165 583 +4 34 165 50 237 +4 495 17 507 248 +4 495 17 498 123 +4 256 120 331 590 +4 117 590 331 120 +4 530 117 590 331 +4 532 419 178 142 +4 184 505 220 156 +4 423 574 354 145 +4 202 352 258 335 +4 534 352 258 202 +4 146 462 297 488 +4 484 341 235 141 +4 381 254 386 383 +4 138 330 161 150 +4 230 274 449 366 +4 473 272 225 231 +4 13 253 171 493 +4 484 366 141 358 +4 486 42 507 184 +4 486 42 184 406 +4 340 68 281 305 +4 249 431 55 347 +4 498 495 123 154 +4 51 67 515 168 +4 476 302 380 215 +4 18 496 563 532 +4 226 312 179 331 +4 18 190 563 496 +4 18 496 532 163 +4 42 153 123 184 +4 408 259 160 227 +4 551 185 78 575 +4 408 435 513 160 +4 151 161 162 139 +4 482 580 332 589 +4 481 482 332 589 +4 542 416 570 399 +4 96 480 215 149 +4 554 192 420 16 +4 499 176 253 500 +4 301 426 361 153 +4 551 540 78 166 +4 551 325 559 185 +4 377 72 234 130 +4 177 564 599 412 +4 564 514 595 397 +4 226 340 281 305 +4 556 397 595 199 +4 556 199 129 397 +4 556 199 56 129 +4 207 347 236 242 +4 207 263 242 236 +4 453 567 364 454 +4 297 386 436 296 +4 299 48 30 564 +4 446 214 321 345 +4 116 278 332 320 +4 481 116 278 332 +4 278 582 332 320 +4 481 278 582 332 +4 471 327 294 119 +4 294 119 327 328 +4 471 472 327 119 +4 148 223 342 568 +4 257 223 342 148 +4 219 342 247 217 +4 265 197 131 267 +4 549 200 559 368 +4 325 185 269 346 +4 346 367 323 269 +4 109 323 319 525 +4 250 290 267 287 +4 264 287 250 267 +4 239 209 171 268 +4 52 245 251 222 +4 290 558 320 317 +4 267 287 317 285 +4 154 357 343 184 +4 335 219 217 216 +4 358 232 448 561 +4 448 561 232 261 +4 231 275 431 557 +4 270 585 588 132 +4 255 374 473 457 +4 258 208 124 143 +4 124 143 144 176 +4 373 143 154 456 +4 549 83 429 520 +4 585 364 588 131 +4 360 260 138 167 +4 26 237 493 595 +4 138 344 167 334 +4 584 52 222 578 +4 343 156 220 219 +4 126 275 347 474 +4 126 347 236 359 +4 306 342 257 219 +4 251 264 250 267 +4 251 265 264 267 +4 239 268 598 541 +4 342 558 598 223 +4 506 533 150 552 +4 556 599 448 564 +4 138 260 0 139 +4 232 599 448 261 +4 232 261 224 599 +4 195 261 599 160 +4 592 296 259 435 +4 53 222 132 63 +4 226 312 279 263 +4 243 263 279 285 +4 243 285 265 263 +4 141 341 235 239 +4 264 267 285 287 +4 175 596 243 178 +4 380 279 149 450 +4 598 314 279 313 +4 380 313 450 215 +4 325 346 558 321 +4 33 293 478 162 +4 346 475 333 113 +4 201 306 573 44 +4 216 44 573 306 +4 366 226 562 279 +4 564 503 177 125 +4 588 522 132 180 +4 488 273 462 297 +4 13 176 174 171 +4 39 54 244 593 +4 454 597 157 100 +4 157 100 597 526 +4 157 280 116 597 +4 116 597 332 157 +4 116 157 332 307 +4 144 456 440 392 +4 198 474 228 229 +4 229 230 474 228 +4 161 126 229 233 +4 126 233 230 229 +4 473 162 347 474 +4 55 473 347 231 +4 207 242 211 347 +4 145 574 354 2 +4 207 266 243 236 +4 243 263 207 236 +4 594 178 243 264 +4 111 312 531 483 +4 1 271 142 391 +4 474 231 273 274 +4 231 274 158 273 +4 297 303 274 273 +4 449 297 328 304 +4 273 274 297 449 +4 366 304 328 562 +4 562 304 226 366 +4 450 279 562 312 +4 149 562 450 279 +4 314 312 450 256 +4 314 598 529 313 +4 285 558 317 598 +4 285 317 455 312 +4 136 572 341 149 +4 484 261 341 136 +4 454 280 157 597 +4 454 110 280 597 +4 150 330 161 228 +4 54 470 244 593 +4 544 138 139 161 +4 138 161 260 139 +4 360 344 266 167 +4 344 266 167 358 +4 533 300 150 14 +4 533 300 506 150 +4 16 300 150 506 +4 423 354 574 15 +4 423 574 138 15 +4 162 198 474 473 +4 162 457 198 473 +4 11 42 123 241 +4 491 9 547 139 +4 182 550 596 571 +4 181 8 135 20 +4 182 596 252 571 +4 571 52 252 182 +4 571 52 51 252 +4 190 19 262 151 +4 190 359 151 262 +4 355 21 324 172 +4 257 342 223 559 +4 426 8 181 315 +4 176 335 216 47 +4 138 330 150 533 +4 363 138 533 330 +4 363 14 533 138 +4 138 260 360 0 +4 144 594 392 464 +4 162 161 198 554 +4 15 595 503 30 +4 15 502 595 30 +4 556 599 199 448 +4 564 595 448 556 +4 43 457 162 473 +4 334 125 229 138 +4 594 357 264 213 +4 550 596 51 593 +4 212 53 578 35 +4 554 37 24 192 +4 217 268 342 598 +4 255 457 577 37 +4 274 474 449 273 +4 229 487 233 592 +4 229 230 592 233 +4 404 41 147 198 +4 236 243 263 366 +4 534 258 28 202 +4 243 244 263 265 +4 301 153 361 46 +4 213 598 217 247 +4 217 598 342 247 +4 44 216 335 238 +4 325 321 558 223 +4 325 346 290 558 +4 328 428 327 519 +4 586 570 303 297 +4 562 304 329 331 +4 105 529 314 582 +4 314 121 256 118 +4 314 582 121 118 +4 529 582 317 314 +4 314 332 582 317 +4 314 121 582 332 +4 314 121 312 256 +4 43 374 473 478 +4 57 159 473 469 +4 228 60 404 402 +4 509 469 272 225 +4 512 60 225 402 +4 219 559 551 325 +4 581 513 599 61 +4 235 64 541 127 +4 236 242 347 275 +4 242 275 431 347 +4 220 250 247 325 +4 336 357 153 251 +4 122 221 269 270 +4 221 222 269 270 +4 466 559 257 66 +4 468 321 320 333 +4 108 333 278 379 +4 469 444 272 74 +4 512 81 272 509 +4 429 83 549 368 +4 486 370 406 505 +4 156 370 486 505 +4 388 584 222 578 +4 549 461 559 540 +4 539 376 132 63 +4 549 427 461 540 +4 277 427 461 565 +4 123 135 153 426 +4 71 283 261 195 +4 258 28 124 208 +4 19 262 139 491 +4 79 323 439 442 +4 399 416 570 91 +4 306 257 466 219 +4 88 572 261 326 +4 226 93 340 305 +4 45 573 566 128 +4 365 45 573 566 +4 128 393 566 45 +4 52 539 222 578 +4 222 245 132 539 +4 52 245 222 539 +4 374 508 473 478 +4 98 281 226 340 +4 84 446 368 321 +4 147 506 554 198 +4 135 20 336 155 +4 155 182 336 222 +4 460 364 417 443 +4 526 597 455 100 +4 447 90 197 455 +4 228 403 194 452 +4 80 158 557 284 +4 408 227 194 259 +4 452 403 194 259 +4 304 303 465 102 +4 276 103 437 378 +4 555 390 313 302 +4 89 541 380 302 +4 47 216 137 65 +4 555 302 541 89 +4 522 548 459 86 +4 522 417 364 459 +4 522 417 459 548 +4 572 196 326 88 +4 477 196 572 88 +4 480 472 327 106 +4 472 471 327 106 +4 95 451 529 390 +4 154 343 373 352 +4 597 110 280 475 +4 443 460 364 323 +4 443 460 323 525 +4 270 53 132 193 +4 570 273 158 303 +4 303 570 586 91 +4 586 297 303 114 +4 554 192 24 420 +4 96 380 149 215 +4 336 182 155 20 +4 482 116 332 580 +4 414 289 211 433 +4 554 384 544 16 +4 24 384 554 420 +4 341 572 467 170 +4 589 121 582 118 +4 492 271 140 409 +4 1 271 492 409 +4 498 373 456 12 +4 498 456 6 12 +4 328 511 587 119 +4 587 114 328 119 +4 228 552 330 405 +4 93 304 226 445 +4 524 331 543 226 +4 508 469 473 398 +4 13 271 490 362 +4 351 127 235 72 +4 410 235 72 351 +4 42 122 153 575 +4 2 409 140 574 +4 362 152 409 574 +4 362 152 574 15 +4 53 270 221 122 +4 324 503 15 125 +4 503 344 595 15 +4 378 386 276 381 +4 276 386 107 381 +4 47 310 176 500 +4 500 176 253 310 +4 335 219 573 343 +4 335 216 573 219 +4 435 82 160 218 +4 160 92 560 218 +4 181 426 135 8 +4 18 419 532 563 +4 225 469 272 473 +4 125 503 177 172 +4 431 516 275 281 +4 284 305 557 576 +4 275 305 281 516 +4 284 305 275 557 +4 253 318 493 187 +4 165 50 205 561 +4 569 22 301 155 +4 514 397 564 48 +4 575 415 185 78 +4 188 494 178 27 +4 419 494 178 464 +4 572 261 326 428 +4 572 428 326 196 +4 503 125 564 344 +4 503 125 344 15 +4 138 344 125 15 +4 73 470 90 87 +4 87 281 282 470 +4 73 282 470 87 +4 9 134 150 14 +4 300 14 9 150 +4 536 282 356 470 +4 473 225 159 198 +4 461 549 66 58 +4 593 51 54 168 +4 58 565 549 520 +4 58 461 549 565 +4 53 193 270 350 +4 58 66 461 393 +4 512 272 225 509 +4 135 155 153 426 +4 181 426 155 135 +4 160 424 513 599 +4 424 288 599 160 +4 293 473 478 162 +4 458 190 262 563 +4 50 234 583 518 +4 448 165 205 561 +4 50 561 234 235 +4 530 329 511 117 +4 530 331 329 117 +4 281 186 263 244 +4 281 186 226 263 +4 436 76 407 296 +4 297 407 402 259 +4 297 407 259 296 +4 297 402 592 259 +4 331 179 531 312 +4 200 521 166 246 +4 52 67 51 252 +4 469 159 225 509 +4 0 339 140 360 +4 371 0 140 139 +4 492 0 140 371 +4 492 0 339 140 +4 401 599 556 412 +4 412 599 556 564 +4 271 140 391 492 +4 7 133 142 391 +4 439 442 323 109 +4 104 246 113 109 +4 352 365 573 566 +4 150 16 506 554 +4 417 453 364 460 +4 302 541 380 313 +4 555 313 541 302 +4 380 541 279 313 +4 161 359 151 126 +4 334 161 487 167 +4 334 487 161 229 +4 527 383 107 386 +4 131 317 597 455 +4 139 260 262 359 +4 524 331 117 543 +4 140 266 262 260 +4 267 364 131 597 +4 471 519 112 294 +4 114 303 465 304 +4 270 269 79 364 +4 250 220 153 269 +4 222 539 132 63 +4 10 133 142 419 +4 486 505 406 184 +4 370 461 45 277 +4 96 106 572 196 +4 389 138 324 4 +4 479 188 596 27 +4 72 396 541 341 +4 72 235 541 127 +4 127 396 541 72 +4 33 43 24 162 +4 491 139 0 371 +4 531 312 179 483 +4 356 68 242 281 +4 189 242 356 68 +4 491 0 139 547 +4 363 14 138 355 +4 391 133 142 1 +4 470 197 265 168 +4 91 570 272 158 +4 94 567 588 364 +4 453 94 364 567 +4 50 338 209 235 +4 50 504 209 338 +4 553 209 493 205 +4 297 407 436 146 +4 76 436 438 296 +4 384 554 420 16 +4 544 16 150 554 +4 184 156 154 507 +4 563 419 532 142 +4 105 529 390 313 +4 390 169 529 105 +4 105 169 529 582 +4 418 401 59 599 +4 463 7 563 458 +4 446 200 368 321 +4 503 172 324 21 +4 495 535 154 23 +4 259 402 403 407 +4 252 70 585 245 +4 336 188 182 20 +4 584 182 155 222 +4 502 30 514 595 +4 435 560 592 296 +4 217 171 268 598 +4 501 33 151 591 +4 397 199 129 34 +4 38 292 177 286 +4 550 39 27 593 +4 464 178 419 142 +4 425 155 569 388 +4 32 209 504 310 +4 282 68 281 87 +4 68 340 281 87 +4 44 306 216 238 +4 181 315 155 426 +4 315 181 155 425 +4 211 49 347 210 +4 410 56 377 234 +4 105 314 118 582 +4 32 493 237 553 +4 431 557 516 576 +4 431 557 275 516 +4 194 227 334 369 +4 334 227 599 232 +4 474 274 449 230 +4 405 403 194 228 +4 380 170 477 572 +4 115 256 331 590 +4 115 348 530 329 +4 530 115 331 590 +4 410 235 351 64 +4 237 493 165 553 +4 64 137 209 75 +4 204 120 118 256 +4 121 256 118 120 +4 431 516 281 68 +4 211 289 54 39 +4 147 192 554 506 +4 198 554 150 506 +4 597 367 191 320 +4 191 280 475 597 +4 93 274 275 226 +4 387 168 197 164 +4 313 568 390 555 +4 203 431 231 55 +4 327 119 472 348 +4 61 177 538 485 +4 441 79 442 323 +4 341 170 467 396 +4 512 488 272 81 +4 488 81 489 272 +4 542 272 489 81 +4 424 510 288 82 +4 424 288 160 82 +4 513 160 435 82 +4 180 132 70 400 +4 156 461 45 370 +4 14 134 138 389 +4 14 134 150 138 +4 54 210 289 211 +4 54 211 242 210 +4 572 170 477 88 +4 589 580 332 121 +4 509 444 272 469 +4 323 319 475 109 +4 97 346 308 200 +4 417 443 364 459 +4 417 99 459 548 +4 443 460 525 99 +4 183 428 519 523 +4 447 100 131 85 +4 528 465 303 102 +4 218 103 560 437 +4 346 308 113 97 +4 471 523 428 106 +4 524 445 93 226 +4 392 309 353 421 +4 98 340 87 281 +4 567 364 131 588 +4 50 338 235 410 +4 519 254 386 112 +4 32 26 237 493 +4 528 586 303 114 +4 4 339 138 145 +4 528 114 303 465 +4 451 169 529 390 +4 385 20 3 135 +4 223 321 451 214 +4 204 590 256 115 +4 128 201 573 566 +4 482 481 332 116 +4 156 461 128 45 +4 48 556 129 397 +4 48 556 56 129 +4 216 342 306 219 +4 483 186 179 98 +4 322 582 320 529 +4 541 268 75 209 +4 186 470 281 87 +4 186 244 281 470 +4 301 315 426 155 +4 206 301 315 426 +4 463 458 563 190 +4 358 448 205 561 +4 493 253 171 209 +4 330 229 161 228 +4 344 152 358 493 +4 344 266 358 152 +4 29 298 496 151 +4 563 496 266 142 +4 563 496 142 532 +4 150 9 16 544 +4 135 392 357 336 +4 138 161 167 260 +4 248 156 535 36 +4 269 222 585 270 +4 251 252 585 245 +4 128 559 66 461 +4 572 106 149 428 +4 519 254 294 328 +4 519 254 328 386 +4 380 170 341 396 +4 396 541 341 380 +4 91 303 570 158 +4 277 565 461 58 +4 549 429 368 559 +4 429 66 559 549 +4 461 559 66 549 +4 368 429 66 559 +4 162 151 19 33 +4 515 434 168 67 +4 490 271 144 353 +4 520 427 565 549 +4 140 266 271 142 +4 183 106 428 523 +4 512 402 225 488 +4 512 488 225 272 +4 587 543 328 465 +4 417 364 94 522 +4 144 464 392 353 +4 162 554 19 544 +4 162 554 24 19 +4 384 554 544 19 +4 90 447 197 164 +4 291 400 132 86 +4 322 108 169 529 +4 582 322 169 529 +4 506 552 150 41 +4 187 253 13 493 +4 330 40 405 552 +4 63 376 132 291 +4 63 291 132 193 +4 515 168 434 536 +4 447 100 455 131 +4 131 447 197 455 +4 331 120 256 312 +4 331 531 120 312 +4 135 456 6 123 +4 421 456 6 135 +4 422 209 504 338 +4 568 75 95 413 +4 149 562 366 327 +4 398 203 231 55 +4 77 146 297 488 +4 212 222 578 53 +4 295 450 115 204 +4 364 597 367 323 +4 187 253 499 13 +4 262 563 266 140 +4 375 52 571 182 +4 589 481 322 582 +4 481 332 582 589 +4 9 544 139 19 +4 501 151 298 29 +4 363 172 355 125 +4 204 120 256 590 +4 80 231 398 203 +4 144 353 5 490 +4 311 490 144 5 +4 258 208 143 373 +4 45 573 128 156 +4 595 199 165 448 +4 397 199 34 595 +4 386 146 436 107 +4 318 253 499 187 +4 253 499 500 318 +4 224 572 136 149 +4 366 224 136 149 +4 205 235 141 484 +4 573 156 219 128 +4 122 79 269 415 +4 197 470 90 73 +4 232 224 136 366 +4 261 572 341 136 +4 484 136 232 261 +4 261 224 136 232 +4 261 572 136 224 +4 484 141 136 341 +4 143 335 217 176 +4 335 216 217 176 +4 229 334 138 161 +4 229 194 125 334 +4 474 275 347 231 +4 366 592 428 449 +4 364 269 367 250 +4 449 402 273 474 +4 250 585 267 364 +4 194 177 334 227 +4 125 194 177 334 +4 69 522 364 459 +4 226 263 186 312 +4 352 373 335 343 +4 335 573 352 343 +4 65 342 216 337 +4 51 596 252 593 +4 130 234 56 261 +4 322 278 108 320 +4 499 13 253 176 +4 499 176 28 13 +4 32 504 209 553 +4 429 58 66 549 +4 429 58 549 520 +4 53 63 132 193 +4 132 522 270 69 +4 350 193 270 69 +4 494 188 464 173 +4 188 336 464 173 +4 355 138 324 389 +4 307 111 526 455 +4 111 307 312 455 +4 541 239 209 235 +4 80 557 158 231 +4 553 493 165 205 +4 84 321 559 223 +4 84 223 345 321 +4 148 84 223 345 +4 84 223 257 148 +4 84 257 223 559 +4 562 149 329 327 +4 78 415 185 545 +4 541 341 380 279 +4 20 3 135 173 +4 133 463 7 563 +4 101 570 416 586 +4 586 101 570 546 +4 430 586 546 101 +4 54 470 168 536 +4 51 168 515 54 +4 515 168 536 54 +4 336 264 594 357 +4 139 262 260 140 +4 262 140 139 371 +4 491 139 371 262 +4 141 366 136 279 +4 151 190 496 359 +4 373 343 154 143 +4 456 357 143 154 +4 360 344 152 266 +4 134 138 0 139 +4 0 339 138 4 +4 251 585 267 250 +4 364 367 269 323 +4 362 15 187 152 +4 574 152 344 15 +4 339 140 574 2 +4 492 339 2 140 +4 431 347 249 189 +4 310 176 209 47 +4 46 301 153 221 +4 380 476 477 170 +4 209 268 75 137 +4 33 591 162 151 +4 151 591 162 347 +4 293 591 162 33 +4 485 177 497 172 +4 505 461 156 370 +4 458 491 262 19 +4 471 428 519 327 +4 519 523 428 471 +4 120 256 312 121 +4 120 312 111 121 +4 111 312 120 531 +4 386 527 146 107 +4 554 147 37 192 +4 554 37 147 577 +4 555 568 95 413 +4 61 599 177 227 +4 421 392 456 135 +4 394 71 599 401 +4 7 458 491 262 +4 7 491 371 262 +4 7 262 140 563 +4 7 458 262 563 +4 365 156 154 343 +4 365 573 156 343 +4 365 573 343 352 +4 154 365 343 352 +4 160 560 224 592 +4 268 568 342 598 +4 559 540 166 200 +4 342 223 559 325 +4 219 461 505 551 +4 219 156 505 461 +4 219 128 559 466 +4 306 466 201 219 +4 243 207 263 244 +4 264 265 243 285 +4 449 402 297 273 +4 488 273 297 402 +4 80 272 231 158 +4 598 317 279 314 +4 247 264 598 558 +4 167 233 366 126 +4 167 487 358 366 +4 247 287 264 558 +4 287 558 285 264 +4 342 223 325 558 +4 325 346 559 185 +4 269 79 323 185 +4 269 364 323 79 +4 213 247 217 357 +4 357 247 217 219 +4 153 222 269 221 +4 142 178 175 594 +4 474 231 225 273 +4 231 273 158 272 +4 231 158 274 557 +4 231 557 274 275 +4 296 592 428 560 +4 285 186 312 455 +4 558 346 320 321 +4 267 317 367 597 +4 585 364 131 267 +4 558 223 320 529 +4 243 265 596 593 +4 479 27 596 550 +4 357 250 220 153 +4 134 138 139 544 +4 140 266 260 360 +4 364 270 588 522 +4 141 341 279 136 +4 359 167 126 161 +4 163 39 211 244 +4 39 244 54 211 +4 126 167 359 236 +4 174 357 217 143 +4 596 336 182 251 +4 236 347 207 359 +4 369 366 487 592 +4 592 487 233 366 +4 592 230 366 233 +4 358 213 366 141 +4 141 279 171 213 +4 213 171 598 279 +4 213 264 279 598 +4 244 265 593 470 +4 137 337 65 216 +4 585 269 364 250 +4 252 168 251 585 +4 252 168 585 387 +4 328 329 562 304 +4 304 465 328 543 +4 256 105 450 314 +4 105 118 314 256 +4 455 332 317 597 +4 65 257 306 342 +4 333 346 367 475 +4 597 320 332 317 +4 320 346 367 333 +4 453 364 460 110 +4 321 333 346 320 +4 332 121 312 314 +4 369 366 224 232 +4 224 592 369 227 +4 592 449 230 452 +4 228 402 449 474 +4 60 402 228 225 +4 31 479 372 182 +4 31 372 349 182 +4 598 568 313 541 +4 598 313 568 529 +4 541 568 555 413 +4 346 439 323 109 +4 433 211 163 39 +4 433 289 211 39 +4 581 599 286 538 +4 155 388 584 222 +4 562 115 329 149 +4 13 490 144 311 +4 490 144 271 13 +4 412 401 599 59 +4 581 59 599 510 +4 15 344 26 187 +4 568 95 148 223 +4 442 323 109 441 +4 276 296 438 386 +4 437 296 438 276 +4 437 560 296 378 +4 254 297 328 386 +4 254 297 386 383 +4 564 556 48 397 +4 253 176 209 310 +4 26 595 493 344 +4 34 165 237 595 +4 237 595 165 493 +4 48 56 556 401 +4 576 305 557 516 +4 362 271 152 13 +4 96 149 572 106 +4 216 342 219 217 +4 188 182 20 372 +4 188 596 336 182 +4 479 182 596 188 +4 479 188 372 182 +4 368 321 200 559 +4 200 559 321 346 +4 161 233 487 167 +4 167 366 233 487 +4 161 233 167 126 +4 217 343 219 335 +4 156 505 220 219 +4 449 304 328 366 +4 449 304 366 274 +4 34 583 165 199 +4 0 260 360 140 +4 558 264 598 285 +4 264 285 267 265 +4 229 126 474 230 +4 279 239 598 541 +4 54 470 593 168 +4 263 226 366 279 +4 367 475 323 597 +4 346 323 475 109 +4 544 161 139 162 +4 279 314 312 450 +4 449 274 297 304 +4 558 529 320 317 +4 598 529 558 317 +4 314 598 317 529 +4 598 568 223 529 +4 102 465 304 543 +4 493 152 358 171 +4 263 312 285 186 +4 544 554 161 162 +4 232 561 484 261 +4 314 450 279 313 +4 151 49 496 414 +4 496 211 347 207 +4 163 244 175 593 +4 163 244 593 39 +4 51 316 550 593 +4 27 593 596 550 +4 316 39 550 593 +4 268 598 541 568 +4 537 221 155 301 +4 141 213 366 279 +4 236 366 263 275 +4 236 242 275 263 +4 356 242 470 281 +4 312 317 455 332 +4 224 366 369 592 +4 313 314 105 529 +4 296 519 428 328 +4 519 296 386 328 +4 452 402 592 449 +4 259 592 452 402 +4 290 317 320 367 +4 267 597 367 364 +4 357 219 343 220 +4 251 267 585 168 +4 185 551 78 166 +4 100 364 131 567 +4 450 105 313 314 +4 295 450 204 105 +4 121 307 332 312 +4 307 580 121 332 +4 571 550 596 51 +4 479 182 550 596 +4 31 182 550 479 +4 558 223 321 320 +4 143 343 217 335 +4 343 357 217 219 +4 585 364 270 588 +4 119 511 329 328 +4 511 543 329 328 +4 304 328 329 543 +4 344 187 152 493 +4 187 344 26 493 +4 358 484 205 141 +4 595 334 564 448 +4 493 171 358 205 +4 258 335 143 176 +4 271 142 594 464 +4 230 449 592 366 +4 265 267 131 285 +4 279 312 285 263 +4 304 331 543 329 +4 449 296 428 328 +4 152 358 171 213 +4 189 431 242 68 +4 428 327 366 328 +4 228 229 452 194 +4 262 359 266 563 +4 431 242 281 275 +4 68 431 242 281 +4 219 461 551 559 +4 167 236 266 359 +4 347 473 474 231 +4 162 554 198 457 +4 126 347 162 474 +4 259 402 452 403 +4 153 251 222 336 +4 155 222 336 153 +4 191 475 333 367 +4 466 219 257 559 +4 119 327 328 329 +4 587 114 465 328 +4 454 100 364 597 +4 204 105 256 118 +4 231 74 398 473 +4 254 114 294 328 +4 380 572 341 170 +4 90 197 265 470 +4 434 387 168 67 +4 67 51 252 168 +4 227 599 160 513 +4 106 149 327 480 +4 32 253 209 310 +4 554 457 162 24 +4 344 125 564 334 +4 344 595 334 564 +4 545 439 185 78 +4 79 439 323 185 +4 79 439 185 545 +4 149 327 480 329 +4 579 425 569 388 +4 160 288 599 195 +4 195 288 599 71 +4 486 248 156 507 +4 153 426 155 301 +4 537 569 301 155 +4 184 406 153 220 +4 353 490 271 1 +4 372 20 349 182 +4 137 422 209 47 +4 79 443 459 364 +4 525 323 443 109 +4 109 443 441 323 +4 135 173 464 336 +4 507 248 154 495 +4 201 466 128 219 +4 201 306 219 573 +4 92 560 103 378 +4 433 163 211 496 +4 62 427 505 370 +4 505 551 461 427 +4 165 561 583 50 +4 138 339 0 360 +4 475 191 333 113 +4 408 160 513 227 +4 216 573 219 306 +4 53 537 221 222 +4 53 270 222 221 +4 46 53 537 221 +4 53 122 221 46 +4 570 489 273 462 +4 542 462 489 570 +4 100 131 364 597 +4 100 454 364 567 +4 411 131 588 567 +4 34 199 165 595 +4 129 199 583 34 +4 47 258 176 335 +4 517 422 209 504 +4 84 321 368 559 +4 297 527 146 386 +4 527 383 386 297 +4 146 546 527 297 +4 527 383 297 430 + +CELL_TYPES 2221 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 +10 diff --git a/examples/DeformableDemo/GraspDeformable.cpp b/examples/DeformableDemo/GraspDeformable.cpp index 6596c07d7..c71929234 100644 --- a/examples/DeformableDemo/GraspDeformable.cpp +++ b/examples/DeformableDemo/GraspDeformable.cpp @@ -31,7 +31,8 @@ #include "../CommonInterfaces/CommonMultiBodyBase.h" #include "../CommonInterfaces/CommonGraphicsAppInterface.h" #include "../CommonInterfaces/CommonParameterInterface.h" - +#include "../CommonInterfaces/CommonFileIOInterface.h" +#include "Bullet3Common/b3FileUtils.h" ///The GraspDeformable shows the use of rolling friction. ///Spheres will come to a rest on a sloped plane using a constraint. Damping cannot achieve the same. @@ -125,7 +126,7 @@ public: } //use a smaller internal timestep, there are stability issues - float internalTimeStep = 1. / 250.f; + float internalTimeStep = 1. / 400.f; m_dynamicsWorld->stepSimulation(deltaTime, 5, internalTimeStep); } @@ -312,7 +313,7 @@ void GraspDeformable::initPhysics() btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); btRigidBody* body = new btRigidBody(rbInfo); - body->setFriction(0.5); + body->setFriction(0); //add the ground to the dynamics world m_dynamicsWorld->addRigidBody(body); @@ -320,18 +321,32 @@ void GraspDeformable::initPhysics() // create a soft block { - btSoftBody* psb = btSoftBodyHelpers::CreateFromTetGenData(getDeformableDynamicsWorld()->getWorldInfo(), - TetraCube::getElements(), - 0, - TetraCube::getNodes(), - false, true, true); + char relative_path[1024]; +// b3FileUtils::findFile("banana.vtk", relative_path, 1024); + b3FileUtils::findFile("ball.vtk", relative_path, 1024); +// b3FileUtils::findFile("tube.vtk", relative_path, 1024); +// b3FileUtils::findFile("torus.vtk", relative_path, 1024); +// b3FileUtils::findFile("paper_roll.vtk", relative_path, 1024); +// b3FileUtils::findFile("bread.vtk", relative_path, 1024); +// b3FileUtils::findFile("ditto.vtk", relative_path, 1024); +// b3FileUtils::findFile("boot.vtk", relative_path, 1024); + std::string path(relative_path); +// btSoftBody* psb = btSoftBodyHelpers::CreateFromTetGenData(getDeformableDynamicsWorld()->getWorldInfo(), +// TetraCube::getElements(), +// 0, +// TetraCube::getNodes(), +// false, true, true); + btSoftBody* psb = btSoftBodyHelpers::CreateFromVtkFile(getDeformableDynamicsWorld()->getWorldInfo(), path); +// psb->scale(btVector3(30, 30, 30)); // for banana psb->scale(btVector3(2, 2, 2)); - psb->translate(btVector3(0, 0, 0)); +// psb->scale(btVector3(3, 3, 3)); // for tube, torus, boot +// psb->scale(btVector3(1, 1, 1)); // for ditto +// psb->translate(btVector3(0, 0, 2)); for boot psb->getCollisionShape()->setMargin(0.1); psb->setTotalMass(1); psb->setSpringStiffness(0); - psb->setDampingCoefficient(0.1); + psb->setDampingCoefficient(.1); psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects psb->m_cfg.kCHR = 1; // collision hardness with rigid body psb->m_cfg.kDF = 2; @@ -339,9 +354,43 @@ void GraspDeformable::initPhysics() getDeformableDynamicsWorld()->addSoftBody(psb); getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(1,1)); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(10,10)); } +// // create a piece of cloth +// { +// bool onGround = false; +// const btScalar s = 4; +// btSoftBody* psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, 0, -s), +// btVector3(+s, 0, -s), +// btVector3(-s, 0, +s), +// btVector3(+s, 0, +s), +// 20,20, +// 0, true); +// +// if (onGround) +// psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, 0, -s), +// btVector3(+s, 0, -s), +// btVector3(-s, 0, +s), +// btVector3(+s, 0, +s), +// // 20,20, +// 2,2, +// 0, true); +// +// psb->getCollisionShape()->setMargin(0.1); +// psb->generateBendingConstraints(2); +// psb->setTotalMass(1); +// psb->setSpringStiffness(2); +// psb->setDampingCoefficient(0.03); +// psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects +// psb->m_cfg.kCHR = 1; // collision hardness with rigid body +// psb->m_cfg.kDF = 1; +// psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; +// getDeformableDynamicsWorld()->addSoftBody(psb); +// getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); +// getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); +// } + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); { From 081497a812fde6cd752e7f394b8a25edd452e4f5 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Mon, 12 Aug 2019 12:04:31 -0700 Subject: [PATCH 13/56] reset dt to 1/240 for grasping demos --- examples/DeformableDemo/GraspDeformable.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/DeformableDemo/GraspDeformable.cpp b/examples/DeformableDemo/GraspDeformable.cpp index c71929234..bee1472c1 100644 --- a/examples/DeformableDemo/GraspDeformable.cpp +++ b/examples/DeformableDemo/GraspDeformable.cpp @@ -126,7 +126,7 @@ public: } //use a smaller internal timestep, there are stability issues - float internalTimeStep = 1. / 400.f; + float internalTimeStep = 1. / 240.f; m_dynamicsWorld->stepSimulation(deltaTime, 5, internalTimeStep); } @@ -354,7 +354,7 @@ void GraspDeformable::initPhysics() getDeformableDynamicsWorld()->addSoftBody(psb); getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(10,10)); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(5,5)); } // // create a piece of cloth From cfbd6c512a98ccaa4caa63a50bbead90c38a71aa Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Mon, 12 Aug 2019 12:06:55 -0700 Subject: [PATCH 14/56] fix bug introduced in clearing m_manifold; 7e37d3fd21069571adb4c1e4ffacbd71dd02c0ba --- .../Featherstone/btMultiBodyDynamicsWorld.cpp | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp index 602c94926..9da8496c6 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp @@ -375,15 +375,10 @@ struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager:: m_islandAnalyticsData.push_back(m_solver->m_analyticsData); } m_bodies.resize(0); -// m_manifolds.resize(0); + m_manifolds.resize(0); m_constraints.resize(0); m_multiBodyConstraints.resize(0); } - - void clearContactConstraints() - { - m_manifolds.resize(0); - } }; void btMultiBodyDynamicsWorld::getAnalyticsData(btAlignedObjectArray& islandAnalyticsData) const @@ -435,7 +430,6 @@ void btMultiBodyDynamicsWorld::solveConstraints(btContactSolverInfo& solverInfo) solveExternalForces(solverInfo); buildIslands(); solveInternalConstraints(solverInfo); - m_solverMultiBodyIslandCallback->clearContactConstraints(); } void btMultiBodyDynamicsWorld::buildIslands() From 9e6e571732f6e5850f6cc4560a613aac5214e673 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Mon, 12 Aug 2019 12:07:24 -0700 Subject: [PATCH 15/56] add options to perturb the softbody patch's initial position --- src/BulletSoftBody/btSoftBodyHelpers.cpp | 11 +++++++++-- src/BulletSoftBody/btSoftBodyHelpers.h | 3 ++- 2 files changed, 11 insertions(+), 3 deletions(-) diff --git a/src/BulletSoftBody/btSoftBodyHelpers.cpp b/src/BulletSoftBody/btSoftBodyHelpers.cpp index e30f5af58..3cdf4d7bd 100644 --- a/src/BulletSoftBody/btSoftBodyHelpers.cpp +++ b/src/BulletSoftBody/btSoftBodyHelpers.cpp @@ -724,7 +724,8 @@ btSoftBody* btSoftBodyHelpers::CreatePatch(btSoftBodyWorldInfo& worldInfo, const int resx, int resy, int fixeds, - bool gendiags) + bool gendiags, + btScalar perturbation) { #define IDX(_x_, _y_) ((_y_)*rx + (_x_)) /* Create nodes */ @@ -744,7 +745,13 @@ btSoftBody* btSoftBodyHelpers::CreatePatch(btSoftBodyWorldInfo& worldInfo, const for (int ix = 0; ix < rx; ++ix) { const btScalar tx = ix / (btScalar)(rx - 1); - x[IDX(ix, iy)] = lerp(py0, py1, tx); + btScalar pert = perturbation * btScalar(rand())/RAND_MAX; + btVector4 temp1 = py1; + temp1.setY(py1.getY() + pert); + btVector4 temp = py0; + pert = perturbation * btScalar(rand())/RAND_MAX; + temp.setY(py0.getY() + pert); + x[IDX(ix, iy)] = lerp(temp, temp1, tx); m[IDX(ix, iy)] = 1; } } diff --git a/src/BulletSoftBody/btSoftBodyHelpers.h b/src/BulletSoftBody/btSoftBodyHelpers.h index 927cb6781..6cdeb97c3 100644 --- a/src/BulletSoftBody/btSoftBodyHelpers.h +++ b/src/BulletSoftBody/btSoftBodyHelpers.h @@ -92,7 +92,8 @@ struct btSoftBodyHelpers int resx, int resy, int fixeds, - bool gendiags); + bool gendiags, + btScalar perturbation = 0.); /* Create a patch with UV Texture Coordinates */ static btSoftBody* CreatePatchUV(btSoftBodyWorldInfo& worldInfo, const btVector3& corner00, From 07bf736aeb82099ac3b8f66c0647d85989d4be31 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Tue, 13 Aug 2019 14:37:45 -0700 Subject: [PATCH 16/56] build islands once and process islands arbitrary number of times in update constraints --- .../btSimulationIslandManager.cpp | 8 ++++++-- .../CollisionDispatch/btSimulationIslandManager.h | 2 +- .../Featherstone/btMultiBodyDynamicsWorld.cpp | 14 ++++++++++++-- .../Featherstone/btMultiBodyDynamicsWorld.h | 2 ++ .../btDeformableBackwardEulerObjective.cpp | 2 ++ src/BulletSoftBody/btDeformableBodySolver.cpp | 2 +- .../btDeformableContactProjection.cpp | 8 +++++--- 7 files changed, 29 insertions(+), 9 deletions(-) diff --git a/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp b/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp index 57e1bb494..327b3f076 100644 --- a/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp +++ b/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp @@ -338,13 +338,17 @@ void btSimulationIslandManager::buildIslands(btDispatcher* dispatcher, btCollisi } } + ///@todo: this is random access, it can be walked 'cache friendly'! void btSimulationIslandManager::buildAndProcessIslands(btDispatcher* dispatcher, btCollisionWorld* collisionWorld, IslandCallback* callback) { - btCollisionObjectArray& collisionObjects = collisionWorld->getCollisionObjectArray(); - buildIslands(dispatcher, collisionWorld); + processIslands(dispatcher, collisionWorld, callback); +} +void btSimulationIslandManager::processIslands(btDispatcher* dispatcher, btCollisionWorld* collisionWorld, IslandCallback* callback) +{ + btCollisionObjectArray& collisionObjects = collisionWorld->getCollisionObjectArray(); int endIslandIndex = 1; int startIslandIndex; int numElem = getUnionFind().getNumElements(); diff --git a/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h b/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h index 6c2802141..62c4c574c 100644 --- a/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h +++ b/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h @@ -57,7 +57,7 @@ public: }; void buildAndProcessIslands(btDispatcher* dispatcher, btCollisionWorld* collisionWorld, IslandCallback* callback); - + void processIslands(btDispatcher* dispatcher, btCollisionWorld* collisionWorld, IslandCallback* callback); void buildIslands(btDispatcher* dispatcher, btCollisionWorld* colWorld); bool getSplitIslands() diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp index 9da8496c6..c05ab420f 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp @@ -428,13 +428,18 @@ void btMultiBodyDynamicsWorld::forwardKinematics() void btMultiBodyDynamicsWorld::solveConstraints(btContactSolverInfo& solverInfo) { solveExternalForces(solverInfo); - buildIslands(); + m_islandManager->buildAndProcessIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld(), m_solverMultiBodyIslandCallback); solveInternalConstraints(solverInfo); } void btMultiBodyDynamicsWorld::buildIslands() { - m_islandManager->buildAndProcessIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld(), m_solverMultiBodyIslandCallback); + m_islandManager->buildIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld()); +} + +void btMultiBodyDynamicsWorld::processIslands() +{ + m_islandManager->processIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld(), m_solverMultiBodyIslandCallback); } void btMultiBodyDynamicsWorld::solveInternalConstraints(btContactSolverInfo& solverInfo) @@ -1086,3 +1091,8 @@ void btMultiBodyDynamicsWorld::serializeMultiBodies(btSerializer* serializer) } } } + +void btMultiBodyDynamicsWorld::setSplitIslands(bool split) +{ + m_islandManager->setSplitIslands(split); +} diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h index 653ec36ca..605141bc6 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h @@ -118,6 +118,8 @@ public: virtual void solveExternalForces(btContactSolverInfo& solverInfo); virtual void solveInternalConstraints(btContactSolverInfo& solverInfo); void buildIslands(); + void processIslands(); + void setSplitIslands(bool split); }; #endif //BT_MULTIBODY_DYNAMICS_WORLD_H diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp index f4a3f55e5..d01825ad4 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp @@ -143,6 +143,8 @@ void btDeformableBackwardEulerObjective::setConstraints() { // build islands for multibody solve m_world->btMultiBodyDynamicsWorld::buildIslands(); + // for repeated constraint solve, splitIslands has to be set to true + m_world->setSplitIslands(true); projection.setConstraints(); } diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index 8361abfe5..e2e5740d0 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -19,7 +19,7 @@ btDeformableBodySolver::btDeformableBodySolver() : m_numNodes(0) , m_cg(10) -, m_contact_iterations(10) +, m_contact_iterations(5) { m_objective = new btDeformableBackwardEulerObjective(m_softBodySet, m_backupVelocity); } diff --git a/src/BulletSoftBody/btDeformableContactProjection.cpp b/src/BulletSoftBody/btDeformableContactProjection.cpp index 9bdd8323e..ec155fb68 100644 --- a/src/BulletSoftBody/btDeformableContactProjection.cpp +++ b/src/BulletSoftBody/btDeformableContactProjection.cpp @@ -51,9 +51,11 @@ static btVector3 generateUnitOrthogonalVector(const btVector3& u) void btDeformableContactProjection::update() { ///solve rigid body constraints - m_world->getSolverInfo().m_numIterations = 1; - m_world->btMultiBodyDynamicsWorld::solveInternalConstraints(m_world->getSolverInfo()); - + { + m_world->getSolverInfo().m_numIterations = 1; + m_world->processIslands(); + m_world->btMultiBodyDynamicsWorld::solveInternalConstraints(m_world->getSolverInfo()); // process constraints deferred in the previous step + } // loop through constraints to set constrained values for (int index = 0; index < m_constraints.size(); ++index) { From fce12964139c8073676a50db0201c1460ad3fcad Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Tue, 13 Aug 2019 16:59:42 -0700 Subject: [PATCH 17/56] fix the issue that compound objects's child does not get rotated in the material space in interpolationWorldTransform --- .../CollisionDispatch/btCollisionObjectWrapper.h | 8 +++++++- .../CollisionDispatch/btCompoundCollisionAlgorithm.cpp | 2 +- src/BulletSoftBody/btSoftBody.cpp | 7 ++++--- 3 files changed, 12 insertions(+), 5 deletions(-) diff --git a/src/BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h b/src/BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h index 1cc4a5ac5..56341b7d2 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h @@ -27,13 +27,19 @@ public: const btCollisionShape* m_shape; const btCollisionObject* m_collisionObject; const btTransform& m_worldTransform; + const btTransform* m_preTransform; int m_partId; int m_index; btCollisionObjectWrapper(const btCollisionObjectWrapper* parent, const btCollisionShape* shape, const btCollisionObject* collisionObject, const btTransform& worldTransform, int partId, int index) - : m_parent(parent), m_shape(shape), m_collisionObject(collisionObject), m_worldTransform(worldTransform), m_partId(partId), m_index(index) + : m_parent(parent), m_shape(shape), m_collisionObject(collisionObject), m_worldTransform(worldTransform), m_preTransform(NULL), m_partId(partId), m_index(index) { } + + btCollisionObjectWrapper(const btCollisionObjectWrapper* parent, const btCollisionShape* shape, const btCollisionObject* collisionObject, const btTransform& worldTransform, const btTransform& preTransform, int partId, int index) + : m_parent(parent), m_shape(shape), m_collisionObject(collisionObject), m_worldTransform(worldTransform), m_preTransform(&preTransform), m_partId(partId), m_index(index) + { + } SIMD_FORCE_INLINE const btTransform& getWorldTransform() const { return m_worldTransform; } SIMD_FORCE_INLINE const btCollisionObject* getCollisionObject() const { return m_collisionObject; } diff --git a/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp index 633bee482..1bb21104c 100644 --- a/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp @@ -139,7 +139,7 @@ public: if (TestAabbAgainstAabb2(aabbMin0, aabbMax0, aabbMin1, aabbMax1)) { - btCollisionObjectWrapper compoundWrap(this->m_compoundColObjWrap, childShape, m_compoundColObjWrap->getCollisionObject(), newChildWorldTrans, -1, index); + btCollisionObjectWrapper compoundWrap(this->m_compoundColObjWrap, childShape, m_compoundColObjWrap->getCollisionObject(), newChildWorldTrans, childTrans, -1, index); btCollisionAlgorithm* algo = 0; bool allocatedAlgorithm = false; diff --git a/src/BulletSoftBody/btSoftBody.cpp b/src/BulletSoftBody/btSoftBody.cpp index f65851dec..2da04d491 100644 --- a/src/BulletSoftBody/btSoftBody.cpp +++ b/src/BulletSoftBody/btSoftBody.cpp @@ -20,7 +20,7 @@ subject to the following restrictions: #include "LinearMath/btSerializer.h" #include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" #include "BulletDynamics/Featherstone/btMultiBodyConstraint.h" - +#include // btSoftBody::btSoftBody(btSoftBodyWorldInfo* worldInfo, int node_count, const btVector3* x, const btScalar* m) : m_softBodySolver(0), m_worldInfo(worldInfo) @@ -2301,8 +2301,9 @@ bool btSoftBody::checkDeformableContact(const btCollisionObjectWrapper* colObjWr const btCollisionObject* tmpCollisionObj = colObjWrap->getCollisionObject(); // use the position x_{n+1}^* = x_n + dt * v_{n+1}^* where v_{n+1}^* = v_n + dtg for collision detect // but resolve contact at x_n - const btTransform &wtr = (predict) ? tmpCollisionObj->getInterpolationWorldTransform() : colObjWrap->getWorldTransform(); - + btTransform wtr = (predict) ? + (colObjWrap->m_preTransform != NULL ? tmpCollisionObj->getInterpolationWorldTransform()*(*colObjWrap->m_preTransform) : tmpCollisionObj->getInterpolationWorldTransform()) + : colObjWrap->getWorldTransform(); btScalar dst = m_worldInfo->m_sparsesdf.Evaluate( wtr.invXform(x), From bedaa760c2b299939ad67d40b98515697b16d6a8 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Wed, 14 Aug 2019 10:28:34 -0700 Subject: [PATCH 18/56] speed up corotated force computation --- .../btDeformableCorotatedForce.h | 34 +++++++++++-------- 1 file changed, 19 insertions(+), 15 deletions(-) diff --git a/src/BulletSoftBody/btDeformableCorotatedForce.h b/src/BulletSoftBody/btDeformableCorotatedForce.h index f4d42453f..bf3c52e50 100644 --- a/src/BulletSoftBody/btDeformableCorotatedForce.h +++ b/src/BulletSoftBody/btDeformableCorotatedForce.h @@ -54,6 +54,7 @@ public: { int numNodes = getNumNodes(); btAssert(numNodes <= force.size()) + btVector3 grad_N_hat_1st_col = btVector3(-1,-1,-1); for (int i = 0; i < m_softBodies.size(); ++i) { btSoftBody* psb = m_softBodies[i]; @@ -64,8 +65,7 @@ public: btMatrix3x3 F = tetra.m_ds * tetra.m_Dm_inverse; btMatrix3x3 P; firstPiola(F,P); - btVector3 grad_N_hat_1st_col = btVector3(-1,-1,-1); - btVector3 force_on_node0 = P * tetra.m_Dm_inverse.transpose()*grad_N_hat_1st_col; + btVector3 force_on_node0 = P * (tetra.m_Dm_inverse.transpose()*grad_N_hat_1st_col); btMatrix3x3 force_on_node123 = P * tetra.m_Dm_inverse.transpose(); btSoftBody::Node* node0 = tetra.m_n[0]; @@ -79,26 +79,30 @@ public: // elastic force // explicit elastic force - force[id0] -= scale * tetra.m_element_measure * force_on_node0; - force[id1] -= scale * tetra.m_element_measure * force_on_node123.getColumn(0); - force[id2] -= scale * tetra.m_element_measure * force_on_node123.getColumn(1); - force[id3] -= scale * tetra.m_element_measure * force_on_node123.getColumn(2); + btScalar scale1 = scale * tetra.m_element_measure; + force[id0] -= scale1 * force_on_node0; + force[id1] -= scale1 * force_on_node123.getColumn(0); + force[id2] -= scale1 * force_on_node123.getColumn(1); + force[id3] -= scale1 * force_on_node123.getColumn(2); } } } void firstPiola(const btMatrix3x3& F, btMatrix3x3& P) { - btMatrix3x3 R,S; + // btMatrix3x3 JFinvT = F.adjoint(); btScalar J = F.determinant(); - if (J < 1024 * SIMD_EPSILON) - R.setIdentity(); - else - PolarDecompose(F, R, S); // this QR is not robust, consider using implicit shift svd - /*https://fuchuyuan.github.io/research/svd/paper.pdf*/ - - btMatrix3x3 JFinvT = F.adjoint(); - P = JFinvT * (m_lambda * (J-1)) + (F-R) * 2 * m_mu; + P = F.adjoint() * (m_lambda * (J-1)); + if (m_mu > SIMD_EPSILON) + { + btMatrix3x3 R,S; + if (J < 1024 * SIMD_EPSILON) + R.setIdentity(); + else + PolarDecompose(F, R, S); // this QR is not robust, consider using implicit shift svd + /*https://fuchuyuan.github.io/research/svd/paper.pdf*/ + P += (F-R) * 2 * m_mu; + } } void updateDs(btSoftBody::Tetra& t) { From f8c60e9e3c8e60d00543bd458a9fefd404edc95b Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Thu, 15 Aug 2019 17:15:36 -0700 Subject: [PATCH 19/56] add option for angular momentum conserving damping for mass spring --- .../btDeformableMassSpringForce.h | 23 ++++++++++++++++--- 1 file changed, 20 insertions(+), 3 deletions(-) diff --git a/src/BulletSoftBody/btDeformableMassSpringForce.h b/src/BulletSoftBody/btDeformableMassSpringForce.h index f97ef0a03..4eeae14df 100644 --- a/src/BulletSoftBody/btDeformableMassSpringForce.h +++ b/src/BulletSoftBody/btDeformableMassSpringForce.h @@ -18,10 +18,10 @@ class btDeformableMassSpringForce : public btDeformableLagrangianForce { + bool m_momentum_conserving; public: -// using TVStack = btDeformableLagrangianForce::TVStack; typedef btAlignedObjectArray TVStack; - btDeformableMassSpringForce() + btDeformableMassSpringForce() : m_momentum_conserving(false) { } @@ -53,7 +53,15 @@ public: // damping force btVector3 v_diff = (node2->m_v - node1->m_v); btScalar k_damp = psb->m_dampingCoefficient; - btVector3 scaled_force = scale * v_diff * k_damp; + btVector3 scaled_force = scale * k_damp * v_diff; + if (m_momentum_conserving) + { + if ((node2->m_q - node1->m_q).norm() > SIMD_EPSILON) + { + btVector3 dir = (node2->m_q - node1->m_q).normalized(); + scaled_force = scale * k_damp * v_diff.dot(dir) * dir; + } + } force[id1] += scaled_force; force[id2] -= scaled_force; } @@ -102,7 +110,16 @@ public: btSoftBody::Node* node2 = link.m_n[1]; size_t id1 = node1->index; size_t id2 = node2->index; + btVector3 local_scaled_df = scaled_k_damp * (dv[id2] - dv[id1]); + if (m_momentum_conserving) + { + if ((node2->m_q - node1->m_q).norm() > SIMD_EPSILON) + { + btVector3 dir = (node2->m_q - node1->m_q).normalized(); + local_scaled_df= scaled_k_damp * (dv[id2] - dv[id1]).dot(dir) * dir; + } + } df[id1] += local_scaled_df; df[id2] -= local_scaled_df; } From b507fe77ca842c7db6ecd9e625856a4f13be911b Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Thu, 15 Aug 2019 17:16:32 -0700 Subject: [PATCH 20/56] check in a good set of parameters for grasping deformable ball --- examples/DeformableDemo/GraspDeformable.cpp | 38 ++++++++++----------- examples/ExampleBrowser/CMakeLists.txt | 2 ++ 2 files changed, 21 insertions(+), 19 deletions(-) diff --git a/examples/DeformableDemo/GraspDeformable.cpp b/examples/DeformableDemo/GraspDeformable.cpp index bee1472c1..c0ca947af 100644 --- a/examples/DeformableDemo/GraspDeformable.cpp +++ b/examples/DeformableDemo/GraspDeformable.cpp @@ -73,7 +73,7 @@ public: void resetCamera() { - float dist = 20; + float dist = 2; float pitch = -45; float yaw = 100; float targetPos[3] = {0, -0, 0}; @@ -126,8 +126,8 @@ public: } //use a smaller internal timestep, there are stability issues - float internalTimeStep = 1. / 240.f; - m_dynamicsWorld->stepSimulation(deltaTime, 5, internalTimeStep); + float internalTimeStep = 1. / 250.f; + m_dynamicsWorld->stepSimulation(deltaTime, 100, internalTimeStep); } void createGrip() @@ -245,9 +245,9 @@ void GraspDeformable::initPhysics() bool canSleep = false; bool selfCollide = true; int numLinks = 2; - btVector3 linkHalfExtents(1., 2, .4); - btVector3 baseHalfExtents(1, 0.2, 2); - btMultiBody* mbC = createFeatherstoneMultiBody(getDeformableDynamicsWorld(), btVector3(0.f, 7.f,0.f), linkHalfExtents, baseHalfExtents, false); + btVector3 linkHalfExtents(.1, .2, .04); + btVector3 baseHalfExtents(.1, 0.02, .2); + btMultiBody* mbC = createFeatherstoneMultiBody(getDeformableDynamicsWorld(), btVector3(0.f, .7f,0.f), linkHalfExtents, baseHalfExtents, false); mbC->setCanSleep(canSleep); mbC->setHasSelfCollision(selfCollide); @@ -297,7 +297,7 @@ void GraspDeformable::initPhysics() btTransform groundTransform; groundTransform.setIdentity(); - groundTransform.setOrigin(btVector3(0, -25-2.1, 0)); + groundTransform.setOrigin(btVector3(0, -25-.6, 0)); groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0)); //We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here: btScalar mass(0.); @@ -313,7 +313,7 @@ void GraspDeformable::initPhysics() btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); btRigidBody* body = new btRigidBody(rbInfo); - body->setFriction(0); + body->setFriction(0.1); //add the ground to the dynamics world m_dynamicsWorld->addRigidBody(body); @@ -339,22 +339,22 @@ void GraspDeformable::initPhysics() btSoftBody* psb = btSoftBodyHelpers::CreateFromVtkFile(getDeformableDynamicsWorld()->getWorldInfo(), path); // psb->scale(btVector3(30, 30, 30)); // for banana - psb->scale(btVector3(2, 2, 2)); -// psb->scale(btVector3(3, 3, 3)); // for tube, torus, boot +// psb->scale(btVector3(.2, .2, .2)); + psb->scale(btVector3(.3, .3, .3)); // for tube, torus, boot // psb->scale(btVector3(1, 1, 1)); // for ditto // psb->translate(btVector3(0, 0, 2)); for boot - psb->getCollisionShape()->setMargin(0.1); - psb->setTotalMass(1); + psb->getCollisionShape()->setMargin(0.02); + psb->setTotalMass(.1); psb->setSpringStiffness(0); - psb->setDampingCoefficient(.1); + psb->setDampingCoefficient(.01); psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects psb->m_cfg.kCHR = 1; // collision hardness with rigid body - psb->m_cfg.kDF = 2; + psb->m_cfg.kDF = 50; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(5,5)); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(6,6)); } // // create a piece of cloth @@ -395,15 +395,15 @@ void GraspDeformable::initPhysics() { SliderParams slider("Moving velocity", &sGripperVerticalVelocity); - slider.m_minVal = -2; - slider.m_maxVal = 2; + slider.m_minVal = -.2; + slider.m_maxVal = .2; m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); } { SliderParams slider("Closing velocity", &sGripperClosingTargetVelocity); - slider.m_minVal = -1; - slider.m_maxVal = 1; + slider.m_minVal = -.1; + slider.m_maxVal = .1; m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); } diff --git a/examples/ExampleBrowser/CMakeLists.txt b/examples/ExampleBrowser/CMakeLists.txt index 19334b2db..686313f99 100644 --- a/examples/ExampleBrowser/CMakeLists.txt +++ b/examples/ExampleBrowser/CMakeLists.txt @@ -359,6 +359,8 @@ SET(BulletExampleBrowser_SRCS ../MultiBody/MultiBodyConstraintFeedback.cpp ../SoftDemo/SoftDemo.cpp ../SoftDemo/SoftDemo.h + ../DeformableDemo/GraspDeformable.cpp + ../DeformableDemo/GraspDeformable.h ../DeformableDemo/Pinch.cpp ../DeformableDemo/Pinch.h ../DeformableDemo/DeformableMultibody.cpp From 23cf657a1ada05f25d5da44249a539b4dec7b9f6 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Thu, 15 Aug 2019 17:17:37 -0700 Subject: [PATCH 21/56] change voxel size in sparseSDF to handle contact with smaller objects --- src/BulletSoftBody/btSparseSDF.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/BulletSoftBody/btSparseSDF.h b/src/BulletSoftBody/btSparseSDF.h index a52b2cb1c..2b7fabea3 100644 --- a/src/BulletSoftBody/btSparseSDF.h +++ b/src/BulletSoftBody/btSparseSDF.h @@ -103,7 +103,7 @@ struct btSparseSdf pc = pn; } } - voxelsz = 0.25; + voxelsz = 0.025; puid = 0; ncells = 0; nprobes = 1; From 10cb0c368d1689b974a36e2e888aba4ec520a013 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Thu, 15 Aug 2019 17:18:24 -0700 Subject: [PATCH 22/56] solve CG with more accuracy --- src/BulletSoftBody/btDeformableBodySolver.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index e2e5740d0..850a625dc 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -18,7 +18,7 @@ btDeformableBodySolver::btDeformableBodySolver() : m_numNodes(0) -, m_cg(10) +, m_cg(50) , m_contact_iterations(5) { m_objective = new btDeformableBackwardEulerObjective(m_softBodySet, m_backupVelocity); @@ -47,7 +47,7 @@ void btDeformableBodySolver::solveConstraints(float solverdt) void btDeformableBodySolver::computeStep(TVStack& dv, const TVStack& residual) { - btScalar tolerance = std::numeric_limits::epsilon() * 1024 * m_objective->computeNorm(residual); + btScalar tolerance = std::numeric_limits::epsilon() * 16 * m_objective->computeNorm(residual); m_cg.solve(*m_objective, dv, residual, tolerance); } From df7f216bf83c6bf6664ca80ecd99a2557ffcc763 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Thu, 15 Aug 2019 17:18:45 -0700 Subject: [PATCH 23/56] fix bugs introduced in merging --- src/BulletSoftBody/btDeformableCorotatedForce.h | 17 ----------------- .../btDeformableRigidDynamicsWorld.cpp | 9 --------- 2 files changed, 26 deletions(-) diff --git a/src/BulletSoftBody/btDeformableCorotatedForce.h b/src/BulletSoftBody/btDeformableCorotatedForce.h index bf3c52e50..4d9b8440e 100644 --- a/src/BulletSoftBody/btDeformableCorotatedForce.h +++ b/src/BulletSoftBody/btDeformableCorotatedForce.h @@ -117,23 +117,6 @@ public: virtual void addScaledForceDifferential(btScalar scale, const TVStack& dv, TVStack& df) { - // implicit damping force differential - for (int i = 0; i < m_softBodies.size(); ++i) - { - const btSoftBody* psb = m_softBodies[i]; - btScalar scaled_k_damp = psb->m_dampingCoefficient * scale; - for (int j = 0; j < psb->m_links.size(); ++j) - { - const btSoftBody::Link& link = psb->m_links[j]; - btSoftBody::Node* node1 = link.m_n[0]; - btSoftBody::Node* node2 = link.m_n[1]; - size_t id1 = node1->index; - size_t id2 = node2->index; - btVector3 local_scaled_df = scaled_k_damp * (dv[id2] - dv[id1]); - df[id1] += local_scaled_df; - df[id2] -= local_scaled_df; - } - } } virtual btDeformableLagrangianForceType getForceType() diff --git a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp b/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp index 900ca9d8c..26aa7f82f 100644 --- a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp +++ b/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp @@ -131,15 +131,6 @@ void btDeformableRigidDynamicsWorld::positionCorrection(btScalar timeStep) // only perform position correction when penetrating if (dp < 0) { - if (constraint.m_static[j] == true) - { - if (friction.m_static[j] == true) - { - c->m_node->m_v = va; - } - c->m_node->m_v -= dp * cti.m_normal / timeStep; - c->m_node->m_v = va; - } c->m_node->m_v -= dp * cti.m_normal / timeStep; } } From aa4d5bda3ef0caa1546d47e95652121566bb708a Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Thu, 15 Aug 2019 17:47:28 -0700 Subject: [PATCH 24/56] add elastic and damping stiffness of spring into the force class --- src/BulletSoftBody/btDeformableMassSpringForce.h | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/src/BulletSoftBody/btDeformableMassSpringForce.h b/src/BulletSoftBody/btDeformableMassSpringForce.h index 4eeae14df..4d90c904e 100644 --- a/src/BulletSoftBody/btDeformableMassSpringForce.h +++ b/src/BulletSoftBody/btDeformableMassSpringForce.h @@ -19,9 +19,13 @@ class btDeformableMassSpringForce : public btDeformableLagrangianForce { bool m_momentum_conserving; + btScalar m_elasticStiffness, m_dampingStiffness; public: typedef btAlignedObjectArray TVStack; - btDeformableMassSpringForce() : m_momentum_conserving(false) + btDeformableMassSpringForce() : m_momentum_conserving(false), m_elasticStiffness(1), m_dampingStiffness(0.05) + { + } + btDeformableMassSpringForce(btScalar k, btScalar d, bool conserve_angular = false) : m_momentum_conserving(conserve_angular), m_elasticStiffness(k), m_dampingStiffness(d) { } @@ -52,14 +56,13 @@ public: // damping force btVector3 v_diff = (node2->m_v - node1->m_v); - btScalar k_damp = psb->m_dampingCoefficient; - btVector3 scaled_force = scale * k_damp * v_diff; + btVector3 scaled_force = scale * m_dampingStiffness * v_diff; if (m_momentum_conserving) { if ((node2->m_q - node1->m_q).norm() > SIMD_EPSILON) { btVector3 dir = (node2->m_q - node1->m_q).normalized(); - scaled_force = scale * k_damp * v_diff.dot(dir) * dir; + scaled_force = scale * m_dampingStiffness * v_diff.dot(dir) * dir; } } force[id1] += scaled_force; @@ -80,7 +83,6 @@ public: const btSoftBody::Link& link = psb->m_links[j]; btSoftBody::Node* node1 = link.m_n[0]; btSoftBody::Node* node2 = link.m_n[1]; - btScalar kLST = link.Feature::m_material->m_kLST; btScalar r = link.m_rl; size_t id1 = node1->index; size_t id2 = node2->index; @@ -89,7 +91,7 @@ public: // explicit elastic force btVector3 dir = (node2->m_q - node1->m_q); btVector3 dir_normalized = dir.normalized(); - btVector3 scaled_force = scale * kLST * (dir - dir_normalized * r); + btVector3 scaled_force = scale * m_elasticStiffness * (dir - dir_normalized * r); force[id1] += scaled_force; force[id2] -= scaled_force; } @@ -102,7 +104,7 @@ public: for (int i = 0; i < m_softBodies.size(); ++i) { const btSoftBody* psb = m_softBodies[i]; - btScalar scaled_k_damp = psb->m_dampingCoefficient * scale; + btScalar scaled_k_damp = m_dampingStiffness * scale; for (int j = 0; j < psb->m_links.size(); ++j) { const btSoftBody::Link& link = psb->m_links[j]; From c9ab033a8ba2e892de4d3453afcd0a9ae1dd2e95 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Thu, 15 Aug 2019 17:48:36 -0700 Subject: [PATCH 25/56] check in a good set of parameters for grasping deformable ball with nonlinear damping force (not as stable as linear damping) --- examples/DeformableDemo/DeformableMultibody.cpp | 4 +--- examples/DeformableDemo/DeformableRigid.cpp | 4 +--- examples/DeformableDemo/GraspDeformable.cpp | 16 ++++++++++------ examples/DeformableDemo/Pinch.cpp | 8 +------- examples/DeformableDemo/VolumetricDeformable.cpp | 6 +----- 5 files changed, 14 insertions(+), 24 deletions(-) diff --git a/examples/DeformableDemo/DeformableMultibody.cpp b/examples/DeformableDemo/DeformableMultibody.cpp index d32cd67a7..9ce15ff22 100644 --- a/examples/DeformableDemo/DeformableMultibody.cpp +++ b/examples/DeformableDemo/DeformableMultibody.cpp @@ -219,14 +219,12 @@ void DeformableMultibody::initPhysics() psb->getCollisionShape()->setMargin(0.25); psb->generateBendingConstraints(2); psb->setTotalMass(5); - psb->setSpringStiffness(2); - psb->setDampingCoefficient(0.01); psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects psb->m_cfg.kCHR = 1; // collision hardness with rigid body psb->m_cfg.kDF = .1; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(2, 0.01)); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); } diff --git a/examples/DeformableDemo/DeformableRigid.cpp b/examples/DeformableDemo/DeformableRigid.cpp index 6cc3d7b4f..48809cf99 100644 --- a/examples/DeformableDemo/DeformableRigid.cpp +++ b/examples/DeformableDemo/DeformableRigid.cpp @@ -228,14 +228,12 @@ void DeformableRigid::initPhysics() psb->getCollisionShape()->setMargin(0.1); psb->generateBendingConstraints(2); psb->setTotalMass(1); - psb->setSpringStiffness(2); - psb->setDampingCoefficient(0.05); psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects psb->m_cfg.kCHR = 1; // collision hardness with rigid body psb->m_cfg.kDF = 1; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(2, 0.05)); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); // add a few rigid bodies diff --git a/examples/DeformableDemo/GraspDeformable.cpp b/examples/DeformableDemo/GraspDeformable.cpp index c0ca947af..6d8824515 100644 --- a/examples/DeformableDemo/GraspDeformable.cpp +++ b/examples/DeformableDemo/GraspDeformable.cpp @@ -339,20 +339,24 @@ void GraspDeformable::initPhysics() btSoftBody* psb = btSoftBodyHelpers::CreateFromVtkFile(getDeformableDynamicsWorld()->getWorldInfo(), path); // psb->scale(btVector3(30, 30, 30)); // for banana -// psb->scale(btVector3(.2, .2, .2)); - psb->scale(btVector3(.3, .3, .3)); // for tube, torus, boot + psb->scale(btVector3(.25, .25, .25)); +// psb->scale(btVector3(.3, .3, .3)); // for tube, torus, boot // psb->scale(btVector3(1, 1, 1)); // for ditto // psb->translate(btVector3(0, 0, 2)); for boot psb->getCollisionShape()->setMargin(0.02); psb->setTotalMass(.1); - psb->setSpringStiffness(0); - psb->setDampingCoefficient(.01); psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects psb->m_cfg.kCHR = 1; // collision hardness with rigid body - psb->m_cfg.kDF = 50; + psb->m_cfg.kDF = 10; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); + // nonlinear damping +// getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(1,0.04, true)); +// getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); +// getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(0,6)); + + // linear damping + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(0,0.01, false)); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(6,6)); } diff --git a/examples/DeformableDemo/Pinch.cpp b/examples/DeformableDemo/Pinch.cpp index 44e5f4e5f..190658d62 100644 --- a/examples/DeformableDemo/Pinch.cpp +++ b/examples/DeformableDemo/Pinch.cpp @@ -331,18 +331,12 @@ void Pinch::initPhysics() psb->translate(btVector3(0, 4, 0)); psb->getCollisionShape()->setMargin(0.1); psb->setTotalMass(1); -// psb->scale(btVector3(5, 5, 5)); -// psb->translate(btVector3(-2.5, 4, -2.5)); -// psb->getCollisionShape()->setMargin(0.1); -// psb->setTotalMass(1); - psb->setSpringStiffness(2); - psb->setDampingCoefficient(0.02); psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects psb->m_cfg.kCHR = 1; // collision hardness with rigid body psb->m_cfg.kDF = 2; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(2, 0.02)); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); // add a grippers createGrip(); diff --git a/examples/DeformableDemo/VolumetricDeformable.cpp b/examples/DeformableDemo/VolumetricDeformable.cpp index 22755856b..5c5e395bd 100644 --- a/examples/DeformableDemo/VolumetricDeformable.cpp +++ b/examples/DeformableDemo/VolumetricDeformable.cpp @@ -230,17 +230,13 @@ void VolumetricDeformable::initPhysics() getDeformableDynamicsWorld()->addSoftBody(psb); psb->scale(btVector3(2, 2, 2)); psb->translate(btVector3(0, 5, 0)); -// psb->setVolumeMass(10); psb->getCollisionShape()->setMargin(0.25); -// psb->generateBendingConstraints(2); psb->setTotalMass(1); - psb->setSpringStiffness(0); - psb->setDampingCoefficient(0.01); psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects psb->m_cfg.kCHR = 1; // collision hardness with rigid body psb->m_cfg.kDF = 0.5; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(0,0.01)); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(.5,.5)); } From 86a1312875372778c52a6d528deaae6879a71396 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Fri, 16 Aug 2019 13:33:49 -0700 Subject: [PATCH 26/56] add author info --- src/BulletSoftBody/btCGProjection.h | 2 + src/BulletSoftBody/btConjugateGradient.h | 63 +------------------ .../btDeformableBackwardEulerObjective.cpp | 2 + .../btDeformableBackwardEulerObjective.h | 2 + src/BulletSoftBody/btDeformableBodySolver.cpp | 2 + src/BulletSoftBody/btDeformableBodySolver.h | 2 + .../btDeformableContactProjection.cpp | 2 + .../btDeformableContactProjection.h | 2 + .../btDeformableCorotatedForce.h | 2 + src/BulletSoftBody/btDeformableGravityForce.h | 2 + .../btDeformableLagrangianForce.h | 2 + .../btDeformableMassSpringForce.h | 2 + .../btDeformableRigidDynamicsWorld.cpp | 2 + .../btDeformableRigidDynamicsWorld.h | 2 + src/BulletSoftBody/btPreconditioner.h | 3 +- 15 files changed, 30 insertions(+), 62 deletions(-) diff --git a/src/BulletSoftBody/btCGProjection.h b/src/BulletSoftBody/btCGProjection.h index 9dc416cdd..493aafb7a 100644 --- a/src/BulletSoftBody/btCGProjection.h +++ b/src/BulletSoftBody/btCGProjection.h @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. diff --git a/src/BulletSoftBody/btConjugateGradient.h b/src/BulletSoftBody/btConjugateGradient.h index d7e98761c..bb0b1586f 100644 --- a/src/BulletSoftBody/btConjugateGradient.h +++ b/src/BulletSoftBody/btConjugateGradient.h @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. @@ -32,67 +34,6 @@ public: virtual ~btConjugateGradient(){} -// // return the number of iterations taken -// int solve(MatrixX& A, TVStack& x, const TVStack& b, btScalar tolerance) -// { -// BT_PROFILE("CGSolve"); -// btAssert(x.size() == b.size()); -// reinitialize(b); -// -// // r = b - A * x --with assigned dof zeroed out -// A.multiply(x, temp); -// r = sub(b, temp); -// A.project(r); -// -// btScalar r_norm = std::sqrt(squaredNorm(r)); -// if (r_norm < tolerance) { -// std::cout << "Iteration = 0" << std::endl; -// std::cout << "Two norm of the residual = " << r_norm << std::endl; -// return 0; -// } -// -// // z = M^(-1) * r -// A.precondition(r, z); -// p = z; -// // temp = A*p -// A.multiply(p, temp); -// A.project(temp); -// btScalar r_dot_z = dot(z,r), r_dot_z_new; -// // alpha = r^T * z / (p^T * A * p) -// btScalar alpha = r_dot_z / dot(p, temp), beta; -// -// for (int k = 1; k < max_iterations; k++) { -// // x += alpha * p; -// // r -= alpha * temp; -// multAndAddTo(alpha, p, x); -// multAndAddTo(-alpha, temp, r); -// // zero out the dofs of r -// A.project(r); -//// A.enforceConstraint(x); -// r_norm = std::sqrt(squaredNorm(r)); -// -// if (r_norm < tolerance) { -// std::cout << "ConjugateGradient iterations " << k << std::endl; -// return k; -// } -// -// // z = M^(-1) * r -// A.precondition(r, z); -// r_dot_z_new = dot(r,z); -// beta = r_dot_z_new/ r_dot_z; -// r_dot_z = r_dot_z_new; -// // p = z + beta * p; -// p = multAndAdd(beta, p, z); -// // temp = A * p; -// A.multiply(p, temp); -// A.project(temp); -// // alpha = r^T * z / (p^T * A * p) -// alpha = r_dot_z / dot(p, temp); -// } -// std::cout << "ConjugateGradient max iterations reached " << max_iterations << std::endl; -// return max_iterations; -// } - // return the number of iterations taken int solve(MatrixX& A, TVStack& x, const TVStack& b, btScalar tolerance) { diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp index d01825ad4..f722532e2 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h index 3863970c6..1c3e7890a 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index 850a625dc..93558ade3 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. diff --git a/src/BulletSoftBody/btDeformableBodySolver.h b/src/BulletSoftBody/btDeformableBodySolver.h index 206354f52..93e430e8e 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.h +++ b/src/BulletSoftBody/btDeformableBodySolver.h @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. diff --git a/src/BulletSoftBody/btDeformableContactProjection.cpp b/src/BulletSoftBody/btDeformableContactProjection.cpp index ec155fb68..7f7e8184a 100644 --- a/src/BulletSoftBody/btDeformableContactProjection.cpp +++ b/src/BulletSoftBody/btDeformableContactProjection.cpp @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. diff --git a/src/BulletSoftBody/btDeformableContactProjection.h b/src/BulletSoftBody/btDeformableContactProjection.h index 331e1df6d..f9bd371d7 100644 --- a/src/BulletSoftBody/btDeformableContactProjection.h +++ b/src/BulletSoftBody/btDeformableContactProjection.h @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. diff --git a/src/BulletSoftBody/btDeformableCorotatedForce.h b/src/BulletSoftBody/btDeformableCorotatedForce.h index 4d9b8440e..156794a50 100644 --- a/src/BulletSoftBody/btDeformableCorotatedForce.h +++ b/src/BulletSoftBody/btDeformableCorotatedForce.h @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2016 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. diff --git a/src/BulletSoftBody/btDeformableGravityForce.h b/src/BulletSoftBody/btDeformableGravityForce.h index 270222b7e..e238557b5 100644 --- a/src/BulletSoftBody/btDeformableGravityForce.h +++ b/src/BulletSoftBody/btDeformableGravityForce.h @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. diff --git a/src/BulletSoftBody/btDeformableLagrangianForce.h b/src/BulletSoftBody/btDeformableLagrangianForce.h index 2146d4ec5..ea21647bb 100644 --- a/src/BulletSoftBody/btDeformableLagrangianForce.h +++ b/src/BulletSoftBody/btDeformableLagrangianForce.h @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. diff --git a/src/BulletSoftBody/btDeformableMassSpringForce.h b/src/BulletSoftBody/btDeformableMassSpringForce.h index 4d90c904e..7dbd23907 100644 --- a/src/BulletSoftBody/btDeformableMassSpringForce.h +++ b/src/BulletSoftBody/btDeformableMassSpringForce.h @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. diff --git a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp b/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp index 26aa7f82f..18864e126 100644 --- a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp +++ b/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. diff --git a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.h b/src/BulletSoftBody/btDeformableRigidDynamicsWorld.h index 6efbb204b..49b36748a 100644 --- a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.h +++ b/src/BulletSoftBody/btDeformableRigidDynamicsWorld.h @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. diff --git a/src/BulletSoftBody/btPreconditioner.h b/src/BulletSoftBody/btPreconditioner.h index 663731a58..15ee949a5 100644 --- a/src/BulletSoftBody/btPreconditioner.h +++ b/src/BulletSoftBody/btPreconditioner.h @@ -1,4 +1,6 @@ /* + Written by Xuchen Han + Bullet Continuous Collision Detection and Physics Library Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. @@ -18,7 +20,6 @@ class Preconditioner { public: typedef btAlignedObjectArray TVStack; -// using TVStack = btAlignedObjectArray; virtual void operator()(const TVStack& x, TVStack& b) = 0; virtual void reinitialize(bool nodeUpdated) = 0; }; From 8860f8bacc50403b4eb5ad74f68d139d8955be0d Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Fri, 16 Aug 2019 13:34:10 -0700 Subject: [PATCH 27/56] remove unused functions --- .../btDeformableContactProjection.cpp | 33 ------------------- 1 file changed, 33 deletions(-) diff --git a/src/BulletSoftBody/btDeformableContactProjection.cpp b/src/BulletSoftBody/btDeformableContactProjection.cpp index 7f7e8184a..61d08b3b8 100644 --- a/src/BulletSoftBody/btDeformableContactProjection.cpp +++ b/src/BulletSoftBody/btDeformableContactProjection.cpp @@ -17,39 +17,6 @@ #include "btDeformableRigidDynamicsWorld.h" #include #include -static void findJacobian(const btMultiBodyLinkCollider* multibodyLinkCol, - btMultiBodyJacobianData& jacobianData, - const btVector3& contact_point, - const btVector3& dir) -{ - const int ndof = multibodyLinkCol->m_multiBody->getNumDofs() + 6; - jacobianData.m_jacobians.resize(ndof); - jacobianData.m_deltaVelocitiesUnitImpulse.resize(ndof); - btScalar* jac = &jacobianData.m_jacobians[0]; - - multibodyLinkCol->m_multiBody->fillContactJacobianMultiDof(multibodyLinkCol->m_link, contact_point, dir, jac, jacobianData.scratch_r, jacobianData.scratch_v, jacobianData.scratch_m); - multibodyLinkCol->m_multiBody->calcAccelerationDeltasMultiDof(&jacobianData.m_jacobians[0], &jacobianData.m_deltaVelocitiesUnitImpulse[0], jacobianData.scratch_r, jacobianData.scratch_v); -} - -static btVector3 generateUnitOrthogonalVector(const btVector3& u) -{ - btScalar ux = u.getX(); - btScalar uy = u.getY(); - btScalar uz = u.getZ(); - btScalar ax = std::abs(ux); - btScalar ay = std::abs(uy); - btScalar az = std::abs(uz); - btVector3 v; - if (ax <= ay && ax <= az) - v = btVector3(0, -uz, uy); - else if (ay <= ax && ay <= az) - v = btVector3(-uz, 0, ux); - else - v = btVector3(-uy, ux, 0); - v.normalize(); - return v; -} - void btDeformableContactProjection::update() { ///solve rigid body constraints From bf215a3ce1c5404cab7a12877a09be6ac0731fbe Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Fri, 16 Aug 2019 13:42:53 -0700 Subject: [PATCH 28/56] rename btDeformableRigidDynamicsWorld to btDeformableMultiBodyDynamicsWorld --- .../DeformableDemo/DeformableMultibody.cpp | 14 +++++------ examples/DeformableDemo/DeformableRigid.cpp | 14 +++++------ examples/DeformableDemo/GraspDeformable.cpp | 14 +++++------ examples/DeformableDemo/Pinch.cpp | 16 ++++++------- .../DeformableDemo/VolumetricDeformable.cpp | 14 +++++------ src/BulletSoftBody/CMakeLists.txt | 4 ++-- src/BulletSoftBody/btCGProjection.h | 6 ++--- .../btDeformableBackwardEulerObjective.h | 8 +++---- src/BulletSoftBody/btDeformableBodySolver.cpp | 2 +- src/BulletSoftBody/btDeformableBodySolver.h | 6 ++--- .../btDeformableContactProjection.cpp | 2 +- ...=> btDeformableMultiBodyDynamicsWorld.cpp} | 24 +++++++++---------- ...h => btDeformableMultiBodyDynamicsWorld.h} | 8 +++---- src/BulletSoftBody/premake4.lua | 2 +- 14 files changed, 67 insertions(+), 67 deletions(-) rename src/BulletSoftBody/{btDeformableRigidDynamicsWorld.cpp => btDeformableMultiBodyDynamicsWorld.cpp} (90%) rename src/BulletSoftBody/{btDeformableRigidDynamicsWorld.h => btDeformableMultiBodyDynamicsWorld.h} (91%) diff --git a/examples/DeformableDemo/DeformableMultibody.cpp b/examples/DeformableDemo/DeformableMultibody.cpp index 9ce15ff22..6c3740edf 100644 --- a/examples/DeformableDemo/DeformableMultibody.cpp +++ b/examples/DeformableDemo/DeformableMultibody.cpp @@ -28,7 +28,7 @@ #include "DeformableMultibody.h" ///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. #include "btBulletDynamicsCommon.h" -#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" #include "BulletSoftBody/btSoftBody.h" #include "BulletSoftBody/btSoftBodyHelpers.h" #include "BulletSoftBody/btDeformableBodySolver.h" @@ -79,20 +79,20 @@ public: void addColliders_testMultiDof(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents); - virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const + virtual const btDeformableMultiBodyDynamicsWorld* getDeformableDynamicsWorld() const { - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + return (btDeformableMultiBodyDynamicsWorld*)m_dynamicsWorld; } - virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() + virtual btDeformableMultiBodyDynamicsWorld* getDeformableDynamicsWorld() { - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + return (btDeformableMultiBodyDynamicsWorld*)m_dynamicsWorld; } virtual void renderScene() { CommonMultiBodyBase::renderScene(); - btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) { @@ -121,7 +121,7 @@ void DeformableMultibody::initPhysics() sol = new btMultiBodyConstraintSolver; m_solver = sol; - m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); deformableBodySolver->setWorld(getDeformableDynamicsWorld()); btVector3 gravity = btVector3(0, -10, 0); m_dynamicsWorld->setGravity(gravity); diff --git a/examples/DeformableDemo/DeformableRigid.cpp b/examples/DeformableDemo/DeformableRigid.cpp index 48809cf99..2b5186595 100644 --- a/examples/DeformableDemo/DeformableRigid.cpp +++ b/examples/DeformableDemo/DeformableRigid.cpp @@ -28,7 +28,7 @@ #include "DeformableRigid.h" ///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. #include "btBulletDynamicsCommon.h" -#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" #include "BulletSoftBody/btSoftBody.h" #include "BulletSoftBody/btSoftBodyHelpers.h" #include "BulletSoftBody/btDeformableBodySolver.h" @@ -115,24 +115,24 @@ public: createRigidBody(mass, startTransform, shape[0]); } - virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const + virtual const btDeformableMultiBodyDynamicsWorld* getDeformableDynamicsWorld() const { ///just make it a btSoftRigidDynamicsWorld please ///or we will add type checking - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + return (btDeformableMultiBodyDynamicsWorld*)m_dynamicsWorld; } - virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() + virtual btDeformableMultiBodyDynamicsWorld* getDeformableDynamicsWorld() { ///just make it a btSoftRigidDynamicsWorld please ///or we will add type checking - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + return (btDeformableMultiBodyDynamicsWorld*)m_dynamicsWorld; } virtual void renderScene() { CommonRigidBodyBase::renderScene(); - btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) { @@ -163,7 +163,7 @@ void DeformableRigid::initPhysics() btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); m_solver = sol; - m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); deformableBodySolver->setWorld(getDeformableDynamicsWorld()); // m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality btVector3 gravity = btVector3(0, -10, 0); diff --git a/examples/DeformableDemo/GraspDeformable.cpp b/examples/DeformableDemo/GraspDeformable.cpp index 6d8824515..f439e9983 100644 --- a/examples/DeformableDemo/GraspDeformable.cpp +++ b/examples/DeformableDemo/GraspDeformable.cpp @@ -14,7 +14,7 @@ #include "GraspDeformable.h" ///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. #include "btBulletDynamicsCommon.h" -#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" #include "BulletSoftBody/btSoftBody.h" #include "BulletSoftBody/btSoftBodyHelpers.h" #include "BulletSoftBody/btDeformableBodySolver.h" @@ -148,20 +148,20 @@ public: } } - virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const + virtual const btDeformableMultiBodyDynamicsWorld* getDeformableDynamicsWorld() const { - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + return (btDeformableMultiBodyDynamicsWorld*)m_dynamicsWorld; } - virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() + virtual btDeformableMultiBodyDynamicsWorld* getDeformableDynamicsWorld() { - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + return (btDeformableMultiBodyDynamicsWorld*)m_dynamicsWorld; } virtual void renderScene() { CommonRigidBodyBase::renderScene(); - btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) { @@ -189,7 +189,7 @@ void GraspDeformable::initPhysics() btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); m_solver = sol; - m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); deformableBodySolver->setWorld(getDeformableDynamicsWorld()); btVector3 gravity = btVector3(0, -10, 0); m_dynamicsWorld->setGravity(gravity); diff --git a/examples/DeformableDemo/Pinch.cpp b/examples/DeformableDemo/Pinch.cpp index 190658d62..abe428577 100644 --- a/examples/DeformableDemo/Pinch.cpp +++ b/examples/DeformableDemo/Pinch.cpp @@ -28,7 +28,7 @@ #include "Pinch.h" ///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. #include "btBulletDynamicsCommon.h" -#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" #include "BulletSoftBody/btSoftBody.h" #include "BulletSoftBody/btSoftBodyHelpers.h" #include "BulletSoftBody/btDeformableBodySolver.h" @@ -102,20 +102,20 @@ public: } } - virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const + virtual const btDeformableMultiBodyDynamicsWorld* getDeformableDynamicsWorld() const { - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + return (btDeformableMultiBodyDynamicsWorld*)m_dynamicsWorld; } - virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() + virtual btDeformableMultiBodyDynamicsWorld* getDeformableDynamicsWorld() { - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + return (btDeformableMultiBodyDynamicsWorld*)m_dynamicsWorld; } virtual void renderScene() { CommonRigidBodyBase::renderScene(); - btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) { @@ -128,7 +128,7 @@ public: } }; -void dynamics(btScalar time, btDeformableRigidDynamicsWorld* world) +void dynamics(btScalar time, btDeformableMultiBodyDynamicsWorld* world) { btAlignedObjectArray& rbs = world->getNonStaticRigidBodies(); if (rbs.size()<2) @@ -247,7 +247,7 @@ void Pinch::initPhysics() btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); m_solver = sol; - m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); deformableBodySolver->setWorld(getDeformableDynamicsWorld()); // m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality btVector3 gravity = btVector3(0, -10, 0); diff --git a/examples/DeformableDemo/VolumetricDeformable.cpp b/examples/DeformableDemo/VolumetricDeformable.cpp index 5c5e395bd..745c0cd87 100644 --- a/examples/DeformableDemo/VolumetricDeformable.cpp +++ b/examples/DeformableDemo/VolumetricDeformable.cpp @@ -28,7 +28,7 @@ #include "VolumetricDeformable.h" ///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. #include "btBulletDynamicsCommon.h" -#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h" +#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h" #include "BulletSoftBody/btSoftBody.h" #include "BulletSoftBody/btSoftBodyHelpers.h" #include "BulletSoftBody/btDeformableBodySolver.h" @@ -133,24 +133,24 @@ public: } } - virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const + virtual const btDeformableMultiBodyDynamicsWorld* getDeformableDynamicsWorld() const { ///just make it a btSoftRigidDynamicsWorld please ///or we will add type checking - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + return (btDeformableMultiBodyDynamicsWorld*)m_dynamicsWorld; } - virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() + virtual btDeformableMultiBodyDynamicsWorld* getDeformableDynamicsWorld() { ///just make it a btSoftRigidDynamicsWorld please ///or we will add type checking - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + return (btDeformableMultiBodyDynamicsWorld*)m_dynamicsWorld; } virtual void renderScene() { CommonRigidBodyBase::renderScene(); - btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + btDeformableMultiBodyDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) { @@ -181,7 +181,7 @@ void VolumetricDeformable::initPhysics() btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); m_solver = sol; - m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); + m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); deformableBodySolver->setWorld(getDeformableDynamicsWorld()); // m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality btVector3 gravity = btVector3(0, -10, 0); diff --git a/src/BulletSoftBody/CMakeLists.txt b/src/BulletSoftBody/CMakeLists.txt index 40155786e..262b27e36 100644 --- a/src/BulletSoftBody/CMakeLists.txt +++ b/src/BulletSoftBody/CMakeLists.txt @@ -20,7 +20,7 @@ SET(BulletSoftBody_SRCS btDeformableBackwardEulerObjective.cpp btDeformableBodySolver.cpp btDeformableContactProjection.cpp - btDeformableRigidDynamicsWorld.cpp + btDeformableMultiBodyDynamicsWorld.cpp ) @@ -49,7 +49,7 @@ SET(BulletSoftBody_HDRS btDeformableBackwardEulerObjective.h btDeformableBodySolver.h btDeformableContactProjection.h - btDeformableRigidDynamicsWorld.h + btDeformableMultiBodyDynamicsWorld.h btSoftBodySolverVertexBuffer.h ) diff --git a/src/BulletSoftBody/btCGProjection.h b/src/BulletSoftBody/btCGProjection.h index 493aafb7a..bdc219945 100644 --- a/src/BulletSoftBody/btCGProjection.h +++ b/src/BulletSoftBody/btCGProjection.h @@ -20,7 +20,7 @@ #include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" #include "BulletDynamics/Featherstone/btMultiBodyConstraint.h" -class btDeformableRigidDynamicsWorld; +class btDeformableMultiBodyDynamicsWorld; struct DeformableContactConstraint { @@ -62,7 +62,7 @@ public: typedef btAlignedObjectArray > TVArrayStack; typedef btAlignedObjectArray > TArrayStack; btAlignedObjectArray& m_softBodies; - btDeformableRigidDynamicsWorld* m_world; + btDeformableMultiBodyDynamicsWorld* m_world; const btScalar& m_dt; btCGProjection(btAlignedObjectArray& softBodies, const btScalar& dt) @@ -87,7 +87,7 @@ public: { } - virtual void setWorld(btDeformableRigidDynamicsWorld* world) + virtual void setWorld(btDeformableMultiBodyDynamicsWorld* world) { m_world = world; } diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h index 1c3e7890a..9dd85da6d 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h @@ -22,16 +22,16 @@ #include "btDeformableCorotatedForce.h" #include "btDeformableContactProjection.h" #include "btPreconditioner.h" -#include "btDeformableRigidDynamicsWorld.h" +#include "btDeformableMultiBodyDynamicsWorld.h" #include "LinearMath/btQuickprof.h" -class btDeformableRigidDynamicsWorld; +class btDeformableMultiBodyDynamicsWorld; class btDeformableBackwardEulerObjective { public: typedef btAlignedObjectArray TVStack; btScalar m_dt; - btDeformableRigidDynamicsWorld* m_world; + btDeformableMultiBodyDynamicsWorld* m_world; btAlignedObjectArray m_lf; btAlignedObjectArray& m_softBodies; Preconditioner* m_preconditioner; @@ -98,7 +98,7 @@ public: m_preconditioner->operator()(x,b); } - virtual void setWorld(btDeformableRigidDynamicsWorld* world) + virtual void setWorld(btDeformableMultiBodyDynamicsWorld* world) { m_world = world; projection.setWorld(world); diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index 93558ade3..b173aa53b 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -87,7 +87,7 @@ void btDeformableBodySolver::setConstraints() } } -void btDeformableBodySolver::setWorld(btDeformableRigidDynamicsWorld* world) +void btDeformableBodySolver::setWorld(btDeformableMultiBodyDynamicsWorld* world) { m_objective->setWorld(world); } diff --git a/src/BulletSoftBody/btDeformableBodySolver.h b/src/BulletSoftBody/btDeformableBodySolver.h index 93e430e8e..205086d84 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.h +++ b/src/BulletSoftBody/btDeformableBodySolver.h @@ -19,13 +19,13 @@ #include "btSoftBodySolvers.h" #include "btDeformableBackwardEulerObjective.h" -#include "btDeformableRigidDynamicsWorld.h" +#include "btDeformableMultiBodyDynamicsWorld.h" #include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" #include "BulletDynamics/Featherstone/btMultiBodyConstraint.h" struct btCollisionObjectWrapper; class btDeformableBackwardEulerObjective; -class btDeformableRigidDynamicsWorld; +class btDeformableMultiBodyDynamicsWorld; class btDeformableBodySolver : public btSoftBodySolver { @@ -91,7 +91,7 @@ public: } virtual void optimize(btAlignedObjectArray &softBodies, bool forceUpdate = false){} virtual bool checkInitialized(){return true;} - virtual void setWorld(btDeformableRigidDynamicsWorld* world); + virtual void setWorld(btDeformableMultiBodyDynamicsWorld* world); }; #endif /* btDeformableBodySolver_h */ diff --git a/src/BulletSoftBody/btDeformableContactProjection.cpp b/src/BulletSoftBody/btDeformableContactProjection.cpp index 61d08b3b8..e03001c3f 100644 --- a/src/BulletSoftBody/btDeformableContactProjection.cpp +++ b/src/BulletSoftBody/btDeformableContactProjection.cpp @@ -14,7 +14,7 @@ */ #include "btDeformableContactProjection.h" -#include "btDeformableRigidDynamicsWorld.h" +#include "btDeformableMultiBodyDynamicsWorld.h" #include #include void btDeformableContactProjection::update() diff --git a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp similarity index 90% rename from src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp rename to src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp index 18864e126..354ce3304 100644 --- a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.cpp +++ b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp @@ -30,11 +30,11 @@ The algorithm also closely resembles the one in http://physbam.stanford.edu/~fed */ #include -#include "btDeformableRigidDynamicsWorld.h" +#include "btDeformableMultiBodyDynamicsWorld.h" #include "btDeformableBodySolver.h" #include "LinearMath/btQuickprof.h" -void btDeformableRigidDynamicsWorld::internalSingleStepSimulation(btScalar timeStep) +void btDeformableMultiBodyDynamicsWorld::internalSingleStepSimulation(btScalar timeStep) { BT_PROFILE("internalSingleStepSimulation"); reinitialize(timeStep); @@ -66,7 +66,7 @@ void btDeformableRigidDynamicsWorld::internalSingleStepSimulation(btScalar timeS // /////////////////////////////// } -void btDeformableRigidDynamicsWorld::positionCorrection(btScalar timeStep) +void btDeformableMultiBodyDynamicsWorld::positionCorrection(btScalar timeStep) { // perform position correction for all constraints BT_PROFILE("positionCorrection"); @@ -141,7 +141,7 @@ void btDeformableRigidDynamicsWorld::positionCorrection(btScalar timeStep) } -void btDeformableRigidDynamicsWorld::integrateTransforms(btScalar timeStep) +void btDeformableMultiBodyDynamicsWorld::integrateTransforms(btScalar timeStep) { BT_PROFILE("integrateTransforms"); m_deformableBodySolver->backupVelocity(); @@ -159,12 +159,12 @@ void btDeformableRigidDynamicsWorld::integrateTransforms(btScalar timeStep) m_deformableBodySolver->revertVelocity(); } -void btDeformableRigidDynamicsWorld::solveDeformableBodiesConstraints(btScalar timeStep) +void btDeformableMultiBodyDynamicsWorld::solveDeformableBodiesConstraints(btScalar timeStep) { m_deformableBodySolver->solveConstraints(timeStep); } -void btDeformableRigidDynamicsWorld::addSoftBody(btSoftBody* body, int collisionFilterGroup, int collisionFilterMask) +void btDeformableMultiBodyDynamicsWorld::addSoftBody(btSoftBody* body, int collisionFilterGroup, int collisionFilterMask) { m_softBodies.push_back(body); @@ -177,14 +177,14 @@ void btDeformableRigidDynamicsWorld::addSoftBody(btSoftBody* body, int collision collisionFilterMask); } -void btDeformableRigidDynamicsWorld::predictUnconstraintMotion(btScalar timeStep) +void btDeformableMultiBodyDynamicsWorld::predictUnconstraintMotion(btScalar timeStep) { BT_PROFILE("predictUnconstraintMotion"); btMultiBodyDynamicsWorld::predictUnconstraintMotion(timeStep); m_deformableBodySolver->predictMotion(timeStep); } -void btDeformableRigidDynamicsWorld::reinitialize(btScalar timeStep) +void btDeformableMultiBodyDynamicsWorld::reinitialize(btScalar timeStep) { m_internalTime += timeStep; m_deformableBodySolver->reinitialize(m_softBodies, timeStep); @@ -195,7 +195,7 @@ void btDeformableRigidDynamicsWorld::reinitialize(btScalar timeStep) btMultiBodyDynamicsWorld::getSolverInfo().m_timeStep = timeStep; } -void btDeformableRigidDynamicsWorld::applyRigidBodyGravity(btScalar timeStep) +void btDeformableMultiBodyDynamicsWorld::applyRigidBodyGravity(btScalar timeStep) { // Gravity is applied in stepSimulation and then cleared here and then applied here and then cleared here again // so that 1) gravity is applied to velocity before constraint solve and 2) gravity is applied in each substep @@ -215,7 +215,7 @@ void btDeformableRigidDynamicsWorld::applyRigidBodyGravity(btScalar timeStep) clearMultiBodyForces(); } -void btDeformableRigidDynamicsWorld::beforeSolverCallbacks(btScalar timeStep) +void btDeformableMultiBodyDynamicsWorld::beforeSolverCallbacks(btScalar timeStep) { if (0 != m_internalTickCallback) { @@ -228,7 +228,7 @@ void btDeformableRigidDynamicsWorld::beforeSolverCallbacks(btScalar timeStep) } } -void btDeformableRigidDynamicsWorld::afterSolverCallbacks(btScalar timeStep) +void btDeformableMultiBodyDynamicsWorld::afterSolverCallbacks(btScalar timeStep) { if (0 != m_solverCallback) { @@ -236,7 +236,7 @@ void btDeformableRigidDynamicsWorld::afterSolverCallbacks(btScalar timeStep) } } -void btDeformableRigidDynamicsWorld::addForce(btSoftBody* psb, btDeformableLagrangianForce* force) +void btDeformableMultiBodyDynamicsWorld::addForce(btSoftBody* psb, btDeformableLagrangianForce* force) { btAlignedObjectArray& forces = m_deformableBodySolver->m_objective->m_lf; bool added = false; diff --git a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.h b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h similarity index 91% rename from src/BulletSoftBody/btDeformableRigidDynamicsWorld.h rename to src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h index 49b36748a..bd886d4dc 100644 --- a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.h +++ b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h @@ -28,7 +28,7 @@ class btDeformableBodySolver; class btDeformableLagrangianForce; typedef btAlignedObjectArray btSoftBodyArray; -class btDeformableRigidDynamicsWorld : public btMultiBodyDynamicsWorld +class btDeformableMultiBodyDynamicsWorld : public btMultiBodyDynamicsWorld { typedef btAlignedObjectArray TVStack; // using TVStack = btAlignedObjectArray; @@ -42,7 +42,7 @@ class btDeformableRigidDynamicsWorld : public btMultiBodyDynamicsWorld btSoftBodyWorldInfo m_sbi; btScalar m_internalTime; - typedef void (*btSolverCallback)(btScalar time, btDeformableRigidDynamicsWorld* world); + typedef void (*btSolverCallback)(btScalar time, btDeformableMultiBodyDynamicsWorld* world); btSolverCallback m_solverCallback; protected: @@ -55,7 +55,7 @@ protected: void solveDeformableBodiesConstraints(btScalar timeStep); public: - btDeformableRigidDynamicsWorld(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btMultiBodyConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration, btDeformableBodySolver* deformableBodySolver = 0) + btDeformableMultiBodyDynamicsWorld(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btMultiBodyConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration, btDeformableBodySolver* deformableBodySolver = 0) : btMultiBodyDynamicsWorld(dispatcher, pairCache, constraintSolver, collisionConfiguration), m_deformableBodySolver(deformableBodySolver), m_solverCallback(0) { @@ -83,7 +83,7 @@ public: m_solverCallback = cb; } - virtual ~btDeformableRigidDynamicsWorld() + virtual ~btDeformableMultiBodyDynamicsWorld() { } diff --git a/src/BulletSoftBody/premake4.lua b/src/BulletSoftBody/premake4.lua index 6f09196fa..c8a6e5151 100644 --- a/src/BulletSoftBody/premake4.lua +++ b/src/BulletSoftBody/premake4.lua @@ -11,4 +11,4 @@ files { "**.cpp", "**.h" - } \ No newline at end of file + } From 6d4e93d3bf064ade92ee007a1685aae7361c6f3d Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Fri, 16 Aug 2019 14:03:14 -0700 Subject: [PATCH 29/56] mods for compatibility with older compiler --- examples/DeformableDemo/GraspDeformable.cpp | 3 +-- src/BulletSoftBody/btSoftBodyHelpers.cpp | 6 +++--- src/BulletSoftBody/btSoftBodyHelpers.h | 2 +- 3 files changed, 5 insertions(+), 6 deletions(-) diff --git a/examples/DeformableDemo/GraspDeformable.cpp b/examples/DeformableDemo/GraspDeformable.cpp index f439e9983..8fdc2752b 100644 --- a/examples/DeformableDemo/GraspDeformable.cpp +++ b/examples/DeformableDemo/GraspDeformable.cpp @@ -330,13 +330,12 @@ void GraspDeformable::initPhysics() // b3FileUtils::findFile("bread.vtk", relative_path, 1024); // b3FileUtils::findFile("ditto.vtk", relative_path, 1024); // b3FileUtils::findFile("boot.vtk", relative_path, 1024); - std::string path(relative_path); // btSoftBody* psb = btSoftBodyHelpers::CreateFromTetGenData(getDeformableDynamicsWorld()->getWorldInfo(), // TetraCube::getElements(), // 0, // TetraCube::getNodes(), // false, true, true); - btSoftBody* psb = btSoftBodyHelpers::CreateFromVtkFile(getDeformableDynamicsWorld()->getWorldInfo(), path); + btSoftBody* psb = btSoftBodyHelpers::CreateFromVtkFile(getDeformableDynamicsWorld()->getWorldInfo(), relative_path); // psb->scale(btVector3(30, 30, 30)); // for banana psb->scale(btVector3(.25, .25, .25)); diff --git a/src/BulletSoftBody/btSoftBodyHelpers.cpp b/src/BulletSoftBody/btSoftBodyHelpers.cpp index 3cdf4d7bd..6c67a3b78 100644 --- a/src/BulletSoftBody/btSoftBodyHelpers.cpp +++ b/src/BulletSoftBody/btSoftBodyHelpers.cpp @@ -746,9 +746,9 @@ btSoftBody* btSoftBodyHelpers::CreatePatch(btSoftBodyWorldInfo& worldInfo, const { const btScalar tx = ix / (btScalar)(rx - 1); btScalar pert = perturbation * btScalar(rand())/RAND_MAX; - btVector4 temp1 = py1; + btVector3 temp1 = py1; temp1.setY(py1.getY() + pert); - btVector4 temp = py0; + btVector3 temp = py0; pert = perturbation * btScalar(rand())/RAND_MAX; temp.setY(py0.getY() + pert); x[IDX(ix, iy)] = lerp(temp, temp1, tx); @@ -1239,7 +1239,7 @@ if(face&&face[0]) return (psb); } -btSoftBody* btSoftBodyHelpers::CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, const std::string& vtk_file) +btSoftBody* btSoftBodyHelpers::CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, const char* vtk_file) { std::ifstream fs; fs.open(vtk_file); diff --git a/src/BulletSoftBody/btSoftBodyHelpers.h b/src/BulletSoftBody/btSoftBodyHelpers.h index 6cdeb97c3..24c86afdd 100644 --- a/src/BulletSoftBody/btSoftBodyHelpers.h +++ b/src/BulletSoftBody/btSoftBodyHelpers.h @@ -142,7 +142,7 @@ struct btSoftBodyHelpers bool bfacelinks, bool btetralinks, bool bfacesfromtetras); - static btSoftBody* CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, const std::string& vtk_file); + static btSoftBody* CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, const char* vtk_file); static btSoftBody* CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, std::istream& in); From 74adce732200a51fc5945f6c10c2de3fdb2ea385 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Mon, 19 Aug 2019 11:28:41 -0700 Subject: [PATCH 30/56] bug fix in momentum conserving damping model for mass spring; update default damping model to momentum conserving one --- src/BulletSoftBody/btDeformableMassSpringForce.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/BulletSoftBody/btDeformableMassSpringForce.h b/src/BulletSoftBody/btDeformableMassSpringForce.h index 7dbd23907..8caf7702f 100644 --- a/src/BulletSoftBody/btDeformableMassSpringForce.h +++ b/src/BulletSoftBody/btDeformableMassSpringForce.h @@ -27,7 +27,7 @@ public: btDeformableMassSpringForce() : m_momentum_conserving(false), m_elasticStiffness(1), m_dampingStiffness(0.05) { } - btDeformableMassSpringForce(btScalar k, btScalar d, bool conserve_angular = false) : m_momentum_conserving(conserve_angular), m_elasticStiffness(k), m_dampingStiffness(d) + btDeformableMassSpringForce(btScalar k, btScalar d, bool conserve_angular = true) : m_momentum_conserving(conserve_angular), m_elasticStiffness(k), m_dampingStiffness(d) { } @@ -63,7 +63,7 @@ public: { if ((node2->m_q - node1->m_q).norm() > SIMD_EPSILON) { - btVector3 dir = (node2->m_q - node1->m_q).normalized(); + btVector3 dir = (node2->m_x - node1->m_x).normalized(); scaled_force = scale * m_dampingStiffness * v_diff.dot(dir) * dir; } } @@ -120,7 +120,7 @@ public: { if ((node2->m_q - node1->m_q).norm() > SIMD_EPSILON) { - btVector3 dir = (node2->m_q - node1->m_q).normalized(); + btVector3 dir = (node2->m_x - node1->m_x).normalized(); local_scaled_df= scaled_k_damp * (dv[id2] - dv[id1]).dot(dir) * dir; } } From 54bd93aad2fcb12b09ddbe1603da4ee98271f977 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Mon, 19 Aug 2019 11:30:25 -0700 Subject: [PATCH 31/56] move deformation update to before explicit force calculation to prevent repetition of F calculation --- .../btDeformableBackwardEulerObjective.cpp | 5 +++++ src/BulletSoftBody/btDeformableCorotatedForce.h | 16 ++-------------- src/BulletSoftBody/btSoftBody.cpp | 14 ++++++++++++++ src/BulletSoftBody/btSoftBody.h | 3 ++- 4 files changed, 23 insertions(+), 15 deletions(-) diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp index f722532e2..244fbb6ce 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp @@ -119,6 +119,11 @@ btScalar btDeformableBackwardEulerObjective::computeNorm(const TVStack& residual void btDeformableBackwardEulerObjective::applyExplicitForce(TVStack& force) { + for (int i = 0; i < m_softBodies.size(); ++i) + { + m_softBodies[i]->updateDeformation(); + } + for (int i = 0; i < m_lf.size(); ++i) { m_lf[i]->addScaledExplicitForce(m_dt, force); diff --git a/src/BulletSoftBody/btDeformableCorotatedForce.h b/src/BulletSoftBody/btDeformableCorotatedForce.h index 156794a50..14896514e 100644 --- a/src/BulletSoftBody/btDeformableCorotatedForce.h +++ b/src/BulletSoftBody/btDeformableCorotatedForce.h @@ -2,7 +2,7 @@ Written by Xuchen Han Bullet Continuous Collision Detection and Physics Library - Copyright (c) 2016 Google Inc. http://bulletphysics.org + Copyright (c) 2019 Google Inc. http://bulletphysics.org This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. Permission is granted to anyone to use this software for any purpose, @@ -63,10 +63,8 @@ public: for (int j = 0; j < psb->m_tetras.size(); ++j) { btSoftBody::Tetra& tetra = psb->m_tetras[j]; - updateDs(tetra); - btMatrix3x3 F = tetra.m_ds * tetra.m_Dm_inverse; btMatrix3x3 P; - firstPiola(F,P); + firstPiola(tetra.m_F,P); btVector3 force_on_node0 = P * (tetra.m_Dm_inverse.transpose()*grad_N_hat_1st_col); btMatrix3x3 force_on_node123 = P * tetra.m_Dm_inverse.transpose(); @@ -106,16 +104,6 @@ public: P += (F-R) * 2 * m_mu; } } - void updateDs(btSoftBody::Tetra& t) - { - btVector3 c1 = t.m_n[1]->m_q - t.m_n[0]->m_q; - btVector3 c2 = t.m_n[2]->m_q - t.m_n[0]->m_q; - btVector3 c3 = t.m_n[3]->m_q - t.m_n[0]->m_q; - btMatrix3x3 Ds(c1.getX(), c2.getX(), c3.getX(), - c1.getY(), c2.getY(), c3.getY(), - c1.getZ(), c2.getZ(), c3.getZ()); - t.m_ds = Ds; - } virtual void addScaledForceDifferential(btScalar scale, const TVStack& dv, TVStack& df) { diff --git a/src/BulletSoftBody/btSoftBody.cpp b/src/BulletSoftBody/btSoftBody.cpp index 2da04d491..ac7b8ae7e 100644 --- a/src/BulletSoftBody/btSoftBody.cpp +++ b/src/BulletSoftBody/btSoftBody.cpp @@ -2831,6 +2831,20 @@ void btSoftBody::initializeDmInverse() } } +void btSoftBody::updateDeformation() +{ + for (int i = 0; i < m_tetras.size(); ++i) + { + btSoftBody::Tetra& t = m_tetras[i]; + btVector3 c1 = t.m_n[1]->m_q - t.m_n[0]->m_q; + btVector3 c2 = t.m_n[2]->m_q - t.m_n[0]->m_q; + btVector3 c3 = t.m_n[3]->m_q - t.m_n[0]->m_q; + btMatrix3x3 Ds(c1.getX(), c2.getX(), c3.getX(), + c1.getY(), c2.getY(), c3.getY(), + c1.getZ(), c2.getZ(), c3.getZ()); + t.m_F = Ds * t.m_Dm_inverse; + } +} // void btSoftBody::Joint::Prepare(btScalar dt, int) { diff --git a/src/BulletSoftBody/btSoftBody.h b/src/BulletSoftBody/btSoftBody.h index 0ee9e827d..cd235c29d 100644 --- a/src/BulletSoftBody/btSoftBody.h +++ b/src/BulletSoftBody/btSoftBody.h @@ -293,7 +293,7 @@ public: btScalar m_c1; // (4*kVST)/(im0+im1+im2+im3) btScalar m_c2; // m_c1/sum(|g0..3|^2) btMatrix3x3 m_Dm_inverse; // rest Dm^-1 - btMatrix3x3 m_ds; + btMatrix3x3 m_F; btScalar m_element_measure; }; /* RContact */ @@ -1027,6 +1027,7 @@ public: void dampClusters(); void setSpringStiffness(btScalar k); void initializeDmInverse(); + void updateDeformation(); void applyForces(); static void PSolve_Anchors(btSoftBody* psb, btScalar kst, btScalar ti); static void PSolve_RContacts(btSoftBody* psb, btScalar kst, btScalar ti); From 04595961cdd8efb9eb56236cd9933e021b9aa411 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Mon, 19 Aug 2019 12:02:57 -0700 Subject: [PATCH 32/56] add velocity clamp to prevent deformable objects from going too fast --- .../btDeformableMultiBodyDynamicsWorld.cpp | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp index 354ce3304..60e3bbbbd 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp +++ b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp @@ -153,6 +153,19 @@ void btDeformableMultiBodyDynamicsWorld::integrateTransforms(btScalar timeStep) for (int j = 0; j < psb->m_nodes.size(); ++j) { btSoftBody::Node& node = psb->m_nodes[j]; + btScalar maxDisplacement = psb->getWorldInfo()->m_maxDisplacement; + btScalar clampDeltaV = maxDisplacement / timeStep; + for (int c = 0; c < 3; c++) + { + if (node.m_v[c] > clampDeltaV) + { + node.m_v[c] = clampDeltaV; + } + if (node.m_v[c] < -clampDeltaV) + { + node.m_v[c] = -clampDeltaV; + } + } node.m_x = node.m_q + timeStep * node.m_v; } } From 44e7c4a96dd14ba2ccf517e326a4cf076963237e Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Mon, 19 Aug 2019 12:03:45 -0700 Subject: [PATCH 33/56] add stable NeoHookean Model --- .../btDeformableBackwardEulerObjective.h | 1 + .../btDeformableLagrangianForce.h | 4 +- .../btDeformableNeoHookeanForce.h | 136 ++++++++++++++++++ 3 files changed, 139 insertions(+), 2 deletions(-) create mode 100644 src/BulletSoftBody/btDeformableNeoHookeanForce.h diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h index 9dd85da6d..7e1bae29f 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h @@ -20,6 +20,7 @@ #include "btDeformableMassSpringForce.h" #include "btDeformableGravityForce.h" #include "btDeformableCorotatedForce.h" +#include "btDeformableNeoHookeanForce.h" #include "btDeformableContactProjection.h" #include "btPreconditioner.h" #include "btDeformableMultiBodyDynamicsWorld.h" diff --git a/src/BulletSoftBody/btDeformableLagrangianForce.h b/src/BulletSoftBody/btDeformableLagrangianForce.h index ea21647bb..daea0e86a 100644 --- a/src/BulletSoftBody/btDeformableLagrangianForce.h +++ b/src/BulletSoftBody/btDeformableLagrangianForce.h @@ -23,13 +23,13 @@ enum btDeformableLagrangianForceType { BT_GRAVITY_FORCE = 1, BT_MASSSPRING_FORCE = 2, - BT_COROTATED_FORCE = 3 + BT_COROTATED_FORCE = 3, + BT_NEOHOOKEAN_FORCE = 4 }; class btDeformableLagrangianForce { public: -// using TVStack = btAlignedObjectArray; typedef btAlignedObjectArray TVStack; btAlignedObjectArray m_softBodies; const btAlignedObjectArray* m_nodes; diff --git a/src/BulletSoftBody/btDeformableNeoHookeanForce.h b/src/BulletSoftBody/btDeformableNeoHookeanForce.h new file mode 100644 index 000000000..9bc232e24 --- /dev/null +++ b/src/BulletSoftBody/btDeformableNeoHookeanForce.h @@ -0,0 +1,136 @@ +/* +Written by Xuchen Han + +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2019 Google Inc. http://bulletphysics.org +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + +#ifndef BT_NEOHOOKEAN_H +#define BT_NEOHOOKEAN_H + +#include "btDeformableLagrangianForce.h" + +class btDeformableNeoHookeanForce : public btDeformableLagrangianForce +{ +public: + typedef btAlignedObjectArray TVStack; + btScalar m_mu, m_lambda; + btDeformableNeoHookeanForce(): m_mu(1), m_lambda(1) + { + + } + + btDeformableNeoHookeanForce(btScalar mu, btScalar lambda): m_mu(mu), m_lambda(lambda) + { + } + + virtual void addScaledImplicitForce(btScalar scale, TVStack& force) + { + addScaledDampingForce(scale, force); + } + + virtual void addScaledExplicitForce(btScalar scale, TVStack& force) + { + addScaledElasticForce(scale, force); + } + + virtual void addScaledDampingForce(btScalar scale, TVStack& force) + { + } + + virtual void addScaledElasticForce(btScalar scale, TVStack& force) + { + int numNodes = getNumNodes(); + btAssert(numNodes <= force.size()) + btVector3 grad_N_hat_1st_col = btVector3(-1,-1,-1); + for (int i = 0; i < m_softBodies.size(); ++i) + { + btSoftBody* psb = m_softBodies[i]; + for (int j = 0; j < psb->m_tetras.size(); ++j) + { + btSoftBody::Tetra& tetra = psb->m_tetras[j]; + btMatrix3x3 P; + firstPiola(tetra.m_F,P); + btVector3 force_on_node0 = P * (tetra.m_Dm_inverse.transpose()*grad_N_hat_1st_col); + btMatrix3x3 force_on_node123 = P * tetra.m_Dm_inverse.transpose(); + + btSoftBody::Node* node0 = tetra.m_n[0]; + btSoftBody::Node* node1 = tetra.m_n[1]; + btSoftBody::Node* node2 = tetra.m_n[2]; + btSoftBody::Node* node3 = tetra.m_n[3]; + size_t id0 = node0->index; + size_t id1 = node1->index; + size_t id2 = node2->index; + size_t id3 = node3->index; + + // elastic force + // explicit elastic force + btScalar scale1 = scale * tetra.m_element_measure; + force[id0] -= scale1 * force_on_node0; + force[id1] -= scale1 * force_on_node123.getColumn(0); + force[id2] -= scale1 * force_on_node123.getColumn(1); + force[id3] -= scale1 * force_on_node123.getColumn(2); + } + } + } + + void firstPiola(const btMatrix3x3& F, btMatrix3x3& P) + { + btMatrix3x3 C = F.transpose()*F; + btScalar J = F.determinant(); + btScalar trace = C[0].getX() + C[1].getY() + C[2].getZ(); + P = F * m_mu * ( 1. - 1. / (trace + 1.)) + F.adjoint() * (m_lambda * (J - 1) - 0.75 * m_mu); + } + + virtual void addScaledForceDifferential(btScalar scale, const TVStack& dv, TVStack& df) + { + } + + void firstPiolaDifferential(const btMatrix3x3& F, const btMatrix3x3& G, btMatrix3x3& P) + { + btScalar J = F.determinant(); + addScaledCofactorMatrixDifferential(F, G, m_lambda*(J-1), P); + P += F.adjoint() * m_lambda * DotProduct(F.adjoint(), G); + } + + btScalar DotProduct(const btMatrix3x3& A, const btMatrix3x3& B) + { + btScalar ans = 0; + for (int i = 0; i < 3; ++i) + { + for (int j = 0; j < 3; ++j) + { + ans += A[i][j] * B[i][j]; + } + } + return ans; + } + + void addScaledCofactorMatrixDifferential(const btMatrix3x3& F, const btMatrix3x3& dF, btScalar scale, btMatrix3x3& M) + { + M[0][0] = scale * (dF[1][1] * F[2][2] + F[1][1] * dF[2][2] - dF[2][1] * F[1][2] - F[2][1] * dF[1][2]); + M[1][0] = scale * (dF[2][1] * F[0][2] + F[2][1] * dF[0][2] - dF[0][1] * F[2][2] - F[0][1] * dF[2][2]); + M[2][0] = scale * (dF[0][1] * F[1][2] + F[0][1] * dF[1][2] - dF[1][1] * F[0][2] - F[1][1] * dF[0][2]); + M[0][1] = scale * (dF[2][0] * F[1][2] + F[2][0] * dF[1][2] - dF[1][0] * F[2][2] - F[1][0] * dF[2][2]); + M[1][1] = scale * (dF[0][0] * F[2][2] + F[0][0] * dF[2][2] - dF[2][0] * F[0][2] - F[2][0] * dF[0][2]); + M[2][1] = scale * (dF[1][0] * F[0][2] + F[1][0] * dF[0][2] - dF[0][0] * F[1][2] - F[0][0] * dF[1][2]); + M[0][2] = scale * (dF[1][0] * F[2][1] + F[1][0] * dF[2][1] - dF[2][0] * F[1][1] - F[2][0] * dF[1][1]); + M[1][2] = scale * (dF[2][0] * F[0][1] + F[2][0] * dF[0][1] - dF[0][0] * F[2][1] - F[0][0] * dF[2][1]); + M[2][2] = scale * (dF[0][0] * F[1][1] + F[0][0] * dF[1][1] - dF[1][0] * F[0][1] - F[1][0] * dF[0][1]); + } + + virtual btDeformableLagrangianForceType getForceType() + { + return BT_NEOHOOKEAN_FORCE; + } + +}; +#endif /* BT_NEOHOOKEAN_H */ From 9af25430ac03c7b313d8a1b8cd1d7ab9c0d4e223 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Mon, 19 Aug 2019 12:04:10 -0700 Subject: [PATCH 34/56] update examples to include NeoHookean Model and new damping model --- examples/DeformableDemo/DeformableMultibody.cpp | 2 +- examples/DeformableDemo/DeformableRigid.cpp | 2 +- examples/DeformableDemo/GraspDeformable.cpp | 13 +++++++------ examples/DeformableDemo/Pinch.cpp | 3 ++- examples/DeformableDemo/VolumetricDeformable.cpp | 4 ++-- 5 files changed, 13 insertions(+), 11 deletions(-) diff --git a/examples/DeformableDemo/DeformableMultibody.cpp b/examples/DeformableDemo/DeformableMultibody.cpp index 6c3740edf..f9c527b3c 100644 --- a/examples/DeformableDemo/DeformableMultibody.cpp +++ b/examples/DeformableDemo/DeformableMultibody.cpp @@ -224,7 +224,7 @@ void DeformableMultibody::initPhysics() psb->m_cfg.kDF = .1; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(2, 0.01)); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(2, 0.01, false)); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); } diff --git a/examples/DeformableDemo/DeformableRigid.cpp b/examples/DeformableDemo/DeformableRigid.cpp index 2b5186595..f6b0c3184 100644 --- a/examples/DeformableDemo/DeformableRigid.cpp +++ b/examples/DeformableDemo/DeformableRigid.cpp @@ -233,7 +233,7 @@ void DeformableRigid::initPhysics() psb->m_cfg.kDF = 1; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(2, 0.05)); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(2, 0.01, false)); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); // add a few rigid bodies diff --git a/examples/DeformableDemo/GraspDeformable.cpp b/examples/DeformableDemo/GraspDeformable.cpp index 8fdc2752b..10b273a2e 100644 --- a/examples/DeformableDemo/GraspDeformable.cpp +++ b/examples/DeformableDemo/GraspDeformable.cpp @@ -191,7 +191,7 @@ void GraspDeformable::initPhysics() m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); deformableBodySolver->setWorld(getDeformableDynamicsWorld()); - btVector3 gravity = btVector3(0, -10, 0); + btVector3 gravity = btVector3(0, -9.81, 0); m_dynamicsWorld->setGravity(gravity); getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); @@ -316,7 +316,7 @@ void GraspDeformable::initPhysics() body->setFriction(0.1); //add the ground to the dynamics world - m_dynamicsWorld->addRigidBody(body); + m_dynamicsWorld->addRigidBody(body,1,1+2); } // create a soft block @@ -342,22 +342,23 @@ void GraspDeformable::initPhysics() // psb->scale(btVector3(.3, .3, .3)); // for tube, torus, boot // psb->scale(btVector3(1, 1, 1)); // for ditto // psb->translate(btVector3(0, 0, 2)); for boot - psb->getCollisionShape()->setMargin(0.02); + psb->getCollisionShape()->setMargin(0.01); psb->setTotalMass(.1); psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects psb->m_cfg.kCHR = 1; // collision hardness with rigid body - psb->m_cfg.kDF = 10; + psb->m_cfg.kDF = 2; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); + psb->getWorldInfo()->m_maxDisplacement = .1f; // nonlinear damping // getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(1,0.04, true)); // getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); // getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(0,6)); // linear damping - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(0,0.01, false)); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(.5,0.04, true)); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(6,6)); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableNeoHookeanForce(2,10)); } // // create a piece of cloth diff --git a/examples/DeformableDemo/Pinch.cpp b/examples/DeformableDemo/Pinch.cpp index abe428577..7bfbc7712 100644 --- a/examples/DeformableDemo/Pinch.cpp +++ b/examples/DeformableDemo/Pinch.cpp @@ -336,8 +336,9 @@ void Pinch::initPhysics() psb->m_cfg.kDF = 2; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(2, 0.02)); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(1, 0.05)); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableNeoHookeanForce(.2,1)); // add a grippers createGrip(); } diff --git a/examples/DeformableDemo/VolumetricDeformable.cpp b/examples/DeformableDemo/VolumetricDeformable.cpp index 745c0cd87..55331b5d5 100644 --- a/examples/DeformableDemo/VolumetricDeformable.cpp +++ b/examples/DeformableDemo/VolumetricDeformable.cpp @@ -236,9 +236,9 @@ void VolumetricDeformable::initPhysics() psb->m_cfg.kCHR = 1; // collision hardness with rigid body psb->m_cfg.kDF = 0.5; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(0,0.01)); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(0,0.03)); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(.5,.5)); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableNeoHookeanForce(.5,2.5)); } // add a few rigid bodies Ctor_RbUpStack(4); From 9f559af2a8d25d275601471a6c4d9b1e6ca9d231 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Mon, 19 Aug 2019 13:07:26 -0700 Subject: [PATCH 35/56] set m_contact_iterations to solverInfo.m_solverIterations --- src/BulletSoftBody/btDeformableBodySolver.cpp | 5 ++++- src/BulletSoftBody/btDeformableContactProjection.cpp | 1 + 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index b173aa53b..85730cc1e 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -21,7 +21,6 @@ btDeformableBodySolver::btDeformableBodySolver() : m_numNodes(0) , m_cg(50) -, m_contact_iterations(5) { m_objective = new btDeformableBackwardEulerObjective(m_softBodySet, m_backupVelocity); } @@ -79,12 +78,16 @@ void btDeformableBodySolver::setConstraints() { BT_PROFILE("setConstraint"); m_objective->setConstraints(); + // m_contact_iterations takes over m_numIterations + m_contact_iterations = m_objective->m_world->getSolverInfo().m_numIterations; for (int i = 0; i < m_contact_iterations; ++i) { m_objective->projection.update(); m_objective->enforceConstraint(m_dv); m_objective->updateVelocity(m_dv); } + // recover m_numIterations from m_contact_iterations + m_objective->m_world->getSolverInfo().m_numIterations = m_contact_iterations; } void btDeformableBodySolver::setWorld(btDeformableMultiBodyDynamicsWorld* world) diff --git a/src/BulletSoftBody/btDeformableContactProjection.cpp b/src/BulletSoftBody/btDeformableContactProjection.cpp index e03001c3f..ba8f74144 100644 --- a/src/BulletSoftBody/btDeformableContactProjection.cpp +++ b/src/BulletSoftBody/btDeformableContactProjection.cpp @@ -21,6 +21,7 @@ void btDeformableContactProjection::update() { ///solve rigid body constraints { + // m_numIterations get temporarily to 1 so that we interleave one step of multibody solve with one step of multibody/deformable contact solve m_world->getSolverInfo().m_numIterations = 1; m_world->processIslands(); m_world->btMultiBodyDynamicsWorld::solveInternalConstraints(m_world->getSolverInfo()); // process constraints deferred in the previous step From 5cdfbf331300d9fd2c6fd7dafc13f29a3116ab1d Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Mon, 19 Aug 2019 13:09:14 -0700 Subject: [PATCH 36/56] add CMakeLists --- src/BulletSoftBody/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/BulletSoftBody/CMakeLists.txt b/src/BulletSoftBody/CMakeLists.txt index 262b27e36..40d07bd66 100644 --- a/src/BulletSoftBody/CMakeLists.txt +++ b/src/BulletSoftBody/CMakeLists.txt @@ -43,6 +43,8 @@ SET(BulletSoftBody_HDRS btConjugateGradient.h btDeformableGravityForce.h btDeformableMassSpringForce.h + btDeformableCorotatedForce.h + btDeformableNeoHookeanForce.h btDeformableLagrangianForce.h btPreconditioner.h From ef65d6422b0ec4e730de799f936d81c3fc5ad4bd Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Mon, 19 Aug 2019 17:28:22 -0700 Subject: [PATCH 37/56] remove CG printf outputs --- src/BulletSoftBody/btConjugateGradient.h | 19 ++++++++++++++----- 1 file changed, 14 insertions(+), 5 deletions(-) diff --git a/src/BulletSoftBody/btConjugateGradient.h b/src/BulletSoftBody/btConjugateGradient.h index bb0b1586f..6fad0e60a 100644 --- a/src/BulletSoftBody/btConjugateGradient.h +++ b/src/BulletSoftBody/btConjugateGradient.h @@ -35,7 +35,7 @@ public: virtual ~btConjugateGradient(){} // return the number of iterations taken - int solve(MatrixX& A, TVStack& x, const TVStack& b, btScalar tolerance) + int solve(MatrixX& A, TVStack& x, const TVStack& b, btScalar tolerance, bool verbose = false) { BT_PROFILE("CGSolve"); btAssert(x.size() == b.size()); @@ -49,8 +49,11 @@ public: A.project(z); btScalar r_dot_z = dot(z,r); if (r_dot_z < tolerance) { - std::cout << "Iteration = 0" << std::endl; - std::cout << "Two norm of the residual = " << r_dot_z << std::endl; + if (verbose) + { + std::cout << "Iteration = 0" << std::endl; + std::cout << "Two norm of the residual = " << r_dot_z << std::endl; + } return 0; } p = z; @@ -70,13 +73,19 @@ public: r_dot_z = r_dot_z_new; r_dot_z_new = dot(r,z); if (r_dot_z_new < tolerance) { - std::cout << "ConjugateGradient iterations " << k << std::endl; + if (verbose) + { + std::cout << "ConjugateGradient iterations " << k << std::endl; + } return k; } btScalar beta = r_dot_z_new/ r_dot_z; p = multAndAdd(beta, p, z); } - std::cout << "ConjugateGradient max iterations reached " << max_iterations << std::endl; + if (verbose) + { + std::cout << "ConjugateGradient max iterations reached " << max_iterations << std::endl; + } return max_iterations; } From 3bf3b66fb72cb228d4ff8cc61b16c689efbc0b2d Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Mon, 19 Aug 2019 19:18:02 -0700 Subject: [PATCH 38/56] add method to remove softbody --- src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp | 5 ++++- src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp | 8 ++++++++ src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h | 2 ++ 3 files changed, 14 insertions(+), 1 deletion(-) diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp index 244fbb6ce..bf88ae550 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp @@ -27,7 +27,10 @@ btDeformableBackwardEulerObjective::btDeformableBackwardEulerObjective(btAligned void btDeformableBackwardEulerObjective::reinitialize(bool nodeUpdated, btScalar dt) { BT_PROFILE("reinitialize"); - setDt(dt); + if (dt > 0) + { + setDt(dt); + } if(nodeUpdated) { updateId(); diff --git a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp index 60e3bbbbd..05e1c1ac9 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp +++ b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp @@ -269,3 +269,11 @@ void btDeformableMultiBodyDynamicsWorld::addForce(btSoftBody* psb, btDeformableL forces.push_back(force); } } + +void btDeformableMultiBodyDynamicsWorld::removeSoftBody(btSoftBody* body) +{ + m_softBodies.remove(body); + btCollisionWorld::removeCollisionObject(body); + // force a reinitialize so that node indices get updated. + m_deformableBodySolver->reinitialize(m_softBodies, btScalar(-1)); +} diff --git a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h index bd886d4dc..f8d368c5f 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h +++ b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h @@ -136,6 +136,8 @@ public: void addForce(btSoftBody* psb, btDeformableLagrangianForce* force); + void removeSoftBody(btSoftBody* body); + int getDrawFlags() const { return (m_drawFlags); } void setDrawFlags(int f) { m_drawFlags = f; } }; From 76d37ec4756b0770c86a70434cc963e043cd9952 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Tue, 20 Aug 2019 10:37:25 -0700 Subject: [PATCH 39/56] bug fix in updateDeformation --- src/BulletSoftBody/btSoftBody.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/src/BulletSoftBody/btSoftBody.cpp b/src/BulletSoftBody/btSoftBody.cpp index ac7b8ae7e..c8d20e35a 100644 --- a/src/BulletSoftBody/btSoftBody.cpp +++ b/src/BulletSoftBody/btSoftBody.cpp @@ -2835,10 +2835,12 @@ void btSoftBody::updateDeformation() { for (int i = 0; i < m_tetras.size(); ++i) { + // updateDeformation is called before predictMotion where m_q is sync'd. + // So m_x is the current position of the node. btSoftBody::Tetra& t = m_tetras[i]; - btVector3 c1 = t.m_n[1]->m_q - t.m_n[0]->m_q; - btVector3 c2 = t.m_n[2]->m_q - t.m_n[0]->m_q; - btVector3 c3 = t.m_n[3]->m_q - t.m_n[0]->m_q; + btVector3 c1 = t.m_n[1]->m_x - t.m_n[0]->m_x; + btVector3 c2 = t.m_n[2]->m_x - t.m_n[0]->m_x; + btVector3 c3 = t.m_n[3]->m_x - t.m_n[0]->m_x; btMatrix3x3 Ds(c1.getX(), c2.getX(), c3.getX(), c1.getY(), c2.getY(), c3.getY(), c1.getZ(), c2.getZ(), c3.getZ()); From 7e971d9f638db29519c5eaee59bf5f2d78c8df74 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Tue, 20 Aug 2019 11:12:36 -0700 Subject: [PATCH 40/56] safe guard against NaN in dv after CG solve --- src/BulletSoftBody/btDeformableBodySolver.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index 85730cc1e..d36c19718 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -103,6 +103,11 @@ void btDeformableBodySolver::updateVelocity() btSoftBody* psb = m_softBodySet[i]; for (int j = 0; j < psb->m_nodes.size(); ++j) { + // set NaN to zero; + if (m_dv[counter] != m_dv[counter]) + { + m_dv[counter].setZero(); + } psb->m_nodes[j].m_v = m_backupVelocity[counter]+m_dv[counter]; ++counter; } From fadf6aa61249ae84aa7e0760fc96714af4501eee Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Tue, 20 Aug 2019 16:26:19 -0700 Subject: [PATCH 41/56] prevent division by zero in mass spring --- src/BulletSoftBody/btDeformableMassSpringForce.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/BulletSoftBody/btDeformableMassSpringForce.h b/src/BulletSoftBody/btDeformableMassSpringForce.h index 8caf7702f..14d4e8260 100644 --- a/src/BulletSoftBody/btDeformableMassSpringForce.h +++ b/src/BulletSoftBody/btDeformableMassSpringForce.h @@ -92,7 +92,7 @@ public: // elastic force // explicit elastic force btVector3 dir = (node2->m_q - node1->m_q); - btVector3 dir_normalized = dir.normalized(); + btVector3 dir_normalized = (dir.norm() > SIMD_EPSILON) ? dir.normalized() : btVector3(0,0,0); btVector3 scaled_force = scale * m_elasticStiffness * (dir - dir_normalized * r); force[id1] += scaled_force; force[id2] -= scaled_force; From 076c8b11df6392421a6d7b5b2e8090c4400aac4f Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Fri, 16 Aug 2019 13:51:50 -0700 Subject: [PATCH 42/56] revert the changes to damping of multibody external forces --- src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp index c05ab420f..386f1dfd1 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp @@ -593,14 +593,10 @@ void btMultiBodyDynamicsWorld::solveExternalForces(btContactSolverInfo& solverIn { if (!bod->isUsingRK4Integration()) { - // avoid damping in external forces (e.g. gravity) - const btScalar linearDamp = bod->getLinearDamping(); - bod->setLinearDamping(0); bod->computeAccelerationsArticulatedBodyAlgorithmMultiDof(solverInfo.m_timeStep, m_scratch_r, m_scratch_v, m_scratch_m,isConstraintPass, getSolverInfo().m_jointFeedbackInWorldSpace, getSolverInfo().m_jointFeedbackInJointFrame); - bod->setLinearDamping(linearDamp); } else { From f33532273a243cd3d0869540a5a0c2383be7e65a Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Wed, 21 Aug 2019 16:03:54 -0700 Subject: [PATCH 43/56] sync interpolationTransform for multibody in integrateTransform; revert changes to voxel size in sparseSDF --- src/BulletDynamics/Featherstone/btMultiBody.cpp | 2 ++ src/BulletSoftBody/btSparseSDF.h | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/src/BulletDynamics/Featherstone/btMultiBody.cpp b/src/BulletDynamics/Featherstone/btMultiBody.cpp index 4d634b699..654f77c09 100644 --- a/src/BulletDynamics/Featherstone/btMultiBody.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBody.cpp @@ -2142,6 +2142,7 @@ void btMultiBody::updateCollisionObjectWorldTransforms(btAlignedObjectArraysetWorldTransform(tr); + getBaseCollider()->setInterpolationWorldTransform(tr); } for (int k = 0; k < getNumLinks(); k++) @@ -2170,6 +2171,7 @@ void btMultiBody::updateCollisionObjectWorldTransforms(btAlignedObjectArraysetWorldTransform(tr); + col->setInterpolationWorldTransform(tr); } } } diff --git a/src/BulletSoftBody/btSparseSDF.h b/src/BulletSoftBody/btSparseSDF.h index 2b7fabea3..a52b2cb1c 100644 --- a/src/BulletSoftBody/btSparseSDF.h +++ b/src/BulletSoftBody/btSparseSDF.h @@ -103,7 +103,7 @@ struct btSparseSdf pc = pn; } } - voxelsz = 0.025; + voxelsz = 0.25; puid = 0; ncells = 0; nprobes = 1; From 4e1c1a30a7077d0b491545f8c540abe4c58a020c Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Wed, 21 Aug 2019 22:17:46 -0700 Subject: [PATCH 44/56] remove world dependency from btDeformableBodySolver,btDeformableBackwardEulerObjective, and btCGProjection; reduce invasion into multibody world, all chnages are cosmetic now --- .../DeformableDemo/DeformableMultibody.cpp | 2 +- examples/DeformableDemo/DeformableRigid.cpp | 2 +- examples/DeformableDemo/GraspDeformable.cpp | 3 +- examples/DeformableDemo/Pinch.cpp | 2 +- .../DeformableDemo/VolumetricDeformable.cpp | 2 +- .../btSimulationIslandManager.h | 4 +- .../Featherstone/btMultiBodyDynamicsWorld.cpp | 48 +++++++++++-------- .../Featherstone/btMultiBodyDynamicsWorld.h | 7 +-- src/BulletSoftBody/btCGProjection.h | 8 +--- .../btDeformableBackwardEulerObjective.cpp | 4 -- .../btDeformableBackwardEulerObjective.h | 12 ++--- src/BulletSoftBody/btDeformableBodySolver.cpp | 25 ++++------ src/BulletSoftBody/btDeformableBodySolver.h | 11 +++-- .../btDeformableContactProjection.cpp | 9 +--- .../btDeformableMultiBodyDynamicsWorld.cpp | 29 +++++++++-- .../btDeformableMultiBodyDynamicsWorld.h | 10 +++- 16 files changed, 98 insertions(+), 80 deletions(-) diff --git a/examples/DeformableDemo/DeformableMultibody.cpp b/examples/DeformableDemo/DeformableMultibody.cpp index f9c527b3c..084ff5a04 100644 --- a/examples/DeformableDemo/DeformableMultibody.cpp +++ b/examples/DeformableDemo/DeformableMultibody.cpp @@ -122,7 +122,7 @@ void DeformableMultibody::initPhysics() m_solver = sol; m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); - deformableBodySolver->setWorld(getDeformableDynamicsWorld()); +// deformableBodySolver->setWorld(getDeformableDynamicsWorld()); btVector3 gravity = btVector3(0, -10, 0); m_dynamicsWorld->setGravity(gravity); getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; diff --git a/examples/DeformableDemo/DeformableRigid.cpp b/examples/DeformableDemo/DeformableRigid.cpp index f6b0c3184..9b546086d 100644 --- a/examples/DeformableDemo/DeformableRigid.cpp +++ b/examples/DeformableDemo/DeformableRigid.cpp @@ -164,7 +164,7 @@ void DeformableRigid::initPhysics() m_solver = sol; m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); - deformableBodySolver->setWorld(getDeformableDynamicsWorld()); +// deformableBodySolver->setWorld(getDeformableDynamicsWorld()); // m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality btVector3 gravity = btVector3(0, -10, 0); m_dynamicsWorld->setGravity(gravity); diff --git a/examples/DeformableDemo/GraspDeformable.cpp b/examples/DeformableDemo/GraspDeformable.cpp index 10b273a2e..d07c3cb01 100644 --- a/examples/DeformableDemo/GraspDeformable.cpp +++ b/examples/DeformableDemo/GraspDeformable.cpp @@ -190,7 +190,7 @@ void GraspDeformable::initPhysics() m_solver = sol; m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); - deformableBodySolver->setWorld(getDeformableDynamicsWorld()); +// deformableBodySolver->setWorld(getDeformableDynamicsWorld()); btVector3 gravity = btVector3(0, -9.81, 0); m_dynamicsWorld->setGravity(gravity); getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; @@ -357,6 +357,7 @@ void GraspDeformable::initPhysics() // linear damping getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(.5,0.04, true)); +// getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(3,0.04, true)); getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); getDeformableDynamicsWorld()->addForce(psb, new btDeformableNeoHookeanForce(2,10)); } diff --git a/examples/DeformableDemo/Pinch.cpp b/examples/DeformableDemo/Pinch.cpp index 7bfbc7712..e1c3fd348 100644 --- a/examples/DeformableDemo/Pinch.cpp +++ b/examples/DeformableDemo/Pinch.cpp @@ -248,7 +248,7 @@ void Pinch::initPhysics() m_solver = sol; m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); - deformableBodySolver->setWorld(getDeformableDynamicsWorld()); +// deformableBodySolver->setWorld(getDeformableDynamicsWorld()); // m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality btVector3 gravity = btVector3(0, -10, 0); m_dynamicsWorld->setGravity(gravity); diff --git a/examples/DeformableDemo/VolumetricDeformable.cpp b/examples/DeformableDemo/VolumetricDeformable.cpp index 55331b5d5..9796ab963 100644 --- a/examples/DeformableDemo/VolumetricDeformable.cpp +++ b/examples/DeformableDemo/VolumetricDeformable.cpp @@ -182,7 +182,7 @@ void VolumetricDeformable::initPhysics() m_solver = sol; m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); - deformableBodySolver->setWorld(getDeformableDynamicsWorld()); +// deformableBodySolver->setWorld(getDeformableDynamicsWorld()); // m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality btVector3 gravity = btVector3(0, -10, 0); m_dynamicsWorld->setGravity(gravity); diff --git a/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h b/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h index 62c4c574c..197bb457c 100644 --- a/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h +++ b/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h @@ -57,9 +57,11 @@ public: }; void buildAndProcessIslands(btDispatcher* dispatcher, btCollisionWorld* collisionWorld, IslandCallback* callback); - void processIslands(btDispatcher* dispatcher, btCollisionWorld* collisionWorld, IslandCallback* callback); + void buildIslands(btDispatcher* dispatcher, btCollisionWorld* colWorld); + void processIslands(btDispatcher* dispatcher, btCollisionWorld* collisionWorld, IslandCallback* callback); + bool getSplitIslands() { return m_splitIslands; diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp index 386f1dfd1..950edb1a2 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp @@ -428,27 +428,41 @@ void btMultiBodyDynamicsWorld::forwardKinematics() void btMultiBodyDynamicsWorld::solveConstraints(btContactSolverInfo& solverInfo) { solveExternalForces(solverInfo); - m_islandManager->buildAndProcessIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld(), m_solverMultiBodyIslandCallback); + buildIslands(); solveInternalConstraints(solverInfo); } void btMultiBodyDynamicsWorld::buildIslands() { - m_islandManager->buildIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld()); -} - -void btMultiBodyDynamicsWorld::processIslands() -{ - m_islandManager->processIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld(), m_solverMultiBodyIslandCallback); + m_islandManager->buildAndProcessIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld(), m_solverMultiBodyIslandCallback); } void btMultiBodyDynamicsWorld::solveInternalConstraints(btContactSolverInfo& solverInfo) { /// solve all the constraints for this island m_solverMultiBodyIslandCallback->processConstraints(); - m_constraintSolver->allSolved(solverInfo, m_debugDrawer); + calculateJointForce(solverInfo); + processDeltaVee(); +} +void btMultiBodyDynamicsWorld::btMultiBodyDynamicsWorld::processConstraintsAndDeltaVee() +{ + m_solverMultiBodyIslandCallback->processConstraints(); + processDeltaVee(); +} + +void btMultiBodyDynamicsWorld::processDeltaVee() +{ + for (int i = 0; i < this->m_multiBodies.size(); i++) + { + btMultiBody* bod = m_multiBodies[i]; + bod->processDeltaVeeMultiDof2(); + } +} + +void btMultiBodyDynamicsWorld::calculateJointForce(btContactSolverInfo& solverInfo) +{ { BT_PROFILE("btMultiBody stepVelocities"); for (int i = 0; i < this->m_multiBodies.size(); i++) @@ -489,13 +503,7 @@ void btMultiBodyDynamicsWorld::solveInternalConstraints(btContactSolverInfo& sol } } } - } - - for (int i = 0; i < this->m_multiBodies.size(); i++) - { - btMultiBody* bod = m_multiBodies[i]; - bod->processDeltaVeeMultiDof2(); - } + } } void btMultiBodyDynamicsWorld::solveExternalForces(btContactSolverInfo& solverInfo) @@ -1087,8 +1095,8 @@ void btMultiBodyDynamicsWorld::serializeMultiBodies(btSerializer* serializer) } } } - -void btMultiBodyDynamicsWorld::setSplitIslands(bool split) -{ - m_islandManager->setSplitIslands(split); -} +// +//void btMultiBodyDynamicsWorld::setSplitIslands(bool split) +//{ +// m_islandManager->setSplitIslands(split); +//} diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h index 605141bc6..a03687859 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h @@ -57,6 +57,7 @@ public: virtual ~btMultiBodyDynamicsWorld(); virtual void solveConstraints(btContactSolverInfo& solverInfo); + virtual void addMultiBody(btMultiBody* body, int group = btBroadphaseProxy::DefaultFilter, int mask = btBroadphaseProxy::AllFilter); virtual void removeMultiBody(btMultiBody* body); @@ -118,8 +119,8 @@ public: virtual void solveExternalForces(btContactSolverInfo& solverInfo); virtual void solveInternalConstraints(btContactSolverInfo& solverInfo); void buildIslands(); - void processIslands(); - void setSplitIslands(bool split); - + void calculateJointForce(btContactSolverInfo& solverInfo); + void processDeltaVee(); + void processConstraintsAndDeltaVee(); }; #endif //BT_MULTIBODY_DYNAMICS_WORLD_H diff --git a/src/BulletSoftBody/btCGProjection.h b/src/BulletSoftBody/btCGProjection.h index bdc219945..c5a1bb55b 100644 --- a/src/BulletSoftBody/btCGProjection.h +++ b/src/BulletSoftBody/btCGProjection.h @@ -20,7 +20,7 @@ #include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" #include "BulletDynamics/Featherstone/btMultiBodyConstraint.h" -class btDeformableMultiBodyDynamicsWorld; +//class btDeformableMultiBodyDynamicsWorld; struct DeformableContactConstraint { @@ -62,7 +62,6 @@ public: typedef btAlignedObjectArray > TVArrayStack; typedef btAlignedObjectArray > TArrayStack; btAlignedObjectArray& m_softBodies; - btDeformableMultiBodyDynamicsWorld* m_world; const btScalar& m_dt; btCGProjection(btAlignedObjectArray& softBodies, const btScalar& dt) @@ -86,11 +85,6 @@ public: virtual void reinitialize(bool nodeUpdated) { } - - virtual void setWorld(btDeformableMultiBodyDynamicsWorld* world) - { - m_world = world; - } }; diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp index bf88ae550..1dee17be8 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp @@ -151,10 +151,6 @@ void btDeformableBackwardEulerObjective::initialGuess(TVStack& dv, const TVStack //set constraints as projections void btDeformableBackwardEulerObjective::setConstraints() { - // build islands for multibody solve - m_world->btMultiBodyDynamicsWorld::buildIslands(); - // for repeated constraint solve, splitIslands has to be set to true - m_world->setSplitIslands(true); projection.setConstraints(); } diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h index 7e1bae29f..cf8ba9920 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h @@ -26,13 +26,13 @@ #include "btDeformableMultiBodyDynamicsWorld.h" #include "LinearMath/btQuickprof.h" -class btDeformableMultiBodyDynamicsWorld; +//class btDeformableMultiBodyDynamicsWorld; class btDeformableBackwardEulerObjective { public: typedef btAlignedObjectArray TVStack; btScalar m_dt; - btDeformableMultiBodyDynamicsWorld* m_world; +// btDeformableMultiBodyDynamicsWorld* m_world; btAlignedObjectArray m_lf; btAlignedObjectArray& m_softBodies; Preconditioner* m_preconditioner; @@ -98,13 +98,7 @@ public: { m_preconditioner->operator()(x,b); } - - virtual void setWorld(btDeformableMultiBodyDynamicsWorld* world) - { - m_world = world; - projection.setWorld(world); - } - + virtual void updateId() { size_t id = 0; diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index d36c19718..03a9be07e 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -30,14 +30,14 @@ btDeformableBodySolver::~btDeformableBodySolver() delete m_objective; } -void btDeformableBodySolver::solveConstraints(float solverdt) +void btDeformableBodySolver::solveDeformableConstraints(float solverdt) { BT_PROFILE("solveConstraints"); // save v_{n+1}^* velocity after explicit forces - backupVelocity(); +// backupVelocity(); // add constraints to the solver - setConstraints(); +// setConstraints(); m_objective->computeResidual(solverdt, m_residual); m_objective->applyDynamicFriction(m_residual); computeStep(m_dv, m_residual); @@ -47,7 +47,6 @@ void btDeformableBodySolver::solveConstraints(float solverdt) void btDeformableBodySolver::computeStep(TVStack& dv, const TVStack& residual) { - btScalar tolerance = std::numeric_limits::epsilon() * 16 * m_objective->computeNorm(residual); m_cg.solve(*m_objective, dv, residual, tolerance); } @@ -78,23 +77,17 @@ void btDeformableBodySolver::setConstraints() { BT_PROFILE("setConstraint"); m_objective->setConstraints(); - // m_contact_iterations takes over m_numIterations - m_contact_iterations = m_objective->m_world->getSolverInfo().m_numIterations; - for (int i = 0; i < m_contact_iterations; ++i) - { - m_objective->projection.update(); - m_objective->enforceConstraint(m_dv); - m_objective->updateVelocity(m_dv); - } - // recover m_numIterations from m_contact_iterations - m_objective->m_world->getSolverInfo().m_numIterations = m_contact_iterations; } -void btDeformableBodySolver::setWorld(btDeformableMultiBodyDynamicsWorld* world) +void btDeformableBodySolver::solveContactConstraints() { - m_objective->setWorld(world); + BT_PROFILE("setConstraint"); + m_objective->projection.update(); + m_objective->enforceConstraint(m_dv); + m_objective->updateVelocity(m_dv); } + void btDeformableBodySolver::updateVelocity() { int counter = 0; diff --git a/src/BulletSoftBody/btDeformableBodySolver.h b/src/BulletSoftBody/btDeformableBodySolver.h index 205086d84..55f940328 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.h +++ b/src/BulletSoftBody/btDeformableBodySolver.h @@ -61,7 +61,11 @@ public: void extracted(float solverdt); - virtual void solveConstraints(float solverdt); + virtual void solveDeformableConstraints(btScalar solverdt); + + void solveContactConstraints(); + + virtual void solveConstraints(float dt){} void reinitialize(const btAlignedObjectArray& softBodies, btScalar dt); @@ -77,7 +81,7 @@ public: void computeStep(TVStack& dv, const TVStack& residual); - virtual void predictMotion(float solverdt); + virtual void predictMotion(btScalar solverdt); virtual void copySoftBodyToVertexBuffer(const btSoftBody *const softBody, btVertexBufferDescriptor *vertexBuffer) {} @@ -90,8 +94,9 @@ public: softBody->defaultCollisionHandler(otherSoftBody); } virtual void optimize(btAlignedObjectArray &softBodies, bool forceUpdate = false){} + virtual bool checkInitialized(){return true;} - virtual void setWorld(btDeformableMultiBodyDynamicsWorld* world); + }; #endif /* btDeformableBodySolver_h */ diff --git a/src/BulletSoftBody/btDeformableContactProjection.cpp b/src/BulletSoftBody/btDeformableContactProjection.cpp index ba8f74144..f9d4b7d99 100644 --- a/src/BulletSoftBody/btDeformableContactProjection.cpp +++ b/src/BulletSoftBody/btDeformableContactProjection.cpp @@ -19,13 +19,8 @@ #include void btDeformableContactProjection::update() { - ///solve rigid body constraints - { - // m_numIterations get temporarily to 1 so that we interleave one step of multibody solve with one step of multibody/deformable contact solve - m_world->getSolverInfo().m_numIterations = 1; - m_world->processIslands(); - m_world->btMultiBodyDynamicsWorld::solveInternalConstraints(m_world->getSolverInfo()); // process constraints deferred in the previous step - } +// m_world->getSolverInfo().m_numIterations = 1; + // loop through constraints to set constrained values for (int index = 0; index < m_constraints.size(); ++index) { diff --git a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp index 05e1c1ac9..825e7cd66 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp +++ b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp @@ -33,7 +33,6 @@ The algorithm also closely resembles the one in http://physbam.stanford.edu/~fed #include "btDeformableMultiBodyDynamicsWorld.h" #include "btDeformableBodySolver.h" #include "LinearMath/btQuickprof.h" - void btDeformableMultiBodyDynamicsWorld::internalSingleStepSimulation(btScalar timeStep) { BT_PROFILE("internalSingleStepSimulation"); @@ -52,7 +51,7 @@ void btDeformableMultiBodyDynamicsWorld::internalSingleStepSimulation(btScalar t beforeSolverCallbacks(timeStep); ///solve deformable bodies constraints - solveDeformableBodiesConstraints(timeStep); + solveConstraints(timeStep); afterSolverCallbacks(timeStep); @@ -172,9 +171,31 @@ void btDeformableMultiBodyDynamicsWorld::integrateTransforms(btScalar timeStep) m_deformableBodySolver->revertVelocity(); } -void btDeformableMultiBodyDynamicsWorld::solveDeformableBodiesConstraints(btScalar timeStep) +void btDeformableMultiBodyDynamicsWorld::solveConstraints(btScalar timeStep) { - m_deformableBodySolver->solveConstraints(timeStep); + // save v_{n+1}^* velocity after explicit forces + m_deformableBodySolver->backupVelocity(); + + // setup constraints among multibodies and between multibodies and deformable bodies + setupConstraints(); + solveMultiBodyConstraints(); + m_deformableBodySolver->solveDeformableConstraints(timeStep); +} + +void btDeformableMultiBodyDynamicsWorld::setupConstraints() +{ + m_deformableBodySolver->setConstraints(); + m_islandManager->buildIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld()); +} + +void btDeformableMultiBodyDynamicsWorld::solveMultiBodyConstraints() +{ + for (int i = 0; i < m_contact_iterations; ++i) + { + m_islandManager->processIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld(), (btSimulationIslandManager::IslandCallback*)m_solverMultiBodyIslandCallback); + btMultiBodyDynamicsWorld::processConstraintsAndDeltaVee(); + m_deformableBodySolver->solveContactConstraints(); + } } void btDeformableMultiBodyDynamicsWorld::addSoftBody(btSoftBody* body, int collisionFilterGroup, int collisionFilterMask) diff --git a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h index f8d368c5f..b4f7dbe5a 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h +++ b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h @@ -21,11 +21,14 @@ #include "btDeformableMassSpringForce.h" #include "btDeformableBodySolver.h" #include "btSoftBodyHelpers.h" +#include "BulletCollision/CollisionDispatch/btSimulationIslandManager.h" #include typedef btAlignedObjectArray btSoftBodyArray; class btDeformableBodySolver; class btDeformableLagrangianForce; +struct MultiBodyInplaceSolverIslandCallback; + typedef btAlignedObjectArray btSoftBodyArray; class btDeformableMultiBodyDynamicsWorld : public btMultiBodyDynamicsWorld @@ -41,6 +44,7 @@ class btDeformableMultiBodyDynamicsWorld : public btMultiBodyDynamicsWorld bool m_drawClusterTree; btSoftBodyWorldInfo m_sbi; btScalar m_internalTime; + int m_contact_iterations; typedef void (*btSolverCallback)(btScalar time, btDeformableMultiBodyDynamicsWorld* world); btSolverCallback m_solverCallback; @@ -52,7 +56,7 @@ protected: void positionCorrection(btScalar timeStep); - void solveDeformableBodiesConstraints(btScalar timeStep); + void solveConstraints(btScalar timeStep); public: btDeformableMultiBodyDynamicsWorld(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btMultiBodyConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration, btDeformableBodySolver* deformableBodySolver = 0) @@ -76,6 +80,7 @@ public: m_sbi.m_sparsesdf.Initialize(); m_internalTime = 0.0; + m_contact_iterations = 1; } void setSolverCallback(btSolverCallback cb) @@ -140,6 +145,9 @@ public: int getDrawFlags() const { return (m_drawFlags); } void setDrawFlags(int f) { m_drawFlags = f; } + + void setupConstraints(); + void solveMultiBodyConstraints(); }; #endif //BT_DEFORMABLE_RIGID_DYNAMICS_WORLD_H From 75d0cfaf695b9e0841c4c23af9c1b3173b8cc9ea Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Wed, 21 Aug 2019 22:29:53 -0700 Subject: [PATCH 45/56] restore default voxelsz and add option to change voxelsz --- .../btDeformableMultiBodyDynamicsWorld.h | 1 + src/BulletSoftBody/btSparseSDF.h | 10 +++++++++- 2 files changed, 10 insertions(+), 1 deletion(-) diff --git a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h index b4f7dbe5a..1b1806bac 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h +++ b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h @@ -70,6 +70,7 @@ public: m_sbi.m_broadphase = pairCache; m_sbi.m_dispatcher = dispatcher; m_sbi.m_sparsesdf.Initialize(); + m_sbi.m_sparsesdf.setDefaultVoxelsz(0.0025); m_sbi.m_sparsesdf.Reset(); m_sbi.air_density = (btScalar)1.2; diff --git a/src/BulletSoftBody/btSparseSDF.h b/src/BulletSoftBody/btSparseSDF.h index a52b2cb1c..8258c3eeb 100644 --- a/src/BulletSoftBody/btSparseSDF.h +++ b/src/BulletSoftBody/btSparseSDF.h @@ -70,6 +70,7 @@ struct btSparseSdf btAlignedObjectArray cells; btScalar voxelsz; + btScalar m_defaultVoxelsz; int puid; int ncells; int m_clampCells; @@ -87,9 +88,16 @@ struct btSparseSdf //if this limit is reached, the SDF is reset (at the cost of some performance during the reset) m_clampCells = clampCells; cells.resize(hashsize, 0); + m_defaultVoxelsz = 0.25; Reset(); } // + + void setDefaultVoxelsz(btScalar sz) + { + m_defaultVoxelsz = sz; + } + void Reset() { for (int i = 0, ni = cells.size(); i < ni; ++i) @@ -103,7 +111,7 @@ struct btSparseSdf pc = pn; } } - voxelsz = 0.25; + voxelsz = m_defaultVoxelsz; puid = 0; ncells = 0; nprobes = 1; From 4df31305a8677828725318805b5555c56e612ab5 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Wed, 21 Aug 2019 22:31:30 -0700 Subject: [PATCH 46/56] remove iostream dependency --- src/BulletSoftBody/btSoftBody.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/BulletSoftBody/btSoftBody.cpp b/src/BulletSoftBody/btSoftBody.cpp index c8d20e35a..fcfb330c3 100644 --- a/src/BulletSoftBody/btSoftBody.cpp +++ b/src/BulletSoftBody/btSoftBody.cpp @@ -20,7 +20,6 @@ subject to the following restrictions: #include "LinearMath/btSerializer.h" #include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" #include "BulletDynamics/Featherstone/btMultiBodyConstraint.h" -#include // btSoftBody::btSoftBody(btSoftBodyWorldInfo* worldInfo, int node_count, const btVector3* x, const btScalar* m) : m_softBodySolver(0), m_worldInfo(worldInfo) From 750ff33f265ced732e08c1381866824d52c62013 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Wed, 21 Aug 2019 22:39:07 -0700 Subject: [PATCH 47/56] remove the std::istream version of vtkfileread --- src/BulletSoftBody/btSoftBodyHelpers.cpp | 16 +++++----------- src/BulletSoftBody/btSoftBodyHelpers.h | 2 +- 2 files changed, 6 insertions(+), 12 deletions(-) diff --git a/src/BulletSoftBody/btSoftBodyHelpers.cpp b/src/BulletSoftBody/btSoftBodyHelpers.cpp index 6c67a3b78..d9bd513ad 100644 --- a/src/BulletSoftBody/btSoftBodyHelpers.cpp +++ b/src/BulletSoftBody/btSoftBodyHelpers.cpp @@ -1244,13 +1244,7 @@ btSoftBody* btSoftBodyHelpers::CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, std::ifstream fs; fs.open(vtk_file); btAssert(fs); - btSoftBody* psb = CreateFromVtkFile(worldInfo, fs); - fs.close(); - return psb; -} - -btSoftBody* btSoftBodyHelpers::CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, std::istream& in) -{ + typedef btAlignedObjectArray Index; std::string line; btAlignedObjectArray X; @@ -1262,7 +1256,7 @@ btSoftBody* btSoftBodyHelpers::CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, size_t n_tets = 0; size_t x_count = 0; size_t indices_count = 0; - while (std::getline(in, line)) + while (std::getline(fs, line)) { std::stringstream ss(line); if (line.size() == (size_t)(0)) @@ -1332,7 +1326,7 @@ btSoftBody* btSoftBodyHelpers::CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, printf("Links: %u\r\n", psb->m_links.size()); printf("Faces: %u\r\n", psb->m_faces.size()); printf("Tetras: %u\r\n", psb->m_tetras.size()); - return (psb); + + fs.close(); + return psb; } - - diff --git a/src/BulletSoftBody/btSoftBodyHelpers.h b/src/BulletSoftBody/btSoftBodyHelpers.h index 24c86afdd..60e0d6133 100644 --- a/src/BulletSoftBody/btSoftBodyHelpers.h +++ b/src/BulletSoftBody/btSoftBodyHelpers.h @@ -143,7 +143,7 @@ struct btSoftBodyHelpers bool btetralinks, bool bfacesfromtetras); static btSoftBody* CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, const char* vtk_file); - static btSoftBody* CreateFromVtkFile(btSoftBodyWorldInfo& worldInfo, std::istream& in); + /// Sort the list of links to move link calculations that are dependent upon earlier From b93c3c56eda08f06ed3b28d1beeb9dd08d4b3a96 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Wed, 21 Aug 2019 22:44:10 -0700 Subject: [PATCH 48/56] delete preconditioner in destructor --- src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp | 5 +++++ src/BulletSoftBody/btDeformableBackwardEulerObjective.h | 4 +--- src/BulletSoftBody/btPreconditioner.h | 4 +++- 3 files changed, 9 insertions(+), 4 deletions(-) diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp index 1dee17be8..41b1f74c7 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.cpp @@ -24,6 +24,11 @@ btDeformableBackwardEulerObjective::btDeformableBackwardEulerObjective(btAligned m_preconditioner = new DefaultPreconditioner(); } +btDeformableBackwardEulerObjective::~btDeformableBackwardEulerObjective() +{ + delete m_preconditioner; +} + void btDeformableBackwardEulerObjective::reinitialize(bool nodeUpdated, btScalar dt) { BT_PROFILE("reinitialize"); diff --git a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h index cf8ba9920..e028564c5 100644 --- a/src/BulletSoftBody/btDeformableBackwardEulerObjective.h +++ b/src/BulletSoftBody/btDeformableBackwardEulerObjective.h @@ -26,13 +26,11 @@ #include "btDeformableMultiBodyDynamicsWorld.h" #include "LinearMath/btQuickprof.h" -//class btDeformableMultiBodyDynamicsWorld; class btDeformableBackwardEulerObjective { public: typedef btAlignedObjectArray TVStack; btScalar m_dt; -// btDeformableMultiBodyDynamicsWorld* m_world; btAlignedObjectArray m_lf; btAlignedObjectArray& m_softBodies; Preconditioner* m_preconditioner; @@ -41,7 +39,7 @@ public: btAlignedObjectArray m_nodes; btDeformableBackwardEulerObjective(btAlignedObjectArray& softBodies, const TVStack& backup_v); - virtual ~btDeformableBackwardEulerObjective() {} + virtual ~btDeformableBackwardEulerObjective(); void initialize(){} diff --git a/src/BulletSoftBody/btPreconditioner.h b/src/BulletSoftBody/btPreconditioner.h index 15ee949a5..32d697a63 100644 --- a/src/BulletSoftBody/btPreconditioner.h +++ b/src/BulletSoftBody/btPreconditioner.h @@ -22,6 +22,7 @@ public: typedef btAlignedObjectArray TVStack; virtual void operator()(const TVStack& x, TVStack& b) = 0; virtual void reinitialize(bool nodeUpdated) = 0; + virtual ~Preconditioner(){} }; class DefaultPreconditioner : public Preconditioner @@ -35,8 +36,9 @@ public: } virtual void reinitialize(bool nodeUpdated) { - } + + virtual ~DefaultPreconditioner(){} }; class MassPreconditioner : public Preconditioner From 3fbd7a7eddc0f8505858dec52e716b56bf6606ba Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Wed, 21 Aug 2019 23:00:18 -0700 Subject: [PATCH 49/56] delete forces in exitPhysics --- .../DeformableDemo/DeformableMultibody.cpp | 19 +++++++++++--- examples/DeformableDemo/DeformableRigid.cpp | 17 +++++++++--- examples/DeformableDemo/GraspDeformable.cpp | 24 ++++++++++++----- examples/DeformableDemo/Pinch.cpp | 25 +++++++++++++----- .../DeformableDemo/VolumetricDeformable.cpp | 26 ++++++++++++++----- 5 files changed, 86 insertions(+), 25 deletions(-) diff --git a/examples/DeformableDemo/DeformableMultibody.cpp b/examples/DeformableDemo/DeformableMultibody.cpp index 084ff5a04..e1a75f07a 100644 --- a/examples/DeformableDemo/DeformableMultibody.cpp +++ b/examples/DeformableDemo/DeformableMultibody.cpp @@ -49,6 +49,7 @@ static bool g_floatingBase = true; static float friction = 1.; class DeformableMultibody : public CommonMultiBodyBase { + btAlignedObjectArray forces; public: DeformableMultibody(struct GUIHelperInterface* helper) : CommonMultiBodyBase(helper) @@ -122,7 +123,6 @@ void DeformableMultibody::initPhysics() m_solver = sol; m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); -// deformableBodySolver->setWorld(getDeformableDynamicsWorld()); btVector3 gravity = btVector3(0, -10, 0); m_dynamicsWorld->setGravity(gravity); getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; @@ -224,8 +224,14 @@ void DeformableMultibody::initPhysics() psb->m_cfg.kDF = .1; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(2, 0.01, false)); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); + + btDeformableMassSpringForce* mass_spring = new btDeformableMassSpringForce(2, 0.01, false); + getDeformableDynamicsWorld()->addForce(psb, mass_spring); + forces.push_back(mass_spring); + + btDeformableGravityForce* gravity_force = new btDeformableGravityForce(gravity); + getDeformableDynamicsWorld()->addForce(psb, gravity_force); + forces.push_back(gravity_force); } m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); @@ -248,7 +254,12 @@ void DeformableMultibody::exitPhysics() m_dynamicsWorld->removeCollisionObject(obj); delete obj; } - + // delete forces + for (int j = 0; j < forces.size(); j++) + { + btDeformableLagrangianForce* force = forces[j]; + delete force; + } //delete collision shapes for (int j = 0; j < m_collisionShapes.size(); j++) { diff --git a/examples/DeformableDemo/DeformableRigid.cpp b/examples/DeformableDemo/DeformableRigid.cpp index 9b546086d..5c149ad19 100644 --- a/examples/DeformableDemo/DeformableRigid.cpp +++ b/examples/DeformableDemo/DeformableRigid.cpp @@ -44,6 +44,7 @@ ///Generally it is best to leave the rolling friction coefficient zero (or close to zero). class DeformableRigid : public CommonRigidBodyBase { + btAlignedObjectArray forces; public: DeformableRigid(struct GUIHelperInterface* helper) : CommonRigidBodyBase(helper) @@ -233,9 +234,14 @@ void DeformableRigid::initPhysics() psb->m_cfg.kDF = 1; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(2, 0.01, false)); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); + btDeformableMassSpringForce* mass_spring = new btDeformableMassSpringForce(2,0.01, false); + getDeformableDynamicsWorld()->addForce(psb, mass_spring); + forces.push_back(mass_spring); + + btDeformableGravityForce* gravity_force = new btDeformableGravityForce(gravity); + getDeformableDynamicsWorld()->addForce(psb, gravity_force); + forces.push_back(gravity_force); // add a few rigid bodies Ctor_RbUpStack(1); } @@ -259,7 +265,12 @@ void DeformableRigid::exitPhysics() m_dynamicsWorld->removeCollisionObject(obj); delete obj; } - + // delete forces + for (int j = 0; j < forces.size(); j++) + { + btDeformableLagrangianForce* force = forces[j]; + delete force; + } //delete collision shapes for (int j = 0; j < m_collisionShapes.size(); j++) { diff --git a/examples/DeformableDemo/GraspDeformable.cpp b/examples/DeformableDemo/GraspDeformable.cpp index d07c3cb01..31cc97734 100644 --- a/examples/DeformableDemo/GraspDeformable.cpp +++ b/examples/DeformableDemo/GraspDeformable.cpp @@ -59,6 +59,7 @@ static bool supportsJointMotor(btMultiBody* mb, int mbLinkIndex) class GraspDeformable : public CommonRigidBodyBase { + btAlignedObjectArray forces; public: GraspDeformable(struct GUIHelperInterface* helper) : CommonRigidBodyBase(helper) @@ -355,11 +356,17 @@ void GraspDeformable::initPhysics() // getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); // getDeformableDynamicsWorld()->addForce(psb, new btDeformableCorotatedForce(0,6)); - // linear damping - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(.5,0.04, true)); -// getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(3,0.04, true)); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableNeoHookeanForce(2,10)); + btDeformableMassSpringForce* mass_spring = new btDeformableMassSpringForce(.5,0.04, true); + getDeformableDynamicsWorld()->addForce(psb, mass_spring); + forces.push_back(mass_spring); + + btDeformableGravityForce* gravity_force = new btDeformableGravityForce(gravity); + getDeformableDynamicsWorld()->addForce(psb, gravity_force); + forces.push_back(gravity_force); + + btDeformableNeoHookeanForce* neohookean = new btDeformableNeoHookeanForce(2,10); + getDeformableDynamicsWorld()->addForce(psb, neohookean); + forces.push_back(neohookean); } // // create a piece of cloth @@ -431,7 +438,12 @@ void GraspDeformable::exitPhysics() m_dynamicsWorld->removeCollisionObject(obj); delete obj; } - + // delete forces + for (int j = 0; j < forces.size(); j++) + { + btDeformableLagrangianForce* force = forces[j]; + delete force; + } //delete collision shapes for (int j = 0; j < m_collisionShapes.size(); j++) { diff --git a/examples/DeformableDemo/Pinch.cpp b/examples/DeformableDemo/Pinch.cpp index e1c3fd348..733a60f08 100644 --- a/examples/DeformableDemo/Pinch.cpp +++ b/examples/DeformableDemo/Pinch.cpp @@ -56,6 +56,7 @@ struct TetraBunny class Pinch : public CommonRigidBodyBase { + btAlignedObjectArray forces; public: Pinch(struct GUIHelperInterface* helper) : CommonRigidBodyBase(helper) @@ -248,8 +249,6 @@ void Pinch::initPhysics() m_solver = sol; m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); -// deformableBodySolver->setWorld(getDeformableDynamicsWorld()); - // m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality btVector3 gravity = btVector3(0, -10, 0); m_dynamicsWorld->setGravity(gravity); getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; @@ -336,9 +335,18 @@ void Pinch::initPhysics() psb->m_cfg.kDF = 2; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; getDeformableDynamicsWorld()->addSoftBody(psb); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(1, 0.05)); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableNeoHookeanForce(.2,1)); + + btDeformableMassSpringForce* mass_spring = new btDeformableMassSpringForce(1,0.05); + getDeformableDynamicsWorld()->addForce(psb, mass_spring); + forces.push_back(mass_spring); + + btDeformableGravityForce* gravity_force = new btDeformableGravityForce(gravity); + getDeformableDynamicsWorld()->addForce(psb, gravity_force); + forces.push_back(gravity_force); + + btDeformableNeoHookeanForce* neohookean = new btDeformableNeoHookeanForce(.2,1); + getDeformableDynamicsWorld()->addForce(psb, neohookean); + forces.push_back(neohookean); // add a grippers createGrip(); } @@ -362,7 +370,12 @@ void Pinch::exitPhysics() m_dynamicsWorld->removeCollisionObject(obj); delete obj; } - + // delete forces + for (int j = 0; j < forces.size(); j++) + { + btDeformableLagrangianForce* force = forces[j]; + delete force; + } //delete collision shapes for (int j = 0; j < m_collisionShapes.size(); j++) { diff --git a/examples/DeformableDemo/VolumetricDeformable.cpp b/examples/DeformableDemo/VolumetricDeformable.cpp index 9796ab963..8bdafc5e9 100644 --- a/examples/DeformableDemo/VolumetricDeformable.cpp +++ b/examples/DeformableDemo/VolumetricDeformable.cpp @@ -51,6 +51,7 @@ struct TetraCube class VolumetricDeformable : public CommonRigidBodyBase { + btAlignedObjectArray forces; public: VolumetricDeformable(struct GUIHelperInterface* helper) : CommonRigidBodyBase(helper) @@ -177,13 +178,10 @@ void VolumetricDeformable::initPhysics() m_broadphase = new btDbvtBroadphase(); btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); - ///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded) btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); m_solver = sol; m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); -// deformableBodySolver->setWorld(getDeformableDynamicsWorld()); - // m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality btVector3 gravity = btVector3(0, -10, 0); m_dynamicsWorld->setGravity(gravity); getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; @@ -236,9 +234,19 @@ void VolumetricDeformable::initPhysics() psb->m_cfg.kCHR = 1; // collision hardness with rigid body psb->m_cfg.kDF = 0.5; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(0,0.03)); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableNeoHookeanForce(.5,2.5)); + + btDeformableMassSpringForce* mass_spring = new btDeformableMassSpringForce(0,0.03); + getDeformableDynamicsWorld()->addForce(psb, mass_spring); + forces.push_back(mass_spring); + + btDeformableGravityForce* gravity_force = new btDeformableGravityForce(gravity); + getDeformableDynamicsWorld()->addForce(psb, gravity_force); + forces.push_back(gravity_force); + + btDeformableNeoHookeanForce* neohookean = new btDeformableNeoHookeanForce(.5,2.5); + getDeformableDynamicsWorld()->addForce(psb, neohookean); + forces.push_back(neohookean); + } // add a few rigid bodies Ctor_RbUpStack(4); @@ -263,6 +271,12 @@ void VolumetricDeformable::exitPhysics() m_dynamicsWorld->removeCollisionObject(obj); delete obj; } + // delete forces + for (int j = 0; j < forces.size(); j++) + { + btDeformableLagrangianForce* force = forces[j]; + delete force; + } //delete collision shapes for (int j = 0; j < m_collisionShapes.size(); j++) From ccd8c3a47c4c5885ed50a0fc79573790d339f660 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Thu, 22 Aug 2019 10:12:14 -0700 Subject: [PATCH 50/56] fix scope override in btMultiBody and scalar type inconsistency in btDeformableBodySolver --- src/BulletDynamics/Featherstone/btMultiBody.cpp | 8 ++++---- src/BulletSoftBody/btDeformableBodySolver.cpp | 9 ++------- .../btDeformableMultiBodyDynamicsWorld.cpp | 1 + 3 files changed, 7 insertions(+), 11 deletions(-) diff --git a/src/BulletDynamics/Featherstone/btMultiBody.cpp b/src/BulletDynamics/Featherstone/btMultiBody.cpp index 654f77c09..bdaa47347 100644 --- a/src/BulletDynamics/Featherstone/btMultiBody.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBody.cpp @@ -1707,9 +1707,9 @@ void btMultiBody::predictPositionsMultiDof(btScalar dt) { //reset to current pos - for (int i = 0; i < 4; ++i) + for (int j = 0; j < 4; ++j) { - pJointPos[i] = m_links[i].m_jointPos[i]; + pJointPos[j] = m_links[i].m_jointPos[j]; } btVector3 jointVel; @@ -1725,9 +1725,9 @@ void btMultiBody::predictPositionsMultiDof(btScalar dt) } case btMultibodyLink::ePlanar: { - for (int i = 0; i < 3; ++i) + for (int j = 0; j < 3; ++j) { - pJointPos[i] = m_links[i].m_jointPos[i]; + pJointPos[j] = m_links[i].m_jointPos[j]; } pJointPos[0] += dt * getJointVelMultiDof(i)[0]; diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index 03a9be07e..f7a26e01e 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -30,14 +30,9 @@ btDeformableBodySolver::~btDeformableBodySolver() delete m_objective; } -void btDeformableBodySolver::solveDeformableConstraints(float solverdt) +void btDeformableBodySolver::solveDeformableConstraints(btScalar solverdt) { BT_PROFILE("solveConstraints"); - // save v_{n+1}^* velocity after explicit forces -// backupVelocity(); - - // add constraints to the solver -// setConstraints(); m_objective->computeResidual(solverdt, m_residual); m_objective->applyDynamicFriction(m_residual); computeStep(m_dv, m_residual); @@ -147,7 +142,7 @@ bool btDeformableBodySolver::updateNodes() } -void btDeformableBodySolver::predictMotion(float solverdt) +void btDeformableBodySolver::predictMotion(btScalar solverdt) { for (int i = 0; i < m_softBodySet.size(); ++i) { diff --git a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp index 825e7cd66..95f9b48b5 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp +++ b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp @@ -196,6 +196,7 @@ void btDeformableMultiBodyDynamicsWorld::solveMultiBodyConstraints() btMultiBodyDynamicsWorld::processConstraintsAndDeltaVee(); m_deformableBodySolver->solveContactConstraints(); } + // todo @xuchenhan: add joint force feedback } void btDeformableMultiBodyDynamicsWorld::addSoftBody(btSoftBody* body, int collisionFilterGroup, int collisionFilterMask) From 6beeac7065b9799f2bf7f5fb4f6127d7ca4b29f1 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Fri, 23 Aug 2019 13:41:14 -0700 Subject: [PATCH 51/56] refactor contact solve --- .../DeformableDemo/DeformableMultibody.cpp | 6 +- examples/DeformableDemo/DeformableRigid.cpp | 13 +- examples/DeformableDemo/GraspDeformable.cpp | 3 +- examples/DeformableDemo/Pinch.cpp | 3 +- .../DeformableDemo/VolumetricDeformable.cpp | 3 +- .../Featherstone/btMultiBodyDynamicsWorld.cpp | 310 +++--------------- .../Featherstone/btMultiBodyDynamicsWorld.h | 4 +- .../btMultiBodyInplaceSolverIslandCallback.h | 229 +++++++++++++ src/BulletSoftBody/CMakeLists.txt | 2 + src/BulletSoftBody/btCGProjection.h | 2 +- src/BulletSoftBody/btDeformableBodySolver.cpp | 7 +- src/BulletSoftBody/btDeformableBodySolver.h | 4 +- .../btDeformableContactProjection.cpp | 15 +- .../btDeformableContactProjection.h | 2 +- .../btDeformableMultiBodyConstraintSolver.cpp | 44 +++ .../btDeformableMultiBodyConstraintSolver.h | 98 ++++++ .../btDeformableMultiBodyDynamicsWorld.cpp | 145 +++++++- .../btDeformableMultiBodyDynamicsWorld.h | 16 +- 18 files changed, 597 insertions(+), 309 deletions(-) create mode 100644 src/BulletDynamics/Featherstone/btMultiBodyInplaceSolverIslandCallback.h create mode 100644 src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp create mode 100644 src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.h diff --git a/examples/DeformableDemo/DeformableMultibody.cpp b/examples/DeformableDemo/DeformableMultibody.cpp index e1a75f07a..6a99e08db 100644 --- a/examples/DeformableDemo/DeformableMultibody.cpp +++ b/examples/DeformableDemo/DeformableMultibody.cpp @@ -118,8 +118,9 @@ void DeformableMultibody::initPhysics() m_broadphase = new btDbvtBroadphase(); btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); - btMultiBodyConstraintSolver* sol; - sol = new btMultiBodyConstraintSolver; + btDeformableMultiBodyConstraintSolver* sol; + sol = new btDeformableMultiBodyConstraintSolver; + sol->setDeformableSolver(deformableBodySolver); m_solver = sol; m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); @@ -223,6 +224,7 @@ void DeformableMultibody::initPhysics() psb->m_cfg.kCHR = 1; // collision hardness with rigid body psb->m_cfg.kDF = .1; psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + psb->setCollisionFlags(0); getDeformableDynamicsWorld()->addSoftBody(psb); btDeformableMassSpringForce* mass_spring = new btDeformableMassSpringForce(2, 0.01, false); diff --git a/examples/DeformableDemo/DeformableRigid.cpp b/examples/DeformableDemo/DeformableRigid.cpp index 5c149ad19..576803cc8 100644 --- a/examples/DeformableDemo/DeformableRigid.cpp +++ b/examples/DeformableDemo/DeformableRigid.cpp @@ -161,7 +161,8 @@ void DeformableRigid::initPhysics() btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); ///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded) - btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(deformableBodySolver); m_solver = sol; m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); @@ -208,10 +209,12 @@ void DeformableRigid::initPhysics() { bool onGround = false; const btScalar s = 4; - btSoftBody* psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, 0, -s), - btVector3(+s, 0, -s), - btVector3(-s, 0, +s), - btVector3(+s, 0, +s), + const btScalar h = 0; + + btSoftBody* psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, h, -s), + btVector3(+s, h, -s), + btVector3(-s, h, +s), + btVector3(+s, h, +s), // 3,3, 20,20, 1 + 2 + 4 + 8, true); diff --git a/examples/DeformableDemo/GraspDeformable.cpp b/examples/DeformableDemo/GraspDeformable.cpp index 31cc97734..6b01bc66d 100644 --- a/examples/DeformableDemo/GraspDeformable.cpp +++ b/examples/DeformableDemo/GraspDeformable.cpp @@ -187,7 +187,8 @@ void GraspDeformable::initPhysics() m_broadphase = new btDbvtBroadphase(); btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); - btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(deformableBodySolver); m_solver = sol; m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); diff --git a/examples/DeformableDemo/Pinch.cpp b/examples/DeformableDemo/Pinch.cpp index 733a60f08..3685869a0 100644 --- a/examples/DeformableDemo/Pinch.cpp +++ b/examples/DeformableDemo/Pinch.cpp @@ -245,7 +245,8 @@ void Pinch::initPhysics() m_broadphase = new btDbvtBroadphase(); btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); - btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(deformableBodySolver); m_solver = sol; m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); diff --git a/examples/DeformableDemo/VolumetricDeformable.cpp b/examples/DeformableDemo/VolumetricDeformable.cpp index 8bdafc5e9..b6657de0c 100644 --- a/examples/DeformableDemo/VolumetricDeformable.cpp +++ b/examples/DeformableDemo/VolumetricDeformable.cpp @@ -178,7 +178,8 @@ void VolumetricDeformable::initPhysics() m_broadphase = new btDbvtBroadphase(); btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); - btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); + btDeformableMultiBodyConstraintSolver* sol = new btDeformableMultiBodyConstraintSolver(); + sol->setDeformableSolver(deformableBodySolver); m_solver = sol; m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp index 950edb1a2..cd1bad089 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp @@ -169,218 +169,6 @@ void btMultiBodyDynamicsWorld::updateActivationState(btScalar timeStep) btDiscreteDynamicsWorld::updateActivationState(timeStep); } -SIMD_FORCE_INLINE int btGetConstraintIslandId2(const btTypedConstraint* lhs) -{ - int islandId; - - const btCollisionObject& rcolObj0 = lhs->getRigidBodyA(); - const btCollisionObject& rcolObj1 = lhs->getRigidBodyB(); - islandId = rcolObj0.getIslandTag() >= 0 ? rcolObj0.getIslandTag() : rcolObj1.getIslandTag(); - return islandId; -} - -class btSortConstraintOnIslandPredicate2 -{ -public: - bool operator()(const btTypedConstraint* lhs, const btTypedConstraint* rhs) const - { - int rIslandId0, lIslandId0; - rIslandId0 = btGetConstraintIslandId2(rhs); - lIslandId0 = btGetConstraintIslandId2(lhs); - return lIslandId0 < rIslandId0; - } -}; - -SIMD_FORCE_INLINE int btGetMultiBodyConstraintIslandId(const btMultiBodyConstraint* lhs) -{ - int islandId; - - int islandTagA = lhs->getIslandIdA(); - int islandTagB = lhs->getIslandIdB(); - islandId = islandTagA >= 0 ? islandTagA : islandTagB; - return islandId; -} - -class btSortMultiBodyConstraintOnIslandPredicate -{ -public: - bool operator()(const btMultiBodyConstraint* lhs, const btMultiBodyConstraint* rhs) const - { - int rIslandId0, lIslandId0; - rIslandId0 = btGetMultiBodyConstraintIslandId(rhs); - lIslandId0 = btGetMultiBodyConstraintIslandId(lhs); - return lIslandId0 < rIslandId0; - } -}; - - -struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager::IslandCallback -{ - btContactSolverInfo* m_solverInfo; - btMultiBodyConstraintSolver* m_solver; - btMultiBodyConstraint** m_multiBodySortedConstraints; - int m_numMultiBodyConstraints; - - btTypedConstraint** m_sortedConstraints; - int m_numConstraints; - btIDebugDraw* m_debugDrawer; - btDispatcher* m_dispatcher; - - btAlignedObjectArray m_bodies; - btAlignedObjectArray m_manifolds; - btAlignedObjectArray m_constraints; - btAlignedObjectArray m_multiBodyConstraints; - - btAlignedObjectArray m_islandAnalyticsData; - - MultiBodyInplaceSolverIslandCallback(btMultiBodyConstraintSolver* solver, - btDispatcher* dispatcher) - : m_solverInfo(NULL), - m_solver(solver), - m_multiBodySortedConstraints(NULL), - m_numConstraints(0), - m_debugDrawer(NULL), - m_dispatcher(dispatcher) - { - } - - MultiBodyInplaceSolverIslandCallback& operator=(const MultiBodyInplaceSolverIslandCallback& other) - { - btAssert(0); - (void)other; - return *this; - } - - SIMD_FORCE_INLINE void setup(btContactSolverInfo* solverInfo, btTypedConstraint** sortedConstraints, int numConstraints, btMultiBodyConstraint** sortedMultiBodyConstraints, int numMultiBodyConstraints, btIDebugDraw* debugDrawer) - { - m_islandAnalyticsData.clear(); - btAssert(solverInfo); - m_solverInfo = solverInfo; - - m_multiBodySortedConstraints = sortedMultiBodyConstraints; - m_numMultiBodyConstraints = numMultiBodyConstraints; - m_sortedConstraints = sortedConstraints; - m_numConstraints = numConstraints; - - m_debugDrawer = debugDrawer; - m_bodies.resize(0); - m_manifolds.resize(0); - m_constraints.resize(0); - m_multiBodyConstraints.resize(0); - } - - void setMultiBodyConstraintSolver(btMultiBodyConstraintSolver* solver) - { - m_solver = solver; - } - - virtual void processIsland(btCollisionObject** bodies, int numBodies, btPersistentManifold** manifolds, int numManifolds, int islandId) - { - if (islandId < 0) - { - ///we don't split islands, so all constraints/contact manifolds/bodies are passed into the solver regardless the island id - m_solver->solveMultiBodyGroup(bodies, numBodies, manifolds, numManifolds, m_sortedConstraints, m_numConstraints, &m_multiBodySortedConstraints[0], m_numConstraints, *m_solverInfo, m_debugDrawer, m_dispatcher); - if (m_solverInfo->m_reportSolverAnalytics&1) - { - m_solver->m_analyticsData.m_islandId = islandId; - m_islandAnalyticsData.push_back(m_solver->m_analyticsData); - } - } - else - { - //also add all non-contact constraints/joints for this island - btTypedConstraint** startConstraint = 0; - btMultiBodyConstraint** startMultiBodyConstraint = 0; - - int numCurConstraints = 0; - int numCurMultiBodyConstraints = 0; - - int i; - - //find the first constraint for this island - - for (i = 0; i < m_numConstraints; i++) - { - if (btGetConstraintIslandId2(m_sortedConstraints[i]) == islandId) - { - startConstraint = &m_sortedConstraints[i]; - break; - } - } - //count the number of constraints in this island - for (; i < m_numConstraints; i++) - { - if (btGetConstraintIslandId2(m_sortedConstraints[i]) == islandId) - { - numCurConstraints++; - } - } - - for (i = 0; i < m_numMultiBodyConstraints; i++) - { - if (btGetMultiBodyConstraintIslandId(m_multiBodySortedConstraints[i]) == islandId) - { - startMultiBodyConstraint = &m_multiBodySortedConstraints[i]; - break; - } - } - //count the number of multi body constraints in this island - for (; i < m_numMultiBodyConstraints; i++) - { - if (btGetMultiBodyConstraintIslandId(m_multiBodySortedConstraints[i]) == islandId) - { - numCurMultiBodyConstraints++; - } - } - - //if (m_solverInfo->m_minimumSolverBatchSize<=1) - //{ - // m_solver->solveGroup( bodies,numBodies,manifolds, numManifolds,startConstraint,numCurConstraints,*m_solverInfo,m_debugDrawer,m_dispatcher); - //} else - { - for (i = 0; i < numBodies; i++) - m_bodies.push_back(bodies[i]); - for (i = 0; i < numManifolds; i++) - m_manifolds.push_back(manifolds[i]); - for (i = 0; i < numCurConstraints; i++) - m_constraints.push_back(startConstraint[i]); - - for (i = 0; i < numCurMultiBodyConstraints; i++) - m_multiBodyConstraints.push_back(startMultiBodyConstraint[i]); - - if ((m_multiBodyConstraints.size() + m_constraints.size() + m_manifolds.size()) > m_solverInfo->m_minimumSolverBatchSize) - { - processConstraints(islandId); - } - else - { - //printf("deferred\n"); - } - } - } - } - void processConstraints(int islandId=-1) - { - btCollisionObject** bodies = m_bodies.size() ? &m_bodies[0] : 0; - btPersistentManifold** manifold = m_manifolds.size() ? &m_manifolds[0] : 0; - btTypedConstraint** constraints = m_constraints.size() ? &m_constraints[0] : 0; - btMultiBodyConstraint** multiBodyConstraints = m_multiBodyConstraints.size() ? &m_multiBodyConstraints[0] : 0; - - //printf("mb contacts = %d, mb constraints = %d\n", mbContacts, m_multiBodyConstraints.size()); - - m_solver->solveMultiBodyGroup(bodies, m_bodies.size(), manifold, m_manifolds.size(), constraints, m_constraints.size(), multiBodyConstraints, m_multiBodyConstraints.size(), *m_solverInfo, m_debugDrawer, m_dispatcher); - if (m_bodies.size() && (m_solverInfo->m_reportSolverAnalytics&1)) - { - m_solver->m_analyticsData.m_islandId = islandId; - m_islandAnalyticsData.push_back(m_solver->m_analyticsData); - } - m_bodies.resize(0); - m_manifolds.resize(0); - m_constraints.resize(0); - m_multiBodyConstraints.resize(0); - } -}; - void btMultiBodyDynamicsWorld::getAnalyticsData(btAlignedObjectArray& islandAnalyticsData) const { islandAnalyticsData = m_solverMultiBodyIslandCallback->m_islandAnalyticsData; @@ -442,18 +230,47 @@ void btMultiBodyDynamicsWorld::solveInternalConstraints(btContactSolverInfo& sol /// solve all the constraints for this island m_solverMultiBodyIslandCallback->processConstraints(); m_constraintSolver->allSolved(solverInfo, m_debugDrawer); - calculateJointForce(solverInfo); - processDeltaVee(); -} - -void btMultiBodyDynamicsWorld::btMultiBodyDynamicsWorld::processConstraintsAndDeltaVee() -{ - m_solverMultiBodyIslandCallback->processConstraints(); - processDeltaVee(); -} - -void btMultiBodyDynamicsWorld::processDeltaVee() -{ + { + BT_PROFILE("btMultiBody stepVelocities"); + for (int i = 0; i < this->m_multiBodies.size(); i++) + { + btMultiBody* bod = m_multiBodies[i]; + + bool isSleeping = false; + + if (bod->getBaseCollider() && bod->getBaseCollider()->getActivationState() == ISLAND_SLEEPING) + { + isSleeping = true; + } + for (int b = 0; b < bod->getNumLinks(); b++) + { + if (bod->getLink(b).m_collider && bod->getLink(b).m_collider->getActivationState() == ISLAND_SLEEPING) + isSleeping = true; + } + + if (!isSleeping) + { + //useless? they get resized in stepVelocities once again (AND DIFFERENTLY) + m_scratch_r.resize(bod->getNumLinks() + 1); //multidof? ("Y"s use it and it is used to store qdd) + m_scratch_v.resize(bod->getNumLinks() + 1); + m_scratch_m.resize(bod->getNumLinks() + 1); + + if (bod->internalNeedsJointFeedback()) + { + if (!bod->isUsingRK4Integration()) + { + if (bod->internalNeedsJointFeedback()) + { + bool isConstraintPass = true; + bod->computeAccelerationsArticulatedBodyAlgorithmMultiDof(solverInfo.m_timeStep, m_scratch_r, m_scratch_v, m_scratch_m, isConstraintPass, + getSolverInfo().m_jointFeedbackInWorldSpace, + getSolverInfo().m_jointFeedbackInJointFrame); + } + } + } + } + } + } for (int i = 0; i < this->m_multiBodies.size(); i++) { btMultiBody* bod = m_multiBodies[i]; @@ -461,51 +278,6 @@ void btMultiBodyDynamicsWorld::processDeltaVee() } } -void btMultiBodyDynamicsWorld::calculateJointForce(btContactSolverInfo& solverInfo) -{ - { - BT_PROFILE("btMultiBody stepVelocities"); - for (int i = 0; i < this->m_multiBodies.size(); i++) - { - btMultiBody* bod = m_multiBodies[i]; - - bool isSleeping = false; - - if (bod->getBaseCollider() && bod->getBaseCollider()->getActivationState() == ISLAND_SLEEPING) - { - isSleeping = true; - } - for (int b = 0; b < bod->getNumLinks(); b++) - { - if (bod->getLink(b).m_collider && bod->getLink(b).m_collider->getActivationState() == ISLAND_SLEEPING) - isSleeping = true; - } - - if (!isSleeping) - { - //useless? they get resized in stepVelocities once again (AND DIFFERENTLY) - m_scratch_r.resize(bod->getNumLinks() + 1); //multidof? ("Y"s use it and it is used to store qdd) - m_scratch_v.resize(bod->getNumLinks() + 1); - m_scratch_m.resize(bod->getNumLinks() + 1); - - if (bod->internalNeedsJointFeedback()) - { - if (!bod->isUsingRK4Integration()) - { - if (bod->internalNeedsJointFeedback()) - { - bool isConstraintPass = true; - bod->computeAccelerationsArticulatedBodyAlgorithmMultiDof(solverInfo.m_timeStep, m_scratch_r, m_scratch_v, m_scratch_m, isConstraintPass, - getSolverInfo().m_jointFeedbackInWorldSpace, - getSolverInfo().m_jointFeedbackInJointFrame); - } - } - } - } - } - } -} - void btMultiBodyDynamicsWorld::solveExternalForces(btContactSolverInfo& solverInfo) { forwardKinematics(); diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h index a03687859..9ac46f4b6 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h @@ -17,6 +17,7 @@ subject to the following restrictions: #define BT_MULTIBODY_DYNAMICS_WORLD_H #include "BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h" +#include "BulletDynamics/Featherstone/btMultiBodyInplaceSolverIslandCallback.h" #define BT_USE_VIRTUAL_CLEARFORCES_AND_GRAVITY @@ -119,8 +120,5 @@ public: virtual void solveExternalForces(btContactSolverInfo& solverInfo); virtual void solveInternalConstraints(btContactSolverInfo& solverInfo); void buildIslands(); - void calculateJointForce(btContactSolverInfo& solverInfo); - void processDeltaVee(); - void processConstraintsAndDeltaVee(); }; #endif //BT_MULTIBODY_DYNAMICS_WORLD_H diff --git a/src/BulletDynamics/Featherstone/btMultiBodyInplaceSolverIslandCallback.h b/src/BulletDynamics/Featherstone/btMultiBodyInplaceSolverIslandCallback.h new file mode 100644 index 000000000..accf7c50b --- /dev/null +++ b/src/BulletDynamics/Featherstone/btMultiBodyInplaceSolverIslandCallback.h @@ -0,0 +1,229 @@ +// +// btMultiBodyInplaceSolverCallback.h +// BulletDynamics +// +// Created by Xuchen Han on 8/22/19. +// + +#ifndef BT_MULTIBODY_INPLACE_SOLVER_ISLAND_CALLBACK_H +#define BT_MULTIBODY_INPLACE_SOLVER_ISLAND_CALLBACK_H + +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include "BulletCollision/CollisionDispatch/btSimulationIslandManager.h" +#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h" +#include "btMultiBodyConstraintSolver.h" + +SIMD_FORCE_INLINE int btGetConstraintIslandId2(const btTypedConstraint* lhs) +{ + int islandId; + + const btCollisionObject& rcolObj0 = lhs->getRigidBodyA(); + const btCollisionObject& rcolObj1 = lhs->getRigidBodyB(); + islandId = rcolObj0.getIslandTag() >= 0 ? rcolObj0.getIslandTag() : rcolObj1.getIslandTag(); + return islandId; +} +class btSortConstraintOnIslandPredicate2 +{ +public: + bool operator()(const btTypedConstraint* lhs, const btTypedConstraint* rhs) const + { + int rIslandId0, lIslandId0; + rIslandId0 = btGetConstraintIslandId2(rhs); + lIslandId0 = btGetConstraintIslandId2(lhs); + return lIslandId0 < rIslandId0; + } +}; + +SIMD_FORCE_INLINE int btGetMultiBodyConstraintIslandId(const btMultiBodyConstraint* lhs) +{ + int islandId; + + int islandTagA = lhs->getIslandIdA(); + int islandTagB = lhs->getIslandIdB(); + islandId = islandTagA >= 0 ? islandTagA : islandTagB; + return islandId; +} + +class btSortMultiBodyConstraintOnIslandPredicate +{ +public: + bool operator()(const btMultiBodyConstraint* lhs, const btMultiBodyConstraint* rhs) const + { + int rIslandId0, lIslandId0; + rIslandId0 = btGetMultiBodyConstraintIslandId(rhs); + lIslandId0 = btGetMultiBodyConstraintIslandId(lhs); + return lIslandId0 < rIslandId0; + } +}; + +struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager::IslandCallback +{ + + btContactSolverInfo* m_solverInfo; + btMultiBodyConstraintSolver* m_solver; + btMultiBodyConstraint** m_multiBodySortedConstraints; + int m_numMultiBodyConstraints; + + btTypedConstraint** m_sortedConstraints; + int m_numConstraints; + btIDebugDraw* m_debugDrawer; + btDispatcher* m_dispatcher; + + btAlignedObjectArray m_bodies; + btAlignedObjectArray m_manifolds; + btAlignedObjectArray m_constraints; + btAlignedObjectArray m_multiBodyConstraints; + + btAlignedObjectArray m_islandAnalyticsData; + + MultiBodyInplaceSolverIslandCallback(btMultiBodyConstraintSolver* solver, + btDispatcher* dispatcher) + : m_solverInfo(NULL), + m_solver(solver), + m_multiBodySortedConstraints(NULL), + m_numConstraints(0), + m_debugDrawer(NULL), + m_dispatcher(dispatcher) + { + } + + MultiBodyInplaceSolverIslandCallback& operator=(const MultiBodyInplaceSolverIslandCallback& other) + { + btAssert(0); + (void)other; + return *this; + } + + SIMD_FORCE_INLINE virtual void setup(btContactSolverInfo* solverInfo, btTypedConstraint** sortedConstraints, int numConstraints, btMultiBodyConstraint** sortedMultiBodyConstraints, int numMultiBodyConstraints, btIDebugDraw* debugDrawer) + { + m_islandAnalyticsData.clear(); + btAssert(solverInfo); + m_solverInfo = solverInfo; + + m_multiBodySortedConstraints = sortedMultiBodyConstraints; + m_numMultiBodyConstraints = numMultiBodyConstraints; + m_sortedConstraints = sortedConstraints; + m_numConstraints = numConstraints; + + m_debugDrawer = debugDrawer; + m_bodies.resize(0); + m_manifolds.resize(0); + m_constraints.resize(0); + m_multiBodyConstraints.resize(0); + } + + void setMultiBodyConstraintSolver(btMultiBodyConstraintSolver* solver) + { + m_solver = solver; + } + + virtual void processIsland(btCollisionObject** bodies, int numBodies, btPersistentManifold** manifolds, int numManifolds, int islandId) + { + if (islandId < 0) + { + ///we don't split islands, so all constraints/contact manifolds/bodies are passed into the solver regardless the island id + m_solver->solveMultiBodyGroup(bodies, numBodies, manifolds, numManifolds, m_sortedConstraints, m_numConstraints, &m_multiBodySortedConstraints[0], m_numConstraints, *m_solverInfo, m_debugDrawer, m_dispatcher); + if (m_solverInfo->m_reportSolverAnalytics&1) + { + m_solver->m_analyticsData.m_islandId = islandId; + m_islandAnalyticsData.push_back(m_solver->m_analyticsData); + } + } + else + { + //also add all non-contact constraints/joints for this island + btTypedConstraint** startConstraint = 0; + btMultiBodyConstraint** startMultiBodyConstraint = 0; + + int numCurConstraints = 0; + int numCurMultiBodyConstraints = 0; + + int i; + + //find the first constraint for this island + + for (i = 0; i < m_numConstraints; i++) + { + if (btGetConstraintIslandId2(m_sortedConstraints[i]) == islandId) + { + startConstraint = &m_sortedConstraints[i]; + break; + } + } + //count the number of constraints in this island + for (; i < m_numConstraints; i++) + { + if (btGetConstraintIslandId2(m_sortedConstraints[i]) == islandId) + { + numCurConstraints++; + } + } + + for (i = 0; i < m_numMultiBodyConstraints; i++) + { + if (btGetMultiBodyConstraintIslandId(m_multiBodySortedConstraints[i]) == islandId) + { + startMultiBodyConstraint = &m_multiBodySortedConstraints[i]; + break; + } + } + //count the number of multi body constraints in this island + for (; i < m_numMultiBodyConstraints; i++) + { + if (btGetMultiBodyConstraintIslandId(m_multiBodySortedConstraints[i]) == islandId) + { + numCurMultiBodyConstraints++; + } + } + + //if (m_solverInfo->m_minimumSolverBatchSize<=1) + //{ + // m_solver->solveGroup( bodies,numBodies,manifolds, numManifolds,startConstraint,numCurConstraints,*m_solverInfo,m_debugDrawer,m_dispatcher); + //} else + { + for (i = 0; i < numBodies; i++) + m_bodies.push_back(bodies[i]); + for (i = 0; i < numManifolds; i++) + m_manifolds.push_back(manifolds[i]); + for (i = 0; i < numCurConstraints; i++) + m_constraints.push_back(startConstraint[i]); + + for (i = 0; i < numCurMultiBodyConstraints; i++) + m_multiBodyConstraints.push_back(startMultiBodyConstraint[i]); + + if ((m_multiBodyConstraints.size() + m_constraints.size() + m_manifolds.size()) > m_solverInfo->m_minimumSolverBatchSize) + { + processConstraints(islandId); + } + else + { + //printf("deferred\n"); + } + } + } + } + + virtual void processConstraints(int islandId=-1) + { + btCollisionObject** bodies = m_bodies.size() ? &m_bodies[0] : 0; + btPersistentManifold** manifold = m_manifolds.size() ? &m_manifolds[0] : 0; + btTypedConstraint** constraints = m_constraints.size() ? &m_constraints[0] : 0; + btMultiBodyConstraint** multiBodyConstraints = m_multiBodyConstraints.size() ? &m_multiBodyConstraints[0] : 0; + + //printf("mb contacts = %d, mb constraints = %d\n", mbContacts, m_multiBodyConstraints.size()); + + m_solver->solveMultiBodyGroup(bodies, m_bodies.size(), manifold, m_manifolds.size(), constraints, m_constraints.size(), multiBodyConstraints, m_multiBodyConstraints.size(), *m_solverInfo, m_debugDrawer, m_dispatcher); + if (m_bodies.size() && (m_solverInfo->m_reportSolverAnalytics&1)) + { + m_solver->m_analyticsData.m_islandId = islandId; + m_islandAnalyticsData.push_back(m_solver->m_analyticsData); + } + m_bodies.resize(0); + m_manifolds.resize(0); + m_constraints.resize(0); + m_multiBodyConstraints.resize(0); + } +}; + + +#endif /*BT_MULTIBODY_INPLACE_SOLVER_ISLAND_CALLBACK_H */ diff --git a/src/BulletSoftBody/CMakeLists.txt b/src/BulletSoftBody/CMakeLists.txt index 40d07bd66..1e9edbd91 100644 --- a/src/BulletSoftBody/CMakeLists.txt +++ b/src/BulletSoftBody/CMakeLists.txt @@ -16,6 +16,7 @@ SET(BulletSoftBody_SRCS btSoftMultiBodyDynamicsWorld.cpp btSoftSoftCollisionAlgorithm.cpp btDefaultSoftBodySolver.cpp + btDeformableMultiBodyConstraintSolver.cpp btDeformableBackwardEulerObjective.cpp btDeformableBodySolver.cpp @@ -50,6 +51,7 @@ SET(BulletSoftBody_HDRS btDeformableBackwardEulerObjective.h btDeformableBodySolver.h + btDeformableMultiBodyConstraintSolver.h btDeformableContactProjection.h btDeformableMultiBodyDynamicsWorld.h diff --git a/src/BulletSoftBody/btCGProjection.h b/src/BulletSoftBody/btCGProjection.h index c5a1bb55b..d074ca6ed 100644 --- a/src/BulletSoftBody/btCGProjection.h +++ b/src/BulletSoftBody/btCGProjection.h @@ -80,7 +80,7 @@ public: virtual void setConstraints() = 0; // update the constraints - virtual void update() = 0; + virtual btScalar update() = 0; virtual void reinitialize(bool nodeUpdated) { diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index f7a26e01e..0e26e2c6d 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -74,12 +74,13 @@ void btDeformableBodySolver::setConstraints() m_objective->setConstraints(); } -void btDeformableBodySolver::solveContactConstraints() +btScalar btDeformableBodySolver::solveContactConstraints() { BT_PROFILE("setConstraint"); - m_objective->projection.update(); + btScalar maxSquaredResidual = m_objective->projection.update(); m_objective->enforceConstraint(m_dv); m_objective->updateVelocity(m_dv); + return maxSquaredResidual; } @@ -142,7 +143,7 @@ bool btDeformableBodySolver::updateNodes() } -void btDeformableBodySolver::predictMotion(btScalar solverdt) +void btDeformableBodySolver::predictMotion(float solverdt) { for (int i = 0; i < m_softBodySet.size(); ++i) { diff --git a/src/BulletSoftBody/btDeformableBodySolver.h b/src/BulletSoftBody/btDeformableBodySolver.h index 55f940328..9839df7f2 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.h +++ b/src/BulletSoftBody/btDeformableBodySolver.h @@ -63,7 +63,7 @@ public: virtual void solveDeformableConstraints(btScalar solverdt); - void solveContactConstraints(); + btScalar solveContactConstraints(); virtual void solveConstraints(float dt){} @@ -81,7 +81,7 @@ public: void computeStep(TVStack& dv, const TVStack& residual); - virtual void predictMotion(btScalar solverdt); + virtual void predictMotion(float solverdt); virtual void copySoftBodyToVertexBuffer(const btSoftBody *const softBody, btVertexBufferDescriptor *vertexBuffer) {} diff --git a/src/BulletSoftBody/btDeformableContactProjection.cpp b/src/BulletSoftBody/btDeformableContactProjection.cpp index f9d4b7d99..25c14b5b9 100644 --- a/src/BulletSoftBody/btDeformableContactProjection.cpp +++ b/src/BulletSoftBody/btDeformableContactProjection.cpp @@ -17,10 +17,9 @@ #include "btDeformableMultiBodyDynamicsWorld.h" #include #include -void btDeformableContactProjection::update() +btScalar btDeformableContactProjection::update() { -// m_world->getSolverInfo().m_numIterations = 1; - + btScalar residualSquare = 0; // loop through constraints to set constrained values for (int index = 0; index < m_constraints.size(); ++index) { @@ -129,21 +128,28 @@ void btDeformableContactProjection::update() } } impulse = impulse_normal + impulse_tangent; + + // dn is the normal component of velocity diffrerence. Approximates the residual. + residualSquare = btMax(residualSquare, dn*dn); + if (cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY) { if (rigidCol) + { rigidCol->applyImpulse(impulse, c->m_c1); + } } else if (cti.m_colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK) { if (multibodyLinkCol) { + multibodyLinkCol->m_multiBody->processDeltaVeeMultiDof2(); // make sure velocity is up-to-date; // apply normal component of the impulse multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof(deltaV_normal, impulse.dot(cti.m_normal)); if (impulse_tangent.norm() > SIMD_EPSILON) { // apply tangential component of the impulse - const btScalar* deltaV_t1 = &c->jacobianData_t1.m_deltaVelocitiesUnitImpulse[0]; + const btScalar* deltaV_t1 = &c->jacobianData_t1.m_deltaVelocitiesUnitImpulse[0]; multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof(deltaV_t1, impulse.dot(c->t1)); const btScalar* deltaV_t2 = &c->jacobianData_t2.m_deltaVelocitiesUnitImpulse[0]; multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof(deltaV_t2, impulse.dot(c->t2)); @@ -153,6 +159,7 @@ void btDeformableContactProjection::update() } } } + return residualSquare; } void btDeformableContactProjection::setConstraints() diff --git a/src/BulletSoftBody/btDeformableContactProjection.h b/src/BulletSoftBody/btDeformableContactProjection.h index f9bd371d7..774da1ae3 100644 --- a/src/BulletSoftBody/btDeformableContactProjection.h +++ b/src/BulletSoftBody/btDeformableContactProjection.h @@ -44,7 +44,7 @@ public: virtual void enforceConstraint(TVStack& x); // update the constraints - virtual void update(); + virtual btScalar update(); virtual void setConstraints(); diff --git a/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp b/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp new file mode 100644 index 000000000..a331d1ba2 --- /dev/null +++ b/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp @@ -0,0 +1,44 @@ +// +// btDeformableMultiBodyConstraintSolver.cpp +// BulletSoftBody +// +// Created by Xuchen Han on 8/23/19. +// + +#include "btDeformableMultiBodyConstraintSolver.h" +#include +// override the iterations method to include deformable/multibody contact +btScalar btDeformableMultiBodyConstraintSolver::solveGroupCacheFriendlyIterations(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer) +{ + { + ///this is a special step to resolve penetrations (just for contacts) + solveGroupCacheFriendlySplitImpulseIterations(bodies, numBodies, manifoldPtr, numManifolds, constraints, numConstraints, infoGlobal, debugDrawer); + + int maxIterations = m_maxOverrideNumSolverIterations > infoGlobal.m_numIterations ? m_maxOverrideNumSolverIterations : infoGlobal.m_numIterations; + for (int iteration = 0; iteration < maxIterations; iteration++) + { + m_leastSquaresResidual = solveSingleIteration(iteration, bodies, numBodies, manifoldPtr, numManifolds, constraints, numConstraints, infoGlobal, debugDrawer); + + solverBodyWriteBack(infoGlobal); + m_leastSquaresResidual = btMax(m_leastSquaresResidual, m_deformableSolver->solveContactConstraints()); + writeToSolverBody(bodies, numBodies, infoGlobal); + + if (m_leastSquaresResidual <= infoGlobal.m_leastSquaresResidualThreshold || (iteration >= (maxIterations - 1))) + { +#ifdef VERBOSE_RESIDUAL_PRINTF + printf("residual = %f at iteration #%d\n", m_leastSquaresResidual, iteration); +#endif + m_analyticsData.m_numSolverCalls++; + m_analyticsData.m_numIterationsUsed = iteration+1; + m_analyticsData.m_islandId = -2; + if (numBodies>0) + m_analyticsData.m_islandId = bodies[0]->getCompanionId(); + m_analyticsData.m_numBodies = numBodies; + m_analyticsData.m_numContactManifolds = numManifolds; + m_analyticsData.m_remainingLeastSquaresResidual = m_leastSquaresResidual; + break; + } + } + } + return 0.f; +} diff --git a/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.h b/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.h new file mode 100644 index 000000000..c5c37cefc --- /dev/null +++ b/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.h @@ -0,0 +1,98 @@ +// +// btDeformableMultiBodyConstraintSolver.h +// BulletSoftBody +// +// Created by Xuchen Han on 8/22/19. +// + +#ifndef BT_DEFORMABLE_MULTIBODY_CONSTRAINT_SOLVER_H +#define BT_DEFORMABLE_MULTIBODY_CONSTRAINT_SOLVER_H + +#include "btDeformableBodySolver.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" + +class btDeformableBodySolver; + +ATTRIBUTE_ALIGNED16(class) +btDeformableMultiBodyConstraintSolver : public btMultiBodyConstraintSolver +{ + btDeformableBodySolver* m_deformableSolver; + +protected: + // override the iterations method to include deformable/multibody contact + virtual btScalar solveGroupCacheFriendlyIterations(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer); + + void solverBodyWriteBack(const btContactSolverInfo& infoGlobal) + { + for (int i = 0; i < m_tmpSolverBodyPool.size(); i++) + { + btRigidBody* body = m_tmpSolverBodyPool[i].m_originalBody; + if (body) + { + m_tmpSolverBodyPool[i].m_originalBody->setLinearVelocity(m_tmpSolverBodyPool[i].m_linearVelocity + m_tmpSolverBodyPool[i].m_deltaLinearVelocity); + m_tmpSolverBodyPool[i].m_originalBody->setAngularVelocity(m_tmpSolverBodyPool[i].m_angularVelocity+m_tmpSolverBodyPool[i].m_deltaAngularVelocity); + } + } + } + + void writeToSolverBody(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal) + { + btSISolverSingleIterationData siData(m_tmpSolverBodyPool, + m_tmpSolverContactConstraintPool, + m_tmpSolverNonContactConstraintPool, + m_tmpSolverContactFrictionConstraintPool, + m_tmpSolverContactRollingFrictionConstraintPool, + m_orderTmpConstraintPool, + m_orderNonContactConstraintPool, + m_orderFrictionConstraintPool, + m_tmpConstraintSizesPool, + m_resolveSingleConstraintRowGeneric, + m_resolveSingleConstraintRowLowerLimit, + m_resolveSplitPenetrationImpulse, + m_kinematicBodyUniqueIdToSolverBodyTable, + m_btSeed2, + m_fixedBodyId, + m_maxOverrideNumSolverIterations); + + for (int i = 0; i < numBodies; i++) + { + int bodyId = siData.getOrInitSolverBody(*bodies[i], infoGlobal.m_timeStep); + + btRigidBody* body = btRigidBody::upcast(bodies[i]); + if (body && body->getInvMass()) + { + btSolverBody& solverBody = siData.m_tmpSolverBodyPool[bodyId]; + solverBody.m_linearVelocity = body->getLinearVelocity() - solverBody.m_deltaLinearVelocity; + solverBody.m_angularVelocity = body->getAngularVelocity() - solverBody.m_deltaAngularVelocity; + } + } + } + +public: + BT_DECLARE_ALIGNED_ALLOCATOR(); + + void setDeformableSolver(btDeformableBodySolver* deformableSolver) + { + m_deformableSolver = deformableSolver; + } + + virtual void solveMultiBodyGroup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, btMultiBodyConstraint** multiBodyConstraints, int numMultiBodyConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher) + { + m_tmpMultiBodyConstraints = multiBodyConstraints; + m_tmpNumMultiBodyConstraints = numMultiBodyConstraints; + + // inherited from MultiBodyConstraintSolver + solveGroupCacheFriendlySetup(bodies, numBodies, manifold, numManifolds, constraints, numConstraints, info, debugDrawer); + + // overriden + solveGroupCacheFriendlyIterations(bodies, numBodies, manifold, numManifolds, constraints, numConstraints, info, debugDrawer); + + // inherited from MultiBodyConstraintSolver + solveGroupCacheFriendlyFinish(bodies, numBodies, info); + + m_tmpMultiBodyConstraints = 0; + m_tmpNumMultiBodyConstraints = 0; + } +}; + +#endif /* BT_DEFORMABLE_MULTIBODY_CONSTRAINT_SOLVER_H */ diff --git a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp index 95f9b48b5..58907fcd3 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp +++ b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp @@ -33,6 +33,7 @@ The algorithm also closely resembles the one in http://physbam.stanford.edu/~fed #include "btDeformableMultiBodyDynamicsWorld.h" #include "btDeformableBodySolver.h" #include "LinearMath/btQuickprof.h" + void btDeformableMultiBodyDynamicsWorld::internalSingleStepSimulation(btScalar timeStep) { BT_PROFILE("internalSingleStepSimulation"); @@ -176,27 +177,108 @@ void btDeformableMultiBodyDynamicsWorld::solveConstraints(btScalar timeStep) // save v_{n+1}^* velocity after explicit forces m_deformableBodySolver->backupVelocity(); - // setup constraints among multibodies and between multibodies and deformable bodies + // set up constraints among multibodies and between multibodies and deformable bodies setupConstraints(); - solveMultiBodyConstraints(); + solveMultiBodyRelatedConstraints(); m_deformableBodySolver->solveDeformableConstraints(timeStep); } void btDeformableMultiBodyDynamicsWorld::setupConstraints() { + // set up constraints between multibody and deformable bodies m_deformableBodySolver->setConstraints(); - m_islandManager->buildIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld()); + + // set up constraints among multibodies + { + sortConstraints(); + // setup the solver callback + btMultiBodyConstraint** sortedMultiBodyConstraints = m_sortedMultiBodyConstraints.size() ? &m_sortedMultiBodyConstraints[0] : 0; + btTypedConstraint** constraintsPtr = getNumConstraints() ? &m_sortedConstraints[0] : 0; + m_solverMultiBodyIslandCallback->setup(&m_solverInfo, constraintsPtr, m_sortedConstraints.size(), sortedMultiBodyConstraints, m_sortedMultiBodyConstraints.size(), getDebugDrawer()); + m_constraintSolver->prepareSolve(getCollisionWorld()->getNumCollisionObjects(), getCollisionWorld()->getDispatcher()->getNumManifolds()); + + // build islands + m_islandManager->buildIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld()); + // write the constraint information of each island to the callback, and also setup the constraints in solver + } } -void btDeformableMultiBodyDynamicsWorld::solveMultiBodyConstraints() +void btDeformableMultiBodyDynamicsWorld::sortConstraints() { - for (int i = 0; i < m_contact_iterations; ++i) + m_sortedConstraints.resize(m_constraints.size()); + int i; + for (i = 0; i < getNumConstraints(); i++) { - m_islandManager->processIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld(), (btSimulationIslandManager::IslandCallback*)m_solverMultiBodyIslandCallback); - btMultiBodyDynamicsWorld::processConstraintsAndDeltaVee(); - m_deformableBodySolver->solveContactConstraints(); + m_sortedConstraints[i] = m_constraints[i]; + } + m_sortedConstraints.quickSort(btSortConstraintOnIslandPredicate2()); + + m_sortedMultiBodyConstraints.resize(m_multiBodyConstraints.size()); + for (i = 0; i < m_multiBodyConstraints.size(); i++) + { + m_sortedMultiBodyConstraints[i] = m_multiBodyConstraints[i]; + } + m_sortedMultiBodyConstraints.quickSort(btSortMultiBodyConstraintOnIslandPredicate()); +} + + +void btDeformableMultiBodyDynamicsWorld::solveMultiBodyRelatedConstraints() +{ + // process constraints on each island + m_islandManager->processIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld(), m_solverMultiBodyIslandCallback); + + // process deferred + m_solverMultiBodyIslandCallback->processConstraints(); + m_constraintSolver->allSolved(m_solverInfo, m_debugDrawer); + + // write joint feedback + { + for (int i = 0; i < this->m_multiBodies.size(); i++) + { + btMultiBody* bod = m_multiBodies[i]; + + bool isSleeping = false; + + if (bod->getBaseCollider() && bod->getBaseCollider()->getActivationState() == ISLAND_SLEEPING) + { + isSleeping = true; + } + for (int b = 0; b < bod->getNumLinks(); b++) + { + if (bod->getLink(b).m_collider && bod->getLink(b).m_collider->getActivationState() == ISLAND_SLEEPING) + isSleeping = true; + } + + if (!isSleeping) + { + //useless? they get resized in stepVelocities once again (AND DIFFERENTLY) + m_scratch_r.resize(bod->getNumLinks() + 1); //multidof? ("Y"s use it and it is used to store qdd) + m_scratch_v.resize(bod->getNumLinks() + 1); + m_scratch_m.resize(bod->getNumLinks() + 1); + + if (bod->internalNeedsJointFeedback()) + { + if (!bod->isUsingRK4Integration()) + { + if (bod->internalNeedsJointFeedback()) + { + bool isConstraintPass = true; + bod->computeAccelerationsArticulatedBodyAlgorithmMultiDof(m_solverInfo.m_timeStep, m_scratch_r, m_scratch_v, m_scratch_m, isConstraintPass, + getSolverInfo().m_jointFeedbackInWorldSpace, + getSolverInfo().m_jointFeedbackInJointFrame); + } + } + } + } + } + } + + // todo : may not be necessary + for (int i = 0; i < this->m_multiBodies.size(); i++) + { + btMultiBody* bod = m_multiBodies[i]; + bod->processDeltaVeeMultiDof2(); } - // todo @xuchenhan: add joint force feedback } void btDeformableMultiBodyDynamicsWorld::addSoftBody(btSoftBody* body, int collisionFilterGroup, int collisionFilterMask) @@ -244,8 +326,51 @@ void btDeformableMultiBodyDynamicsWorld::applyRigidBodyGravity(btScalar timeStep btRigidBody* rb = m_nonStaticRigidBodies[i]; rb->integrateVelocities(timeStep); } + // integrate multibody gravity - btMultiBodyDynamicsWorld::solveExternalForces(btMultiBodyDynamicsWorld::getSolverInfo()); + { + forwardKinematics(); + clearMultiBodyConstraintForces(); + { + for (int i = 0; i < this->m_multiBodies.size(); i++) + { + btMultiBody* bod = m_multiBodies[i]; + + bool isSleeping = false; + + if (bod->getBaseCollider() && bod->getBaseCollider()->getActivationState() == ISLAND_SLEEPING) + { + isSleeping = true; + } + for (int b = 0; b < bod->getNumLinks(); b++) + { + if (bod->getLink(b).m_collider && bod->getLink(b).m_collider->getActivationState() == ISLAND_SLEEPING) + isSleeping = true; + } + + if (!isSleeping) + { + m_scratch_r.resize(bod->getNumLinks() + 1); + m_scratch_v.resize(bod->getNumLinks() + 1); + m_scratch_m.resize(bod->getNumLinks() + 1); + bool isConstraintPass = false; + { + if (!bod->isUsingRK4Integration()) + { + bod->computeAccelerationsArticulatedBodyAlgorithmMultiDof(m_solverInfo.m_timeStep, + m_scratch_r, m_scratch_v, m_scratch_m,isConstraintPass, + getSolverInfo().m_jointFeedbackInWorldSpace, + getSolverInfo().m_jointFeedbackInJointFrame); + } + else + { + btAssert(" RK4Integration is not supported" ); + } + } + } + } + } + } clearForces(); clearMultiBodyForces(); } diff --git a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h index 1b1806bac..a91944c55 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h +++ b/src/BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h @@ -20,6 +20,7 @@ #include "btDeformableLagrangianForce.h" #include "btDeformableMassSpringForce.h" #include "btDeformableBodySolver.h" +#include "btDeformableMultiBodyConstraintSolver.h" #include "btSoftBodyHelpers.h" #include "BulletCollision/CollisionDispatch/btSimulationIslandManager.h" #include @@ -28,6 +29,7 @@ typedef btAlignedObjectArray btSoftBodyArray; class btDeformableBodySolver; class btDeformableLagrangianForce; struct MultiBodyInplaceSolverIslandCallback; +class btDeformableMultiBodyConstraintSolver; typedef btAlignedObjectArray btSoftBodyArray; @@ -59,8 +61,8 @@ protected: void solveConstraints(btScalar timeStep); public: - btDeformableMultiBodyDynamicsWorld(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btMultiBodyConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration, btDeformableBodySolver* deformableBodySolver = 0) - : btMultiBodyDynamicsWorld(dispatcher, pairCache, constraintSolver, collisionConfiguration), + btDeformableMultiBodyDynamicsWorld(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btDeformableMultiBodyConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration, btDeformableBodySolver* deformableBodySolver = 0) + : btMultiBodyDynamicsWorld(dispatcher, pairCache, (btMultiBodyConstraintSolver*)constraintSolver, collisionConfiguration), m_deformableBodySolver(deformableBodySolver), m_solverCallback(0) { m_drawFlags = fDrawFlags::Std; @@ -70,7 +72,7 @@ public: m_sbi.m_broadphase = pairCache; m_sbi.m_dispatcher = dispatcher; m_sbi.m_sparsesdf.Initialize(); - m_sbi.m_sparsesdf.setDefaultVoxelsz(0.0025); + m_sbi.m_sparsesdf.setDefaultVoxelsz(0.025); m_sbi.m_sparsesdf.Reset(); m_sbi.air_density = (btScalar)1.2; @@ -78,10 +80,7 @@ public: m_sbi.water_offset = 0; m_sbi.water_normal = btVector3(0, 0, 0); m_sbi.m_gravity.setValue(0, -10, 0); - - m_sbi.m_sparsesdf.Initialize(); m_internalTime = 0.0; - m_contact_iterations = 1; } void setSolverCallback(btSolverCallback cb) @@ -148,7 +147,12 @@ public: void setDrawFlags(int f) { m_drawFlags = f; } void setupConstraints(); + void solveMultiBodyConstraints(); + + void solveMultiBodyRelatedConstraints(); + + void sortConstraints(); }; #endif //BT_DEFORMABLE_RIGID_DYNAMICS_WORLD_H From f2d8ed71ac03fa4310fa07620acd3271138db7c6 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Fri, 23 Aug 2019 20:06:41 -0700 Subject: [PATCH 52/56] float->btScalar --- src/BulletSoftBody/btDefaultSoftBodySolver.cpp | 2 +- src/BulletSoftBody/btDefaultSoftBodySolver.h | 4 ++-- src/BulletSoftBody/btDeformableBodySolver.cpp | 2 +- src/BulletSoftBody/btDeformableBodySolver.h | 6 ++---- src/BulletSoftBody/btSoftBodySolvers.h | 4 ++-- 5 files changed, 8 insertions(+), 10 deletions(-) diff --git a/src/BulletSoftBody/btDefaultSoftBodySolver.cpp b/src/BulletSoftBody/btDefaultSoftBodySolver.cpp index 8b7ff9abc..dfd7072b6 100644 --- a/src/BulletSoftBody/btDefaultSoftBodySolver.cpp +++ b/src/BulletSoftBody/btDefaultSoftBodySolver.cpp @@ -132,7 +132,7 @@ void btDefaultSoftBodySolver::processCollision(btSoftBody *softBody, const btCol softBody->defaultCollisionHandler(collisionObjectWrap); } // btDefaultSoftBodySolver::processCollision -void btDefaultSoftBodySolver::predictMotion(float timeStep) +void btDefaultSoftBodySolver::predictMotion(btScalar timeStep) { for (int i = 0; i < m_softBodySet.size(); ++i) { diff --git a/src/BulletSoftBody/btDefaultSoftBodySolver.h b/src/BulletSoftBody/btDefaultSoftBodySolver.h index 50bd73516..3965b07c5 100644 --- a/src/BulletSoftBody/btDefaultSoftBodySolver.h +++ b/src/BulletSoftBody/btDefaultSoftBodySolver.h @@ -46,9 +46,9 @@ public: virtual void copyBackToSoftBodies(bool bMove = true); - virtual void solveConstraints(float solverdt); + virtual void solveConstraints(btScalar solverdt); - virtual void predictMotion(float solverdt); + virtual void predictMotion(btScalar solverdt); virtual void copySoftBodyToVertexBuffer(const btSoftBody *const softBody, btVertexBufferDescriptor *vertexBuffer); diff --git a/src/BulletSoftBody/btDeformableBodySolver.cpp b/src/BulletSoftBody/btDeformableBodySolver.cpp index 0e26e2c6d..4489296f0 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.cpp +++ b/src/BulletSoftBody/btDeformableBodySolver.cpp @@ -143,7 +143,7 @@ bool btDeformableBodySolver::updateNodes() } -void btDeformableBodySolver::predictMotion(float solverdt) +void btDeformableBodySolver::predictMotion(btScalar solverdt) { for (int i = 0; i < m_softBodySet.size(); ++i) { diff --git a/src/BulletSoftBody/btDeformableBodySolver.h b/src/BulletSoftBody/btDeformableBodySolver.h index 9839df7f2..a40d1fb99 100644 --- a/src/BulletSoftBody/btDeformableBodySolver.h +++ b/src/BulletSoftBody/btDeformableBodySolver.h @@ -58,14 +58,12 @@ public: virtual void updateSoftBodies(); virtual void copyBackToSoftBodies(bool bMove = true) {} - - void extracted(float solverdt); virtual void solveDeformableConstraints(btScalar solverdt); btScalar solveContactConstraints(); - virtual void solveConstraints(float dt){} + virtual void solveConstraints(btScalar dt){} void reinitialize(const btAlignedObjectArray& softBodies, btScalar dt); @@ -81,7 +79,7 @@ public: void computeStep(TVStack& dv, const TVStack& residual); - virtual void predictMotion(float solverdt); + virtual void predictMotion(btScalar solverdt); virtual void copySoftBodyToVertexBuffer(const btSoftBody *const softBody, btVertexBufferDescriptor *vertexBuffer) {} diff --git a/src/BulletSoftBody/btSoftBodySolvers.h b/src/BulletSoftBody/btSoftBodySolvers.h index 405475529..c4ac4141a 100644 --- a/src/BulletSoftBody/btSoftBodySolvers.h +++ b/src/BulletSoftBody/btSoftBodySolvers.h @@ -72,10 +72,10 @@ public: virtual void copyBackToSoftBodies(bool bMove = true) = 0; /** Predict motion of soft bodies into next timestep */ - virtual void predictMotion(float solverdt) = 0; + virtual void predictMotion(btScalar solverdt) = 0; /** Solve constraints for a set of soft bodies */ - virtual void solveConstraints(float solverdt) = 0; + virtual void solveConstraints(btScalar solverdt) = 0; /** Perform necessary per-step updates of soft bodies such as recomputing normals and bounding boxes */ virtual void updateSoftBodies() = 0; From bb4a554e68a75141ab725a22f84e219f947ae9a1 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Sat, 24 Aug 2019 11:51:33 -0700 Subject: [PATCH 53/56] bug fix in multibody interpolation world transform: update cached rotation and vector --- src/BulletDynamics/Featherstone/btMultiBodyLink.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/BulletDynamics/Featherstone/btMultiBodyLink.h b/src/BulletDynamics/Featherstone/btMultiBodyLink.h index 565bb6b3e..01d5583c2 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyLink.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyLink.h @@ -197,7 +197,7 @@ struct btMultibodyLink { btScalar *pJointPos = (pq ? pq : &m_jointPos[0]); btQuaternion& cachedRot = m_cachedRotParentToThis; - btVector3& cachedVector =m_cachedRVector; + btVector3& cachedVector = m_cachedRVector; switch (m_jointType) { case eRevolute: @@ -241,6 +241,8 @@ struct btMultibodyLink btAssert(0); } } + m_cachedRotParentToThis_interpolate = m_cachedRotParentToThis; + m_cachedRVector_interpolate = m_cachedRVector; } void updateInterpolationCacheMultiDof() From b0a91bb30696bfeea5f9b3350992d6f948a6e586 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Sat, 24 Aug 2019 11:55:34 -0700 Subject: [PATCH 54/56] float->btScalar --- src/BulletSoftBody/btDefaultSoftBodySolver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/BulletSoftBody/btDefaultSoftBodySolver.cpp b/src/BulletSoftBody/btDefaultSoftBodySolver.cpp index dfd7072b6..5a79ef86e 100644 --- a/src/BulletSoftBody/btDefaultSoftBodySolver.cpp +++ b/src/BulletSoftBody/btDefaultSoftBodySolver.cpp @@ -60,7 +60,7 @@ bool btDefaultSoftBodySolver::checkInitialized() return true; } -void btDefaultSoftBodySolver::solveConstraints(float solverdt) +void btDefaultSoftBodySolver::solveConstraints(btScalar solverdt) { // Solve constraints for non-solver softbodies for (int i = 0; i < m_softBodySet.size(); ++i) From 8b38076376afe1bcbb7723e0174c9dd652f63c88 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Sat, 24 Aug 2019 12:44:58 -0700 Subject: [PATCH 55/56] update license --- .../btMultiBodyInplaceSolverIslandCallback.h | 18 ++++++++++------ .../btDeformableMultiBodyConstraintSolver.cpp | 21 +++++++++++++------ .../btDeformableMultiBodyConstraintSolver.h | 21 +++++++++++++------ 3 files changed, 42 insertions(+), 18 deletions(-) diff --git a/src/BulletDynamics/Featherstone/btMultiBodyInplaceSolverIslandCallback.h b/src/BulletDynamics/Featherstone/btMultiBodyInplaceSolverIslandCallback.h index accf7c50b..458e62a78 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyInplaceSolverIslandCallback.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyInplaceSolverIslandCallback.h @@ -1,9 +1,15 @@ -// -// btMultiBodyInplaceSolverCallback.h -// BulletDynamics -// -// Created by Xuchen Han on 8/22/19. -// +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ #ifndef BT_MULTIBODY_INPLACE_SOLVER_ISLAND_CALLBACK_H #define BT_MULTIBODY_INPLACE_SOLVER_ISLAND_CALLBACK_H diff --git a/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp b/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp index a331d1ba2..65ba43e04 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp +++ b/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp @@ -1,9 +1,18 @@ -// -// btDeformableMultiBodyConstraintSolver.cpp -// BulletSoftBody -// -// Created by Xuchen Han on 8/23/19. -// +/* + Written by Xuchen Han + + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + #include "btDeformableMultiBodyConstraintSolver.h" #include diff --git a/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.h b/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.h index c5c37cefc..f7d156e4d 100644 --- a/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.h +++ b/src/BulletSoftBody/btDeformableMultiBodyConstraintSolver.h @@ -1,9 +1,18 @@ -// -// btDeformableMultiBodyConstraintSolver.h -// BulletSoftBody -// -// Created by Xuchen Han on 8/22/19. -// +/* + Written by Xuchen Han + + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2019 Google Inc. http://bulletphysics.org + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + #ifndef BT_DEFORMABLE_MULTIBODY_CONSTRAINT_SOLVER_H #define BT_DEFORMABLE_MULTIBODY_CONSTRAINT_SOLVER_H From 908cf69f0673baee92f3c2ad2f1477b00505d0a4 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Sat, 24 Aug 2019 14:58:11 -0700 Subject: [PATCH 56/56] change deformable/multibody solve to be in dv space --- src/BulletDynamics/Featherstone/btMultiBody.h | 5 +++++ .../btDeformableContactProjection.cpp | 16 +++++++--------- 2 files changed, 12 insertions(+), 9 deletions(-) diff --git a/src/BulletDynamics/Featherstone/btMultiBody.h b/src/BulletDynamics/Featherstone/btMultiBody.h index 91b5c3edb..afed669a7 100644 --- a/src/BulletDynamics/Featherstone/btMultiBody.h +++ b/src/BulletDynamics/Featherstone/btMultiBody.h @@ -273,6 +273,11 @@ public: { return &m_realBuf[0]; } + + const btScalar *getDeltaVelocityVector() const + { + return &m_deltaV[0]; + } /* btScalar * getVelocityVector() { return &real_buf[0]; diff --git a/src/BulletSoftBody/btDeformableContactProjection.cpp b/src/BulletSoftBody/btDeformableContactProjection.cpp index 25c14b5b9..33feb4bc6 100644 --- a/src/BulletSoftBody/btDeformableContactProjection.cpp +++ b/src/BulletSoftBody/btDeformableContactProjection.cpp @@ -58,26 +58,26 @@ btScalar btDeformableContactProjection::update() const btScalar* J_t1 = &c->jacobianData_t1.m_jacobians[0]; const btScalar* J_t2 = &c->jacobianData_t2.m_jacobians[0]; const btScalar* local_v = multibodyLinkCol->m_multiBody->getVelocityVector(); + const btScalar* local_dv = multibodyLinkCol->m_multiBody->getDeltaVelocityVector(); deltaV_normal = &c->jacobianData_normal.m_deltaVelocitiesUnitImpulse[0]; // add in the normal component of the va btScalar vel = 0.0; for (int k = 0; k < ndof; ++k) { - vel += local_v[k] * J_n[k]; + vel += (local_v[k]+local_dv[k]) * J_n[k]; } va = cti.m_normal * vel * m_dt; - // add in the tangential components of the va vel = 0.0; for (int k = 0; k < ndof; ++k) { - vel += local_v[k] * J_t1[k]; + vel += (local_v[k]+local_dv[k]) * J_t1[k]; } va += c->t1 * vel * m_dt; vel = 0.0; for (int k = 0; k < ndof; ++k) { - vel += local_v[k] * J_t2[k]; + vel += (local_v[k]+local_dv[k]) * J_t2[k]; } va += c->t2 * vel * m_dt; } @@ -131,7 +131,6 @@ btScalar btDeformableContactProjection::update() // dn is the normal component of velocity diffrerence. Approximates the residual. residualSquare = btMax(residualSquare, dn*dn); - if (cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY) { if (rigidCol) @@ -143,16 +142,15 @@ btScalar btDeformableContactProjection::update() { if (multibodyLinkCol) { - multibodyLinkCol->m_multiBody->processDeltaVeeMultiDof2(); // make sure velocity is up-to-date; // apply normal component of the impulse - multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof(deltaV_normal, impulse.dot(cti.m_normal)); + multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof2(deltaV_normal, impulse.dot(cti.m_normal)); if (impulse_tangent.norm() > SIMD_EPSILON) { // apply tangential component of the impulse const btScalar* deltaV_t1 = &c->jacobianData_t1.m_deltaVelocitiesUnitImpulse[0]; - multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof(deltaV_t1, impulse.dot(c->t1)); + multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof2(deltaV_t1, impulse.dot(c->t1)); const btScalar* deltaV_t2 = &c->jacobianData_t2.m_deltaVelocitiesUnitImpulse[0]; - multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof(deltaV_t2, impulse.dot(c->t2)); + multibodyLinkCol->m_multiBody->applyDeltaVeeMultiDof2(deltaV_t2, impulse.dot(c->t2)); } } }